diff --git a/.clang-format b/.clang-format new file mode 100644 index 00000000..ada61da2 --- /dev/null +++ b/.clang-format @@ -0,0 +1,8 @@ +--- +BasedOnStyle: Google +IndentWidth: 2 +--- +Language: Cpp +ColumnLimit: 100 +ReflowComments: true +--- diff --git a/.gitignore b/.gitignore index c51106ea..c337ab89 100644 --- a/.gitignore +++ b/.gitignore @@ -8,6 +8,9 @@ !misc/eclipse/**/.cproject !misc/eclipse/**/.project +#vscode +/.vscode + # Python __pycache__ .idea diff --git a/CMakeLists.txt b/CMakeLists.txt index e9b1b68c..03d51ac2 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -13,34 +13,32 @@ cmake_minimum_required(VERSION 3.13) set(CMAKE_SCRIPT_PATH "${CMAKE_CURRENT_SOURCE_DIR}/cmake") -if(TGT_BSP MATCHES "arm/q7s") - option(EIVE_BUILD_WATCHDOG "Compile the OBSW watchdog insted" OFF) - option(BUILD_Q7S_SIMPLE_MODE OFF "Simple mode with a minimal main function") -endif() -option(ADD_ETL_LIB "Add ETL library" ON) -option(ADD_JSON_LIB "Add JSON library" ON) +option(EIVE_ADD_ETL_LIB "Add ETL library" ON) +option(EIVE_ADD_JSON_LIB "Add JSON library" ON) + option(EIVE_SYSROOT_MAGIC "Perform sysroot magic which might not be necessary" OFF) +option(EIVE_CREATE_UNIQUE_OBSW_BIN "Append username to generated binary name" ON) if(NOT FSFW_OSAL) - set(FSFW_OSAL host CACHE STRING "OS for the FSFW.") + set(FSFW_OSAL linux CACHE STRING "OS for the FSFW.") endif() -if(TGT_BSP MATCHES "arm/raspberrypi" OR TGT_BSP MATCHES "arm/beagleboneblack") - option(LINUX_CROSS_COMPILE ON) +if(TGT_BSP) + if(TGT_BSP MATCHES "arm/raspberrypi" OR TGT_BSP MATCHES "arm/beagleboneblack") + option(LINUX_CROSS_COMPILE ON) + option(EIVE_BUILD_GPSD_GPS_HANDLER "Build GPSD dependent GPS Handler" OFF) + elseif(TGT_BSP MATCHES "arm/q7s") + option(EIVE_BUILD_GPSD_GPS_HANDLER "Build GPSD dependent GPS Handler" ON) + endif() endif() # Perform steps like loading toolchain files where applicable. include(${CMAKE_SCRIPT_PATH}/PreProjectConfig.cmake) pre_project_config() -set(PROJECT_NAME_TO_SET eive-obsw-$ENV{USERNAME}) -if(EIVE_BUILD_WATCHDOG) - set(PROJECT_NAME_TO_SET eive-watchdog) -endif() - # Project Name -project(${PROJECT_NAME_TO_SET} ASM C CXX) +project(eive-obsw ASM C CXX) ################################################################################ # Pre-Sources preparation @@ -51,34 +49,42 @@ set(CMAKE_CXX_STANDARD 17) set(CMAKE_CXX_STANDARD_REQUIRED True) # Set names and variables -set(TARGET_NAME ${CMAKE_PROJECT_NAME}) +set(OBSW_NAME ${CMAKE_PROJECT_NAME}) +set(WATCHDOG_NAME eive-watchdog) +set(SIMPLE_OBSW_NAME eive-simple) +set(UNITTEST_NAME eive-unittest) set(LIB_FSFW_NAME fsfw) +set(LIB_EIVE_MISSION eive-mission) set(LIB_ETL_NAME etl) set(LIB_CSP_NAME libcsp) set(LIB_LWGPS_NAME lwgps) set(LIB_ARCSEC wire) set(THIRD_PARTY_FOLDER thirdparty) set(LIB_CXX_FS -lstdc++fs) +set(LIB_CATCH2 Catch2) +set(LIB_GPS gps) set(LIB_JSON_NAME nlohmann_json::nlohmann_json) # Set path names set(FSFW_PATH fsfw) -set(MISSION_PATH mission) set(TEST_PATH test/testtasks) +set(UNITTEST_PATH unittest) set(LINUX_PATH linux) set(COMMON_PATH common) set(WATCHDOG_PATH watchdog) set(COMMON_CONFIG_PATH ${COMMON_PATH}/config) +set(UNITTEST_CFG_PATH ${UNITTEST_PATH}/testcfg) -set(FSFW_HAL_LIB_PATH fsfw_hal) -set(CSP_LIB_PATH ${THIRD_PARTY_FOLDER}/libcsp) -set(ETL_LIB_PATH ${THIRD_PARTY_FOLDER}/etl) -set(LWGPS_LIB_PATH ${THIRD_PARTY_FOLDER}/lwgps) -set(ARCSEC_LIB_PATH ${THIRD_PARTY_FOLDER}/arcsec_star_tracker) +set(LIB_EIVE_MISSION_PATH mission) +set(LIB_CSP_PATH ${THIRD_PARTY_FOLDER}/libcsp) +set(LIB_ETL_PATH ${THIRD_PARTY_FOLDER}/etl) +set(LIB_CATCH2_PATH ${THIRD_PARTY_FOLDER}/Catch2) +set(LIB_LWGPS_PATH ${THIRD_PARTY_FOLDER}/lwgps) +set(LIB_ARCSEC_PATH ${THIRD_PARTY_FOLDER}/arcsec_star_tracker) set(LIB_JSON_PATH ${THIRD_PARTY_FOLDER}/json) set(FSFW_WARNING_SHADOW_LOCAL_GCC OFF) -set(ADD_LINUX_FILES False) +set(EIVE_ADD_LINUX_FILES False) # Analyse different OS and architecture/target options, determine BSP_PATH, # display information about compiler etc. @@ -87,21 +93,27 @@ pre_source_hw_os_config() if(TGT_BSP) if(TGT_BSP MATCHES "arm/q7s" OR TGT_BSP MATCHES "arm/raspberrypi" - OR TGT_BSP MATCHES "arm/beagleboneblack" + OR TGT_BSP MATCHES "arm/beagleboneblack" OR TGT_BSP MATCHES "arm/egse" ) set(FSFW_CONFIG_PATH "linux/fsfwconfig") if(NOT BUILD_Q7S_SIMPLE_MODE) - set(ADD_LINUX_FILES TRUE) + 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") + 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) + endif() if(TGT_BSP MATCHES "arm/beagleboneblack") # Used by configure file @@ -117,17 +129,19 @@ else() set(FSFW_CONFIG_PATH "${BSP_PATH}/fsfwconfig") endif() + # Configuration files -if(NOT EIVE_BUILD_WATCHDOG) - configure_file(${COMMON_CONFIG_PATH}/commonConfig.h.in commonConfig.h) - configure_file(${FSFW_CONFIG_PATH}/FSFWConfig.h.in FSFWConfig.h) - configure_file(${FSFW_CONFIG_PATH}/OBSWConfig.h.in OBSWConfig.h) - if(TGT_BSP MATCHES "arm/q7s") - configure_file(${BSP_PATH}/boardconfig/q7sConfig.h.in q7sConfig.h) - elseif(TGT_BSP MATCHES "arm/raspberrypi") - configure_file(${BSP_PATH}/boardconfig/rpiConfig.h.in rpiConfig.h) - endif() +configure_file(${COMMON_CONFIG_PATH}/commonConfig.h.in commonConfig.h) +configure_file(${FSFW_CONFIG_PATH}/FSFWConfig.h.in FSFWConfig.h) +configure_file(${FSFW_CONFIG_PATH}/OBSWConfig.h.in OBSWConfig.h) +if(TGT_BSP MATCHES "arm/q7s") + 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) endif() + + + configure_file(${WATCHDOG_PATH}/watchdogConf.h.in watchdogConf.h) # Set common config path for FSFW @@ -136,136 +150,211 @@ set(FSFW_ADDITIONAL_INC_PATHS ${CMAKE_CURRENT_BINARY_DIR} ) +# Check whether the user has already installed Catch2 first +find_package(Catch2 3) + ################################################################################ # Executable and Sources ################################################################################ -# Add executable -add_executable(${TARGET_NAME}) +#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 ( General information @@ -35,7 +40,7 @@ Target systems: relevant pages. The most recent datasheet can be found [here](https://trac2.xiphos.ca/manual/wiki/Q7RevB/UserManual). * Linux OS built with Yocto 2.5 - * Linux Kernel https://github.com/XiphosSystemsCorp/linux-xlnx.git . EIVE version can be found + * [Linux Kernel](https://github.com/XiphosSystemsCorp/linux-xlnx.git) . EIVE version can be found [here](https://github.com/spacefisch/linux-xlnx) . Pre-compiled files can be found [here](https://eive-cloud.irs.uni-stuttgart.de/index.php/apps/files/?dir=/EIVE_IRS/Software/q7s-linux-components&fileid=777299). * Q7S base project can be found [here](https://egit.irs.uni-stuttgart.de/eive/q7s-base) @@ -102,7 +107,7 @@ When using Windows, run theses steps in MSYS2. ```sh mkdir build-Debug-Q7S && cd build-Debug-Q7S - cmake -DTGT_BSP="arm/q7s" -DCMAKE_BUILD_TYPE=Debug -DOS_FSFW=linux .. + cmake -DTGT_BSP="arm/q7s" -DCMAKE_BUILD_TYPE=Debug .. cmake --build . -j ``` @@ -117,8 +122,7 @@ When using Windows, run theses steps in MSYS2. This will invoke a Python script which in turn invokes CMake with the correct arguments to configure CMake for Q7S cross-compilation. - You can build the hosted variant of the OBSW by replacing `-DOS_FSFW=linux` with - `-DOS_FSFW=host`. There are also different values for `-DTGT_BSP` to build for the Raspberry Pi + There are also different values for `-DTGT_BSP` to build for the Raspberry Pi or the Beagle Bone Black: `arm/raspberrypi` and `arm/beagleboneblack`. 5. Build the software with @@ -157,20 +161,47 @@ automatically. ### Q7S OBSW +The EIVE OBSW is the default target if no target is specified. + ```sh mkdir build-Debug-Q7S && cd build-Debug-Q7S -cmake -DTGT_BSP=arm/q7s -DFSFW_OSAL=linux -DCMAKE_BUILD_TYPE=Debug .. +cmake -DTGT_BSP=arm/q7s -DCMAKE_BUILD_TYPE=Debug .. cmake --build . -j ``` ### Q7S Watchdog +To build the EIVE watchdog, the corresponding target must be specified in the build command. +The configure steps do not need to be repeated if the folder has already been configured. + ```sh -mkdir build-Debug-Q7S && cd build-Debug-Q7S -cmake -DTGT_BSP=arm/q7s -DFSFW_OSAL=linux -DEIVE_BUILD_WATCHDOG=ON -DCMAKE_BUILD_TYPE=Debug .. +mkdir build-Debug-Watchdog && cd build-Debug-Watchdog +cmake -DTGT_BSP=arm/q7s -DCMAKE_BUILD_TYPE=Debug .. +cmake --build . --target eive-watchdog -j +``` + +### Hosted + +You can also use the FSFW OSAL `host` to build on Windows or for generic OSes. +Note: Currently this is not supported. + +```sh +mkdir build-Debug-Host && cd build-Debug-Host +cmake -DFSFW_OSAL=host -DCMAKE_BUILD_TYPE=Debug .. cmake --build . -j ``` +### Unittests + +To build the unittests, the corresponding target must be specified in the build command. +The configure steps do not need to be repeated if the folder has already been configured. + +```sh +mkdir build-Debug-Unittest && cd build-Debug-Unittest +cmake .. +cmake --build . --target eive-unittests -j +``` + ## Connect to EIVE flatsat ### DNS @@ -411,12 +442,24 @@ Beagle Bone Black for download here Download it and unzip it somewhere in the Xilinx installation folder. You can use the following command if `wget` can be used or for CI/CD: -``` -wget https://eive-cloud.irs.uni-stuttgart.de/index.php/s/agnJGYeRf6fw2ci/download/cortexa9hf-neon-xiphos-linux-gnueabi.tar.gz +```sh +wget https://eive-cloud.irs.uni-stuttgart.de/index.php/s/SyXpdBBQX32xPgE/download/cortexa9hf-neon-xiphos-linux-gnueabi.tar.gz ``` Then, create a new environmental variables `Q7S_SYSROOT` and set it to the local system root path. +### Updating system root for CI + +If the system root is updated, it needs to be manually updated on the buggy file server. +If access on `buggy.irs.uni-stuttgart.de` is possible with `ssh` and the rootfs in the cloud +[was updated](https://eive-cloud.irs.uni-stuttgart.de/index.php/apps/files/?dir=/EIVE_IRS/Software/rootfs&fileid=831849) +as well, you can update the rootfs like this: + +```sh +cd /var/www/eive/tools +wget https://eive-cloud.irs.uni-stuttgart.de/index.php/s/SyXpdBBQX32xPgE/download/cortexa9hf-neon-xiphos-linux-gnueabi.tar.gz +``` + ## Setting up UNIX environment for real-time functionalities Please note that on most UNIX environments (e.g. Ubuntu), the real time functionalities @@ -514,10 +557,10 @@ ssh root@192.168.133.10 ``` If this has not been done yet, you can access the serial -console of the Q7S like this to set it +console of the Q7S like this ```sh -picocom -b 115200 /dev/ttyUSB0 +picocom -b 115200 /dev/q7sSerial ``` The flatsat has the aliases and shell scripts `q7s_ssh` and `q7s_serial` for this task as well. @@ -554,6 +597,63 @@ alias or shell script to do this quickly. Note: When now setting up a debug session in the Xilinx SDK or Eclipse, the host must be set to localhost instead of the IP address of the Q7S. +# Remote Reset +1. Launch xilinx hardware server on flatsat with alias +```` +launch-hwserver-xilinx +```` +2. On host PC start xsc +3. In xsct console type the follwing command to connect to the hardware server (replace with the IP address of the flatsat PC. Can be found out with ifconfig) +```` +connect -url tcp::3121 +```` +4. The following command will list all available devices +```` +targets +```` +5. Connect to the APU of the Q7S +```` +target +```` +6. Perform reset +```` +rst +```` + +# TMTC testing + +The OBSW supports sending PUS TM packets via TCP or the PDEC IP Core which transmits the data as +CADU frames. To make the CADU frames receivabel by the +[TMTC porgram](https://egit.irs.uni-stuttgart.de/eive/eive-tmtc), a python script is running as +`systemd` service named `tmtc_bridge` on the flatsat PC which forwards TCP commands to the TCP +server of the OBC and reads CADU frames from a serial interface. + +You can check whether the service is running the following command on the flatsat PC + +```sh +systemctl status tmtc_bridge +``` + +The PUS packets transported with the CADU frames are extracted +and forwared to the TMTC program's TCP client. The code of the TMTC bridge can be found +[here](https://egit.irs.uni-stuttgart.de/eive/tmtc-bridge). To connect the TMTC program to the +TMTC-bridge a port forwarding from a host must be set up with the following command: + +```sh +ssh -L 1537:127.0.0.1:7100 eive@2001:7c0:2018:1099:babe:0:e1fe:f1a5 -t bash +``` + +You can print the output of the `systemd` service with + +```sh +journalctl -u tmtc_bridge +``` + +This can be helpful to determine whether any TCs arrive or TMs are coming back. + +Note: The encoding of the TM packets and conversion of CADU frames takes some time. +Thus the replies are received with a larger delay compared to a direct TCP connection. + # Direct Debugging 1. Assign static IP address to Q7S @@ -966,26 +1066,7 @@ cat file.bin | hexdump -v -n X ## Preparation of a fresh rootfs and SD card -This section summarizes important changes between a fresh rootfs and the current -EIVE implementation - -### rootfs - -- Mount point `/mnt/sd0` created for SD card 0. Created with `mkdir` -- Mount point `/mnt/sd1` created for SD card 1. Created with `mkdir` -- Folder `scripts` in `/home/root` folder. -- `scripts` folder currently contains a few shell helper scripts -- Folder `profile.d` in `/etc` folder which contains the `path-set.sh` script - which is sourced at software startup -- Library `libwire.so` in `/usr/lib` folder - -### SD Cards - -- Folder `bin` for binaries, for example the OBSW -- Folder `misc` for miscellaneous files. Contains `ls` for directory listings -- Folder `tc` for telecommands -- Folder `tm` for telemetry -- Folder `xdi` for XDI components (e.g. for firmware or device tree updates) +See [q7s-package repository README](https://egit.irs.uni-stuttgart.de/eive/q7s-package) # Running cppcheck on the Software @@ -1033,7 +1114,7 @@ The [TCF agent](https://wiki.eclipse.org/TCF) can be used to perform remote debu 1. 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.6/1.6.2/ to search for the plugin and install it. + 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**. Here, the Q7S should show up if the local port forwarding was set up as explained previously. @@ -1072,6 +1153,38 @@ sudo apt-get install gpiod libgpiod-dev to install the required GPIO libraries before cloning the system root folder. +# Running OBSW on EGSE +The EGSE is a test system from arcsec build arround a raspberry pi 4 to test the star tracker. The IP address of the EGSE (raspberry pi) is 192.168.18.31. An ssh session can be opened with +```` +ssh pi@192.168.18.31 +```` +Password: raspberry + +To run the obsw perform the following steps: +1. Build the cmake EGSE Configuration + * the sysroots for the EGSE can be found [here](https://eive-cloud.irs.uni-stuttgart.de/index.php/apps/files/?dir=/EIVE_IRS/Software/egse&fileid=1190471) + * toolchain for linux host can be downloaded from [here](https://github.com/Pro/raspi-toolchain) + * toolchain for windows host from [here](https://gnutoolchains.com/raspberry/) (the raspios-buster-armhf toolchain is the right one for the EGSE) +2. Disable the ser2net systemd service on the EGSE +````sh +$ sudo systemctl stop ser2net.service +```` +3. Power on the star tracker by running +````sh +$ ~/powerctrl/enable0.sh` +```` +4. Run portforwarding script for tmtc tcp connection and tcf agent on host PC +````sh +$ ./scripts/egse-port.sh +```` +5. The star tracker can be powered off by running +````sh +$ ~/powerctrl/disable0.sh +```` + +# Manually preparing sysroots to compile gpsd +Copy all header files from [here](https://eive-cloud.irs.uni-stuttgart.de/index.php/apps/files/?dir=/EIVE_IRS/Software/gpsd&fileid=1189985) to the /usr/include directory and all static libraries to /usr/lib. + # Flight Software Framework (FSFW) An EIVE fork of the FSFW is submodules into this repository. @@ -1091,3 +1204,15 @@ git merge upstream/master Alternatively, changes from other upstreams (forks) and branches can be merged like that in the same way. + +# Coding Style +* the formatting is based on the clang-format tools +## Setting up eclipse auto-fromatter with clang-format +1. Help → Install New Software → Add +2. In location insert the link http://www.cppstyle.com/luna +3. The software package CppStyle should now be available for installation +4. On windows download the clang-formatting tools from https://llvm.org/builds/. On linux clang-format can be installed with the package manager. +5. Navigate to Preferences → C/C++ → CppStyle +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 diff --git a/linux/archive/gpio/CMakeLists.txt b/archive/gpio/CMakeLists.txt similarity index 100% rename from linux/archive/gpio/CMakeLists.txt rename to archive/gpio/CMakeLists.txt diff --git a/archive/gpio/GpioCookie.cpp b/archive/gpio/GpioCookie.cpp new file mode 100644 index 00000000..b1bb2db4 --- /dev/null +++ b/archive/gpio/GpioCookie.cpp @@ -0,0 +1,32 @@ +#include "GpioCookie.h" + +#include + +GpioCookie::GpioCookie() {} + +ReturnValue_t GpioCookie::addGpio(gpioId_t gpioId, GpioBase* gpioConfig) { + if (gpioConfig == nullptr) { + sif::debug << "GpioCookie::addGpio: gpioConfig is nullpointer" << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } + auto gpioMapIter = gpioMap.find(gpioId); + if (gpioMapIter == gpioMap.end()) { + auto statusPair = gpioMap.emplace(gpioId, gpioConfig); + if (statusPair.second == false) { +#if FSFW_VERBOSE_LEVEL >= 1 + sif::error << "GpioCookie::addGpio: Failed to add GPIO " << gpioId << " to GPIO map" + << std::endl; +#endif + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; + } +#if FSFW_VERBOSE_LEVEL >= 1 + sif::error << "GpioCookie::addGpio: GPIO already exists in GPIO map " << std::endl; +#endif + return HasReturnvaluesIF::RETURN_FAILED; +} + +GpioMap GpioCookie::getGpioMap() const { return gpioMap; } + +GpioCookie::~GpioCookie() {} diff --git a/linux/archive/gpio/GpioCookie.h b/archive/gpio/GpioCookie.h similarity index 64% rename from linux/archive/gpio/GpioCookie.h rename to archive/gpio/GpioCookie.h index 3f8531ee..9295a4ac 100644 --- a/linux/archive/gpio/GpioCookie.h +++ b/archive/gpio/GpioCookie.h @@ -1,11 +1,12 @@ #ifndef LINUX_GPIO_GPIOCOOKIE_H_ #define LINUX_GPIO_GPIOCOOKIE_H_ -#include "GpioIF.h" -#include "gpioDefinitions.h" #include #include +#include "GpioIF.h" +#include "gpioDefinitions.h" + /** * @brief Cookie for the GpioIF. Allows the GpioIF to determine which * GPIOs to initialize and whether they should be configured as in- or @@ -16,24 +17,23 @@ * * @author J. Meier */ -class GpioCookie: public CookieIF { -public: +class GpioCookie : public CookieIF { + public: + GpioCookie(); - GpioCookie(); + virtual ~GpioCookie(); - virtual ~GpioCookie(); + ReturnValue_t addGpio(gpioId_t gpioId, GpioBase* gpioConfig); + /** + * @brief Get map with registered GPIOs. + */ + GpioMap getGpioMap() const; - ReturnValue_t addGpio(gpioId_t gpioId, GpioBase* gpioConfig); - /** - * @brief Get map with registered GPIOs. - */ - GpioMap getGpioMap() const; - -private: - /** - * Returns a copy of the internal GPIO map. - */ - GpioMap gpioMap; + private: + /** + * Returns a copy of the internal GPIO map. + */ + GpioMap gpioMap; }; #endif /* LINUX_GPIO_GPIOCOOKIE_H_ */ diff --git a/archive/gpio/GpioIF.h b/archive/gpio/GpioIF.h new file mode 100644 index 00000000..045af556 --- /dev/null +++ b/archive/gpio/GpioIF.h @@ -0,0 +1,54 @@ +#ifndef LINUX_GPIO_GPIOIF_H_ +#define LINUX_GPIO_GPIOIF_H_ + +#include +#include + +#include "gpioDefinitions.h" + +class GpioCookie; + +/** + * @brief This class defines the interface for objects requiring the control + * over GPIOs. + * @author J. Meier + */ +class GpioIF : public HasReturnvaluesIF { + public: + virtual ~GpioIF(){}; + + /** + * @brief Called by the GPIO using object. + * @param cookie Cookie specifying informations of the GPIOs required + * by a object. + */ + virtual ReturnValue_t addGpios(GpioCookie* cookie) = 0; + + /** + * @brief By implementing this function a child must provide the + * functionality to pull a certain GPIO to high logic level. + * + * @param gpioId A unique number which specifies the GPIO to drive. + * @return Returns RETURN_OK for success. This should never return RETURN_FAILED. + */ + virtual ReturnValue_t pullHigh(gpioId_t gpioId) = 0; + + /** + * @brief By implementing this function a child must provide the + * functionality to pull a certain GPIO to low logic level. + * + * @param gpioId A unique number which specifies the GPIO to drive. + */ + virtual ReturnValue_t pullLow(gpioId_t gpioId) = 0; + + /** + * @brief This function requires a child to implement the functionality to read the state of + * an ouput or input gpio. + * + * @param gpioId A unique number which specifies the GPIO to read. + * @param gpioState State of GPIO will be written to this pointer. + */ + virtual ReturnValue_t readGpio(gpioId_t gpioId, int* gpioState) = 0; +}; + +#endif /* LINUX_GPIO_GPIOIF_H_ */ diff --git a/archive/gpio/LinuxLibgpioIF.cpp b/archive/gpio/LinuxLibgpioIF.cpp new file mode 100644 index 00000000..e5dcc1f2 --- /dev/null +++ b/archive/gpio/LinuxLibgpioIF.cpp @@ -0,0 +1,295 @@ +#include "LinuxLibgpioIF.h" + +#include +#include +#include +#include + +#include + +#include "GpioCookie.h" + +LinuxLibgpioIF::LinuxLibgpioIF(object_id_t objectId) : SystemObject(objectId) { + struct gpiod_chip* chip = gpiod_chip_open_by_label("/amba_pl/gpio@42030000"); + + sif::debug << chip->name << std::endl; +} + +LinuxLibgpioIF::~LinuxLibgpioIF() {} + +ReturnValue_t LinuxLibgpioIF::addGpios(GpioCookie* gpioCookie) { + ReturnValue_t result; + if (gpioCookie == nullptr) { + sif::error << "LinuxLibgpioIF::initialize: Invalid cookie" << std::endl; + return RETURN_FAILED; + } + + GpioMap mapToAdd = gpioCookie->getGpioMap(); + + /* Check whether this ID already exists in the map and remove duplicates */ + result = checkForConflicts(mapToAdd); + if (result != RETURN_OK) { + return result; + } + + result = configureGpios(mapToAdd); + if (result != RETURN_OK) { + return RETURN_FAILED; + } + + /* Register new GPIOs in gpioMap */ + gpioMap.insert(mapToAdd.begin(), mapToAdd.end()); + + return RETURN_OK; +} + +ReturnValue_t LinuxLibgpioIF::configureGpios(GpioMap& mapToAdd) { + for (auto& gpioConfig : mapToAdd) { + switch (gpioConfig.second->gpioType) { + case (gpio::GpioTypes::NONE): { + return GPIO_INVALID_INSTANCE; + } + case (gpio::GpioTypes::GPIOD_REGULAR): { + GpiodRegular* regularGpio = dynamic_cast(gpioConfig.second); + if (regularGpio == nullptr) { + return GPIO_INVALID_INSTANCE; + } + configureRegularGpio(gpioConfig.first, regularGpio); + break; + } + case (gpio::GpioTypes::CALLBACK): { + auto gpioCallback = dynamic_cast(gpioConfig.second); + if (gpioCallback->callback == nullptr) { + return GPIO_INVALID_INSTANCE; + } + gpioCallback->callback(gpioConfig.first, gpio::GpioOperation::WRITE, + gpioCallback->initValue, gpioCallback->callbackArgs); + } + } + } + return RETURN_OK; +} + +ReturnValue_t LinuxLibgpioIF::configureRegularGpio(gpioId_t gpioId, GpiodRegular* regularGpio) { + std::string chipname; + unsigned int lineNum; + struct gpiod_chip* chip; + gpio::Direction direction; + std::string consumer; + struct gpiod_line* lineHandle; + int result = 0; + + chipname = regularGpio->chipname; + chip = gpiod_chip_open_by_name(chipname.c_str()); + if (!chip) { + sif::error << "LinuxLibgpioIF::configureGpios: Failed to open chip " << chipname + << ". Gpio ID: " << gpioId << std::endl; + return RETURN_FAILED; + } + + lineNum = regularGpio->lineNum; + lineHandle = gpiod_chip_get_line(chip, lineNum); + if (!lineHandle) { + sif::error << "LinuxLibgpioIF::configureGpios: Failed to open line for GPIO with id " << gpioId + << std::endl; + gpiod_chip_close(chip); + return RETURN_FAILED; + } + + direction = regularGpio->direction; + consumer = regularGpio->consumer; + /* Configure direction and add a description to the GPIO */ + switch (direction) { + case (gpio::OUT): { + result = gpiod_line_request_output(lineHandle, consumer.c_str(), regularGpio->initValue); + if (result < 0) { + sif::error << "LinuxLibgpioIF::configureGpios: Failed to request line " << lineNum + << " from GPIO instance with ID: " << gpioId << std::endl; + gpiod_line_release(lineHandle); + return RETURN_FAILED; + } + break; + } + case (gpio::IN): { + result = gpiod_line_request_input(lineHandle, consumer.c_str()); + if (result < 0) { + sif::error << "LinuxLibgpioIF::configureGpios: Failed to request line " << lineNum + << " from GPIO instance with ID: " << gpioId << std::endl; + gpiod_line_release(lineHandle); + return RETURN_FAILED; + } + break; + } + default: { + sif::error << "LinuxLibgpioIF::configureGpios: Invalid direction specified" << std::endl; + return GPIO_INVALID_INSTANCE; + } + } + /** + * Write line handle to GPIO configuration instance so it can later be used to set or + * read states of GPIOs. + */ + regularGpio->lineHandle = lineHandle; + return RETURN_OK; +} + +ReturnValue_t LinuxLibgpioIF::pullHigh(gpioId_t gpioId) { + gpioMapIter = gpioMap.find(gpioId); + if (gpioMapIter == gpioMap.end()) { + sif::warning << "LinuxLibgpioIF::driveGpio: Unknown GPIOD ID " << gpioId << std::endl; + return UNKNOWN_GPIO_ID; + } + + if (gpioMapIter->second->gpioType == gpio::GpioTypes::GPIOD_REGULAR) { + return driveGpio(gpioId, dynamic_cast(gpioMapIter->second), 1); + } else { + auto gpioCallback = dynamic_cast(gpioMapIter->second); + if (gpioCallback->callback == nullptr) { + return GPIO_INVALID_INSTANCE; + } + gpioCallback->callback(gpioMapIter->first, gpio::GpioOperation::WRITE, 1, + gpioCallback->callbackArgs); + } + return GPIO_TYPE_FAILURE; +} + +ReturnValue_t LinuxLibgpioIF::pullLow(gpioId_t gpioId) { + gpioMapIter = gpioMap.find(gpioId); + if (gpioMapIter == gpioMap.end()) { + sif::warning << "LinuxLibgpioIF::driveGpio: Unknown GPIOD ID " << gpioId << std::endl; + return UNKNOWN_GPIO_ID; + } + + if (gpioMapIter->second->gpioType == gpio::GpioTypes::GPIOD_REGULAR) { + return driveGpio(gpioId, dynamic_cast(gpioMapIter->second), 0); + } else { + auto gpioCallback = dynamic_cast(gpioMapIter->second); + if (gpioCallback->callback == nullptr) { + return GPIO_INVALID_INSTANCE; + } + gpioCallback->callback(gpioMapIter->first, gpio::GpioOperation::WRITE, 0, + gpioCallback->callbackArgs); + } + return GPIO_TYPE_FAILURE; +} + +ReturnValue_t LinuxLibgpioIF::driveGpio(gpioId_t gpioId, GpiodRegular* regularGpio, + unsigned int logicLevel) { + if (regularGpio == nullptr) { + return GPIO_TYPE_FAILURE; + } + + int result = gpiod_line_set_value(regularGpio->lineHandle, logicLevel); + if (result < 0) { + sif::warning << "LinuxLibgpioIF::driveGpio: Failed to pull GPIO with ID " << gpioId + << " to logic level " << logicLevel << std::endl; + return DRIVE_GPIO_FAILURE; + } + + return RETURN_OK; +} + +ReturnValue_t LinuxLibgpioIF::readGpio(gpioId_t gpioId, int* gpioState) { + gpioMapIter = gpioMap.find(gpioId); + if (gpioMapIter == gpioMap.end()) { + sif::warning << "LinuxLibgpioIF::readGpio: Unknown GPIOD ID " << gpioId << std::endl; + return UNKNOWN_GPIO_ID; + } + + if (gpioMapIter->second->gpioType == gpio::GpioTypes::GPIOD_REGULAR) { + GpiodRegular* regularGpio = dynamic_cast(gpioMapIter->second); + if (regularGpio == nullptr) { + return GPIO_TYPE_FAILURE; + } + *gpioState = gpiod_line_get_value(regularGpio->lineHandle); + } else { + } + + return RETURN_OK; +} + +ReturnValue_t LinuxLibgpioIF::checkForConflicts(GpioMap& mapToAdd) { + ReturnValue_t status = HasReturnvaluesIF::RETURN_OK; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + for (auto& gpioConfig : mapToAdd) { + switch (gpioConfig.second->gpioType) { + case (gpio::GpioTypes::GPIOD_REGULAR): { + auto regularGpio = dynamic_cast(gpioConfig.second); + if (regularGpio == nullptr) { + return GPIO_TYPE_FAILURE; + } + /* Check for conflicts and remove duplicates if necessary */ + result = checkForConflictsRegularGpio(gpioConfig.first, regularGpio, mapToAdd); + if (result != HasReturnvaluesIF::RETURN_OK) { + status = result; + } + break; + } + case (gpio::GpioTypes::CALLBACK): { + auto callbackGpio = dynamic_cast(gpioConfig.second); + if (callbackGpio == nullptr) { + return GPIO_TYPE_FAILURE; + } + /* Check for conflicts and remove duplicates if necessary */ + result = checkForConflictsCallbackGpio(gpioConfig.first, callbackGpio, mapToAdd); + if (result != HasReturnvaluesIF::RETURN_OK) { + status = result; + } + break; + } + default: { + } + } + } + return status; +} + +ReturnValue_t LinuxLibgpioIF::checkForConflictsRegularGpio(gpioId_t gpioIdToCheck, + GpiodRegular* gpioToCheck, + GpioMap& mapToAdd) { + /* Cross check with private map */ + gpioMapIter = gpioMap.find(gpioIdToCheck); + if (gpioMapIter != gpioMap.end()) { + if (gpioMapIter->second->gpioType != gpio::GpioTypes::GPIOD_REGULAR) { + sif::warning << "LinuxLibgpioIF::checkForConflicts: ID already exists for different " + "GPIO type" + << gpioIdToCheck << ". Removing duplicate." << std::endl; + mapToAdd.erase(gpioIdToCheck); + return HasReturnvaluesIF::RETURN_OK; + } + auto ownRegularGpio = dynamic_cast(gpioMapIter->second); + if (ownRegularGpio == nullptr) { + return GPIO_TYPE_FAILURE; + } + + /* Remove element from map to add because a entry for this GPIO + already exists */ + sif::warning << "LinuxLibgpioIF::checkForConflictsRegularGpio: Duplicate GPIO definition" + << " detected. Duplicate will be removed from map to add." << std::endl; + mapToAdd.erase(gpioIdToCheck); + } + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t LinuxLibgpioIF::checkForConflictsCallbackGpio(gpioId_t gpioIdToCheck, + GpioCallback* callbackGpio, + GpioMap& mapToAdd) { + /* Cross check with private map */ + gpioMapIter = gpioMap.find(gpioIdToCheck); + if (gpioMapIter != gpioMap.end()) { + if (gpioMapIter->second->gpioType != gpio::GpioTypes::CALLBACK) { + sif::warning << "LinuxLibgpioIF::checkForConflicts: ID already exists for different " + "GPIO type" + << gpioIdToCheck << ". Removing duplicate." << std::endl; + mapToAdd.erase(gpioIdToCheck); + return HasReturnvaluesIF::RETURN_OK; + } + + /* Remove element from map to add because a entry for this GPIO + already exists */ + sif::warning << "LinuxLibgpioIF::checkForConflictsRegularGpio: Duplicate GPIO definition" + << " detected. Duplicate will be removed from map to add." << std::endl; + mapToAdd.erase(gpioIdToCheck); + } + return HasReturnvaluesIF::RETURN_OK; +} diff --git a/archive/gpio/LinuxLibgpioIF.h b/archive/gpio/LinuxLibgpioIF.h new file mode 100644 index 00000000..1c974efb --- /dev/null +++ b/archive/gpio/LinuxLibgpioIF.h @@ -0,0 +1,75 @@ +#ifndef LINUX_GPIO_LINUXLIBGPIOIF_H_ +#define LINUX_GPIO_LINUXLIBGPIOIF_H_ + +#include +#include +#include + +class GpioCookie; + +/** + * @brief This class implements the GpioIF for a linux based system. The + * implementation is based on the libgpiod lib which requires linux 4.8 + * or higher. + * @note The Petalinux SDK from Xilinx supports libgpiod since Petalinux + * 2019.1. + */ +class LinuxLibgpioIF : public GpioIF, public SystemObject { + public: + static const uint8_t gpioRetvalId = CLASS_ID::LINUX_LIBGPIO_IF; + + static constexpr ReturnValue_t UNKNOWN_GPIO_ID = + HasReturnvaluesIF::makeReturnCode(gpioRetvalId, 1); + static constexpr ReturnValue_t DRIVE_GPIO_FAILURE = + HasReturnvaluesIF::makeReturnCode(gpioRetvalId, 2); + static constexpr ReturnValue_t GPIO_TYPE_FAILURE = + HasReturnvaluesIF::makeReturnCode(gpioRetvalId, 3); + static constexpr ReturnValue_t GPIO_INVALID_INSTANCE = + HasReturnvaluesIF::makeReturnCode(gpioRetvalId, 4); + + LinuxLibgpioIF(object_id_t objectId); + virtual ~LinuxLibgpioIF(); + + ReturnValue_t addGpios(GpioCookie* gpioCookie) override; + ReturnValue_t pullHigh(gpioId_t gpioId) override; + ReturnValue_t pullLow(gpioId_t gpioId) override; + ReturnValue_t readGpio(gpioId_t gpioId, int* gpioState) override; + + private: + /* Holds the information and configuration of all used GPIOs */ + GpioMap gpioMap; + GpioMapIter gpioMapIter; + + /** + * @brief This functions drives line of a GPIO specified by the GPIO ID. + * + * @param gpioId The GPIO ID of the GPIO to drive. + * @param logiclevel The logic level to set. O or 1. + */ + ReturnValue_t driveGpio(gpioId_t gpioId, GpiodRegularBase& regularGpio, unsigned int logiclevel); + + ReturnValue_t configureRegularGpio(gpioId_t gpioId, GpiodRegularBase& regularGpio); + + /** + * @brief This function checks if GPIOs are already registered and whether + * there exists a conflict in the GPIO configuration. E.g. the + * direction. + * + * @param mapToAdd The GPIOs which shall be added to the gpioMap. + * + * @return RETURN_OK if successful, otherwise RETURN_FAILED + */ + ReturnValue_t checkForConflicts(GpioMap& mapToAdd); + + ReturnValue_t checkForConflictsRegularGpio(gpioId_t gpiodId, GpiodRegular* regularGpio, + GpioMap& mapToAdd); + ReturnValue_t checkForConflictsCallbackGpio(gpioId_t gpiodId, GpioCallback* regularGpio, + GpioMap& mapToAdd); + + /** + * @brief Performs the initial configuration of all GPIOs specified in the GpioMap mapToAdd. + */ + ReturnValue_t configureGpios(GpioMap& mapToAdd); +}; + +#endif /* LINUX_GPIO_LINUXLIBGPIOIF_H_ */ diff --git a/archive/gpio/gpioDefinitions.h b/archive/gpio/gpioDefinitions.h new file mode 100644 index 00000000..0db4db11 --- /dev/null +++ b/archive/gpio/gpioDefinitions.h @@ -0,0 +1,83 @@ +#ifndef LINUX_GPIO_GPIODEFINITIONS_H_ +#define LINUX_GPIO_GPIODEFINITIONS_H_ + +#include +#include + +using gpioId_t = uint16_t; + +namespace gpio { + +enum Levels { LOW = 0, HIGH = 1 }; + +enum Direction { IN = 0, OUT = 1 }; + +enum GpioOperation { READ, WRITE }; + +enum GpioTypes { NONE, GPIOD_REGULAR, CALLBACK }; + +static constexpr gpioId_t NO_GPIO = -1; +} // namespace gpio + +/** + * @brief Struct containing information about the GPIO to use. This is + * required by the libgpiod to access and drive a GPIO. + * @param chipname String of the chipname specifying the group which contains the GPIO to + * access. E.g. gpiochip0. To detect names of GPIO groups run gpiodetect on + * the linux command line. + * @param lineNum The offset of the GPIO within the GPIO group. + * @param consumer Name of the consumer. Simply a description of the GPIO configuration. + * @param direction Specifies whether the GPIO should be used as in- or output. + * @param initValue Defines the initial state of the GPIO when configured as output. + * Only required for output GPIOs. + * @param lineHandle The handle returned by gpiod_chip_get_line will be later written to this + * pointer. + */ +class GpioBase { + public: + GpioBase() = default; + + GpioBase(gpio::GpioTypes gpioType, std::string consumer, gpio::Direction direction, int initValue) + : gpioType(gpioType), consumer(consumer), direction(direction), initValue(initValue) {} + + virtual ~GpioBase(){}; + + /* Can be used to cast GpioBase to a concrete child implementation */ + gpio::GpioTypes gpioType = gpio::GpioTypes::NONE; + std::string consumer; + gpio::Direction direction = gpio::Direction::IN; + int initValue = 0; +}; + +class GpiodRegular : public GpioBase { + public: + GpiodRegular() + : GpioBase(gpio::GpioTypes::GPIOD_REGULAR, std::string(), gpio::Direction::IN, 0){}; + + GpiodRegular(std::string chipname_, int lineNum_, std::string consumer_, + gpio::Direction direction_, int initValue_) + : GpioBase(gpio::GpioTypes::GPIOD_REGULAR, consumer_, direction_, initValue_), + chipname(chipname_), + lineNum(lineNum_) {} + std::string chipname; + int lineNum = 0; + struct gpiod_line* lineHandle = nullptr; +}; + +class GpioCallback : public GpioBase { + public: + GpioCallback(std::string consumer, gpio::Direction direction_, int initValue_, + void (*callback)(gpioId_t gpioId, gpio::GpioOperation gpioOp, int value, void* args), + void* callbackArgs) + : GpioBase(gpio::GpioTypes::CALLBACK, consumer, direction_, initValue_), + callback(callback), + callbackArgs(callbackArgs) {} + + void (*callback)(gpioId_t gpioId, gpio::GpioOperation gpioOp, int value, void* args) = nullptr; + void* callbackArgs = nullptr; +}; + +using GpioMap = std::unordered_map; +using GpioMapIter = GpioMap::iterator; + +#endif /* LINUX_GPIO_GPIODEFINITIONS_H_ */ diff --git a/archive/tmtc/CCSDSIPCoreBridge.cpp b/archive/tmtc/CCSDSIPCoreBridge.cpp new file mode 100644 index 00000000..607ccebd --- /dev/null +++ b/archive/tmtc/CCSDSIPCoreBridge.cpp @@ -0,0 +1,128 @@ +#include +#include +#include + +CCSDSIPCoreBridge::CCSDSIPCoreBridge(object_id_t objectId, object_id_t tcDestination, + object_id_t tmStoreId, object_id_t tcStoreId, + LinuxLibgpioIF* gpioComIF, std::string uioPtme, + gpioId_t papbBusyId, gpioId_t papbEmptyId) + : TmTcBridge(objectId, tcDestination, tmStoreId, tcStoreId), + gpioComIF(gpioComIF), + uioPtme(uioPtme), + papbBusyId(papbBusyId), + papbEmptyId(papbEmptyId) {} + +CCSDSIPCoreBridge::~CCSDSIPCoreBridge() {} + +ReturnValue_t CCSDSIPCoreBridge::initialize() { + ReturnValue_t result = TmTcBridge::initialize(); + + fd = open("/dev/uio0", O_RDWR); + if (fd < 1) { + sif::debug << "CCSDSIPCoreBridge::initialize: Invalid UIO device file" << std::endl; + return RETURN_FAILED; + } + + /** + * Map uio device in virtual address space + * PROT_WRITE: Map uio device in writable only mode + */ + ptmeBaseAddress = + static_cast(mmap(NULL, MAP_SIZE, PROT_READ | PROT_WRITE, MAP_SHARED, fd, 0)); + + if (ptmeBaseAddress == MAP_FAILED) { + sif::error << "CCSDSIPCoreBridge::initialize: Failed to map uio address" << std::endl; + return RETURN_FAILED; + } + + return result; +} + +ReturnValue_t CCSDSIPCoreBridge::handleTm() { +#if OBSW_TEST_CCSDS_PTME == 1 + return sendTestFrame(); +#else + return TmTcBridge::handleTm(); +#endif +} + +ReturnValue_t CCSDSIPCoreBridge::sendTm(const uint8_t* data, size_t dataLen) { + if (pollPapbBusySignal() == RETURN_OK) { + startPacketTransfer(); + } + + for (size_t idx = 0; idx < dataLen; idx++) { + if (pollPapbBusySignal() == RETURN_OK) { + *(ptmeBaseAddress + PTME_DATA_REG_OFFSET) = static_cast(*(data + idx)); + } else { + sif::debug << "CCSDSIPCoreBridge::sendTm: Only written " << idx - 1 << " of " << dataLen + << " data" << std::endl; + return RETURN_FAILED; + } + } + + if (pollPapbBusySignal() == RETURN_OK) { + endPacketTransfer(); + } + return RETURN_OK; +} + +void CCSDSIPCoreBridge::startPacketTransfer() { *ptmeBaseAddress = PTME_CONFIG_START; } + +void CCSDSIPCoreBridge::endPacketTransfer() { *ptmeBaseAddress = PTME_CONFIG_END; } + +ReturnValue_t CCSDSIPCoreBridge::pollPapbBusySignal() { + int papbBusyState = 0; + ReturnValue_t result = RETURN_OK; + + /** Check if PAPB interface is ready to receive data */ + result = gpioComIF->readGpio(papbBusyId, &papbBusyState); + if (result != RETURN_OK) { + sif::debug << "CCSDSIPCoreBridge::pollPapbBusySignal: Failed to read papb busy signal" + << std::endl; + return RETURN_FAILED; + } + if (!papbBusyState) { + sif::debug << "CCSDSIPCoreBridge::pollPapbBusySignal: PAPB busy" << std::endl; + return PAPB_BUSY; + } + + return RETURN_OK; +} + +void CCSDSIPCoreBridge::isPtmeBufferEmpty() { + ReturnValue_t result = RETURN_OK; + int papbEmptyState = 1; + + result = gpioComIF->readGpio(papbEmptyId, &papbEmptyState); + + if (result != RETURN_OK) { + sif::debug << "CCSDSIPCoreBridge::isPtmeBufferEmpty: Failed to read papb empty signal" + << std::endl; + return; + } + + if (papbEmptyState == 1) { + sif::debug << "CCSDSIPCoreBridge::isPtmeBufferEmpty: Buffer is empty" << std::endl; + } else { + sif::debug << "CCSDSIPCoreBridge::isPtmeBufferEmpty: Buffer is not empty" << std::endl; + } + return; +} + +ReturnValue_t CCSDSIPCoreBridge::sendTestFrame() { + /** Size of one complete transfer frame data field amounts to 1105 bytes */ + uint8_t testPacket[1105]; + + /** Fill one test packet */ + for (int idx = 0; idx < 1105; idx++) { + testPacket[idx] = static_cast(idx & 0xFF); + } + + ReturnValue_t result = sendTm(testPacket, 1105); + if (result != RETURN_OK) { + return result; + } + + return RETURN_OK; +} diff --git a/archive/tmtc/CCSDSIPCoreBridge.h b/archive/tmtc/CCSDSIPCoreBridge.h new file mode 100644 index 00000000..074769c4 --- /dev/null +++ b/archive/tmtc/CCSDSIPCoreBridge.h @@ -0,0 +1,129 @@ +#ifndef MISSION_OBC_CCSDSIPCOREBRIDGE_H_ +#define MISSION_OBC_CCSDSIPCOREBRIDGE_H_ + +#include +#include +#include + +#include + +#include "OBSWConfig.h" + +/** + * @brief This class handles the interfacing to the telemetry (PTME) and telecommand (PDEC) IP + * cores responsible for the CCSDS encoding and decoding. The IP cores are implemented + * on the programmable logic and are accessible through the linux UIO driver. + */ +class CCSDSIPCoreBridge : public TmTcBridge { + public: + /** + * @brief Constructor + * + * @param objectId + * @param tcDestination + * @param tmStoreId + * @param tcStoreId + * @param uioPtme Name of the uio device file which provides access to the PTME IP Core. + * @param papbBusyId The ID of the GPIO which is connected to the PAPBBusy_N signal of the + * PTME IP Core. A low logic level indicates the PTME is not ready to + * receive more data. + * @param papbEmptyId The ID of the GPIO which is connected to the PAPBEmpty signal of the + * PTME IP Core. The signal is high when there are no packets in the + * external buffer memory (BRAM). + */ + CCSDSIPCoreBridge(object_id_t objectId, object_id_t tcDestination, object_id_t tmStoreId, + object_id_t tcStoreId, LinuxLibgpioIF* gpioComIF, std::string uioPtme, + gpioId_t papbBusyId, gpioId_t papbEmptyId); + virtual ~CCSDSIPCoreBridge(); + + ReturnValue_t initialize() override; + + protected: + /** + * Overwriting this function to provide the capability of testing the PTME IP Core + * implementation. + */ + virtual ReturnValue_t handleTm() override; + + virtual ReturnValue_t sendTm(const uint8_t* data, size_t dataLen) override; + + private: + static const uint8_t INTERFACE_ID = CLASS_ID::CCSDS_IP_CORE_BRIDGE; + + static const ReturnValue_t PAPB_BUSY = MAKE_RETURN_CODE(0xA0); + + /** Size of mapped address space. 4k (minimal size of pl device) */ + // static const int MAP_SIZE = 0xFA0; + static const int MAP_SIZE = 0x1000; + + /** + * Configuration bits: + * bit[1:0]: Size of data (1,2,3 or 4 bytes). 1 Byte <=> b00 + * bit[2]: Set this bit to 1 to abort a transfered packet + * bit[3]: Signals to PTME the start of a new telemetry packet + */ + static const uint32_t PTME_CONFIG_START = 0x8; + + /** + * Writing this word to the ptme base address signals to the PTME that a complete tm packet has + * been transferred. + */ + static const uint32_t PTME_CONFIG_END = 0x0; + + /** + * Writing to this offset within the PTME memory space will insert data for encoding to the + * PTME IP core. + * The address offset is 0x400 (= 4 * 256) + */ + static const int PTME_DATA_REG_OFFSET = 256; + + LinuxLibgpioIF* gpioComIF = nullptr; + + /** The uio device file related to the PTME IP Core */ + std::string uioPtme; + + /** Pulled to low when PTME not ready to receive data */ + gpioId_t papbBusyId = gpio::NO_GPIO; + + /** High when externally buffer memory of PTME is empty */ + gpioId_t papbEmptyId = gpio::NO_GPIO; + + /** The file descriptor of the UIO driver */ + int fd; + + uint32_t* ptmeBaseAddress = nullptr; + + /** + * @brief This function sends the config byte to the PTME IP Core to initiate a packet + * transfer. + */ + void startPacketTransfer(); + + /** + * @brief This function sends the config byte to the PTME IP Core to signal the end of a + * packet transfer. + */ + void endPacketTransfer(); + + /** + * @brief This function reads the papb busy signal indicating whether the PAPB interface is + * ready to receive more data or not. PAPB is ready when PAPB_Busy_N == '1'. + * + * @return RETURN_OK when ready to receive data else PAPB_BUSY. + */ + ReturnValue_t pollPapbBusySignal(); + + /** + * @brief This function can be used for debugging to check wheter there are packets in + * the packet buffer of the PTME or not. + */ + void isPtmeBufferEmpty(); + + /** + * @brief This function sends a complete telemetry transfer frame data field (1105 bytes) + * to the input of the PTME IP Core. Can be used to test the implementation. + */ + ReturnValue_t sendTestFrame(); +}; + +#endif /* MISSION_OBC_CCSDSIPCOREBRIDGE_H_ */ diff --git a/automation/Dockerfile-q7s b/automation/Dockerfile similarity index 74% rename from automation/Dockerfile-q7s rename to automation/Dockerfile index 21b56439..9042cf13 100644 --- a/automation/Dockerfile-q7s +++ b/automation/Dockerfile @@ -2,7 +2,9 @@ FROM ubuntu:focal RUN apt-get update RUN apt-get --yes upgrade -RUN apt-get --yes install cmake libgpiod-dev xz-utils nano curl +#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 # Q7S root filesystem, required for cross-compilation. RUN mkdir -p /usr/rootfs; \ @@ -14,6 +16,5 @@ 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 Q7S_SYSROOT="/usr/rootfs/cortexa9hf-neon-xiphos-linux-gnueabi" -ENV PATH=$PATH:"/usr/tools/gcc-arm-8.3-2019.03-x86_64-arm-linux-gnueabihf/bin" +ENV PATH=$PATH:"/usr/tools/gcc-arm-8.3-2019.03-x86_64-arm-linux-gnueabihf/bin" \ No newline at end of file diff --git a/automation/Jenkinsfile b/automation/Jenkinsfile index 7b184280..fe79dc73 100644 --- a/automation/Jenkinsfile +++ b/automation/Jenkinsfile @@ -1,48 +1,36 @@ pipeline { - agent any - stages { - stage('Build Container') { - when { - changeset "automation/Dockerfile-q7s" - branch 'develop' - } - steps { - sh 'docker build -t eive-fsw-build-q7s:gcc8 - < automation/Dockerfile-q7s' - - } + environment { + BUILDDIR_Q7 = 'build_q7' + BUILDDIR_LINUX = 'build_linux' + } + agent { + docker { + image 'eive-obsw-ci:d2' + args '--sysctl fs.mqueue.msg_max=100' } + } + stages { stage('Clean') { - when { - anyOf { - changelog 'cleanCI' - changeset '*.cmake' - changeset 'CMakeLists.txt' - } - } steps { - sh 'rm -rf build-q7s-debug' + sh 'rm -rf $BUILDDIR_Q7' + sh 'rm -rf $BUILDDIR_LINUX' } } stage('Build Q7S') { - agent { - docker { - image 'eive-fsw-build-q7s:gcc8' - reuseNode true - } - } steps { - dir('build-q7s-debug') { - sh 'cmake -DTGT_BSP="arm/q7s" -DCMAKE_BUILD_TYPE=Debug -DFSFW_OSAL=linux ..' - sh 'cmake --build . -j' + dir(BUILDDIR_Q7) { + sh 'cmake -DTGT_BSP="arm/q7s" -DCMAKE_BUILD_TYPE=Debug ..' + sh 'cmake --build . -j4' } } } - stage('Deploy') { - when { - tag 'v*.*.*' - } + stage('Unittests') { steps { - sh 'echo Deploying' + dir(BUILDDIR_LINUX) { + sh 'cmake ..' + sh 'cmake --build . -t eive-unittest -j4' + sh './eive-unittest' + } } } } diff --git a/bsp_egse/CMakeLists.txt b/bsp_egse/CMakeLists.txt new file mode 100644 index 00000000..cb02f937 --- /dev/null +++ b/bsp_egse/CMakeLists.txt @@ -0,0 +1,7 @@ +target_sources(${OBSW_NAME} PUBLIC + InitMission.cpp + main.cpp + ObjectFactory.cpp +) + +add_subdirectory(boardconfig) diff --git a/bsp_egse/InitMission.cpp b/bsp_egse/InitMission.cpp new file mode 100644 index 00000000..d6b192c2 --- /dev/null +++ b/bsp_egse/InitMission.cpp @@ -0,0 +1,192 @@ +#include "InitMission.h" + +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include "OBSWConfig.h" +#include "ObjectFactory.h" +#include "objects/systemObjectList.h" +#include "pollingsequence/pollingSequenceFactory.h" + +ServiceInterfaceStream sif::debug("DEBUG"); +ServiceInterfaceStream sif::info("INFO"); +ServiceInterfaceStream sif::warning("WARNING"); +ServiceInterfaceStream sif::error("ERROR"); + +ObjectManagerIF* objectManager = nullptr; + +void initmission::initMission() { + sif::info << "Make sure the systemd service ser2net on the egse has been stopped " + << "(alias stop-ser2net)" << std::endl; + sif::info << "Make sure the power lines of the star tracker have been enabled " + << "(alias enable-startracker)" << std::endl; + sif::info << "Building global objects.." << std::endl; + /* Instantiate global object manager and also create all objects */ + ObjectManager::instance()->setObjectFactoryFunction(ObjectFactory::produce, nullptr); + sif::info << "Initializing all objects.." << std::endl; + ObjectManager::instance()->initialize(); + + /* This function creates and starts all tasks */ + initTasks(); +} + +void initmission::initTasks() { + TaskFactory* factory = TaskFactory::instance(); + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + if (factory == nullptr) { + /* Should never happen ! */ + return; + } +#if OBSW_PRINT_MISSED_DEADLINES == 1 + void (*missedDeadlineFunc)(void) = TaskFactory::printMissedDeadline; +#else + void (*missedDeadlineFunc)(void) = nullptr; +#endif + + /* TMTC Distribution */ + PeriodicTaskIF* tmtcDistributor = factory->createPeriodicTask( + "DIST", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc); + result = tmtcDistributor->addComponent(objects::CCSDS_PACKET_DISTRIBUTOR); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "Object add component failed" << std::endl; + } + result = tmtcDistributor->addComponent(objects::PUS_PACKET_DISTRIBUTOR); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "Object add component failed" << std::endl; + } + result = tmtcDistributor->addComponent(objects::TM_FUNNEL); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "Object add component failed" << std::endl; + } + + PeriodicTaskIF* tmtcBridgeTask = factory->createPeriodicTask( + "TMTC_BRIDGE", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc); + result = tmtcBridgeTask->addComponent(objects::TMTC_BRIDGE); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "Add component TMTC Bridge failed" << std::endl; + } + PeriodicTaskIF* tmtcPollingTask = factory->createPeriodicTask( + "TMTC_POLLING", 80, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc); + result = tmtcPollingTask->addComponent(objects::TMTC_POLLING_TASK); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "Add component TMTC Polling failed" << std::endl; + } + + /* PUS Services */ + std::vector pusTasks; + createPusTasks(*factory, missedDeadlineFunc, pusTasks); + + std::vector pstTasks; + FixedTimeslotTaskIF* pst = factory->createFixedTimeslotTask( + "STAR_TRACKER_PST", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 0.5, missedDeadlineFunc); + result = pst::pstUart(pst); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "InitMission::initTasks: Creating PST failed!" << std::endl; + } + pstTasks.push_back(pst); + + PeriodicTaskIF* strHelperTask = factory->createPeriodicTask( + "STR_HELPER", 20, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc); + result = strHelperTask->addComponent(objects::STR_HELPER); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("STR_HELPER", objects::STR_HELPER); + } + pstTasks.push_back(strHelperTask); + + auto taskStarter = [](std::vector& taskVector, std::string name) { + for (const auto& task : taskVector) { + if (task != nullptr) { + task->startTask(); + } else { + sif::error << "Task in vector " << name << " is invalid!" << std::endl; + } + } + }; + + sif::info << "Starting tasks.." << std::endl; + tmtcDistributor->startTask(); + tmtcBridgeTask->startTask(); + tmtcPollingTask->startTask(); + + taskStarter(pstTasks, "PST Tasks"); + taskStarter(pusTasks, "PUS Tasks"); + + sif::info << "Tasks started.." << std::endl; +} + +void initmission::createPusTasks(TaskFactory& factory, + TaskDeadlineMissedFunction missedDeadlineFunc, + std::vector& taskVec) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + PeriodicTaskIF* pusVerification = factory.createPeriodicTask( + "PUS_VERIF", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); + result = pusVerification->addComponent(objects::PUS_SERVICE_1_VERIFICATION); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "Object add component failed" << std::endl; + } + taskVec.push_back(pusVerification); + + PeriodicTaskIF* pusEvents = factory.createPeriodicTask( + "PUS_EVENTS", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); + result = pusEvents->addComponent(objects::PUS_SERVICE_5_EVENT_REPORTING); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS_EVENTS", objects::PUS_SERVICE_5_EVENT_REPORTING); + } + result = pusEvents->addComponent(objects::EVENT_MANAGER); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS_MGMT", objects::EVENT_MANAGER); + } + taskVec.push_back(pusEvents); + + PeriodicTaskIF* pusHighPrio = factory.createPeriodicTask( + "PUS_HIGH_PRIO", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); + result = pusHighPrio->addComponent(objects::PUS_SERVICE_2_DEVICE_ACCESS); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS2", objects::PUS_SERVICE_2_DEVICE_ACCESS); + } + result = pusHighPrio->addComponent(objects::PUS_SERVICE_9_TIME_MGMT); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS9", objects::PUS_SERVICE_9_TIME_MGMT); + } + taskVec.push_back(pusHighPrio); + + PeriodicTaskIF* pusMedPrio = factory.createPeriodicTask( + "PUS_MED_PRIO", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.8, missedDeadlineFunc); + result = pusMedPrio->addComponent(objects::PUS_SERVICE_8_FUNCTION_MGMT); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS8", objects::PUS_SERVICE_8_FUNCTION_MGMT); + } + result = pusMedPrio->addComponent(objects::PUS_SERVICE_200_MODE_MGMT); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS200", objects::PUS_SERVICE_200_MODE_MGMT); + } + result = pusMedPrio->addComponent(objects::PUS_SERVICE_20_PARAMETERS); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS20", objects::PUS_SERVICE_20_PARAMETERS); + } + result = pusMedPrio->addComponent(objects::PUS_SERVICE_3_HOUSEKEEPING); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS3", objects::PUS_SERVICE_3_HOUSEKEEPING); + } + taskVec.push_back(pusMedPrio); + + PeriodicTaskIF* pusLowPrio = factory.createPeriodicTask( + "PUS_LOW_PRIO", 30, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.6, missedDeadlineFunc); + result = pusLowPrio->addComponent(objects::PUS_SERVICE_17_TEST); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS17", objects::PUS_SERVICE_17_TEST); + } + result = pusLowPrio->addComponent(objects::INTERNAL_ERROR_REPORTER); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("INT_ERR_RPRT", objects::INTERNAL_ERROR_REPORTER); + } + taskVec.push_back(pusLowPrio); +} diff --git a/bsp_egse/InitMission.h b/bsp_egse/InitMission.h new file mode 100644 index 00000000..c3ba58ec --- /dev/null +++ b/bsp_egse/InitMission.h @@ -0,0 +1,21 @@ +#ifndef BSP_LINUX_INITMISSION_H_ +#define BSP_LINUX_INITMISSION_H_ + +#include + +#include "fsfw/tasks/Typedef.h" + +class PeriodicTaskIF; +class TaskFactory; + +namespace initmission { +void initMission(); +void initTasks(); + +void createPstTasks(TaskFactory& factory, TaskDeadlineMissedFunction missedDeadlineFunc, + std::vector& taskVec); +void createPusTasks(TaskFactory& factory, TaskDeadlineMissedFunction missedDeadlineFunc, + std::vector& taskVec); +}; // namespace initmission + +#endif /* BSP_LINUX_INITMISSION_H_ */ diff --git a/bsp_egse/ObjectFactory.cpp b/bsp_egse/ObjectFactory.cpp new file mode 100644 index 00000000..10eea471 --- /dev/null +++ b/bsp_egse/ObjectFactory.cpp @@ -0,0 +1,49 @@ +#include "ObjectFactory.h" + +#include +#include +#include +#include + +#include "OBSWConfig.h" +#include "busConf.h" +#include "fsfw/datapoollocal/LocalDataPoolManager.h" +#include "fsfw/tmtcpacket/pus/tm.h" +#include "fsfw/tmtcservices/CommandingServiceBase.h" +#include "fsfw/tmtcservices/PusServiceBase.h" +#include "linux/devices/devicedefinitions/StarTrackerDefinitions.h" +#include "linux/devices/startracker/StarTrackerHandler.h" +#include "mission/core/GenericFactory.h" +#include "mission/utility/TmFunnel.h" +#include "objects/systemObjectList.h" +#include "tmtc/apid.h" +#include "tmtc/pusIds.h" + +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; + + TmFunnel::downlinkDestination = objects::TMTC_BRIDGE; + TmFunnel::storageDestination = objects::NO_OBJECT; + + VerificationReporter::messageReceiver = objects::PUS_SERVICE_1_VERIFICATION; + TmPacketBase::timeStamperId = objects::TIME_STAMPER; +} + +void ObjectFactory::produce(void* args) { + Factory::setStaticFrameworkObjectIds(); + ObjectFactory::produceGenericObjects(); + + UartCookie* starTrackerCookie = + new UartCookie(objects::STAR_TRACKER, egse::STAR_TRACKER_UART, UartModes::NON_CANONICAL, + uart::STAR_TRACKER_BAUD, startracker::MAX_FRAME_SIZE * 2 + 2); + new UartComIF(objects::UART_COM_IF); + starTrackerCookie->setNoFixedSizeReply(); + StrHelper* strHelper = new StrHelper(objects::STR_HELPER); + StarTrackerHandler* starTrackerHandler = new StarTrackerHandler( + objects::STAR_TRACKER, objects::UART_COM_IF, starTrackerCookie, strHelper); + starTrackerHandler->setStartUpImmediately(); +} diff --git a/bsp_egse/ObjectFactory.h b/bsp_egse/ObjectFactory.h new file mode 100644 index 00000000..b24dd321 --- /dev/null +++ b/bsp_egse/ObjectFactory.h @@ -0,0 +1,8 @@ +#ifndef BSP_LINUX_OBJECTFACTORY_H_ +#define BSP_LINUX_OBJECTFACTORY_H_ + +namespace ObjectFactory { +void produce(void* args); +}; // namespace ObjectFactory + +#endif /* BSP_LINUX_OBJECTFACTORY_H_ */ diff --git a/bsp_egse/boardconfig/CMakeLists.txt b/bsp_egse/boardconfig/CMakeLists.txt new file mode 100644 index 00000000..f9136e3e --- /dev/null +++ b/bsp_egse/boardconfig/CMakeLists.txt @@ -0,0 +1,7 @@ +target_sources(${OBSW_NAME} PRIVATE + print.c +) + +target_include_directories(${OBSW_NAME} PUBLIC + ${CMAKE_CURRENT_SOURCE_DIR} +) diff --git a/bsp_egse/boardconfig/busConf.h b/bsp_egse/boardconfig/busConf.h new file mode 100644 index 00000000..4df55edc --- /dev/null +++ b/bsp_egse/boardconfig/busConf.h @@ -0,0 +1,8 @@ +#ifndef BSP_EGSE_BOARDCONFIG_BUSCONF_H_ +#define BSP_EGSE_BOARDCONFIG_BUSCONF_H_ + +namespace egse { +static constexpr char STAR_TRACKER_UART[] = "/dev/serial0"; +} + +#endif /* BSP_EGSE_BOARDCONFIG_BUSCONF_H_ */ diff --git a/bsp_egse/boardconfig/etl_profile.h b/bsp_egse/boardconfig/etl_profile.h new file mode 100644 index 00000000..54aca344 --- /dev/null +++ b/bsp_egse/boardconfig/etl_profile.h @@ -0,0 +1,38 @@ +///\file + +/****************************************************************************** +The MIT License(MIT) + +Embedded Template Library. +https://github.com/ETLCPP/etl +https://www.etlcpp.com + +Copyright(c) 2019 jwellbelove + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files(the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and / or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions : + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT.IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +******************************************************************************/ +#ifndef __ETL_PROFILE_H__ +#define __ETL_PROFILE_H__ + +#define ETL_CHECK_PUSH_POP + +#define ETL_CPP11_SUPPORTED 1 +#define ETL_NO_NULLPTR_SUPPORT 0 + +#endif diff --git a/bsp_egse/boardconfig/gcov.h b/bsp_egse/boardconfig/gcov.h new file mode 100644 index 00000000..80acdd86 --- /dev/null +++ b/bsp_egse/boardconfig/gcov.h @@ -0,0 +1,15 @@ +#ifndef LINUX_GCOV_H_ +#define LINUX_GCOV_H_ +#include + +#ifdef GCOV +extern "C" void __gcov_flush(); +#else +void __gcov_flush() { + sif::info << "GCC GCOV: Please supply GCOV=1 in Makefile if " + "coverage information is desired.\n" + << std::flush; +} +#endif + +#endif /* LINUX_GCOV_H_ */ diff --git a/bsp_egse/boardconfig/print.c b/bsp_egse/boardconfig/print.c new file mode 100644 index 00000000..5b3a0f91 --- /dev/null +++ b/bsp_egse/boardconfig/print.c @@ -0,0 +1,10 @@ +#include +#include + +void printChar(const char* character, bool errStream) { + if (errStream) { + putc(*character, stderr); + return; + } + putc(*character, stdout); +} diff --git a/bsp_egse/boardconfig/print.h b/bsp_egse/boardconfig/print.h new file mode 100644 index 00000000..8e7e2e5d --- /dev/null +++ b/bsp_egse/boardconfig/print.h @@ -0,0 +1,8 @@ +#ifndef HOSTED_BOARDCONFIG_PRINT_H_ +#define HOSTED_BOARDCONFIG_PRINT_H_ + +#include + +void printChar(const char* character, bool errStream); + +#endif /* HOSTED_BOARDCONFIG_PRINT_H_ */ diff --git a/bsp_egse/boardconfig/rpiConfig.h.in b/bsp_egse/boardconfig/rpiConfig.h.in new file mode 100644 index 00000000..af4f0dd2 --- /dev/null +++ b/bsp_egse/boardconfig/rpiConfig.h.in @@ -0,0 +1,6 @@ +#ifndef BSP_RPI_BOARDCONFIG_RPI_CONFIG_H_ +#define BSP_RPI_BOARDCONFIG_RPI_CONFIG_H_ + +#include + +#endif /* BSP_RPI_BOARDCONFIG_RPI_CONFIG_H_ */ diff --git a/bsp_egse/main.cpp b/bsp_egse/main.cpp new file mode 100644 index 00000000..ce7966ff --- /dev/null +++ b/bsp_egse/main.cpp @@ -0,0 +1,28 @@ +#include + +#include "InitMission.h" +#include "OBSWConfig.h" +#include "OBSWVersion.h" +#include "fsfw/FSFWVersion.h" +#include "fsfw/tasks/TaskFactory.h" + +/** + * @brief This is the main program entry point for the egse (raspberry pi 4) + * @return + */ +int main(void) { + std::cout << "-- EIVE OBSW --" << std::endl; + std::cout << "-- Compiled for EGSE from Arcsec" + << " --" << std::endl; + std::cout << "-- OBSW " << SW_NAME << " v" << SW_VERSION << "." << SW_SUBVERSION << "." + << SW_REVISION << ", FSFW v" << FSFW_VERSION << "." << FSFW_SUBVERSION << FSFW_REVISION + << "--" << std::endl; + std::cout << "-- " << __DATE__ << " " << __TIME__ << " --" << std::endl; + + initmission::initMission(); + + for (;;) { + /* Suspend main thread by sleeping it. */ + TaskFactory::delayTask(5000); + } +} diff --git a/bsp_hosted/CMakeLists.txt b/bsp_hosted/CMakeLists.txt index b8a09a88..7787cf7e 100644 --- a/bsp_hosted/CMakeLists.txt +++ b/bsp_hosted/CMakeLists.txt @@ -1,4 +1,4 @@ -target_sources(${TARGET_NAME} PUBLIC +target_sources(${OBSW_NAME} PUBLIC InitMission.cpp main.cpp ObjectFactory.cpp diff --git a/bsp_hosted/InitMission.cpp b/bsp_hosted/InitMission.cpp index ed6b8820..0ca59db5 100644 --- a/bsp_hosted/InitMission.cpp +++ b/bsp_hosted/InitMission.cpp @@ -1,20 +1,19 @@ #include "InitMission.h" -#include "ObjectFactory.h" #include - +#include #include #include #include -#include #include #include #include - #include #include +#include "ObjectFactory.h" + #ifdef LINUX ServiceInterfaceStream sif::debug("DEBUG"); ServiceInterfaceStream sif::info("INFO"); @@ -27,133 +26,132 @@ ServiceInterfaceStream sif::warning("WARNING", true); ServiceInterfaceStream sif::error("ERROR", true, false, true); #endif -ObjectManagerIF *objectManager = nullptr; +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); - sif::info << "Initializing all objects.." << std::endl; - ObjectManager::instance()->initialize(); + sif::info << "Building global objects.." << std::endl; + /* Instantiate global object manager and also create all objects */ + ObjectManager::instance()->setObjectFactoryFunction(ObjectFactory::produce, nullptr); + sif::info << "Initializing all objects.." << std::endl; + ObjectManager::instance()->initialize(); - /* This function creates and starts all tasks */ - initTasks(); + /* This function creates and starts all tasks */ + initTasks(); } void initmission::initTasks() { - TaskFactory* factory = TaskFactory::instance(); - if(factory == nullptr) { - /* Should never happen ! */ - return; - } + TaskFactory* factory = TaskFactory::instance(); + if (factory == nullptr) { + /* Should never happen ! */ + return; + } #if OBSW_PRINT_MISSED_DEADLINES == 1 - void (*missedDeadlineFunc) (void) = TaskFactory::printMissedDeadline; + void (*missedDeadlineFunc)(void) = TaskFactory::printMissedDeadline; #else - void (*missedDeadlineFunc) (void) = nullptr; + void (*missedDeadlineFunc)(void) = nullptr; #endif - /* TMTC Distribution */ - PeriodicTaskIF* tmTcDistributor = factory->createPeriodicTask( - "DIST", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc); - ReturnValue_t result = tmTcDistributor->addComponent( - objects::CCSDS_PACKET_DISTRIBUTOR); - if(result != HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } - result = tmTcDistributor->addComponent(objects::PUS_PACKET_DISTRIBUTOR); - if(result != HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } - result = tmTcDistributor->addComponent(objects::TM_FUNNEL); - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::error << "Object add component failed" << std::endl; - } + /* TMTC Distribution */ + PeriodicTaskIF* tmTcDistributor = factory->createPeriodicTask( + "DIST", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc); + ReturnValue_t result = tmTcDistributor->addComponent(objects::CCSDS_PACKET_DISTRIBUTOR); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "Object add component failed" << std::endl; + } + result = tmTcDistributor->addComponent(objects::PUS_PACKET_DISTRIBUTOR); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "Object add component failed" << std::endl; + } + result = tmTcDistributor->addComponent(objects::TM_FUNNEL); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "Object add component failed" << std::endl; + } - /* UDP bridge */ - PeriodicTaskIF* tmtcBridgeTask = factory->createPeriodicTask( - "TMTC_UNIX_BRIDGE", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc); - result = tmtcBridgeTask->addComponent(objects::TMTC_BRIDGE); - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::error << "Add component UDP Unix Bridge failed" << std::endl; - } - PeriodicTaskIF* tmtcPollingTask = factory->createPeriodicTask( - "UDP_POLLING", 80, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc); - result = tmtcPollingTask->addComponent(objects::TMTC_POLLING_TASK); - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::error << "Add component UDP Polling failed" << std::endl; - } + /* UDP bridge */ + PeriodicTaskIF* tmtcBridgeTask = factory->createPeriodicTask( + "TMTC_UNIX_BRIDGE", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc); + result = tmtcBridgeTask->addComponent(objects::TMTC_BRIDGE); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "Add component UDP Unix Bridge failed" << std::endl; + } + PeriodicTaskIF* tmtcPollingTask = factory->createPeriodicTask( + "UDP_POLLING", 80, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc); + result = tmtcPollingTask->addComponent(objects::TMTC_POLLING_TASK); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "Add component UDP Polling failed" << std::endl; + } - /* PUS Services */ - PeriodicTaskIF* pusVerification = factory->createPeriodicTask( - "PUS_VERIF", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); - result = pusVerification->addComponent(objects::PUS_SERVICE_1_VERIFICATION); - if(result != HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } + /* PUS Services */ + PeriodicTaskIF* pusVerification = factory->createPeriodicTask( + "PUS_VERIF", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); + result = pusVerification->addComponent(objects::PUS_SERVICE_1_VERIFICATION); + if (result != HasReturnvaluesIF::RETURN_OK) { + 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); - if(result != HasReturnvaluesIF::RETURN_OK){ - initmission::printAddObjectError("PUS5", objects::PUS_SERVICE_5_EVENT_REPORTING); - } + PeriodicTaskIF* pusEvents = factory->createPeriodicTask( + "PUS_EVENTS", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); + result = pusVerification->addComponent(objects::PUS_SERVICE_5_EVENT_REPORTING); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS5", objects::PUS_SERVICE_5_EVENT_REPORTING); + } - PeriodicTaskIF* pusHighPrio = factory->createPeriodicTask( - "PUS_HIGH_PRIO", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); - result = pusHighPrio->addComponent(objects::PUS_SERVICE_2_DEVICE_ACCESS); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("PUS2", objects::PUS_SERVICE_2_DEVICE_ACCESS); - } - result = pusHighPrio->addComponent(objects::PUS_SERVICE_9_TIME_MGMT); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("PUS9", objects::PUS_SERVICE_9_TIME_MGMT); - } + PeriodicTaskIF* pusHighPrio = factory->createPeriodicTask( + "PUS_HIGH_PRIO", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); + result = pusHighPrio->addComponent(objects::PUS_SERVICE_2_DEVICE_ACCESS); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS2", objects::PUS_SERVICE_2_DEVICE_ACCESS); + } + result = pusHighPrio->addComponent(objects::PUS_SERVICE_9_TIME_MGMT); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS9", objects::PUS_SERVICE_9_TIME_MGMT); + } - PeriodicTaskIF* pusMedPrio = factory->createPeriodicTask( - "PUS_MED_PRIO", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.8, missedDeadlineFunc); - result = pusMedPrio->addComponent(objects::PUS_SERVICE_8_FUNCTION_MGMT); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("PUS8", objects::PUS_SERVICE_8_FUNCTION_MGMT); - } - result = pusMedPrio->addComponent(objects::PUS_SERVICE_200_MODE_MGMT); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("PUS200", objects::PUS_SERVICE_200_MODE_MGMT); - } - result = pusMedPrio->addComponent(objects::PUS_SERVICE_20_PARAMETERS); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("PUS20", objects::PUS_SERVICE_20_PARAMETERS); - } + PeriodicTaskIF* pusMedPrio = factory->createPeriodicTask( + "PUS_MED_PRIO", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.8, missedDeadlineFunc); + result = pusMedPrio->addComponent(objects::PUS_SERVICE_8_FUNCTION_MGMT); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS8", objects::PUS_SERVICE_8_FUNCTION_MGMT); + } + result = pusMedPrio->addComponent(objects::PUS_SERVICE_200_MODE_MGMT); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS200", objects::PUS_SERVICE_200_MODE_MGMT); + } + result = pusMedPrio->addComponent(objects::PUS_SERVICE_20_PARAMETERS); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS20", objects::PUS_SERVICE_20_PARAMETERS); + } - PeriodicTaskIF* pusLowPrio = factory->createPeriodicTask( - "PUS_LOW_PRIO", 30, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.6, missedDeadlineFunc); - result = pusLowPrio->addComponent(objects::PUS_SERVICE_17_TEST); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("PUS17", objects::PUS_SERVICE_17_TEST); - } + PeriodicTaskIF* pusLowPrio = factory->createPeriodicTask( + "PUS_LOW_PRIO", 30, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.6, missedDeadlineFunc); + result = pusLowPrio->addComponent(objects::PUS_SERVICE_17_TEST); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS17", objects::PUS_SERVICE_17_TEST); + } - PeriodicTaskIF* testTask = factory->createPeriodicTask( - "TEST_TASK", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc); + PeriodicTaskIF* testTask = factory->createPeriodicTask( + "TEST_TASK", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc); #if OBSW_ADD_TEST_CODE == 1 - result = testTask->addComponent(objects::TEST_TASK); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("TEST_TASK", objects::TEST_TASK); - } + result = testTask->addComponent(objects::TEST_TASK); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("TEST_TASK", objects::TEST_TASK); + } #endif /* OBSW_ADD_TEST_CODE == 1 */ - sif::info << "Starting tasks.." << std::endl; - tmTcDistributor->startTask(); - tmtcBridgeTask->startTask(); - tmtcPollingTask->startTask(); + sif::info << "Starting tasks.." << std::endl; + tmTcDistributor->startTask(); + tmtcBridgeTask->startTask(); + tmtcPollingTask->startTask(); - pusVerification->startTask(); - pusEvents->startTask(); - pusHighPrio->startTask(); - pusMedPrio->startTask(); - pusLowPrio->startTask(); + pusVerification->startTask(); + pusEvents->startTask(); + pusHighPrio->startTask(); + pusMedPrio->startTask(); + pusLowPrio->startTask(); #if OBSW_ADD_TEST_CODE == 1 - testTask->startTask(); + testTask->startTask(); #endif /* OBSW_ADD_TEST_CODE == 1 */ - sif::info << "Tasks started.." << std::endl; + sif::info << "Tasks started.." << std::endl; } diff --git a/bsp_hosted/InitMission.h b/bsp_hosted/InitMission.h index 01c72008..507de592 100644 --- a/bsp_hosted/InitMission.h +++ b/bsp_hosted/InitMission.h @@ -4,6 +4,6 @@ namespace initmission { void initMission(); void initTasks(); -}; +}; // namespace initmission #endif /* BSP_LINUX_INITMISSION_H_ */ diff --git a/bsp_hosted/ObjectFactory.cpp b/bsp_hosted/ObjectFactory.cpp index d7878e46..e1be7588 100644 --- a/bsp_hosted/ObjectFactory.cpp +++ b/bsp_hosted/ObjectFactory.cpp @@ -1,14 +1,14 @@ #include "ObjectFactory.h" -#include "OBSWConfig.h" + +#include +#include +#include +#include #include #include #include -#include -#include - -#include -#include +#include "OBSWConfig.h" #if OBSW_USE_TMTC_TCP_BRIDGE == 0 #include "fsfw/osal/common/UdpTcPollingTask.h" @@ -20,42 +20,28 @@ #include - #if OBSW_ADD_TEST_CODE == 1 #include #endif -void Factory::setStaticFrameworkObjectIds(){ - PusServiceBase::packetSource = objects::PUS_PACKET_DISTRIBUTOR; - PusServiceBase::packetDestination = objects::TM_FUNNEL; +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; + CommandingServiceBase::defaultPacketSource = objects::PUS_PACKET_DISTRIBUTOR; + CommandingServiceBase::defaultPacketDestination = objects::TM_FUNNEL; - TmFunnel::downlinkDestination = objects::TMTC_BRIDGE; - // No storage object for now. - TmFunnel::storageDestination = objects::NO_OBJECT; + TmFunnel::downlinkDestination = objects::TMTC_BRIDGE; + // No storage object for now. + TmFunnel::storageDestination = objects::NO_OBJECT; - VerificationReporter::messageReceiver = objects::PUS_SERVICE_1_VERIFICATION; - TmPacketBase::timeStamperId = objects::TIME_STAMPER; + VerificationReporter::messageReceiver = objects::PUS_SERVICE_1_VERIFICATION; + TmPacketBase::timeStamperId = objects::TIME_STAMPER; } -void ObjectFactory::produce(void* args){ - Factory::setStaticFrameworkObjectIds(); - ObjectFactory::produceGenericObjects(); - -#if OBSW_USE_TMTC_TCP_BRIDGE == 0 - sif::info << "Setting up UDP TMTC bridge with listener port " << - UdpTmTcBridge::DEFAULT_SERVER_PORT << std::endl; - new UdpTmTcBridge(objects::TMTC_BRIDGE, objects::CCSDS_PACKET_DISTRIBUTOR); - new UdpTcPollingTask(objects::TMTC_POLLING_TASK, objects::TMTC_BRIDGE); -#else - sif::info << "Setting up TCP TMTC bridge with listener port " << - TcpTmTcServer::DEFAULT_SERVER_PORT << std::endl; - new TcpTmTcBridge(objects::TMTC_BRIDGE, objects::CCSDS_PACKET_DISTRIBUTOR); - new TcpTmTcServer(objects::TMTC_POLLING_TASK, objects::TMTC_BRIDGE); -#endif - - new TestTask(objects::TEST_TASK); +void ObjectFactory::produce(void* args) { + Factory::setStaticFrameworkObjectIds(); + ObjectFactory::produceGenericObjects(); + new TestTask(objects::TEST_TASK); } diff --git a/bsp_hosted/ObjectFactory.h b/bsp_hosted/ObjectFactory.h index feaba70e..b042f9dc 100644 --- a/bsp_hosted/ObjectFactory.h +++ b/bsp_hosted/ObjectFactory.h @@ -1,10 +1,9 @@ #ifndef BSP_LINUX_OBJECTFACTORY_H_ #define BSP_LINUX_OBJECTFACTORY_H_ - namespace ObjectFactory { - void setStatics(); - void produce(void* args); -}; +void setStatics(); +void produce(void* args); +}; // namespace ObjectFactory #endif /* BSP_LINUX_OBJECTFACTORY_H_ */ diff --git a/bsp_hosted/boardconfig/CMakeLists.txt b/bsp_hosted/boardconfig/CMakeLists.txt index c32b326d..81c8c93d 100644 --- a/bsp_hosted/boardconfig/CMakeLists.txt +++ b/bsp_hosted/boardconfig/CMakeLists.txt @@ -1,8 +1,8 @@ -target_sources(${TARGET_NAME} PRIVATE +target_sources(${OBSW_NAME} PRIVATE print.c ) -target_include_directories(${TARGET_NAME} PUBLIC +target_include_directories(${OBSW_NAME} PUBLIC ${CMAKE_CURRENT_SOURCE_DIR} ) diff --git a/bsp_hosted/boardconfig/etl_profile.h b/bsp_hosted/boardconfig/etl_profile.h index c35ffb46..54aca344 100644 --- a/bsp_hosted/boardconfig/etl_profile.h +++ b/bsp_hosted/boardconfig/etl_profile.h @@ -32,7 +32,7 @@ SOFTWARE. #define ETL_CHECK_PUSH_POP -#define ETL_CPP11_SUPPORTED 1 -#define ETL_NO_NULLPTR_SUPPORT 0 +#define ETL_CPP11_SUPPORTED 1 +#define ETL_NO_NULLPTR_SUPPORT 0 #endif diff --git a/bsp_hosted/boardconfig/gcov.h b/bsp_hosted/boardconfig/gcov.h index 491d24c6..80acdd86 100644 --- a/bsp_hosted/boardconfig/gcov.h +++ b/bsp_hosted/boardconfig/gcov.h @@ -6,8 +6,9 @@ extern "C" void __gcov_flush(); #else void __gcov_flush() { - sif::info << "GCC GCOV: Please supply GCOV=1 in Makefile if " - "coverage information is desired.\n" << std::flush; + sif::info << "GCC GCOV: Please supply GCOV=1 in Makefile if " + "coverage information is desired.\n" + << std::flush; } #endif diff --git a/bsp_hosted/boardconfig/print.c b/bsp_hosted/boardconfig/print.c index f35f9447..9653fe5f 100644 --- a/bsp_hosted/boardconfig/print.c +++ b/bsp_hosted/boardconfig/print.c @@ -3,13 +3,9 @@ #include void printChar(const char* character, bool errStream) { - if(errStream) { - putc(*character, stderr); - return; - } - putc(*character, stdout); + if (errStream) { + putc(*character, stderr); + return; + } + putc(*character, stdout); } - - - - diff --git a/bsp_hosted/comIF/ArduinoComIF.cpp b/bsp_hosted/comIF/ArduinoComIF.cpp index 2db293e6..be136e45 100644 --- a/bsp_hosted/comIF/ArduinoComIF.cpp +++ b/bsp_hosted/comIF/ArduinoComIF.cpp @@ -1,376 +1,351 @@ #include "ArduinoComIF.h" -#include "ArduinoCookie.h" -#include #include +#include #include +#include "ArduinoCookie.h" + // This only works on Linux #ifdef LINUX -#include #include +#include #include #elif WIN32 -#include #include +#include #endif #include -ArduinoComIF::ArduinoComIF(object_id_t setObjectId, bool promptComIF, - const char *serialDevice): - rxBuffer(MAX_PACKET_SIZE * MAX_NUMBER_OF_SPI_DEVICES*10, true), - SystemObject(setObjectId) { +ArduinoComIF::ArduinoComIF(object_id_t setObjectId, bool promptComIF, const char *serialDevice) + : rxBuffer(MAX_PACKET_SIZE * MAX_NUMBER_OF_SPI_DEVICES * 10, true), SystemObject(setObjectId) { #ifdef LINUX - initialized = false; - serialPort = ::open("/dev/ttyUSB0", O_RDWR); + initialized = false; + serialPort = ::open("/dev/ttyUSB0", O_RDWR); - if (serialPort < 0) { - //configuration error - printf("Error %i from open: %s\n", errno, strerror(errno)); - return; - } + if (serialPort < 0) { + // configuration error + printf("Error %i from open: %s\n", errno, strerror(errno)); + return; + } - struct termios tty; - memset(&tty, 0, sizeof tty); + struct termios tty; + memset(&tty, 0, sizeof tty); - // Read in existing settings, and handle any error - if (tcgetattr(serialPort, &tty) != 0) { - printf("Error %i from tcgetattr: %s\n", errno, strerror(errno)); - return; - } + // Read in existing settings, and handle any error + if (tcgetattr(serialPort, &tty) != 0) { + printf("Error %i from tcgetattr: %s\n", errno, strerror(errno)); + return; + } - tty.c_cflag &= ~PARENB; // Clear parity bit, disabling parity - tty.c_cflag &= ~CSTOPB; // Clear stop field, only one stop bit used in communication - tty.c_cflag |= CS8; // 8 bits per byte - tty.c_cflag &= ~CRTSCTS; // Disable RTS/CTS hardware flow control - tty.c_lflag &= ~ICANON; //Disable Canonical Mode - tty.c_oflag &= ~OPOST; // Prevent special interpretation of output bytes (e.g. newline chars) - tty.c_oflag &= ~ONLCR; // Prevent conversion of newline to carriage return/line feed - tty.c_cc[VTIME] = 0; // Non Blocking - tty.c_cc[VMIN] = 0; + tty.c_cflag &= ~PARENB; // Clear parity bit, disabling parity + tty.c_cflag &= ~CSTOPB; // Clear stop field, only one stop bit used in communication + tty.c_cflag |= CS8; // 8 bits per byte + tty.c_cflag &= ~CRTSCTS; // Disable RTS/CTS hardware flow control + tty.c_lflag &= ~ICANON; // Disable Canonical Mode + tty.c_oflag &= ~OPOST; // Prevent special interpretation of output bytes (e.g. newline chars) + tty.c_oflag &= ~ONLCR; // Prevent conversion of newline to carriage return/line feed + tty.c_cc[VTIME] = 0; // Non Blocking + tty.c_cc[VMIN] = 0; - cfsetispeed(&tty, B9600); //Baudrate + cfsetispeed(&tty, B9600); // Baudrate - if (tcsetattr(serialPort, TCSANOW, &tty) != 0) { - //printf("Error %i from tcsetattr: %s\n", errno, strerror(errno)); - return; - } + if (tcsetattr(serialPort, TCSANOW, &tty) != 0) { + // printf("Error %i from tcsetattr: %s\n", errno, strerror(errno)); + return; + } - initialized = true; + initialized = true; #elif WIN32 - DCB serialParams = { 0 }; + DCB serialParams = {0}; - // we need to ask the COM port from the user. - if(promptComIF) { - sif::info << "Please enter the COM port (c to cancel): " << std::flush; - std::string comPort; - while(hCom == INVALID_HANDLE_VALUE) { + // we need to ask the COM port from the user. + if (promptComIF) { + sif::info << "Please enter the COM port (c to cancel): " << std::flush; + std::string comPort; + while (hCom == INVALID_HANDLE_VALUE) { + std::getline(std::cin, comPort); + if (comPort[0] == 'c') { + break; + } + const TCHAR *pcCommPort = comPort.c_str(); + hCom = CreateFileA(pcCommPort, // port name + GENERIC_READ | GENERIC_WRITE, // Read/Write + 0, // No Sharing + NULL, // No Security + OPEN_EXISTING, // Open existing port only + 0, // Non Overlapped I/O + NULL); // Null for Comm Devices - std::getline(std::cin, comPort); - if(comPort[0] == 'c') { - break; - } - const TCHAR *pcCommPort = comPort.c_str(); - hCom = CreateFileA(pcCommPort, //port name - GENERIC_READ | GENERIC_WRITE, //Read/Write - 0, // No Sharing - NULL, // No Security - OPEN_EXISTING,// Open existing port only - 0, // Non Overlapped I/O - NULL); // Null for Comm Devices + if (hCom == INVALID_HANDLE_VALUE) { + if (GetLastError() == 2) { + sif::error << "COM Port does not found!" << std::endl; + } else { + TCHAR err[128]; + FormatMessage(FORMAT_MESSAGE_FROM_SYSTEM, NULL, GetLastError(), + MAKELANGID(LANG_NEUTRAL, SUBLANG_DEFAULT), err, sizeof(err), NULL); + // Handle the error. + sif::info << "CreateFileA Error code: " << GetLastError() << std::endl; + sif::error << err << std::flush; + } + sif::info << "Please enter a valid COM port: " << std::flush; + } + } + } - if (hCom == INVALID_HANDLE_VALUE) - { - if(GetLastError() == 2) { - sif::error << "COM Port does not found!" << std::endl; - } - else { - TCHAR err[128]; - FormatMessage(FORMAT_MESSAGE_FROM_SYSTEM, NULL, - GetLastError(), - MAKELANGID(LANG_NEUTRAL, SUBLANG_DEFAULT), - err, sizeof(err), NULL); - // Handle the error. - sif::info << "CreateFileA Error code: " << GetLastError() - << std::endl; - sif::error << err << std::flush; - } - sif::info << "Please enter a valid COM port: " << std::flush; - } - } + serialParams.DCBlength = sizeof(serialParams); + if (baudRate == 9600) { + serialParams.BaudRate = CBR_9600; + } + if (baudRate == 115200) { + serialParams.BaudRate = CBR_115200; + } else { + serialParams.BaudRate = baudRate; + } - } + serialParams.ByteSize = 8; + serialParams.Parity = NOPARITY; + serialParams.StopBits = ONESTOPBIT; + SetCommState(hCom, &serialParams); - - serialParams.DCBlength = sizeof(serialParams); - if(baudRate == 9600) { - serialParams.BaudRate = CBR_9600; - } - if(baudRate == 115200) { - serialParams.BaudRate = CBR_115200; - } - else { - serialParams.BaudRate = baudRate; - } - - serialParams.ByteSize = 8; - serialParams.Parity = NOPARITY; - serialParams.StopBits = ONESTOPBIT; - SetCommState(hCom, &serialParams); - - COMMTIMEOUTS timeout = { 0 }; - // This will set the read operation to be blocking until data is received - // and then read continuously until there is a gap of one millisecond. - timeout.ReadIntervalTimeout = 1; - timeout.ReadTotalTimeoutConstant = 0; - timeout.ReadTotalTimeoutMultiplier = 0; - timeout.WriteTotalTimeoutConstant = 0; - timeout.WriteTotalTimeoutMultiplier = 0; - SetCommTimeouts(hCom, &timeout); - // Serial port should now be read for operations. + COMMTIMEOUTS timeout = {0}; + // This will set the read operation to be blocking until data is received + // and then read continuously until there is a gap of one millisecond. + timeout.ReadIntervalTimeout = 1; + timeout.ReadTotalTimeoutConstant = 0; + timeout.ReadTotalTimeoutMultiplier = 0; + timeout.WriteTotalTimeoutConstant = 0; + timeout.WriteTotalTimeoutMultiplier = 0; + SetCommTimeouts(hCom, &timeout); + // Serial port should now be read for operations. #endif } ArduinoComIF::~ArduinoComIF() { #ifdef LINUX - ::close(serialPort); + ::close(serialPort); #elif WIN32 - CloseHandle(hCom); + CloseHandle(hCom); #endif } -ReturnValue_t ArduinoComIF::initializeInterface(CookieIF * cookie) { - return HasReturnvaluesIF::RETURN_OK; +ReturnValue_t ArduinoComIF::initializeInterface(CookieIF *cookie) { + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t ArduinoComIF::sendMessage(CookieIF *cookie, const uint8_t *data, - size_t len) { - ArduinoCookie *arduinoCookie = dynamic_cast(cookie); - if (arduinoCookie == nullptr) { - return INVALID_COOKIE_TYPE; - } +ReturnValue_t ArduinoComIF::sendMessage(CookieIF *cookie, const uint8_t *data, size_t len) { + ArduinoCookie *arduinoCookie = dynamic_cast(cookie); + if (arduinoCookie == nullptr) { + return INVALID_COOKIE_TYPE; + } - return sendMessage(arduinoCookie->command, arduinoCookie->address, data, - len); + return sendMessage(arduinoCookie->command, arduinoCookie->address, data, len); } -ReturnValue_t ArduinoComIF::getSendSuccess(CookieIF *cookie) { - return RETURN_OK; +ReturnValue_t ArduinoComIF::getSendSuccess(CookieIF *cookie) { return RETURN_OK; } + +ReturnValue_t ArduinoComIF::requestReceiveMessage(CookieIF *cookie, size_t requestLen) { + return RETURN_OK; } -ReturnValue_t ArduinoComIF::requestReceiveMessage(CookieIF *cookie, - size_t requestLen) { - return RETURN_OK; +ReturnValue_t ArduinoComIF::readReceivedMessage(CookieIF *cookie, uint8_t **buffer, size_t *size) { + handleSerialPortRx(); + + ArduinoCookie *arduinoCookie = dynamic_cast(cookie); + if (arduinoCookie == nullptr) { + return INVALID_COOKIE_TYPE; + } + + *buffer = arduinoCookie->replyBuffer.data(); + *size = arduinoCookie->receivedDataLen; + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t ArduinoComIF::readReceivedMessage(CookieIF *cookie, - uint8_t **buffer, size_t *size) { +ReturnValue_t ArduinoComIF::sendMessage(uint8_t command, uint8_t address, const uint8_t *data, + size_t dataLen) { + if (dataLen > UINT16_MAX) { + return TOO_MUCH_DATA; + } - handleSerialPortRx(); + // being conservative here + uint8_t sendBuffer[(dataLen + 6) * 2 + 2]; - ArduinoCookie *arduinoCookie = dynamic_cast(cookie); - if (arduinoCookie == nullptr) { - return INVALID_COOKIE_TYPE; - } + sendBuffer[0] = DleEncoder::STX_CHAR; - *buffer = arduinoCookie->replyBuffer.data(); - *size = arduinoCookie->receivedDataLen; - return HasReturnvaluesIF::RETURN_OK; -} + uint8_t *currentPosition = sendBuffer + 1; + size_t remainingLen = sizeof(sendBuffer) - 1; + size_t encodedLen = 0; -ReturnValue_t ArduinoComIF::sendMessage(uint8_t command, - uint8_t address, const uint8_t *data, size_t dataLen) { - if (dataLen > UINT16_MAX) { - return TOO_MUCH_DATA; - } + ReturnValue_t result = + DleEncoder::encode(&command, 1, currentPosition, remainingLen, &encodedLen, false); + if (result != RETURN_OK) { + return result; + } + currentPosition += encodedLen; + remainingLen -= encodedLen; // DleEncoder will never return encodedLen > remainingLen - //being conservative here - uint8_t sendBuffer[(dataLen + 6) * 2 + 2]; + result = DleEncoder::encode(&address, 1, currentPosition, remainingLen, &encodedLen, false); + if (result != RETURN_OK) { + return result; + } + currentPosition += encodedLen; + remainingLen -= encodedLen; // DleEncoder will never return encodedLen > remainingLen - sendBuffer[0] = DleEncoder::STX_CHAR; + uint8_t temporaryBuffer[2]; - uint8_t *currentPosition = sendBuffer + 1; - size_t remainingLen = sizeof(sendBuffer) - 1; - size_t encodedLen = 0; + // note to Lukas: yes we _could_ use Serialize here, but for 16 bit it is a bit too much... + temporaryBuffer[0] = dataLen >> 8; // we checked dataLen above + temporaryBuffer[1] = dataLen; - ReturnValue_t result = DleEncoder::encode(&command, 1, currentPosition, - remainingLen, &encodedLen, false); - if (result != RETURN_OK) { - return result; - } - currentPosition += encodedLen; - remainingLen -= encodedLen; //DleEncoder will never return encodedLen > remainingLen + result = + DleEncoder::encode(temporaryBuffer, 2, currentPosition, remainingLen, &encodedLen, false); + if (result != RETURN_OK) { + return result; + } + currentPosition += encodedLen; + remainingLen -= encodedLen; // DleEncoder will never return encodedLen > remainingLen - result = DleEncoder::encode(&address, 1, currentPosition, remainingLen, - &encodedLen, false); - if (result != RETURN_OK) { - return result; - } - currentPosition += encodedLen; - remainingLen -= encodedLen; //DleEncoder will never return encodedLen > remainingLen + // encoding the actual data + result = DleEncoder::encode(data, dataLen, currentPosition, remainingLen, &encodedLen, false); + if (result != RETURN_OK) { + return result; + } + currentPosition += encodedLen; + remainingLen -= encodedLen; // DleEncoder will never return encodedLen > remainingLen - uint8_t temporaryBuffer[2]; + uint16_t crc = CRC::crc16ccitt(&command, 1); + crc = CRC::crc16ccitt(&address, 1, crc); + // fortunately the length is still there + crc = CRC::crc16ccitt(temporaryBuffer, 2, crc); + crc = CRC::crc16ccitt(data, dataLen, crc); - //note to Lukas: yes we _could_ use Serialize here, but for 16 bit it is a bit too much... - temporaryBuffer[0] = dataLen >> 8; //we checked dataLen above - temporaryBuffer[1] = dataLen; + temporaryBuffer[0] = crc >> 8; + temporaryBuffer[1] = crc; - result = DleEncoder::encode(temporaryBuffer, 2, currentPosition, - remainingLen, &encodedLen, false); - if (result != RETURN_OK) { - return result; - } - currentPosition += encodedLen; - remainingLen -= encodedLen; //DleEncoder will never return encodedLen > remainingLen + result = + DleEncoder::encode(temporaryBuffer, 2, currentPosition, remainingLen, &encodedLen, false); + if (result != RETURN_OK) { + return result; + } + currentPosition += encodedLen; + remainingLen -= encodedLen; // DleEncoder will never return encodedLen > remainingLen - //encoding the actual data - result = DleEncoder::encode(data, dataLen, currentPosition, remainingLen, - &encodedLen, false); - if (result != RETURN_OK) { - return result; - } - currentPosition += encodedLen; - remainingLen -= encodedLen; //DleEncoder will never return encodedLen > remainingLen + if (remainingLen > 0) { + *currentPosition = DleEncoder::ETX_CHAR; + } + remainingLen -= 1; - uint16_t crc = CRC::crc16ccitt(&command, 1); - crc = CRC::crc16ccitt(&address, 1, crc); - //fortunately the length is still there - crc = CRC::crc16ccitt(temporaryBuffer, 2, crc); - crc = CRC::crc16ccitt(data, dataLen, crc); - - temporaryBuffer[0] = crc >> 8; - temporaryBuffer[1] = crc; - - result = DleEncoder::encode(temporaryBuffer, 2, currentPosition, - remainingLen, &encodedLen, false); - if (result != RETURN_OK) { - return result; - } - currentPosition += encodedLen; - remainingLen -= encodedLen; //DleEncoder will never return encodedLen > remainingLen - - if (remainingLen > 0) { - *currentPosition = DleEncoder::ETX_CHAR; - } - remainingLen -= 1; - - encodedLen = sizeof(sendBuffer) - remainingLen; + encodedLen = sizeof(sendBuffer) - remainingLen; #ifdef LINUX - ssize_t writtenlen = ::write(serialPort, sendBuffer, encodedLen); - if (writtenlen < 0) { - //we could try to find out what happened... - return RETURN_FAILED; - } - if (writtenlen != encodedLen) { - //the OS failed us, we do not try to block until everything is written, as - //we can not block the whole system here - return RETURN_FAILED; - } - return RETURN_OK; + ssize_t writtenlen = ::write(serialPort, sendBuffer, encodedLen); + if (writtenlen < 0) { + // we could try to find out what happened... + return RETURN_FAILED; + } + if (writtenlen != encodedLen) { + // the OS failed us, we do not try to block until everything is written, as + // we can not block the whole system here + return RETURN_FAILED; + } + return RETURN_OK; #elif WIN32 - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; #endif } void ArduinoComIF::handleSerialPortRx() { #ifdef LINUX - uint32_t availableSpace = rxBuffer.availableWriteSpace(); + uint32_t availableSpace = rxBuffer.availableWriteSpace(); - uint8_t dataFromSerial[availableSpace]; + uint8_t dataFromSerial[availableSpace]; - ssize_t bytesRead = read(serialPort, dataFromSerial, - sizeof(dataFromSerial)); + ssize_t bytesRead = read(serialPort, dataFromSerial, sizeof(dataFromSerial)); - if (bytesRead < 0) { - return; - } + if (bytesRead < 0) { + return; + } - rxBuffer.writeData(dataFromSerial, bytesRead); + rxBuffer.writeData(dataFromSerial, bytesRead); - uint8_t dataReceivedSoFar[rxBuffer.getMaxSize()]; + uint8_t dataReceivedSoFar[rxBuffer.getMaxSize()]; - uint32_t dataLenReceivedSoFar = 0; + uint32_t dataLenReceivedSoFar = 0; - rxBuffer.readData(dataReceivedSoFar, sizeof(dataReceivedSoFar), true, - &dataLenReceivedSoFar); + rxBuffer.readData(dataReceivedSoFar, sizeof(dataReceivedSoFar), true, &dataLenReceivedSoFar); - //look for STX - size_t firstSTXinRawData = 0; - while ((firstSTXinRawData < dataLenReceivedSoFar) - && (dataReceivedSoFar[firstSTXinRawData] != DleEncoder::STX_CHAR)) { - firstSTXinRawData++; - } + // look for STX + size_t firstSTXinRawData = 0; + while ((firstSTXinRawData < dataLenReceivedSoFar) && + (dataReceivedSoFar[firstSTXinRawData] != DleEncoder::STX_CHAR)) { + firstSTXinRawData++; + } - if (dataReceivedSoFar[firstSTXinRawData] != DleEncoder::STX_CHAR) { - //there is no STX in our data, throw it away... - rxBuffer.deleteData(dataLenReceivedSoFar); - return; - } + if (dataReceivedSoFar[firstSTXinRawData] != DleEncoder::STX_CHAR) { + // there is no STX in our data, throw it away... + rxBuffer.deleteData(dataLenReceivedSoFar); + return; + } - uint8_t packet[MAX_PACKET_SIZE]; - size_t packetLen = 0; + uint8_t packet[MAX_PACKET_SIZE]; + size_t packetLen = 0; - size_t readSize = 0; + size_t readSize = 0; - ReturnValue_t result = DleEncoder::decode( - dataReceivedSoFar + firstSTXinRawData, - dataLenReceivedSoFar - firstSTXinRawData, &readSize, packet, - sizeof(packet), &packetLen); + ReturnValue_t result = DleEncoder::decode(dataReceivedSoFar + firstSTXinRawData, + dataLenReceivedSoFar - firstSTXinRawData, &readSize, + packet, sizeof(packet), &packetLen); - size_t toDelete = firstSTXinRawData; - if (result == HasReturnvaluesIF::RETURN_OK) { - handlePacket(packet, packetLen); + size_t toDelete = firstSTXinRawData; + if (result == HasReturnvaluesIF::RETURN_OK) { + handlePacket(packet, packetLen); - // after handling the packet, we can delete it from the raw stream, - // it has been copied to packet - toDelete += readSize; - } + // after handling the packet, we can delete it from the raw stream, + // it has been copied to packet + toDelete += readSize; + } - //remove Data which was processed - rxBuffer.deleteData(toDelete); + // remove Data which was processed + rxBuffer.deleteData(toDelete); #elif WIN32 #endif } -void ArduinoComIF::setBaudrate(uint32_t baudRate) { - this->baudRate = baudRate; -} +void ArduinoComIF::setBaudrate(uint32_t baudRate) { this->baudRate = baudRate; } void ArduinoComIF::handlePacket(uint8_t *packet, size_t packetLen) { - uint16_t crc = CRC::crc16ccitt(packet, packetLen); - if (crc != 0) { - //CRC error - return; - } + uint16_t crc = CRC::crc16ccitt(packet, packetLen); + if (crc != 0) { + // CRC error + return; + } - uint8_t command = packet[0]; - uint8_t address = packet[1]; + uint8_t command = packet[0]; + uint8_t address = packet[1]; - uint16_t size = (packet[2] << 8) + packet[3]; + uint16_t size = (packet[2] << 8) + packet[3]; - if (size != packetLen - 6) { - //Invalid Length - return; - } + if (size != packetLen - 6) { + // Invalid Length + return; + } - switch (command) { - case ArduinoCookie::SPI: { - //ArduinoCookie **itsComplicated; - auto findIter = spiMap.find(address); - if (findIter == spiMap.end()) { - //we do no know this address - return; - } - ArduinoCookie& cookie = findIter->second; - if (packetLen > cookie.maxReplySize + 6) { - packetLen = cookie.maxReplySize + 6; - } - std::memcpy(cookie.replyBuffer.data(), packet + 4, packetLen - 6); - cookie.receivedDataLen = packetLen - 6; - } - break; - default: - return; - } + switch (command) { + case ArduinoCookie::SPI: { + // ArduinoCookie **itsComplicated; + auto findIter = spiMap.find(address); + if (findIter == spiMap.end()) { + // we do no know this address + return; + } + ArduinoCookie &cookie = findIter->second; + if (packetLen > cookie.maxReplySize + 6) { + packetLen = cookie.maxReplySize + 6; + } + std::memcpy(cookie.replyBuffer.data(), packet + 4, packetLen - 6); + cookie.receivedDataLen = packetLen - 6; + } break; + default: + return; + } } diff --git a/bsp_hosted/comIF/ArduinoComIF.h b/bsp_hosted/comIF/ArduinoComIF.h index 84bd959d..8476b6b5 100644 --- a/bsp_hosted/comIF/ArduinoComIF.h +++ b/bsp_hosted/comIF/ArduinoComIF.h @@ -4,8 +4,8 @@ #include #include #include -#include #include +#include #include #include @@ -14,56 +14,53 @@ #include #endif -//Forward declaration, so users don't peek +// Forward declaration, so users don't peek class ArduinoCookie; -class ArduinoComIF: public SystemObject, - public DeviceCommunicationIF { -public: - static const uint8_t MAX_NUMBER_OF_SPI_DEVICES = 8; - static const uint8_t MAX_PACKET_SIZE = 64; +class ArduinoComIF : public SystemObject, public DeviceCommunicationIF { + public: + static const uint8_t MAX_NUMBER_OF_SPI_DEVICES = 8; + static const uint8_t MAX_PACKET_SIZE = 64; - static const uint8_t COMMAND_INVALID = -1; - static const uint8_t COMMAND_SPI = 1; + static const uint8_t COMMAND_INVALID = -1; + static const uint8_t COMMAND_SPI = 1; - ArduinoComIF(object_id_t setObjectId, bool promptComIF = false, - const char *serialDevice = nullptr); - void setBaudrate(uint32_t baudRate); + ArduinoComIF(object_id_t setObjectId, bool promptComIF = false, + const char *serialDevice = nullptr); + void setBaudrate(uint32_t baudRate); - virtual ~ArduinoComIF(); + virtual ~ArduinoComIF(); - /** DeviceCommunicationIF overrides */ - 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; + /** DeviceCommunicationIF overrides */ + 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; -private: + private: #ifdef LINUX #elif WIN32 - HANDLE hCom = INVALID_HANDLE_VALUE; + HANDLE hCom = INVALID_HANDLE_VALUE; #endif - // remembering if the initialization in the ctor worked - // if not, all calls are disabled - bool initialized = false; - int serialPort = 0; - // Default baud rate is 9600 for now. - uint32_t baudRate = 9600; + // remembering if the initialization in the ctor worked + // if not, all calls are disabled + bool initialized = false; + int serialPort = 0; + // Default baud rate is 9600 for now. + uint32_t baudRate = 9600; - //used to know where to put the data if a reply is received - std::map spiMap; + // used to know where to put the data if a reply is received + std::map spiMap; - SimpleRingBuffer rxBuffer; + SimpleRingBuffer rxBuffer; - ReturnValue_t sendMessage(uint8_t command, uint8_t address, - const uint8_t *data, size_t dataLen); - void handleSerialPortRx(); + ReturnValue_t sendMessage(uint8_t command, uint8_t address, const uint8_t *data, size_t dataLen); + void handleSerialPortRx(); - void handlePacket(uint8_t *packet, size_t packetLen); + void handlePacket(uint8_t *packet, size_t packetLen); }; #endif /* MISSION_ARDUINOCOMMINTERFACE_H_ */ diff --git a/bsp_hosted/comIF/ArduinoCookie.cpp b/bsp_hosted/comIF/ArduinoCookie.cpp index bc698720..89cb1568 100644 --- a/bsp_hosted/comIF/ArduinoCookie.cpp +++ b/bsp_hosted/comIF/ArduinoCookie.cpp @@ -1,8 +1,8 @@ #include -ArduinoCookie::ArduinoCookie(Protocol_t protocol, uint8_t address, - const size_t maxReplySize) : - protocol(protocol), command(protocol), address(address), - maxReplySize(maxReplySize), replyBuffer(maxReplySize) { -} - +ArduinoCookie::ArduinoCookie(Protocol_t protocol, uint8_t address, const size_t maxReplySize) + : protocol(protocol), + command(protocol), + address(address), + maxReplySize(maxReplySize), + replyBuffer(maxReplySize) {} diff --git a/bsp_hosted/comIF/ArduinoCookie.h b/bsp_hosted/comIF/ArduinoCookie.h index a5f91f64..04d4bd83 100644 --- a/bsp_hosted/comIF/ArduinoCookie.h +++ b/bsp_hosted/comIF/ArduinoCookie.h @@ -2,26 +2,21 @@ #define MISSION_ARDUINO_ARDUINOCOOKIE_H_ #include + #include -class ArduinoCookie: public CookieIF { -public: - enum Protocol_t: uint8_t { - INVALID, - SPI, - I2C - }; +class ArduinoCookie : public CookieIF { + public: + enum Protocol_t : uint8_t { INVALID, SPI, I2C }; - ArduinoCookie(Protocol_t protocol, uint8_t address, - const size_t maxReplySize); - - Protocol_t protocol; - uint8_t command; - uint8_t address; - std::vector replyBuffer; - size_t receivedDataLen = 0; - size_t maxReplySize; + ArduinoCookie(Protocol_t protocol, uint8_t address, const size_t maxReplySize); + Protocol_t protocol; + uint8_t command; + uint8_t address; + std::vector replyBuffer; + size_t receivedDataLen = 0; + size_t maxReplySize; }; #endif /* MISSION_ARDUINO_ARDUINOCOOKIE_H_ */ diff --git a/bsp_hosted/fsfwconfig/CMakeLists.txt b/bsp_hosted/fsfwconfig/CMakeLists.txt index fc961da8..4a483eb7 100644 --- a/bsp_hosted/fsfwconfig/CMakeLists.txt +++ b/bsp_hosted/fsfwconfig/CMakeLists.txt @@ -1,21 +1,27 @@ -target_sources(${TARGET_NAME} PRIVATE +target_sources(${OBSW_NAME} PRIVATE ipc/MissionMessageTypes.cpp ) -target_include_directories(${TARGET_NAME} PUBLIC +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(${TARGET_NAME} PRIVATE + 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(${TARGET_NAME} PRIVATE + target_sources(${OBSW_NAME} PRIVATE + events/translateEvents.cpp + ) + target_sources(${UNITTEST_NAME} PRIVATE events/translateEvents.cpp ) endif() diff --git a/bsp_hosted/fsfwconfig/OBSWConfig.h.in b/bsp_hosted/fsfwconfig/OBSWConfig.h.in index 5996e3a2..a2353947 100644 --- a/bsp_hosted/fsfwconfig/OBSWConfig.h.in +++ b/bsp_hosted/fsfwconfig/OBSWConfig.h.in @@ -14,6 +14,12 @@ debugging. */ #define OBSW_VEBOSE_LEVEL 1 +#define OBSW_USE_CCSDS_IP_CORE 0 +// Set to 1 if all telemetry should be sent to the PTME IP Core +#define OBSW_TM_TO_PTME 0 +// Set to 1 if telecommands are received via the PDEC IP Core +#define OBSW_TC_FROM_PDEC 0 + #ifdef __cplusplus #include "objects/systemObjectList.h" diff --git a/bsp_hosted/fsfwconfig/devices/gpioIds.h b/bsp_hosted/fsfwconfig/devices/gpioIds.h deleted file mode 100644 index df49c0b7..00000000 --- a/bsp_hosted/fsfwconfig/devices/gpioIds.h +++ /dev/null @@ -1,59 +0,0 @@ -#ifndef FSFWCONFIG_DEVICES_GPIOIDS_H_ -#define FSFWCONFIG_DEVICES_GPIOIDS_H_ - -#include - -namespace gpioIds { - enum gpioId_t { - HEATER_0, - HEATER_1, - HEATER_2, - HEATER_3, - HEATER_4, - HEATER_5, - HEATER_6, - HEATER_7, - DEPLSA1, - DEPLSA2, - - MGM_0_LIS3_CS, - MGM_1_RM3100_CS, - GYRO_0_ADIS_CS, - GYRO_1_L3G_CS, - GYRO_2_L3G_CS, - MGM_2_LIS3_CS, - MGM_3_RM3100_CS, - - TEST_ID_0, - TEST_ID_1, - - RTD_IC3, - RTD_IC4, - RTD_IC5, - RTD_IC6, - RTD_IC7, - RTD_IC8, - RTD_IC9, - RTD_IC10, - RTD_IC11, - RTD_IC12, - RTD_IC13, - RTD_IC14, - RTD_IC15, - RTD_IC16, - RTD_IC17, - RTD_IC18, - - SPI_MUX_BIT_1, - SPI_MUX_BIT_2, - SPI_MUX_BIT_3, - SPI_MUX_BIT_4, - SPI_MUX_BIT_5, - SPI_MUX_BIT_6 - }; -} - - - - -#endif /* FSFWCONFIG_DEVICES_GPIOIDS_H_ */ diff --git a/bsp_hosted/fsfwconfig/devices/powerSwitcherList.h b/bsp_hosted/fsfwconfig/devices/powerSwitcherList.h index c216c828..ae259374 100644 --- a/bsp_hosted/fsfwconfig/devices/powerSwitcherList.h +++ b/bsp_hosted/fsfwconfig/devices/powerSwitcherList.h @@ -4,55 +4,54 @@ #include namespace pcduSwitches { - /* Switches are uint8_t datatype and go from 0 to 255 */ - enum SwitcherList { - Q7S, - PAYLOAD_PCDU_CH1, - RW, - TCS_BOARD_8V_HEATER_IN, - SUS_REDUNDANT, - DEPLOYMENT_MECHANISM, - PAYLOAD_PCDU_CH6, - ACS_BOARD_SIDE_B, - PAYLOAD_CAMERA, - TCS_BOARD_3V3, - SYRLINKS, - STAR_TRACKER, - MGT, - SUS_NOMINAL, - SOLAR_CELL_EXP, - PLOC, - ACS_BOARD_SIDE_A, - NUMBER_OF_SWITCHES - }; +/* Switches are uint8_t datatype and go from 0 to 255 */ +enum SwitcherList { + Q7S, + PAYLOAD_PCDU_CH1, + RW, + TCS_BOARD_8V_HEATER_IN, + SUS_REDUNDANT, + DEPLOYMENT_MECHANISM, + PAYLOAD_PCDU_CH6, + ACS_BOARD_SIDE_B, + PAYLOAD_CAMERA, + TCS_BOARD_3V3, + SYRLINKS, + STAR_TRACKER, + MGT, + SUS_NOMINAL, + SOLAR_CELL_EXP, + PLOC, + ACS_BOARD_SIDE_A, + NUMBER_OF_SWITCHES +}; - static const uint8_t ON = 1; - static const uint8_t OFF = 0; +static const uint8_t ON = 1; +static const uint8_t OFF = 0; - /* Output states after reboot of the PDUs */ - static const uint8_t INIT_STATE_Q7S = ON; - static const uint8_t INIT_STATE_PAYLOAD_PCDU_CH1 = OFF; - static const uint8_t INIT_STATE_RW = OFF; +/* Output states after reboot of the PDUs */ +static const uint8_t INIT_STATE_Q7S = ON; +static const uint8_t INIT_STATE_PAYLOAD_PCDU_CH1 = OFF; +static const uint8_t INIT_STATE_RW = OFF; #if BOARD_TE0720 == 1 - /* Because the TE0720 is not connected to the PCDU, this switch is always on */ - static const uint8_t INIT_STATE_TCS_BOARD_8V_HEATER_IN = ON; +/* Because the TE0720 is not connected to the PCDU, this switch is always on */ +static const uint8_t INIT_STATE_TCS_BOARD_8V_HEATER_IN = ON; #else - static const uint8_t INIT_STATE_TCS_BOARD_8V_HEATER_IN = OFF; +static const uint8_t INIT_STATE_TCS_BOARD_8V_HEATER_IN = OFF; #endif - static const uint8_t INIT_STATE_SUS_REDUNDANT = OFF; - static const uint8_t INIT_STATE_DEPLOYMENT_MECHANISM = OFF; - static const uint8_t INIT_STATE_PAYLOAD_PCDU_CH6 = OFF; - static const uint8_t INIT_STATE_ACS_BOARD_SIDE_B = OFF; - static const uint8_t INIT_STATE_PAYLOAD_CAMERA = OFF; - static const uint8_t INIT_STATE_TCS_BOARD_3V3 = OFF; - static const uint8_t INIT_STATE_SYRLINKS = OFF; - static const uint8_t INIT_STATE_STAR_TRACKER = OFF; - static const uint8_t INIT_STATE_MGT = OFF; - static const uint8_t INIT_STATE_SUS_NOMINAL = OFF; - static const uint8_t INIT_STATE_SOLAR_CELL_EXP = OFF; - static const uint8_t INIT_STATE_PLOC = OFF; - static const uint8_t INIT_STATE_ACS_BOARD_SIDE_A = OFF; -} - +static const uint8_t INIT_STATE_SUS_REDUNDANT = OFF; +static const uint8_t INIT_STATE_DEPLOYMENT_MECHANISM = OFF; +static const uint8_t INIT_STATE_PAYLOAD_PCDU_CH6 = OFF; +static const uint8_t INIT_STATE_ACS_BOARD_SIDE_B = OFF; +static const uint8_t INIT_STATE_PAYLOAD_CAMERA = OFF; +static const uint8_t INIT_STATE_TCS_BOARD_3V3 = OFF; +static const uint8_t INIT_STATE_SYRLINKS = OFF; +static const uint8_t INIT_STATE_STAR_TRACKER = OFF; +static const uint8_t INIT_STATE_MGT = OFF; +static const uint8_t INIT_STATE_SUS_NOMINAL = OFF; +static const uint8_t INIT_STATE_SOLAR_CELL_EXP = OFF; +static const uint8_t INIT_STATE_PLOC = OFF; +static const uint8_t INIT_STATE_ACS_BOARD_SIDE_A = OFF; +} // namespace pcduSwitches #endif /* FSFWCONFIG_DEVICES_POWERSWITCHERLIST_H_ */ diff --git a/bsp_hosted/fsfwconfig/events/subsystemIdRanges.h b/bsp_hosted/fsfwconfig/events/subsystemIdRanges.h index 7335a804..9dc50c50 100644 --- a/bsp_hosted/fsfwconfig/events/subsystemIdRanges.h +++ b/bsp_hosted/fsfwconfig/events/subsystemIdRanges.h @@ -2,6 +2,7 @@ #define CONFIG_EVENTS_SUBSYSTEMIDRANGES_H_ #include + #include /** @@ -9,9 +10,7 @@ * Numbers 0-80 are reserved for FSFW Subsystem IDs (framework/events/) */ namespace SUBSYSTEM_ID { -enum: uint8_t { - SUBSYSTEM_ID_START = COMMON_SUBSYSTEM_ID_END -}; +enum : uint8_t { SUBSYSTEM_ID_START = COMMON_SUBSYSTEM_ID_END }; } #endif /* CONFIG_EVENTS_SUBSYSTEMIDRANGES_H_ */ diff --git a/bsp_hosted/fsfwconfig/events/translateEvents.cpp b/bsp_hosted/fsfwconfig/events/translateEvents.cpp index 7b9ce4b5..fb9e1bf4 100644 --- a/bsp_hosted/fsfwconfig/events/translateEvents.cpp +++ b/bsp_hosted/fsfwconfig/events/translateEvents.cpp @@ -89,176 +89,176 @@ const char *ACK_FAILURE_STRING = "ACK_FAILURE"; const char *EXE_FAILURE_STRING = "EXE_FAILURE"; const char *CRC_FAILURE_EVENT_STRING = "CRC_FAILURE_EVENT"; -const char * translateEvents(Event event) { - switch( (event & 0xffff) ) { - case(2200): - return STORE_SEND_WRITE_FAILED_STRING; - case(2201): - return STORE_WRITE_FAILED_STRING; - case(2202): - return STORE_SEND_READ_FAILED_STRING; - case(2203): - return STORE_READ_FAILED_STRING; - case(2204): - return UNEXPECTED_MSG_STRING; - case(2205): - return STORING_FAILED_STRING; - case(2206): - return TM_DUMP_FAILED_STRING; - case(2207): - return STORE_INIT_FAILED_STRING; - case(2208): - return STORE_INIT_EMPTY_STRING; - case(2209): - return STORE_CONTENT_CORRUPTED_STRING; - case(2210): - return STORE_INITIALIZE_STRING; - case(2211): - return INIT_DONE_STRING; - case(2212): - return DUMP_FINISHED_STRING; - case(2213): - return DELETION_FINISHED_STRING; - case(2214): - return DELETION_FAILED_STRING; - case(2215): - return AUTO_CATALOGS_SENDING_FAILED_STRING; - case(2600): - return GET_DATA_FAILED_STRING; - case(2601): - return STORE_DATA_FAILED_STRING; - case(2800): - return DEVICE_BUILDING_COMMAND_FAILED_STRING; - case(2801): - return DEVICE_SENDING_COMMAND_FAILED_STRING; - case(2802): - return DEVICE_REQUESTING_REPLY_FAILED_STRING; - case(2803): - return DEVICE_READING_REPLY_FAILED_STRING; - case(2804): - return DEVICE_INTERPRETING_REPLY_FAILED_STRING; - case(2805): - return DEVICE_MISSED_REPLY_STRING; - case(2806): - return DEVICE_UNKNOWN_REPLY_STRING; - case(2807): - return DEVICE_UNREQUESTED_REPLY_STRING; - case(2808): - return INVALID_DEVICE_COMMAND_STRING; - case(2809): - return MONITORING_LIMIT_EXCEEDED_STRING; - case(2810): - return MONITORING_AMBIGUOUS_STRING; - case(4201): - return FUSE_CURRENT_HIGH_STRING; - case(4202): - return FUSE_WENT_OFF_STRING; - case(4204): - return POWER_ABOVE_HIGH_LIMIT_STRING; - case(4205): - return POWER_BELOW_LOW_LIMIT_STRING; - case(4300): - return SWITCH_WENT_OFF_STRING; - case(5000): - return HEATER_ON_STRING; - case(5001): - return HEATER_OFF_STRING; - case(5002): - return HEATER_TIMEOUT_STRING; - case(5003): - return HEATER_STAYED_ON_STRING; - case(5004): - return HEATER_STAYED_OFF_STRING; - case(5200): - return TEMP_SENSOR_HIGH_STRING; - case(5201): - return TEMP_SENSOR_LOW_STRING; - case(5202): - return TEMP_SENSOR_GRADIENT_STRING; - case(5901): - return COMPONENT_TEMP_LOW_STRING; - case(5902): - return COMPONENT_TEMP_HIGH_STRING; - case(5903): - return COMPONENT_TEMP_OOL_LOW_STRING; - case(5904): - return COMPONENT_TEMP_OOL_HIGH_STRING; - case(5905): - return TEMP_NOT_IN_OP_RANGE_STRING; - case(7101): - return FDIR_CHANGED_STATE_STRING; - case(7102): - return FDIR_STARTS_RECOVERY_STRING; - case(7103): - return FDIR_TURNS_OFF_DEVICE_STRING; - case(7201): - return MONITOR_CHANGED_STATE_STRING; - case(7202): - return VALUE_BELOW_LOW_LIMIT_STRING; - case(7203): - return VALUE_ABOVE_HIGH_LIMIT_STRING; - case(7204): - return VALUE_OUT_OF_RANGE_STRING; - case(7301): - return SWITCHING_TM_FAILED_STRING; - case(7400): - return CHANGING_MODE_STRING; - case(7401): - return MODE_INFO_STRING; - case(7402): - return FALLBACK_FAILED_STRING; - case(7403): - return MODE_TRANSITION_FAILED_STRING; - case(7404): - return CANT_KEEP_MODE_STRING; - case(7405): - return OBJECT_IN_INVALID_MODE_STRING; - case(7406): - return FORCING_MODE_STRING; - case(7407): - return MODE_CMD_REJECTED_STRING; - case(7506): - return HEALTH_INFO_STRING; - case(7507): - return CHILD_CHANGED_HEALTH_STRING; - case(7508): - return CHILD_PROBLEMS_STRING; - case(7509): - return OVERWRITING_HEALTH_STRING; - case(7510): - return TRYING_RECOVERY_STRING; - case(7511): - return RECOVERY_STEP_STRING; - case(7512): - return RECOVERY_DONE_STRING; - case(7900): - return RF_AVAILABLE_STRING; - case(7901): - return RF_LOST_STRING; - case(7902): - return BIT_LOCK_STRING; - case(7903): - return BIT_LOCK_LOST_STRING; - case(7905): - return FRAME_PROCESSING_FAILED_STRING; - case(8900): - return CLOCK_SET_STRING; - case(8901): - return CLOCK_SET_FAILURE_STRING; - case(9700): - return TEST_STRING; - case(10600): - return CHANGE_OF_SETUP_PARAMETER_STRING; - case(11101): - return MEMORY_READ_RPT_CRC_FAILURE_STRING; - case(11102): - return ACK_FAILURE_STRING; - case(11103): - return EXE_FAILURE_STRING; - case(11104): - return CRC_FAILURE_EVENT_STRING; - default: - return "UNKNOWN_EVENT"; - } - return 0; +const char *translateEvents(Event event) { + switch ((event & 0xffff)) { + case (2200): + return STORE_SEND_WRITE_FAILED_STRING; + case (2201): + return STORE_WRITE_FAILED_STRING; + case (2202): + return STORE_SEND_READ_FAILED_STRING; + case (2203): + return STORE_READ_FAILED_STRING; + case (2204): + return UNEXPECTED_MSG_STRING; + case (2205): + return STORING_FAILED_STRING; + case (2206): + return TM_DUMP_FAILED_STRING; + case (2207): + return STORE_INIT_FAILED_STRING; + case (2208): + return STORE_INIT_EMPTY_STRING; + case (2209): + return STORE_CONTENT_CORRUPTED_STRING; + case (2210): + return STORE_INITIALIZE_STRING; + case (2211): + return INIT_DONE_STRING; + case (2212): + return DUMP_FINISHED_STRING; + case (2213): + return DELETION_FINISHED_STRING; + case (2214): + return DELETION_FAILED_STRING; + case (2215): + return AUTO_CATALOGS_SENDING_FAILED_STRING; + case (2600): + return GET_DATA_FAILED_STRING; + case (2601): + return STORE_DATA_FAILED_STRING; + case (2800): + return DEVICE_BUILDING_COMMAND_FAILED_STRING; + case (2801): + return DEVICE_SENDING_COMMAND_FAILED_STRING; + case (2802): + return DEVICE_REQUESTING_REPLY_FAILED_STRING; + case (2803): + return DEVICE_READING_REPLY_FAILED_STRING; + case (2804): + return DEVICE_INTERPRETING_REPLY_FAILED_STRING; + case (2805): + return DEVICE_MISSED_REPLY_STRING; + case (2806): + return DEVICE_UNKNOWN_REPLY_STRING; + case (2807): + return DEVICE_UNREQUESTED_REPLY_STRING; + case (2808): + return INVALID_DEVICE_COMMAND_STRING; + case (2809): + return MONITORING_LIMIT_EXCEEDED_STRING; + case (2810): + return MONITORING_AMBIGUOUS_STRING; + case (4201): + return FUSE_CURRENT_HIGH_STRING; + case (4202): + return FUSE_WENT_OFF_STRING; + case (4204): + return POWER_ABOVE_HIGH_LIMIT_STRING; + case (4205): + return POWER_BELOW_LOW_LIMIT_STRING; + case (4300): + return SWITCH_WENT_OFF_STRING; + case (5000): + return HEATER_ON_STRING; + case (5001): + return HEATER_OFF_STRING; + case (5002): + return HEATER_TIMEOUT_STRING; + case (5003): + return HEATER_STAYED_ON_STRING; + case (5004): + return HEATER_STAYED_OFF_STRING; + case (5200): + return TEMP_SENSOR_HIGH_STRING; + case (5201): + return TEMP_SENSOR_LOW_STRING; + case (5202): + return TEMP_SENSOR_GRADIENT_STRING; + case (5901): + return COMPONENT_TEMP_LOW_STRING; + case (5902): + return COMPONENT_TEMP_HIGH_STRING; + case (5903): + return COMPONENT_TEMP_OOL_LOW_STRING; + case (5904): + return COMPONENT_TEMP_OOL_HIGH_STRING; + case (5905): + return TEMP_NOT_IN_OP_RANGE_STRING; + case (7101): + return FDIR_CHANGED_STATE_STRING; + case (7102): + return FDIR_STARTS_RECOVERY_STRING; + case (7103): + return FDIR_TURNS_OFF_DEVICE_STRING; + case (7201): + return MONITOR_CHANGED_STATE_STRING; + case (7202): + return VALUE_BELOW_LOW_LIMIT_STRING; + case (7203): + return VALUE_ABOVE_HIGH_LIMIT_STRING; + case (7204): + return VALUE_OUT_OF_RANGE_STRING; + case (7301): + return SWITCHING_TM_FAILED_STRING; + case (7400): + return CHANGING_MODE_STRING; + case (7401): + return MODE_INFO_STRING; + case (7402): + return FALLBACK_FAILED_STRING; + case (7403): + return MODE_TRANSITION_FAILED_STRING; + case (7404): + return CANT_KEEP_MODE_STRING; + case (7405): + return OBJECT_IN_INVALID_MODE_STRING; + case (7406): + return FORCING_MODE_STRING; + case (7407): + return MODE_CMD_REJECTED_STRING; + case (7506): + return HEALTH_INFO_STRING; + case (7507): + return CHILD_CHANGED_HEALTH_STRING; + case (7508): + return CHILD_PROBLEMS_STRING; + case (7509): + return OVERWRITING_HEALTH_STRING; + case (7510): + return TRYING_RECOVERY_STRING; + case (7511): + return RECOVERY_STEP_STRING; + case (7512): + return RECOVERY_DONE_STRING; + case (7900): + return RF_AVAILABLE_STRING; + case (7901): + return RF_LOST_STRING; + case (7902): + return BIT_LOCK_STRING; + case (7903): + return BIT_LOCK_LOST_STRING; + case (7905): + return FRAME_PROCESSING_FAILED_STRING; + case (8900): + return CLOCK_SET_STRING; + case (8901): + return CLOCK_SET_FAILURE_STRING; + case (9700): + return TEST_STRING; + case (10600): + return CHANGE_OF_SETUP_PARAMETER_STRING; + case (11101): + return MEMORY_READ_RPT_CRC_FAILURE_STRING; + case (11102): + return ACK_FAILURE_STRING; + case (11103): + return EXE_FAILURE_STRING; + case (11104): + return CRC_FAILURE_EVENT_STRING; + default: + return "UNKNOWN_EVENT"; + } + return 0; } diff --git a/bsp_hosted/fsfwconfig/events/translateEvents.h b/bsp_hosted/fsfwconfig/events/translateEvents.h index 9034dcf2..a42d9b5a 100644 --- a/bsp_hosted/fsfwconfig/events/translateEvents.h +++ b/bsp_hosted/fsfwconfig/events/translateEvents.h @@ -3,6 +3,6 @@ #include -const char * translateEvents(Event event); +const char* translateEvents(Event event); #endif /* FSFWCONFIG_EVENTS_TRANSLATEEVENTS_H_ */ diff --git a/bsp_hosted/fsfwconfig/fsfwconfig.mk b/bsp_hosted/fsfwconfig/fsfwconfig.mk deleted file mode 100644 index 53cb0fc7..00000000 --- a/bsp_hosted/fsfwconfig/fsfwconfig.mk +++ /dev/null @@ -1,7 +0,0 @@ -CXXSRC += $(wildcard $(CURRENTPATH)/cdatapool/*.cpp) -CXXSRC += $(wildcard $(CURRENTPATH)/ipc/*.cpp) -CXXSRC += $(wildcard $(CURRENTPATH)/objects/*.cpp) -CXXSRC += $(wildcard $(CURRENTPATH)/pollingsequence/*.cpp) -CXXSRC += $(wildcard $(CURRENTPATH)/events/*.cpp) - -INCLUDES += $(CURRENTPATH) \ No newline at end of file diff --git a/bsp_hosted/fsfwconfig/ipc/MissionMessageTypes.cpp b/bsp_hosted/fsfwconfig/ipc/MissionMessageTypes.cpp index 36ef1b73..fa1c4877 100644 --- a/bsp_hosted/fsfwconfig/ipc/MissionMessageTypes.cpp +++ b/bsp_hosted/fsfwconfig/ipc/MissionMessageTypes.cpp @@ -1,11 +1,10 @@ #include "MissionMessageTypes.h" + #include void messagetypes::clearMissionMessage(CommandMessage* message) { - switch(message->getMessageType()) { - default: - break; - } + switch (message->getMessageType()) { + default: + break; + } } - - diff --git a/bsp_hosted/fsfwconfig/ipc/MissionMessageTypes.h b/bsp_hosted/fsfwconfig/ipc/MissionMessageTypes.h index 7e3c448f..1d93ba21 100644 --- a/bsp_hosted/fsfwconfig/ipc/MissionMessageTypes.h +++ b/bsp_hosted/fsfwconfig/ipc/MissionMessageTypes.h @@ -13,10 +13,10 @@ class CommandMessage; */ namespace messagetypes { enum MESSAGE_TYPE { - MISSION_MESSAGE_TYPE_START = FW_MESSAGES_COUNT, + MISSION_MESSAGE_TYPE_START = FW_MESSAGES_COUNT, }; void clearMissionMessage(CommandMessage* message); -} +} // namespace messagetypes #endif /* CONFIG_IPC_MISSIONMESSAGETYPES_H_ */ diff --git a/bsp_hosted/fsfwconfig/objects/systemObjectList.h b/bsp_hosted/fsfwconfig/objects/systemObjectList.h index 21a5f939..91bd2bed 100644 --- a/bsp_hosted/fsfwconfig/objects/systemObjectList.h +++ b/bsp_hosted/fsfwconfig/objects/systemObjectList.h @@ -1,31 +1,32 @@ #ifndef HOSTED_CONFIG_OBJECTS_SYSTEMOBJECTLIST_H_ #define HOSTED_CONFIG_OBJECTS_SYSTEMOBJECTLIST_H_ -#include #include +#include + // The objects will be instantiated in the ID order namespace objects { - enum sourceObjects: uint32_t { +enum sourceObjects : uint32_t { - PUS_SERVICE_3 = 0x51000300, - PUS_SERVICE_5 = 0x51000400, - PUS_SERVICE_6 = 0x51000500, - PUS_SERVICE_8 = 0x51000800, - PUS_SERVICE_23 = 0x51002300, - PUS_SERVICE_201 = 0x51020100, + PUS_SERVICE_3 = 0x51000300, + PUS_SERVICE_5 = 0x51000400, + PUS_SERVICE_6 = 0x51000500, + PUS_SERVICE_8 = 0x51000800, + PUS_SERVICE_23 = 0x51002300, + PUS_SERVICE_201 = 0x51020100, - TM_FUNNEL = 0x52000002, + TM_FUNNEL = 0x52000002, - /* Test Task */ + /* Test Task */ - TEST_TASK = 0x42694269, - DUMMY_INTERFACE = 0xCAFECAFE, - DUMMY_HANDLER = 0x4400AFFE, + TEST_TASK = 0x42694269, + DUMMY_INTERFACE = 0xCAFECAFE, + DUMMY_HANDLER = 0x4400AFFE, - /* 0x49 ('I') for Communication Interfaces **/ - ARDUINO_COM_IF = 0x49000001 - }; + /* 0x49 ('I') for Communication Interfaces **/ + ARDUINO_COM_IF = 0x49000001 +}; } #endif /* BSP_CONFIG_OBJECTS_SYSTEMOBJECTLIST_H_ */ diff --git a/bsp_hosted/fsfwconfig/objects/translateObjects.cpp b/bsp_hosted/fsfwconfig/objects/translateObjects.cpp index 9aac2b47..f29e4d65 100644 --- a/bsp_hosted/fsfwconfig/objects/translateObjects.cpp +++ b/bsp_hosted/fsfwconfig/objects/translateObjects.cpp @@ -1,4 +1,4 @@ -/** +/** * @brief Auto-generated object translation file. * @details * Contains 31 translations. @@ -38,72 +38,72 @@ const char *FSFW_OBJECTS_END_STRING = "FSFW_OBJECTS_END"; const char *DUMMY_INTERFACE_STRING = "DUMMY_INTERFACE"; const char *NO_OBJECT_STRING = "NO_OBJECT"; -const char* translateObject(object_id_t object) { - switch( (object & 0xFFFFFFFF) ) { - case 0x42694269: - return TEST_TASK_STRING; - case 0x4400AFFE: - return DUMMY_HANDLER_STRING; - case 0x49000001: - return ARDUINO_COM_IF_STRING; - case 0x51000300: - return PUS_SERVICE_3_STRING; - case 0x51000400: - return PUS_SERVICE_5_STRING; - case 0x51000500: - return PUS_SERVICE_6_STRING; - case 0x51000800: - return PUS_SERVICE_8_STRING; - case 0x51002300: - return PUS_SERVICE_23_STRING; - case 0x51020100: - return PUS_SERVICE_201_STRING; - case 0x52000002: - return TM_FUNNEL_STRING; - case 0x53000000: - return FSFW_OBJECTS_START_STRING; - case 0x53000001: - return PUS_SERVICE_1_VERIFICATION_STRING; - case 0x53000002: - return PUS_SERVICE_2_DEVICE_ACCESS_STRING; - case 0x53000003: - return PUS_SERVICE_3_HOUSEKEEPING_STRING; - case 0x53000005: - return PUS_SERVICE_5_EVENT_REPORTING_STRING; - case 0x53000008: - return PUS_SERVICE_8_FUNCTION_MGMT_STRING; - case 0x53000009: - return PUS_SERVICE_9_TIME_MGMT_STRING; - case 0x53000017: - return PUS_SERVICE_17_TEST_STRING; - case 0x53000020: - return PUS_SERVICE_20_PARAMETERS_STRING; - case 0x53000200: - return PUS_SERVICE_200_MODE_MGMT_STRING; - case 0x53010000: - return HEALTH_TABLE_STRING; - case 0x53010100: - return MODE_STORE_STRING; - case 0x53030000: - return EVENT_MANAGER_STRING; - case 0x53040000: - return INTERNAL_ERROR_REPORTER_STRING; - case 0x534f0100: - return TC_STORE_STRING; - case 0x534f0200: - return TM_STORE_STRING; - case 0x534f0300: - return IPC_STORE_STRING; - case 0x53500010: - return TIME_STAMPER_STRING; - case 0x53ffffff: - return FSFW_OBJECTS_END_STRING; - case 0xCAFECAFE: - return DUMMY_INTERFACE_STRING; - case 0xFFFFFFFF: - return NO_OBJECT_STRING; - default: - return "UNKNOWN_OBJECT"; - } - return 0; +const char *translateObject(object_id_t object) { + switch ((object & 0xFFFFFFFF)) { + case 0x42694269: + return TEST_TASK_STRING; + case 0x4400AFFE: + return DUMMY_HANDLER_STRING; + case 0x49000001: + return ARDUINO_COM_IF_STRING; + case 0x51000300: + return PUS_SERVICE_3_STRING; + case 0x51000400: + return PUS_SERVICE_5_STRING; + case 0x51000500: + return PUS_SERVICE_6_STRING; + case 0x51000800: + return PUS_SERVICE_8_STRING; + case 0x51002300: + return PUS_SERVICE_23_STRING; + case 0x51020100: + return PUS_SERVICE_201_STRING; + case 0x52000002: + return TM_FUNNEL_STRING; + case 0x53000000: + return FSFW_OBJECTS_START_STRING; + case 0x53000001: + return PUS_SERVICE_1_VERIFICATION_STRING; + case 0x53000002: + return PUS_SERVICE_2_DEVICE_ACCESS_STRING; + case 0x53000003: + return PUS_SERVICE_3_HOUSEKEEPING_STRING; + case 0x53000005: + return PUS_SERVICE_5_EVENT_REPORTING_STRING; + case 0x53000008: + return PUS_SERVICE_8_FUNCTION_MGMT_STRING; + case 0x53000009: + return PUS_SERVICE_9_TIME_MGMT_STRING; + case 0x53000017: + return PUS_SERVICE_17_TEST_STRING; + case 0x53000020: + return PUS_SERVICE_20_PARAMETERS_STRING; + case 0x53000200: + return PUS_SERVICE_200_MODE_MGMT_STRING; + case 0x53010000: + return HEALTH_TABLE_STRING; + case 0x53010100: + return MODE_STORE_STRING; + case 0x53030000: + return EVENT_MANAGER_STRING; + case 0x53040000: + return INTERNAL_ERROR_REPORTER_STRING; + case 0x534f0100: + return TC_STORE_STRING; + case 0x534f0200: + return TM_STORE_STRING; + case 0x534f0300: + return IPC_STORE_STRING; + case 0x53500010: + return TIME_STAMPER_STRING; + case 0x53ffffff: + return FSFW_OBJECTS_END_STRING; + case 0xCAFECAFE: + return DUMMY_INTERFACE_STRING; + case 0xFFFFFFFF: + return NO_OBJECT_STRING; + default: + return "UNKNOWN_OBJECT"; + } + return 0; } diff --git a/bsp_hosted/fsfwconfig/returnvalues/classIds.h b/bsp_hosted/fsfwconfig/returnvalues/classIds.h index cc159fec..b50e8ac0 100644 --- a/bsp_hosted/fsfwconfig/returnvalues/classIds.h +++ b/bsp_hosted/fsfwconfig/returnvalues/classIds.h @@ -1,9 +1,10 @@ #ifndef CONFIG_RETURNVALUES_CLASSIDS_H_ #define CONFIG_RETURNVALUES_CLASSIDS_H_ -#include "commonClassIds.h" #include +#include "commonClassIds.h" + /** * Source IDs starts at 73 for now * Framework IDs for ReturnValues run from 0 to 56 @@ -11,9 +12,8 @@ */ namespace CLASS_ID { enum { - CLASS_ID_START = COMMON_CLASS_ID_END, + CLASS_ID_START = COMMON_CLASS_ID_END, }; } - #endif /* CONFIG_RETURNVALUES_CLASSIDS_H_ */ diff --git a/bsp_hosted/fsfwconfig/tmtc/apid.h b/bsp_hosted/fsfwconfig/tmtc/apid.h index ee2fc7c4..9d5c9ed5 100644 --- a/bsp_hosted/fsfwconfig/tmtc/apid.h +++ b/bsp_hosted/fsfwconfig/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/bsp_hosted/fsfwconfig/tmtc/pusIds.h index a2dd7575..37503786 100644 --- a/bsp_hosted/fsfwconfig/tmtc/pusIds.h +++ b/bsp_hosted/fsfwconfig/tmtc/pusIds.h @@ -2,21 +2,21 @@ #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, +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, }; }; diff --git a/bsp_hosted/main.cpp b/bsp_hosted/main.cpp index 153cc447..b7ebc422 100644 --- a/bsp_hosted/main.cpp +++ b/bsp_hosted/main.cpp @@ -1,10 +1,9 @@ +#include + #include "InitMission.h" #include "OBSWVersion.h" - #include "fsfw/FSFWVersion.h" #include "fsfw/tasks/TaskFactory.h" - -#include #ifdef WIN32 static const char* COMPILE_PRINTOUT = "Windows"; #elif LINUX @@ -17,21 +16,18 @@ static const char* COMPILE_PRINTOUT = "unknown OS"; * Linux and Windows. * @return */ -int main(void) -{ - std::cout << "-- EIVE OBSW --" << std::endl; - std::cout << "-- Compiled for " << COMPILE_PRINTOUT << " --" << std::endl; - std::cout << "-- OBSW " << SW_NAME << " v" << SW_VERSION << "." << SW_SUBVERSION << - "." << SW_REVISION << ", FSFW v" << FSFW_VERSION << "." << FSFW_SUBVERSION << "." << - FSFW_REVISION << "--" << std::endl; - std::cout << "-- " << __DATE__ << " " << __TIME__ << " --" << std::endl; +int main(void) { + std::cout << "-- EIVE OBSW --" << std::endl; + std::cout << "-- Compiled for " << COMPILE_PRINTOUT << " --" << std::endl; + std::cout << "-- OBSW " << SW_NAME << " v" << SW_VERSION << "." << SW_SUBVERSION << "." + << SW_REVISION << ", FSFW v" << FSFW_VERSION << "." << FSFW_SUBVERSION << "." + << FSFW_REVISION << "--" << std::endl; + std::cout << "-- " << __DATE__ << " " << __TIME__ << " --" << std::endl; - initmission::initMission(); + initmission::initMission(); - for(;;) { - // suspend main thread by sleeping it. - TaskFactory::delayTask(5000); - } + for (;;) { + // suspend main thread by sleeping it. + TaskFactory::delayTask(5000); + } } - - diff --git a/bsp_linux_board/CMakeLists.txt b/bsp_linux_board/CMakeLists.txt index 5963d48c..0272f476 100644 --- a/bsp_linux_board/CMakeLists.txt +++ b/bsp_linux_board/CMakeLists.txt @@ -1,4 +1,4 @@ -target_sources(${TARGET_NAME} PUBLIC +target_sources(${OBSW_NAME} PUBLIC InitMission.cpp main.cpp ObjectFactory.cpp diff --git a/bsp_linux_board/InitMission.cpp b/bsp_linux_board/InitMission.cpp index d265fded..6dfe3af1 100644 --- a/bsp_linux_board/InitMission.cpp +++ b/bsp_linux_board/InitMission.cpp @@ -1,247 +1,245 @@ #include "InitMission.h" -#include "ObjectFactory.h" -#include "objects/systemObjectList.h" -#include "OBSWConfig.h" -#include "pollingsequence/pollingSequenceFactory.h" - -#include +#include #include #include #include -#include #include #include #include +#include #include +#include "OBSWConfig.h" +#include "ObjectFactory.h" +#include "objects/systemObjectList.h" +#include "pollingsequence/pollingSequenceFactory.h" + ServiceInterfaceStream sif::debug("DEBUG"); ServiceInterfaceStream sif::info("INFO"); ServiceInterfaceStream sif::warning("WARNING"); ServiceInterfaceStream sif::error("ERROR"); -ObjectManagerIF *objectManager = nullptr; +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); - sif::info << "Initializing all objects.." << std::endl; - ObjectManager::instance()->initialize(); + sif::info << "Building global objects.." << std::endl; + /* Instantiate global object manager and also create all objects */ + ObjectManager::instance()->setObjectFactoryFunction(ObjectFactory::produce, nullptr); + sif::info << "Initializing all objects.." << std::endl; + ObjectManager::instance()->initialize(); - /* This function creates and starts all tasks */ - initTasks(); + /* This function creates and starts all tasks */ + initTasks(); } void initmission::initTasks() { - TaskFactory* factory = TaskFactory::instance(); - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - if(factory == nullptr) { - /* Should never happen ! */ - return; - } + TaskFactory* factory = TaskFactory::instance(); + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + if (factory == nullptr) { + /* Should never happen ! */ + return; + } #if OBSW_PRINT_MISSED_DEADLINES == 1 - void (*missedDeadlineFunc) (void) = TaskFactory::printMissedDeadline; + void (*missedDeadlineFunc)(void) = TaskFactory::printMissedDeadline; #else - void (*missedDeadlineFunc) (void) = nullptr; + void (*missedDeadlineFunc)(void) = nullptr; #endif + /* TMTC Distribution */ + PeriodicTaskIF* tmTcDistributor = factory->createPeriodicTask( + "DIST", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc); + result = tmTcDistributor->addComponent(objects::CCSDS_PACKET_DISTRIBUTOR); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "Object add component failed" << std::endl; + } + result = tmTcDistributor->addComponent(objects::PUS_PACKET_DISTRIBUTOR); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "Object add component failed" << std::endl; + } + result = tmTcDistributor->addComponent(objects::TM_FUNNEL); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "Object add component failed" << std::endl; + } - /* TMTC Distribution */ - PeriodicTaskIF* tmTcDistributor = factory->createPeriodicTask( - "DIST", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc); - result = tmTcDistributor->addComponent(objects::CCSDS_PACKET_DISTRIBUTOR); - if(result != HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } - result = tmTcDistributor->addComponent(objects::PUS_PACKET_DISTRIBUTOR); - if(result != HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } - result = tmTcDistributor->addComponent(objects::TM_FUNNEL); - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::error << "Object add component failed" << std::endl; - } + /* UDP bridge */ + PeriodicTaskIF* tmtcBridgeTask = factory->createPeriodicTask( + "TMTC_BRIDGE", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc); + result = tmtcBridgeTask->addComponent(objects::TMTC_BRIDGE); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "Add component TMTC Bridge failed" << std::endl; + } + PeriodicTaskIF* tmtcPollingTask = factory->createPeriodicTask( + "TMTC_POLLING", 80, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc); + result = tmtcPollingTask->addComponent(objects::TMTC_POLLING_TASK); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "Add component TMTC Polling failed" << std::endl; + } - /* UDP bridge */ - PeriodicTaskIF* udpBridgeTask = factory->createPeriodicTask( - "UDP_UNIX_BRIDGE", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc); - result = udpBridgeTask->addComponent(objects::TMTC_BRIDGE); - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::error << "Add component UDP Unix Bridge failed" << std::endl; - } - PeriodicTaskIF* udpPollingTask = factory->createPeriodicTask( - "UDP_POLLING", 80, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc); - result = udpPollingTask->addComponent(objects::TMTC_POLLING_TASK); - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::error << "Add component UDP Polling failed" << std::endl; - } + /* PUS Services */ + std::vector pusTasks; + createPusTasks(*factory, missedDeadlineFunc, pusTasks); - /* PUS Services */ - std::vector pusTasks; - createPusTasks(*factory, missedDeadlineFunc, pusTasks); - - std::vector pstTasks; - createPstTasks(*factory, missedDeadlineFunc, pstTasks); + std::vector pstTasks; + createPstTasks(*factory, missedDeadlineFunc, pstTasks); #if OBSW_ADD_TEST_CODE == 1 - std::vector testTasks; - createTestTasks(*factory, missedDeadlineFunc, pstTasks); + std::vector testTasks; + createTestTasks(*factory, missedDeadlineFunc, pstTasks); #endif /* OBSW_ADD_TEST_CODE == 1 */ - auto taskStarter = [](std::vector& taskVector, std::string name) { - for(const auto& task: taskVector) { - if(task != nullptr) { - task->startTask(); - } - else { - sif::error << "Task in vector " << name << " is invalid!" << std::endl; - } - } - }; + auto taskStarter = [](std::vector& taskVector, std::string name) { + for (const auto& task : taskVector) { + if (task != nullptr) { + task->startTask(); + } else { + sif::error << "Task in vector " << name << " is invalid!" << std::endl; + } + } + }; - sif::info << "Starting tasks.." << std::endl; - tmTcDistributor->startTask(); - udpBridgeTask->startTask(); - udpPollingTask->startTask(); + sif::info << "Starting tasks.." << std::endl; + tmTcDistributor->startTask(); + tmtcBridgeTask->startTask(); + tmtcPollingTask->startTask(); - taskStarter(pusTasks, "PUS Tasks"); + taskStarter(pusTasks, "PUS Tasks"); #if OBSW_ADD_TEST_CODE == 1 - taskStarter(testTasks, "Test Tasks"); + taskStarter(testTasks, "Test Tasks"); #endif /* OBSW_ADD_TEST_CODE == 1 */ - taskStarter(pstTasks, "PST Tasks"); + taskStarter(pstTasks, "PST Tasks"); #if OBSW_ADD_TEST_PST == 1 - if(startTestPst) { - pstTestTask->startTask(); - } + if (startTestPst) { + pstTestTask->startTask(); + } #endif /* RPI_TEST_ACS_BOARD == 1 */ - sif::info << "Tasks started.." << std::endl; + sif::info << "Tasks started.." << std::endl; } void initmission::createPusTasks(TaskFactory& factory, - TaskDeadlineMissedFunction missedDeadlineFunc, std::vector& taskVec) { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - PeriodicTaskIF* pusVerification = factory.createPeriodicTask( - "PUS_VERIF", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); - result = pusVerification->addComponent(objects::PUS_SERVICE_1_VERIFICATION); - if(result != HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } - taskVec.push_back(pusVerification); + TaskDeadlineMissedFunction missedDeadlineFunc, + std::vector& taskVec) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + PeriodicTaskIF* pusVerification = factory.createPeriodicTask( + "PUS_VERIF", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); + result = pusVerification->addComponent(objects::PUS_SERVICE_1_VERIFICATION); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "Object add component failed" << std::endl; + } + taskVec.push_back(pusVerification); - PeriodicTaskIF* pusEvents = factory.createPeriodicTask( - "PUS_EVENTS", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); - result = pusEvents->addComponent(objects::PUS_SERVICE_5_EVENT_REPORTING); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("PUS_EVENTS", objects::PUS_SERVICE_5_EVENT_REPORTING); - } - result = pusEvents->addComponent(objects::EVENT_MANAGER); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("PUS_MGMT", objects::EVENT_MANAGER); - } - taskVec.push_back(pusEvents); + PeriodicTaskIF* pusEvents = factory.createPeriodicTask( + "PUS_EVENTS", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); + result = pusEvents->addComponent(objects::PUS_SERVICE_5_EVENT_REPORTING); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS_EVENTS", objects::PUS_SERVICE_5_EVENT_REPORTING); + } + result = pusEvents->addComponent(objects::EVENT_MANAGER); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS_MGMT", objects::EVENT_MANAGER); + } + taskVec.push_back(pusEvents); - PeriodicTaskIF* pusHighPrio = factory.createPeriodicTask( - "PUS_HIGH_PRIO", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); - result = pusHighPrio->addComponent(objects::PUS_SERVICE_2_DEVICE_ACCESS); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("PUS2", objects::PUS_SERVICE_2_DEVICE_ACCESS); - } - result = pusHighPrio->addComponent(objects::PUS_SERVICE_9_TIME_MGMT); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("PUS9", objects::PUS_SERVICE_9_TIME_MGMT); - } - taskVec.push_back(pusHighPrio); + PeriodicTaskIF* pusHighPrio = factory.createPeriodicTask( + "PUS_HIGH_PRIO", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); + result = pusHighPrio->addComponent(objects::PUS_SERVICE_2_DEVICE_ACCESS); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS2", objects::PUS_SERVICE_2_DEVICE_ACCESS); + } + result = pusHighPrio->addComponent(objects::PUS_SERVICE_9_TIME_MGMT); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS9", objects::PUS_SERVICE_9_TIME_MGMT); + } + taskVec.push_back(pusHighPrio); - PeriodicTaskIF* pusMedPrio = factory.createPeriodicTask( - "PUS_MED_PRIO", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.8, missedDeadlineFunc); - result = pusMedPrio->addComponent(objects::PUS_SERVICE_8_FUNCTION_MGMT); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("PUS8", objects::PUS_SERVICE_8_FUNCTION_MGMT); - } - result = pusMedPrio->addComponent(objects::PUS_SERVICE_200_MODE_MGMT); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("PUS200", objects::PUS_SERVICE_200_MODE_MGMT); - } - result = pusMedPrio->addComponent(objects::PUS_SERVICE_20_PARAMETERS); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("PUS20", objects::PUS_SERVICE_20_PARAMETERS); - } - result = pusMedPrio->addComponent(objects::PUS_SERVICE_3_HOUSEKEEPING); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("PUS3", objects::PUS_SERVICE_3_HOUSEKEEPING); - } - taskVec.push_back(pusMedPrio); + PeriodicTaskIF* pusMedPrio = factory.createPeriodicTask( + "PUS_MED_PRIO", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.8, missedDeadlineFunc); + result = pusMedPrio->addComponent(objects::PUS_SERVICE_8_FUNCTION_MGMT); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS8", objects::PUS_SERVICE_8_FUNCTION_MGMT); + } + result = pusMedPrio->addComponent(objects::PUS_SERVICE_200_MODE_MGMT); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS200", objects::PUS_SERVICE_200_MODE_MGMT); + } + result = pusMedPrio->addComponent(objects::PUS_SERVICE_20_PARAMETERS); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS20", objects::PUS_SERVICE_20_PARAMETERS); + } + result = pusMedPrio->addComponent(objects::PUS_SERVICE_3_HOUSEKEEPING); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS3", objects::PUS_SERVICE_3_HOUSEKEEPING); + } + taskVec.push_back(pusMedPrio); - PeriodicTaskIF* pusLowPrio = factory.createPeriodicTask( - "PUS_LOW_PRIO", 30, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.6, missedDeadlineFunc); - result = pusLowPrio->addComponent(objects::PUS_SERVICE_17_TEST); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("PUS17", objects::PUS_SERVICE_17_TEST); - } - result = pusLowPrio->addComponent(objects::INTERNAL_ERROR_REPORTER); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("INT_ERR_RPRT", - objects::INTERNAL_ERROR_REPORTER); - } - taskVec.push_back(pusLowPrio); + PeriodicTaskIF* pusLowPrio = factory.createPeriodicTask( + "PUS_LOW_PRIO", 30, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.6, missedDeadlineFunc); + result = pusLowPrio->addComponent(objects::PUS_SERVICE_17_TEST); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS17", objects::PUS_SERVICE_17_TEST); + } + result = pusLowPrio->addComponent(objects::INTERNAL_ERROR_REPORTER); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("INT_ERR_RPRT", objects::INTERNAL_ERROR_REPORTER); + } + taskVec.push_back(pusLowPrio); } void initmission::createPstTasks(TaskFactory& factory, - TaskDeadlineMissedFunction missedDeadlineFunc, std::vector &taskVec) { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + TaskDeadlineMissedFunction missedDeadlineFunc, + std::vector& taskVec) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; #if OBSW_ADD_SPI_TEST_CODE == 0 - FixedTimeslotTaskIF* spiPst = factory.createFixedTimeslotTask( - "SPI_PST", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 3.0, - missedDeadlineFunc); - result = pst::pstSpi(spiPst); - if (result != HasReturnvaluesIF::RETURN_OK) { - sif::error << "InitMission::initTasks: Creating PST failed!" << std::endl; - } - taskVec.push_back(spiPst); + FixedTimeslotTaskIF* spiPst = factory.createFixedTimeslotTask( + "SPI_PST", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 3.0, missedDeadlineFunc); + result = pst::pstSpi(spiPst); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "InitMission::initTasks: Creating PST failed!" << std::endl; + } + taskVec.push_back(spiPst); #endif } void initmission::createTestTasks(TaskFactory& factory, - TaskDeadlineMissedFunction missedDeadlineFunc, - std::vector &taskVec) { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - PeriodicTaskIF* testTask = factory.createPeriodicTask( - "TEST_TASK", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc); - result = testTask->addComponent(objects::TEST_TASK); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("TEST_TASK", objects::TEST_TASK); - } -#if RPI_ADD_SPI_TEST == 1 - result = testTask->addComponent(objects::SPI_TEST); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("SPI_TEST", objects::SPI_TEST); - } + TaskDeadlineMissedFunction missedDeadlineFunc, + std::vector& taskVec) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + PeriodicTaskIF* testTask = factory.createPeriodicTask( + "TEST_TASK", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc); + result = testTask->addComponent(objects::TEST_TASK); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("TEST_TASK", objects::TEST_TASK); + } +#if OBSW_ADD_SPI_TEST_CODE == 1 + result = testTask->addComponent(objects::SPI_TEST); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("SPI_TEST", objects::SPI_TEST); + } #endif /* RPI_ADD_SPI_TEST == 1 */ #if RPI_ADD_GPIO_TEST == 1 - result = testTask->addComponent(objects::LIBGPIOD_TEST); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("GPIOD_TEST", objects::LIBGPIOD_TEST); - } + result = testTask->addComponent(objects::LIBGPIOD_TEST); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("GPIOD_TEST", objects::LIBGPIOD_TEST); + } #endif /* RPI_ADD_GPIO_TEST == 1 */ -#if RPI_ADD_UART_TEST == 1 - result = testTask->addComponent(objects::UART_TEST); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("UART_TEST", objects::UART_TEST); - } +#if OBSW_ADD_UART_TEST_CODE == 1 + result = testTask->addComponent(objects::UART_TEST); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("UART_TEST", objects::UART_TEST); + } #endif /* RPI_ADD_GPIO_TEST == 1 */ + taskVec.push_back(testTask); - bool startTestPst = true; - static_cast(startTestPst); + bool startTestPst = true; + static_cast(startTestPst); #if OBSW_ADD_TEST_PST == 1 - FixedTimeslotTaskIF* pstTestTask = factory->createFixedTimeslotTask("TEST_PST", 50, - PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, 2.0, missedDeadlineFunc); - result = pst::pstTest(pstTestTask); - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::info << "initmission::initTasks: ACS PST empty or invalid" << std::endl; - startTestPst = false; - } + FixedTimeslotTaskIF* pstTestTask = factory->createFixedTimeslotTask( + "TEST_PST", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, 2.0, missedDeadlineFunc); + result = pst::pstTest(pstTestTask); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::info << "initmission::initTasks: ACS PST empty or invalid" << std::endl; + startTestPst = false; + } #endif /* RPI_TEST_ACS_BOARD == 1 */ - } diff --git a/bsp_linux_board/InitMission.h b/bsp_linux_board/InitMission.h index f5da5855..f14135dd 100644 --- a/bsp_linux_board/InitMission.h +++ b/bsp_linux_board/InitMission.h @@ -1,9 +1,10 @@ #ifndef BSP_LINUX_INITMISSION_H_ #define BSP_LINUX_INITMISSION_H_ -#include "fsfw/tasks/Typedef.h" #include +#include "fsfw/tasks/Typedef.h" + class PeriodicTaskIF; class TaskFactory; @@ -11,14 +12,12 @@ namespace initmission { void initMission(); void initTasks(); -void createPstTasks(TaskFactory& factory, - TaskDeadlineMissedFunction missedDeadlineFunc, - std::vector &taskVec); -void createTestTasks(TaskFactory& factory, - TaskDeadlineMissedFunction missedDeadlineFunc, - std::vector &taskVec); +void createPstTasks(TaskFactory& factory, TaskDeadlineMissedFunction missedDeadlineFunc, + std::vector& taskVec); +void createTestTasks(TaskFactory& factory, TaskDeadlineMissedFunction missedDeadlineFunc, + std::vector& taskVec); void createPusTasks(TaskFactory& factory, TaskDeadlineMissedFunction missedDeadlineFunc, - std::vector& taskVec); -}; + std::vector& taskVec); +}; // namespace initmission #endif /* BSP_LINUX_INITMISSION_H_ */ diff --git a/bsp_linux_board/ObjectFactory.cpp b/bsp_linux_board/ObjectFactory.cpp index 5cd52c91..18da8896 100644 --- a/bsp_linux_board/ObjectFactory.cpp +++ b/bsp_linux_board/ObjectFactory.cpp @@ -1,236 +1,230 @@ -#include #include "ObjectFactory.h" -#include "objects/systemObjectList.h" +#include "OBSWConfig.h" +#include "devConf.h" #include "devices/addresses.h" #include "devices/gpioIds.h" -#include "OBSWConfig.h" -#include "tmtc/apid.h" -#include "tmtc/pusIds.h" +#include "fsfw/datapoollocal/LocalDataPoolManager.h" +#include "fsfw/tasks/TaskFactory.h" +#include "fsfw/tmtcpacket/pus/tm.h" +#include "fsfw/tmtcservices/CommandingServiceBase.h" +#include "fsfw/tmtcservices/PusServiceBase.h" #include "linux/boardtest/LibgpiodTest.h" #include "linux/boardtest/SpiTestClass.h" #include "linux/boardtest/UartTestClass.h" - #include "mission/core/GenericFactory.h" +#include "mission/devices/GPSHyperionHandler.h" +#include "mission/devices/GyroADIS1650XHandler.h" #include "mission/utility/TmFunnel.h" -#include -#include "mission/devices/GyroADIS16507Handler.h" - -#include "fsfw/datapoollocal/LocalDataPoolManager.h" -#include "fsfw/tmtcservices/CommandingServiceBase.h" -#include "fsfw/tmtcservices/PusServiceBase.h" -#include "fsfw/tmtcpacket/pus/tm.h" -#include "fsfw/tasks/TaskFactory.h" +#include "objects/systemObjectList.h" +#include "tmtc/apid.h" +#include "tmtc/pusIds.h" /* UDP server includes */ #if OBSW_USE_TMTC_TCP_BRIDGE == 1 #include #include #else -#include "fsfw/osal/common/UdpTmTcBridge.h" #include "fsfw/osal/common/UdpTcPollingTask.h" +#include "fsfw/osal/common/UdpTmTcBridge.h" #endif -#include "fsfw_hal/devicehandlers/MgmLIS3MDLHandler.h" -#include "fsfw_hal/devicehandlers/MgmRM3100Handler.h" -#include "fsfw_hal/devicehandlers/GyroL3GD20Handler.h" -#include "fsfw_hal/linux/gpio/LinuxLibgpioIF.h" -#include "fsfw_hal/linux/rpi/GpioRPi.h" -#include "fsfw_hal/common/gpio/GpioCookie.h" -#include "fsfw_hal/linux/spi/SpiCookie.h" -#include "fsfw_hal/linux/spi/SpiComIF.h" #include #include +#include "fsfw_hal/common/gpio/GpioCookie.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/rpi/GpioRPi.h" +#include "fsfw_hal/linux/spi/SpiComIF.h" +#include "fsfw_hal/linux/spi/SpiCookie.h" + void Factory::setStaticFrameworkObjectIds() { - PusServiceBase::packetSource = objects::PUS_PACKET_DISTRIBUTOR; - PusServiceBase::packetDestination = objects::TM_FUNNEL; + PusServiceBase::packetSource = objects::PUS_PACKET_DISTRIBUTOR; + PusServiceBase::packetDestination = objects::TM_FUNNEL; - CommandingServiceBase::defaultPacketSource = objects::PUS_PACKET_DISTRIBUTOR; - CommandingServiceBase::defaultPacketDestination = objects::TM_FUNNEL; + CommandingServiceBase::defaultPacketSource = objects::PUS_PACKET_DISTRIBUTOR; + CommandingServiceBase::defaultPacketDestination = objects::TM_FUNNEL; - TmFunnel::downlinkDestination = objects::TMTC_BRIDGE; - // No storage object for now. - TmFunnel::storageDestination = objects::NO_OBJECT; + TmFunnel::downlinkDestination = objects::TMTC_BRIDGE; + // No storage object for now. + TmFunnel::storageDestination = objects::NO_OBJECT; - VerificationReporter::messageReceiver = objects::PUS_SERVICE_1_VERIFICATION; - TmPacketBase::timeStamperId = objects::TIME_STAMPER; + VerificationReporter::messageReceiver = objects::PUS_SERVICE_1_VERIFICATION; + TmPacketBase::timeStamperId = objects::TIME_STAMPER; } +void ObjectFactory::produce(void* args) { + Factory::setStaticFrameworkObjectIds(); + ObjectFactory::produceGenericObjects(); + GpioIF* gpioIF = new LinuxLibgpioIF(objects::GPIO_IF); + GpioCookie* gpioCookie = nullptr; + static_cast(gpioCookie); -void ObjectFactory::produce(void* args){ - Factory::setStaticFrameworkObjectIds(); - ObjectFactory::produceGenericObjects(); + new SpiComIF(objects::SPI_COM_IF, gpioIF); -#if OBSW_USE_TMTC_TCP_BRIDGE == 1 - auto tmtcBridge = new TcpTmTcBridge(objects::TMTC_BRIDGE, objects::CCSDS_PACKET_DISTRIBUTOR); - tmtcBridge->setMaxNumberOfPacketsStored(50); - new TcpTmTcServer(objects::TMTC_POLLING_TASK, objects::TMTC_BRIDGE); -#else - auto tmtcBridge = new UdpTmTcBridge(objects::TMTC_BRIDGE, objects::CCSDS_PACKET_DISTRIBUTOR); - tmtcBridge->setMaxNumberOfPacketsStored(50); - new UdpTcPollingTask(objects::TMTC_POLLING_TASK, objects::TMTC_BRIDGE); -#endif - - GpioIF* gpioIF = new LinuxLibgpioIF(objects::GPIO_IF); - GpioCookie* gpioCookie = nullptr; - static_cast(gpioCookie); - - new SpiComIF(objects::SPI_COM_IF, gpioIF); - - std::string spiDev; - SpiCookie* spiCookie = nullptr; - static_cast(spiCookie); + std::string spiDev; + SpiCookie* spiCookie = nullptr; + static_cast(spiCookie); #if OBSW_ADD_ACS_BOARD == 1 - if(gpioCookie == nullptr) { - gpioCookie = new GpioCookie(); - } - // TODO: Missing pin for Gyro 2 - gpio::createRpiGpioConfig(gpioCookie, gpioIds::MGM_0_LIS3_CS, gpio::MGM_0_BCM_PIN, - "MGM_0_LIS3", gpio::Direction::OUT, 1); - gpio::createRpiGpioConfig(gpioCookie, gpioIds::MGM_1_RM3100_CS, gpio::MGM_1_BCM_PIN, - "MGM_1_RM3100", gpio::Direction::OUT, 1); - gpio::createRpiGpioConfig(gpioCookie, gpioIds::MGM_2_LIS3_CS, gpio::MGM_2_BCM_PIN, - "MGM_2_LIS3", gpio::Direction::OUT, 1); - gpio::createRpiGpioConfig(gpioCookie, gpioIds::MGM_3_RM3100_CS, gpio::MGM_3_BCM_PIN, - "MGM_3_RM3100", gpio::Direction::OUT, 1); - gpio::createRpiGpioConfig(gpioCookie, gpioIds::GYRO_0_ADIS_CS, gpio::GYRO_0_BCM_PIN, - "GYRO_0_ADIS", gpio::Direction::OUT, 1); - gpio::createRpiGpioConfig(gpioCookie, gpioIds::GYRO_1_L3G_CS, gpio::GYRO_1_BCM_PIN, - "GYRO_1_L3G", gpio::Direction::OUT, 1); - gpio::createRpiGpioConfig(gpioCookie, gpioIds::GYRO_2_ADIS_CS, gpio::GYRO_2_BCM_PIN, - "GYRO_2_ADIS", gpio::Direction::OUT, 1); - gpio::createRpiGpioConfig(gpioCookie, gpioIds::GYRO_3_L3G_CS, gpio::GYRO_3_BCM_PIN, - "GYRO_3_L3G", gpio::Direction::OUT, 1); - gpioIF->addGpios(gpioCookie); + if (gpioCookie == nullptr) { + gpioCookie = new GpioCookie(); + } + // TODO: Missing pin for Gyro 2 + gpio::createRpiGpioConfig(gpioCookie, gpioIds::MGM_0_LIS3_CS, gpio::MGM_0_BCM_PIN, "MGM_0_LIS3", + gpio::Direction::OUT, 1); + gpio::createRpiGpioConfig(gpioCookie, gpioIds::MGM_1_RM3100_CS, gpio::MGM_1_BCM_PIN, + "MGM_1_RM3100", gpio::Direction::OUT, 1); + gpio::createRpiGpioConfig(gpioCookie, gpioIds::MGM_2_LIS3_CS, gpio::MGM_2_BCM_PIN, "MGM_2_LIS3", + gpio::Direction::OUT, 1); + gpio::createRpiGpioConfig(gpioCookie, gpioIds::MGM_3_RM3100_CS, gpio::MGM_3_BCM_PIN, + "MGM_3_RM3100", gpio::Direction::OUT, 1); + gpio::createRpiGpioConfig(gpioCookie, gpioIds::GYRO_0_ADIS_CS, gpio::GYRO_0_BCM_PIN, + "GYRO_0_ADIS", gpio::Direction::OUT, 1); + gpio::createRpiGpioConfig(gpioCookie, gpioIds::GYRO_1_L3G_CS, gpio::GYRO_1_BCM_PIN, "GYRO_1_L3G", + gpio::Direction::OUT, 1); + gpio::createRpiGpioConfig(gpioCookie, gpioIds::GYRO_2_ADIS_CS, gpio::GYRO_2_BCM_PIN, + "GYRO_2_ADIS", gpio::Direction::OUT, 1); + gpio::createRpiGpioConfig(gpioCookie, gpioIds::GYRO_3_L3G_CS, gpio::GYRO_3_BCM_PIN, "GYRO_3_L3G", + gpio::Direction::OUT, 1); + gpioIF->addGpios(gpioCookie); - spiDev = "/dev/spidev0.1"; - 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, 0); - mgmLis3Handler->setStartUpImmediately(); + spiDev = "/dev/spidev0.1"; + 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, 0); + mgmLis3Handler->setStartUpImmediately(); #if FSFW_HAL_LIS3MDL_MGM_DEBUG == 1 - mgmLis3Handler->setToGoToNormalMode(true); + 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); - auto mgmRm3100Handler = new MgmRM3100Handler(objects::MGM_1_RM3100_HANDLER, - objects::SPI_COM_IF, spiCookie, 0); - mgmRm3100Handler->setStartUpImmediately(); + 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, 0); + mgmRm3100Handler->setStartUpImmediately(); #if FSFW_HAL_RM3100_MGM_DEBUG == 1 - mgmRm3100Handler->setToGoToNormalMode(true); + 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); - mgmLis3Handler = new MgmLIS3MDLHandler(objects::MGM_2_LIS3_HANDLER, - objects::SPI_COM_IF, spiCookie, 0); - mgmLis3Handler->setStartUpImmediately(); + 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, 0); + mgmLis3Handler->setStartUpImmediately(); #if FSFW_HAL_LIS3MDL_MGM_DEBUG == 1 - mgmLis3Handler->setToGoToNormalMode(true); + 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); - mgmRm3100Handler = new MgmRM3100Handler(objects::MGM_3_RM3100_HANDLER, - objects::SPI_COM_IF, spiCookie, 0); - mgmRm3100Handler->setStartUpImmediately(); + 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, 0); + mgmRm3100Handler->setStartUpImmediately(); #if FSFW_HAL_RM3100_MGM_DEBUG == 1 - mgmRm3100Handler->setToGoToNormalMode(true); + mgmRm3100Handler->setToGoToNormalMode(true); #endif - spiCookie = new SpiCookie(addresses::GYRO_0_ADIS, gpioIds::GYRO_0_ADIS_CS, spiDev, - ADIS16507::MAXIMUM_REPLY_SIZE, spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED); - auto adisHandler = new GyroADIS16507Handler(objects::GYRO_0_ADIS_HANDLER, objects::SPI_COM_IF, - spiCookie); - adisHandler->setStartUpImmediately(); - 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, 0); - gyroL3gHandler->setStartUpImmediately(); -#if FSFW_HAL_L3GD20_GYRO_DEBUG== 1 - gyroL3gHandler->setToGoToNormalMode(true); + spiCookie = + new SpiCookie(addresses::GYRO_0_ADIS, gpioIds::GYRO_0_ADIS_CS, spiDev, + ADIS16507::MAXIMUM_REPLY_SIZE, spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED); + auto adisHandler = + new GyroADIS16507Handler(objects::GYRO_0_ADIS_HANDLER, objects::SPI_COM_IF, spiCookie); + adisHandler->setStartUpImmediately(); + 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, 0); + gyroL3gHandler->setStartUpImmediately(); +#if FSFW_HAL_L3GD20_GYRO_DEBUG == 1 + gyroL3gHandler->setToGoToNormalMode(true); #endif - spiCookie = new SpiCookie(addresses::GYRO_2_ADIS, gpioIds::GYRO_2_ADIS_CS, spiDev, - ADIS16507::MAXIMUM_REPLY_SIZE, spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED); - adisHandler = new GyroADIS16507Handler(objects::GYRO_2_ADIS_HANDLER, objects::SPI_COM_IF, - spiCookie); - adisHandler->setStartUpImmediately(); + spiCookie = + new SpiCookie(addresses::GYRO_2_ADIS, gpioIds::GYRO_2_ADIS_CS, spiDev, + ADIS16507::MAXIMUM_REPLY_SIZE, spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED); + adisHandler = + new GyroADIS16507Handler(objects::GYRO_2_ADIS_HANDLER, objects::SPI_COM_IF, spiCookie); + 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); - gyroL3gHandler = new GyroHandlerL3GD20H(objects::GYRO_3_L3G_HANDLER, objects::SPI_COM_IF, - spiCookie, 0); - gyroL3gHandler->setStartUpImmediately(); -#if FSFW_HAL_L3GD20_GYRO_DEBUG== 1 - gyroL3gHandler->setToGoToNormalMode(true); + 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, 0); + gyroL3gHandler->setStartUpImmediately(); +#if FSFW_HAL_L3GD20_GYRO_DEBUG == 1 + gyroL3gHandler->setToGoToNormalMode(true); #endif #endif /* RPI_TEST_ACS_BOARD == 1 */ #if OBSW_ADD_TEST_CODE == 1 - createTestTasks(); + createTestTasks(); #endif /* OBSW_ADD_TEST_CODE == 1 */ } void ObjectFactory::createTestTasks() { + new TestTask(objects::TEST_TASK); - new TestTask(objects::TEST_TASK); - -#if RPI_ADD_SPI_TEST == 1 - new SpiTestClass(objects::SPI_TEST, gpioIF); +#if OBSW_ADD_SPI_TEST_CODE == 1 + new SpiTestClass(objects::SPI_TEST, gpioIF); #endif -#if RPI_ADD_UART_TEST == 1 - new UartTestClass(objects::UART_TEST); +#if OBSW_ADD_UART_TEST_CODE == 1 + new UartTestClass(objects::UART_TEST); #else - new UartComIF(objects::UART_COM_IF); + new UartComIF(objects::UART_COM_IF); #endif #if RPI_LOOPBACK_TEST_GPIO == 1 - GpioCookie* gpioCookieLoopback = new GpioCookie(); - /* Loopback pins. Adapt according to setup */ - gpioId_t gpioIdSender = gpioIds::TEST_ID_0; - int bcmPinSender = 26; - gpioId_t gpioIdReader = gpioIds::TEST_ID_1; - int bcmPinReader = 16; - gpio::createRpiGpioConfig(gpioCookieLoopback, gpioIdSender, bcmPinSender, "GPIO_LB_SENDER", - gpio::Direction::OUT, 0); - gpio::createRpiGpioConfig(gpioCookieLoopback, gpioIdReader, bcmPinReader, "GPIO_LB_READER", - gpio::Direction::IN, 0); - new LibgpiodTest(objects::LIBGPIOD_TEST, objects::GPIO_IF, gpioCookieLoopback); + GpioCookie* gpioCookieLoopback = new GpioCookie(); + /* Loopback pins. Adapt according to setup */ + gpioId_t gpioIdSender = gpioIds::TEST_ID_0; + int bcmPinSender = 26; + gpioId_t gpioIdReader = gpioIds::TEST_ID_1; + int bcmPinReader = 16; + gpio::createRpiGpioConfig(gpioCookieLoopback, gpioIdSender, bcmPinSender, "GPIO_LB_SENDER", + gpio::Direction::OUT, 0); + gpio::createRpiGpioConfig(gpioCookieLoopback, gpioIdReader, bcmPinReader, "GPIO_LB_READER", + gpio::Direction::IN, 0); + new LibgpiodTest(objects::LIBGPIOD_TEST, objects::GPIO_IF, gpioCookieLoopback); #endif /* RPI_LOOPBACK_TEST_GPIO == 1 */ #if RPI_TEST_ADIS16507 == 1 - if(gpioCookie == nullptr) { - gpioCookie = new GpioCookie(); - } - gpio::createRpiGpioConfig(gpioCookie, gpioIds::GYRO_0_ADIS_CS, gpio::GYRO_0_BCM_PIN, - "GYRO_0_ADIS", gpio::Direction::OUT, 1); - gpioIF->addGpios(gpioCookie); + if (gpioCookie == nullptr) { + gpioCookie = new GpioCookie(); + } + gpio::createRpiGpioConfig(gpioCookie, gpioIds::GYRO_0_ADIS_CS, gpio::GYRO_0_BCM_PIN, + "GYRO_0_ADIS", gpio::Direction::OUT, 1); + gpioIF->addGpios(gpioCookie); - spiDev = "/dev/spidev0.1"; - spiCookie = new SpiCookie(addresses::GYRO_0_ADIS, gpioIds::GYRO_0_ADIS_CS, spiDev, - ADIS16507::MAXIMUM_REPLY_SIZE, spi::DEFAULT_ADIS16507_MODE, spi::DEFAULT_ADIS16507_SPEED, - nullptr, nullptr); - auto adisGyroHandler = new GyroADIS16507Handler(objects::GYRO_0_ADIS_HANDLER, objects::SPI_COM_IF, spiCookie); - adisGyroHandler->setStartUpImmediately(); + spiDev = "/dev/spidev0.1"; + spiCookie = new SpiCookie(addresses::GYRO_0_ADIS, gpioIds::GYRO_0_ADIS_CS, spiDev, + ADIS16507::MAXIMUM_REPLY_SIZE, spi::DEFAULT_ADIS16507_MODE, + spi::DEFAULT_ADIS16507_SPEED, nullptr, nullptr); + auto adisGyroHandler = + new GyroADIS16507Handler(objects::GYRO_0_ADIS_HANDLER, objects::SPI_COM_IF, spiCookie); + adisGyroHandler->setStartUpImmediately(); #endif /* RPI_TEST_ADIS16507 == 1 */ #if RPI_TEST_GPS_HANDLER == 1 - UartCookie* uartCookie = new UartCookie(objects::GPS0_HANDLER, "/dev/serial0", - UartModes::CANONICAL, 9600, 1024); - uartCookie->setToFlushInput(true); - uartCookie->setReadCycles(6); - GPSHyperionHandler* gpsHandler = new GPSHyperionHandler(objects::GPS0_HANDLER, - objects::UART_COM_IF, uartCookie, false); - gpsHandler->setStartUpImmediately(); + UartCookie* uartCookie = + new UartCookie(objects::GPS0_HANDLER, "/dev/serial0", UartModes::CANONICAL, 9600, 1024); + uartCookie->setToFlushInput(true); + uartCookie->setReadCycles(6); + GPSHyperionHandler* gpsHandler = + new GPSHyperionHandler(objects::GPS0_HANDLER, objects::UART_COM_IF, uartCookie, false); + gpsHandler->setStartUpImmediately(); #endif - } diff --git a/bsp_linux_board/ObjectFactory.h b/bsp_linux_board/ObjectFactory.h index 3b9aca49..909baf06 100644 --- a/bsp_linux_board/ObjectFactory.h +++ b/bsp_linux_board/ObjectFactory.h @@ -1,12 +1,11 @@ #ifndef BSP_LINUX_OBJECTFACTORY_H_ #define BSP_LINUX_OBJECTFACTORY_H_ - namespace ObjectFactory { - void setStatics(); - void produce(void* args); +void setStatics(); +void produce(void* args); - void createTestTasks(); -}; +void createTestTasks(); +}; // namespace ObjectFactory #endif /* BSP_LINUX_OBJECTFACTORY_H_ */ diff --git a/bsp_linux_board/boardconfig/CMakeLists.txt b/bsp_linux_board/boardconfig/CMakeLists.txt index 67fbaf88..f9136e3e 100644 --- a/bsp_linux_board/boardconfig/CMakeLists.txt +++ b/bsp_linux_board/boardconfig/CMakeLists.txt @@ -1,7 +1,7 @@ -target_sources(${TARGET_NAME} PRIVATE +target_sources(${OBSW_NAME} PRIVATE print.c ) -target_include_directories(${TARGET_NAME} PUBLIC +target_include_directories(${OBSW_NAME} PUBLIC ${CMAKE_CURRENT_SOURCE_DIR} ) diff --git a/bsp_linux_board/boardconfig/etl_profile.h b/bsp_linux_board/boardconfig/etl_profile.h index c35ffb46..54aca344 100644 --- a/bsp_linux_board/boardconfig/etl_profile.h +++ b/bsp_linux_board/boardconfig/etl_profile.h @@ -32,7 +32,7 @@ SOFTWARE. #define ETL_CHECK_PUSH_POP -#define ETL_CPP11_SUPPORTED 1 -#define ETL_NO_NULLPTR_SUPPORT 0 +#define ETL_CPP11_SUPPORTED 1 +#define ETL_NO_NULLPTR_SUPPORT 0 #endif diff --git a/bsp_linux_board/boardconfig/gcov.h b/bsp_linux_board/boardconfig/gcov.h index 491d24c6..80acdd86 100644 --- a/bsp_linux_board/boardconfig/gcov.h +++ b/bsp_linux_board/boardconfig/gcov.h @@ -6,8 +6,9 @@ extern "C" void __gcov_flush(); #else void __gcov_flush() { - sif::info << "GCC GCOV: Please supply GCOV=1 in Makefile if " - "coverage information is desired.\n" << std::flush; + sif::info << "GCC GCOV: Please supply GCOV=1 in Makefile if " + "coverage information is desired.\n" + << std::flush; } #endif diff --git a/bsp_linux_board/boardconfig/print.c b/bsp_linux_board/boardconfig/print.c index c501e0b7..c2b2e15d 100644 --- a/bsp_linux_board/boardconfig/print.c +++ b/bsp_linux_board/boardconfig/print.c @@ -1,14 +1,10 @@ -#include +#include #include void printChar(const char* character, bool errStream) { - if(errStream) { - putc(*character, stderr); - return; - } - putc(*character, stdout); + if (errStream) { + putc(*character, stderr); + return; + } + putc(*character, stdout); } - - - - diff --git a/bsp_linux_board/boardtest/CMakeLists.txt b/bsp_linux_board/boardtest/CMakeLists.txt index 0599b73f..fe4910f2 100644 --- a/bsp_linux_board/boardtest/CMakeLists.txt +++ b/bsp_linux_board/boardtest/CMakeLists.txt @@ -1,4 +1,4 @@ -target_sources(${TARGET_NAME} PRIVATE +target_sources(${OBSW_NAME} PRIVATE ) diff --git a/bsp_linux_board/main.cpp b/bsp_linux_board/main.cpp index a766f2a0..4e286f5d 100644 --- a/bsp_linux_board/main.cpp +++ b/bsp_linux_board/main.cpp @@ -1,12 +1,11 @@ +#include + #include "InitMission.h" #include "OBSWConfig.h" #include "OBSWVersion.h" - #include "fsfw/FSFWVersion.h" #include "fsfw/tasks/TaskFactory.h" -#include - #ifdef RASPBERRY_PI static const char* const BOARD_NAME = "Raspberry Pi"; #elif defined(BEAGLEBONEBLACK) @@ -19,21 +18,18 @@ static const char* const BOARD_NAME = "Unknown Board"; * @brief This is the main program and entry point for the Raspberry Pi. * @return */ -int main(void) -{ - std::cout << "-- EIVE OBSW --" << std::endl; - std::cout << "-- Compiled for Linux board " << BOARD_NAME << " --" << std::endl; - std::cout << "-- OBSW " << SW_NAME << " v" << SW_VERSION << "." << SW_SUBVERSION << - "." << SW_REVISION << ", FSFW v" << FSFW_VERSION << "." << FSFW_SUBVERSION << - FSFW_REVISION << "--" << std::endl; - std::cout << "-- " << __DATE__ << " " << __TIME__ << " --" << std::endl; +int main(void) { + std::cout << "-- EIVE OBSW --" << std::endl; + std::cout << "-- Compiled for Linux board " << BOARD_NAME << " --" << std::endl; + std::cout << "-- OBSW " << SW_NAME << " v" << SW_VERSION << "." << SW_SUBVERSION << "." + << SW_REVISION << ", FSFW v" << FSFW_VERSION << "." << FSFW_SUBVERSION << FSFW_REVISION + << "--" << std::endl; + std::cout << "-- " << __DATE__ << " " << __TIME__ << " --" << std::endl; - initmission::initMission(); + initmission::initMission(); - for(;;) { - /* Suspend main thread by sleeping it. */ - TaskFactory::delayTask(5000); - } + for (;;) { + /* Suspend main thread by sleeping it. */ + TaskFactory::delayTask(5000); + } } - - diff --git a/bsp_q7s/CMakeLists.txt b/bsp_q7s/CMakeLists.txt index b2c24d5f..17e4ba2d 100644 --- a/bsp_q7s/CMakeLists.txt +++ b/bsp_q7s/CMakeLists.txt @@ -1,17 +1,25 @@ -target_sources(${TARGET_NAME} PUBLIC +#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_compile_definitions(${SIMPLE_OBSW_NAME} PRIVATE "Q7S_SIMPLE_MODE") +add_subdirectory(simple) + +target_sources(${OBSW_NAME} PUBLIC main.cpp ) add_subdirectory(boardtest) -if(Q7S_SIMPLE_MODE) - add_subdirectory(simple) -else() - add_subdirectory(boardconfig) - add_subdirectory(comIF) - add_subdirectory(gpio) - add_subdirectory(core) - add_subdirectory(memory) - add_subdirectory(callbacks) - add_subdirectory(devices) -endif() +add_subdirectory(boardconfig) +add_subdirectory(comIF) +add_subdirectory(core) +add_subdirectory(memory) +add_subdirectory(callbacks) +add_subdirectory(devices) diff --git a/bsp_q7s/boardconfig/CMakeLists.txt b/bsp_q7s/boardconfig/CMakeLists.txt index 67fbaf88..feefbe5a 100644 --- a/bsp_q7s/boardconfig/CMakeLists.txt +++ b/bsp_q7s/boardconfig/CMakeLists.txt @@ -1,7 +1,12 @@ -target_sources(${TARGET_NAME} PRIVATE +target_sources(${OBSW_NAME} PRIVATE print.c ) -target_include_directories(${TARGET_NAME} PUBLIC +target_sources(${SIMPLE_OBSW_NAME} PRIVATE + print.c +) + + +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 a86a6c79..eba4fb36 100644 --- a/bsp_q7s/boardconfig/busConf.h +++ b/bsp_q7s/boardconfig/busConf.h @@ -3,98 +3,98 @@ namespace q7s { -static constexpr char SPI_DEFAULT_DEV[] = "/dev/spidev2.0"; -static constexpr char SPI_RW_DEV[] = "/dev/spidev3.0"; +static constexpr char SPI_DEFAULT_DEV[] = "/dev/spi-main"; +static constexpr char SPI_RW_DEV[] = "/dev/spi-rw"; -static constexpr char I2C_DEFAULT_DEV[] = "/dev/i2c-1"; +static constexpr char I2C_DEFAULT_DEV[] = "/dev/i2c-eive"; -static constexpr char UART_PLOC_MPSOC_DEV[] = "/dev/ttyUL3"; -static constexpr char UART_PLOC_SUPERVSIOR_DEV[] = "/dev/ttyUL4"; -static constexpr char UART_SYRLINKS_DEV[] = "/dev/ttyUL5"; -static constexpr char UART_STAR_TRACKER_DEV[] = "/dev/ttyUL8"; +static constexpr char UART_GNSS_DEV[] = "/dev/ul-gps"; +static constexpr char UART_PLOC_MPSOC_DEV[] = "/dev/ul-plmpsoc"; +static constexpr char UART_PLOC_SUPERVSIOR_DEV[] = "/dev/ul-plsv"; +static constexpr char UART_SYRLINKS_DEV[] = "/dev/ul-syrlinks"; +static constexpr char UART_STAR_TRACKER_DEV[] = "/dev/ul-str"; -static constexpr char UART_GNSS_0_DEV[] = "/dev/ttyUL0"; -static constexpr char UART_GNSS_1_DEV[] = "/dev/ttyUL2"; +static constexpr char UIO_PDEC_REGISTERS[] = "/dev/uio0"; +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; -/**************************************************************/ -/** OBC1E */ -/**************************************************************/ -static constexpr char GPIO_MULTIPURPOSE_1V8_OBC1D[] = "/amba_pl/gpio@42020000"; -static const char* const GPIO_GYRO_ADIS_LABEL = GPIO_MULTIPURPOSE_1V8_OBC1D; -static constexpr uint32_t GPIO_GYRO_0_ADIS_CS = 0; // Package Pin: W20 -static constexpr uint32_t GPIO_GYRO_2_ADIS_CS = 2; // AA22 +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 -/**************************************************************/ -/** OBC1F B0 */ -/**************************************************************/ -static constexpr char GPIO_FLEX_OBC1F_B0[] = "/amba_pl/gpio@42030000"; -static constexpr uint32_t GPIO_FLEX_OBC1F_B0_WIDTH = 20; -static const char* const GPIO_ACS_BOARD_DEFAULT_LABEL = GPIO_FLEX_OBC1F_B0; -static const char* const GPIO_RW_DEFAULT_LABEL = GPIO_FLEX_OBC1F_B0; -static const char* const GPIO_RAD_SENSOR_LABEL = GPIO_FLEX_OBC1F_B0; +namespace gpioNames { +static constexpr char GYRO_0_ADIS_CS[] = "gyro_0_adis_chip_select"; +static constexpr char GYRO_1_L3G_CS[] = "gyro_1_l3g_chip_select"; +static constexpr char GYRO_2_ADIS_CS[] = "gyro_2_adis_chip_select"; +static constexpr char GYRO_3_L3G_CS[] = "gyro_3_l3g_chip_select"; +static constexpr char MGM_0_CS[] = "mgm_0_lis3_chip_select"; +static constexpr char MGM_1_CS[] = "mgm_1_rm3100_chip_select"; +static constexpr char MGM_2_CS[] = "mgm_2_lis3_chip_select"; +static constexpr char MGM_3_CS[] = "mgm_3_rm3100_chip_select"; +static constexpr char RESET_GNSS_0[] = "reset_gnss_0"; +static constexpr char RESET_GNSS_1[] = "reset_gnss_1"; +static constexpr char GNSS_0_ENABLE[] = "enable_gnss_0"; +static constexpr char GNSS_1_ENABLE[] = "enable_gnss_1"; +static constexpr char GYRO_0_ENABLE[] = "enable_gyro_0"; +static constexpr char GYRO_2_ENABLE[] = "enable_gyro_2"; +static constexpr char GNSS_SELECT[] = "gnss_mux_select"; +static constexpr char GNSS_MUX_SELECT[] = "gnss_mux_select"; -static constexpr uint32_t GPIO_RW_0_CS = 7; // B20 -static constexpr uint32_t GPIO_RW_1_CS = 3; // G22 -static constexpr uint32_t GPIO_RW_2_CS = 11; // E18 -static constexpr uint32_t GPIO_RW_3_CS = 6; // B19 +static constexpr char HEATER_0[] = "heater0"; +static constexpr char HEATER_1[] = "heater1"; +static constexpr char HEATER_2[] = "heater2"; +static constexpr char HEATER_3[] = "heater3"; +static constexpr char HEATER_4[] = "heater4"; +static constexpr char HEATER_5[] = "heater5"; +static constexpr char HEATER_6[] = "heater6"; +static constexpr char HEATER_7[] = "heater7"; +static constexpr char SA_DPL_PIN_0[] = "sa_dpl_0"; +static constexpr char SA_DPL_PIN_1[] = "sa_dpl_1"; +static constexpr char SPI_MUX_BIT_0_PIN[] = "spi_mux_bit_0"; +static constexpr char SPI_MUX_BIT_1_PIN[] = "spi_mux_bit_1"; +static constexpr char SPI_MUX_BIT_2_PIN[] = "spi_mux_bit_2"; +static constexpr char SPI_MUX_BIT_3_PIN[] = "spi_mux_bit_3"; +static constexpr char SPI_MUX_BIT_4_PIN[] = "spi_mux_bit_4"; +static constexpr char SPI_MUX_BIT_5_PIN[] = "spi_mux_bit_5"; +static constexpr char EN_RW_CS[] = "en_rw_cs"; +static constexpr char EN_RW_1[] = "enable_rw_1"; +static constexpr char EN_RW_2[] = "enable_rw_2"; +static constexpr char EN_RW_3[] = "enable_rw_3"; +static constexpr char EN_RW_4[] = "enable_rw_4"; -static constexpr uint32_t GPIO_GYRO_1_L3G_CS = 18; // N22 -static constexpr uint32_t GPIO_GYRO_3_L3G_CS = 1; // M21 -static constexpr uint32_t GPIO_MGM_0_LIS3_CS = 5; // C18 -static constexpr uint32_t GPIO_MGM_1_RM3100_CS = 16; // A16 -static constexpr uint32_t GPIO_MGM_3_RM3100_CS = 10; // C17 +static constexpr char RAD_SENSOR_CHIP_SELECT[] = "rad_sensor_chip_select"; +static constexpr char ENABLE_RADFET[] = "enable_radfet"; +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"; -// Active low enable pin (needs to be driven low for regular operations) -static constexpr uint32_t GPIO_GYRO_0_ENABLE = 2; // H22 +static constexpr char PL_PCDU_ENABLE_VBAT0[] = "enable_plpcdu_vbat0"; +static constexpr char PL_PCDU_ENABLE_VBAT1[] = "enable_plpcdu_vbat1"; +static constexpr char PL_PCDU_ENABLE_DRO[] = "enable_plpcdu_dro"; +static constexpr char PL_PCDU_ENABLE_X8[] = "enable_plpcdu_x8"; +static constexpr char PL_PCDU_ENABLE_TX[] = "enable_plpcdu_tx"; +static constexpr char PL_PCDU_ENABLE_HPA[] = "enable_plpcdu_hpa"; +static constexpr char PL_PCDU_ENABLE_MPA[] = "enable_plpcdu_mpa"; +static constexpr char PL_PCDU_ADC_CS[] = "plpcdu_adc_chip_select"; -// Active low reset pin (needs to be driven high for regular operations) -static constexpr uint32_t GPIO_RESET_GNSS_0 = 9; // C22 -static constexpr uint32_t GPIO_RESET_GNSS_1 = 12; // B21 - -static constexpr uint32_t GPIO_RAD_SENSOR_CS = 19; // R18 - -/**************************************************************/ -/** OBC1F B1 */ -/**************************************************************/ -static constexpr char GPIO_FLEX_OBC1F_B1[] = "/amba_pl/gpio@42030000"; -// Need to use chip name here for now because the label name is the name for -// gpiochip 5 and gpiochip6 -static constexpr char GPIO_FLEX_OBC1F_B1_CHIP[] = "gpiochip6"; -static const char* const GPIO_MGM2_LIS3_LABEL = GPIO_FLEX_OBC1F_B1_CHIP; -static constexpr uint32_t GPIO_MGM_2_LIS3_CS = 0; // D18 - -/**************************************************************/ -/** OBC1C */ -/**************************************************************/ -static constexpr char GPIO_3V3_OBC1C[] = "/amba_pl/gpio@42040000"; -static const char* const GPIO_HEATER_LABEL = GPIO_3V3_OBC1C; -static const char* const GPIO_SOLAR_ARR_DEPL_LABEL = GPIO_3V3_OBC1C; -static constexpr uint32_t GPIO_HEATER_0_PIN = 6; -static constexpr uint32_t GPIO_HEATER_1_PIN = 12; -static constexpr uint32_t GPIO_HEATER_2_PIN = 7; -static constexpr uint32_t GPIO_HEATER_3_PIN = 5; -static constexpr uint32_t GPIO_HEATER_4_PIN = 3; -static constexpr uint32_t GPIO_HEATER_5_PIN = 0; -static constexpr uint32_t GPIO_HEATER_6_PIN = 1; -static constexpr uint32_t GPIO_HEATER_7_PIN = 11; -static constexpr uint32_t GPIO_GYRO_2_ENABLE = 18; // F22 - -static constexpr uint32_t GPIO_SOL_DEPL_SA_0_PIN = 4; -static constexpr uint32_t GPIO_SOL_DEPL_SA_1_PIN = 2; - -static constexpr char GPIO_RW_SPI_MUX_LABEL[] = "zynq_gpio"; -// Uses EMIO interface to PL, starts at 54 -static constexpr uint32_t GPIO_RW_SPI_MUX_CS = 54; - -static constexpr uint32_t SPI_MUX_BIT_1 = 13; -static constexpr uint32_t SPI_MUX_BIT_2 = 14; -static constexpr uint32_t SPI_MUX_BIT_3 = 15; -static constexpr uint32_t SPI_MUX_BIT_4 = 16; -static constexpr uint32_t SPI_MUX_BIT_5 = 17; -static constexpr uint32_t SPI_MUX_BIT_6 = 9; -static constexpr uint32_t EN_RW_CS = 17; - -} +} // namespace gpioNames +} // namespace q7s #endif /* BSP_Q7S_BOARDCONFIG_BUSCONF_H_ */ diff --git a/bsp_q7s/boardconfig/etl_profile.h b/bsp_q7s/boardconfig/etl_profile.h index c35ffb46..54aca344 100644 --- a/bsp_q7s/boardconfig/etl_profile.h +++ b/bsp_q7s/boardconfig/etl_profile.h @@ -32,7 +32,7 @@ SOFTWARE. #define ETL_CHECK_PUSH_POP -#define ETL_CPP11_SUPPORTED 1 -#define ETL_NO_NULLPTR_SUPPORT 0 +#define ETL_CPP11_SUPPORTED 1 +#define ETL_NO_NULLPTR_SUPPORT 0 #endif diff --git a/bsp_q7s/boardconfig/gcov.h b/bsp_q7s/boardconfig/gcov.h index 491d24c6..80acdd86 100644 --- a/bsp_q7s/boardconfig/gcov.h +++ b/bsp_q7s/boardconfig/gcov.h @@ -6,8 +6,9 @@ extern "C" void __gcov_flush(); #else void __gcov_flush() { - sif::info << "GCC GCOV: Please supply GCOV=1 in Makefile if " - "coverage information is desired.\n" << std::flush; + sif::info << "GCC GCOV: Please supply GCOV=1 in Makefile if " + "coverage information is desired.\n" + << std::flush; } #endif diff --git a/bsp_q7s/boardconfig/print.c b/bsp_q7s/boardconfig/print.c index c501e0b7..3aba2d73 100644 --- a/bsp_q7s/boardconfig/print.c +++ b/bsp_q7s/boardconfig/print.c @@ -2,13 +2,9 @@ #include void printChar(const char* character, bool errStream) { - if(errStream) { - putc(*character, stderr); - return; - } - putc(*character, stdout); + if (errStream) { + putc(*character, stderr); + return; + } + putc(*character, stdout); } - - - - diff --git a/bsp_q7s/boardconfig/q7sConfig.h.in b/bsp_q7s/boardconfig/q7sConfig.h.in index 43283ea1..1dd1d85a 100644 --- a/bsp_q7s/boardconfig/q7sConfig.h.in +++ b/bsp_q7s/boardconfig/q7sConfig.h.in @@ -3,8 +3,6 @@ #include -#cmakedefine01 Q7S_SIMPLE_MODE - /*******************************************************************/ /** All of the following flags should be enabled for mission code */ /*******************************************************************/ @@ -31,6 +29,10 @@ #define Q7S_SIMPLE_ADD_FILE_SYSTEM_TEST 0 +#ifndef Q7S_SIMPLE_MODE +#define Q7S_SIMPLE_MODE 0 +#endif + namespace config { static const uint32_t SD_CARD_ACCESS_MUTEX_TIMEOUT = 50; diff --git a/bsp_q7s/boardtest/CMakeLists.txt b/bsp_q7s/boardtest/CMakeLists.txt index 1cda38ca..29c9f1e1 100644 --- a/bsp_q7s/boardtest/CMakeLists.txt +++ b/bsp_q7s/boardtest/CMakeLists.txt @@ -1,8 +1,10 @@ -target_sources(${TARGET_NAME} PRIVATE +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 diff --git a/bsp_q7s/boardtest/FileSystemTest.cpp b/bsp_q7s/boardtest/FileSystemTest.cpp index 92c4cf3d..e1dd564d 100644 --- a/bsp_q7s/boardtest/FileSystemTest.cpp +++ b/bsp_q7s/boardtest/FileSystemTest.cpp @@ -1,26 +1,23 @@ #include "FileSystemTest.h" + +#include +#include + #include "fsfw/timemanager/Stopwatch.h" -#include -#include - -enum SdCard { - SDC0, - SDC1 -}; +enum SdCard { SDC0, SDC1 }; FileSystemTest::FileSystemTest() { - using namespace std; - SdCard sdCard = SdCard::SDC0; - cout << "SD Card Test for SD card " << static_cast(sdCard) << std::endl; - //Stopwatch stopwatch; - std::system("q7hw sd info all > /tmp/sd_status.txt"); - //stopwatch.stop(true); - std::system("q7hw sd set 0 on > /tmp/sd_set.txt"); - //stopwatch.stop(true); - std::system("q7hw sd set 0 off > /tmp/sd_set.txt"); - //stopwatch.stop(true); + using namespace std; + SdCard sdCard = SdCard::SDC0; + cout << "SD Card Test for SD card " << static_cast(sdCard) << std::endl; + // Stopwatch stopwatch; + std::system("q7hw sd info all > /tmp/sd_status.txt"); + // stopwatch.stop(true); + std::system("q7hw sd set 0 on > /tmp/sd_set.txt"); + // stopwatch.stop(true); + std::system("q7hw sd set 0 off > /tmp/sd_set.txt"); + // stopwatch.stop(true); } -FileSystemTest::~FileSystemTest() { -} +FileSystemTest::~FileSystemTest() {} diff --git a/bsp_q7s/boardtest/FileSystemTest.h b/bsp_q7s/boardtest/FileSystemTest.h index 256a0b36..bdb7989f 100644 --- a/bsp_q7s/boardtest/FileSystemTest.h +++ b/bsp_q7s/boardtest/FileSystemTest.h @@ -2,12 +2,11 @@ #define BSP_Q7S_BOARDTEST_FILESYSTEMTEST_H_ class FileSystemTest { -public: - FileSystemTest(); - virtual~ FileSystemTest(); -private: + public: + FileSystemTest(); + virtual ~FileSystemTest(); + + private: }; - - #endif /* BSP_Q7S_BOARDTEST_FILESYSTEMTEST_H_ */ diff --git a/bsp_q7s/boardtest/Q7STestTask.cpp b/bsp_q7s/boardtest/Q7STestTask.cpp index 18baf124..1f14d0e1 100644 --- a/bsp_q7s/boardtest/Q7STestTask.cpp +++ b/bsp_q7s/boardtest/Q7STestTask.cpp @@ -1,337 +1,397 @@ +#include "Q7STestTask.h" + #include #include #include -#include "Q7STestTask.h" +#include +#include + +#include +#include +#include +#include +#include +#include #include "bsp_q7s/memory/SdCardManager.h" #include "bsp_q7s/memory/scratchApi.h" - -#include "fsfw/timemanager/Stopwatch.h" #include "fsfw/tasks/TaskFactory.h" - +#include "fsfw/timemanager/Stopwatch.h" #include "test/DummyParameter.h" -#include - -#include -#include -#include - -Q7STestTask::Q7STestTask(object_id_t objectId): TestTask(objectId) { +Q7STestTask::Q7STestTask(object_id_t objectId) : TestTask(objectId) { + doTestSdCard = false; + doTestScratchApi = false; + doTestGps = false; } ReturnValue_t Q7STestTask::performOneShotAction() { - //testSdCard(); - //testScratchApi(); - //testJsonLibDirect(); - //testDummyParams(); - //testProtHandler(); - //FsOpCodes opCode = FsOpCodes::ATTEMPT_DIR_REMOVAL_NON_EMPTY; - //testFileSystemHandlerDirect(opCode); - return TestTask::performOneShotAction(); + if (doTestSdCard) { + testSdCard(); + } + if (doTestScratchApi) { + testScratchApi(); + } + // testJsonLibDirect(); + // testDummyParams(); + // testProtHandler(); + FsOpCodes opCode = FsOpCodes::APPEND_TO_FILE; + testFileSystemHandlerDirect(opCode); + return TestTask::performOneShotAction(); +} + +ReturnValue_t Q7STestTask::performPeriodicAction() { + if (doTestGps) { + testGpsDaemon(); + } + return TestTask::performPeriodicAction(); } void Q7STestTask::testSdCard() { - using namespace std; - Stopwatch stopwatch; - int result = std::system("q7hw sd info all > /tmp/sd_status.txt"); - if(result != 0) { - sif::debug << "system call failed with " << result << endl; + using namespace std; + Stopwatch stopwatch; + int result = std::system("q7hw sd info all > /tmp/sd_status.txt"); + if (result != 0) { + sif::debug << "system call failed with " << result << endl; + } + ifstream sdStatus("/tmp/sd_status.txt"); + string line; + uint8_t idx = 0; + while (std::getline(sdStatus, line)) { + std::istringstream iss(line); + string word; + while (iss >> word) { + if (word == "on") { + sif::info << "SD card " << static_cast(idx) << " is on" << endl; + } else if (word == "off") { + sif::info << "SD card " << static_cast(idx) << " is off" << endl; + } } - ifstream sdStatus("/tmp/sd_status.txt"); - string line; - uint8_t idx = 0; - while (std::getline(sdStatus, line)) { - std::istringstream iss(line); - string word; - while(iss >> word) { - if(word == "on") { - sif::info << "SD card " << static_cast(idx) << " is on" << endl; - } - else if(word == "off") { - sif::info << "SD card " << static_cast(idx) << " is off" << endl; - } - } - idx++; - } - std::remove("/tmp/sd_status.txt"); + idx++; + } + std::remove("/tmp/sd_status.txt"); } void Q7STestTask::fileTests() { - using namespace std; - ofstream testFile("/tmp/test.txt"); - testFile << "Hallo Welt" << endl; - testFile.close(); + using namespace std; + ofstream testFile("/tmp/test.txt"); + testFile << "Hallo Welt" << endl; + testFile.close(); - system("echo \"Hallo Welt\" > /tmp/test2.txt"); - system("echo \"Hallo Welt\""); + system("echo \"Hallo Welt\" > /tmp/test2.txt"); + system("echo \"Hallo Welt\""); } void Q7STestTask::testScratchApi() { - ReturnValue_t result = scratch::writeNumber("TEST", 1); - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::debug << "Q7STestTask::scratchApiTest: Writing number failed" << std::endl; - } - int number = 0; - result = scratch::readNumber("TEST", number); - sif::info << "Q7STestTask::testScratchApi: Value for key \"TEST\": " << number << std::endl; - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::debug << "Q7STestTask::scratchApiTest: Reading number failed" << std::endl; - } + ReturnValue_t result = scratch::writeNumber("TEST", 1); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::debug << "Q7STestTask::scratchApiTest: Writing number failed" << std::endl; + } + int number = 0; + result = scratch::readNumber("TEST", number); + sif::info << "Q7STestTask::testScratchApi: Value for key \"TEST\": " << number << std::endl; + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::debug << "Q7STestTask::scratchApiTest: Reading number failed" << std::endl; + } - result = scratch::writeString("TEST2", "halloWelt"); - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::debug << "Q7STestTask::scratchApiTest: Writing string failed" << std::endl; - } - std::string string; - result = scratch::readString("TEST2", string); - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::debug << "Q7STestTask::scratchApiTest: Reading number failed" << std::endl; - } - sif::info << "Q7STestTask::testScratchApi: Value for key \"TEST2\": " << string << std::endl; + result = scratch::writeString("TEST2", "halloWelt"); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::debug << "Q7STestTask::scratchApiTest: Writing string failed" << std::endl; + } + std::string string; + result = scratch::readString("TEST2", string); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::debug << "Q7STestTask::scratchApiTest: Reading number failed" << std::endl; + } + sif::info << "Q7STestTask::testScratchApi: Value for key \"TEST2\": " << string << std::endl; - result = scratch::clearValue("TEST"); - result = scratch::clearValue("TEST2"); + result = scratch::clearValue("TEST"); + result = scratch::clearValue("TEST2"); } void Q7STestTask::testJsonLibDirect() { - Stopwatch stopwatch; - // for convenience - using json = nlohmann::json; - json helloTest; - // add a number that is stored as double (note the implicit conversion of j to an object) - helloTest["pi"] = 3.141; - std::string mntPrefix = SdCardManager::instance()->getCurrentMountPrefix(); - std::string fileName = mntPrefix + "/pretty.json"; - std::ofstream o(fileName); - o << std::setw(4) << helloTest << std::endl; + Stopwatch stopwatch; + // for convenience + using json = nlohmann::json; + json helloTest; + // add a number that is stored as double (note the implicit conversion of j to an object) + helloTest["pi"] = 3.141; + std::string mntPrefix = SdCardManager::instance()->getCurrentMountPrefix(); + std::string fileName = mntPrefix + "/pretty.json"; + std::ofstream o(fileName); + o << std::setw(4) << helloTest << std::endl; } void Q7STestTask::testDummyParams() { - std::string mntPrefix = SdCardManager::instance()->getCurrentMountPrefix(); - DummyParameter param(mntPrefix, "dummy_json.txt"); - param.printKeys(); - param.print(); - if(not param.getJsonFileExists()) { - param.writeJsonFile(); - } - - ReturnValue_t result = param.readJsonFile(); - if(result != HasReturnvaluesIF::RETURN_OK) { - - } - - param.setValue(DummyParameter::DUMMY_KEY_PARAM_1, 3); - param.setValue(DummyParameter::DUMMY_KEY_PARAM_2, "blirb"); - + std::string mntPrefix = SdCardManager::instance()->getCurrentMountPrefix(); + DummyParameter param(mntPrefix, "dummy_json.txt"); + param.printKeys(); + param.print(); + if (not param.getJsonFileExists()) { param.writeJsonFile(); - param.print(); + } - int test = param.getValue(DummyParameter::DUMMY_KEY_PARAM_1); - std::string test2 = param.getValue(DummyParameter::DUMMY_KEY_PARAM_2); - sif::info << "Test value (3 expected): " << test << std::endl; - sif::info << "Test value 2 (\"blirb\" expected): " << test2 << std::endl; + ReturnValue_t result = param.readJsonFile(); + if (result != HasReturnvaluesIF::RETURN_OK) { + } + + param.setValue(DummyParameter::DUMMY_KEY_PARAM_1, 3); + param.setValue(DummyParameter::DUMMY_KEY_PARAM_2, "blirb"); + + param.writeJsonFile(); + param.print(); + + int test = 0; + 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; + } + 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; + } + sif::info << "Test value (3 expected): " << test << std::endl; + sif::info << "Test value 2 (\"blirb\" expected): " << test2 << std::endl; } 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; - } - return TestTask::initialize(); + coreController = ObjectManager::instance()->get(objects::CORE_CONTROLLER); + if (coreController == nullptr) { + sif::warning << "Q7STestTask::initialize: Could not retrieve CORE_CONTROLLER object" + << std::endl; + } + return TestTask::initialize(); } void Q7STestTask::testProtHandler() { - bool opPerformed = false; - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - // If any chips are unlocked, lock them here - result = coreController->setBootCopyProtection( - CoreController::Chip::ALL_CHIP, CoreController::Copy::ALL_COPY, true, - opPerformed, true); - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::warning << "Q7STestTask::testProtHandler: Op failed" << std::endl; - } + bool opPerformed = false; + 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); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "Q7STestTask::testProtHandler: Op failed" << std::endl; + } - // unlock own copy - result = coreController->setBootCopyProtection( - CoreController::Chip::SELF_CHIP, CoreController::Copy::SELF_COPY, false, - opPerformed, true); - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::warning << "Q7STestTask::testProtHandler: Op failed" << std::endl; - } - if(not opPerformed) { - sif::warning << "Q7STestTask::testProtHandler: No op performed" << std::endl; - } - int retval = std::system("print-chip-prot-status.sh"); - if(retval != 0) { - utility::handleSystemError(retval, "Q7STestTask::testProtHandler"); - } + // unlock own copy + result = coreController->setBootCopyProtection(xsc::Chip::SELF_CHIP, xsc::Copy::SELF_COPY, false, + opPerformed, true); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "Q7STestTask::testProtHandler: Op failed" << std::endl; + } + if (not opPerformed) { + sif::warning << "Q7STestTask::testProtHandler: No op performed" << std::endl; + } + int retval = std::system("print-chip-prot-status.sh"); + if (retval != 0) { + utility::handleSystemError(retval, "Q7STestTask::testProtHandler"); + } - // lock own copy - result = coreController->setBootCopyProtection( - CoreController::Chip::SELF_CHIP, CoreController::Copy::SELF_COPY, true, - opPerformed, true); - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::warning << "Q7STestTask::testProtHandler: Op failed" << std::endl; - } - if(not opPerformed) { - sif::warning << "Q7STestTask::testProtHandler: No op performed" << std::endl; - } - retval = std::system("print-chip-prot-status.sh"); - if(retval != 0) { - utility::handleSystemError(retval, "Q7STestTask::testProtHandler"); - } + // lock own copy + result = coreController->setBootCopyProtection(xsc::Chip::SELF_CHIP, xsc::Copy::SELF_COPY, true, + opPerformed, true); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "Q7STestTask::testProtHandler: Op failed" << std::endl; + } + if (not opPerformed) { + sif::warning << "Q7STestTask::testProtHandler: No op performed" << std::endl; + } + retval = std::system("print-chip-prot-status.sh"); + if (retval != 0) { + utility::handleSystemError(retval, "Q7STestTask::testProtHandler"); + } - // unlock specific copy - result = coreController->setBootCopyProtection( - CoreController::Chip::CHIP_1, CoreController::Copy::COPY_1, false, - opPerformed, true); - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::warning << "Q7STestTask::testProtHandler: Op failed" << std::endl; - } - if(not opPerformed) { - sif::warning << "Q7STestTask::testProtHandler: No op performed" << std::endl; - } - retval = std::system("print-chip-prot-status.sh"); - if(retval != 0) { - utility::handleSystemError(retval, "Q7STestTask::testProtHandler"); - } + // unlock specific copy + result = coreController->setBootCopyProtection(xsc::Chip::CHIP_1, xsc::Copy::COPY_1, false, + opPerformed, true); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "Q7STestTask::testProtHandler: Op failed" << std::endl; + } + if (not opPerformed) { + sif::warning << "Q7STestTask::testProtHandler: No op performed" << std::endl; + } + retval = std::system("print-chip-prot-status.sh"); + if (retval != 0) { + utility::handleSystemError(retval, "Q7STestTask::testProtHandler"); + } - // lock specific copy - result = coreController->setBootCopyProtection( - CoreController::Chip::CHIP_1, CoreController::Copy::COPY_1, true, - opPerformed, true); - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::warning << "Q7STestTask::testProtHandler: Op failed" << std::endl; - } - if(not opPerformed) { - sif::warning << "Q7STestTask::testProtHandler: No op performed" << std::endl; - } - retval = std::system("print-chip-prot-status.sh"); - if(retval != 0) { - utility::handleSystemError(retval, "Q7STestTask::testProtHandler"); - } + // lock specific copy + result = coreController->setBootCopyProtection(xsc::Chip::CHIP_1, xsc::Copy::COPY_1, true, + opPerformed, true); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "Q7STestTask::testProtHandler: Op failed" << std::endl; + } + if (not opPerformed) { + sif::warning << "Q7STestTask::testProtHandler: No op performed" << std::endl; + } + retval = std::system("print-chip-prot-status.sh"); + if (retval != 0) { + utility::handleSystemError(retval, "Q7STestTask::testProtHandler"); + } +} + +void Q7STestTask::testGpsDaemon() { + gpsmm gpsmm(GPSD_SHARED_MEMORY, 0); + gps_data_t* gps; + gps = gpsmm.read(); + if (gps == nullptr) { + sif::warning << "Q7STestTask: Reading GPS data failed" << std::endl; + } + sif::info << "-- Q7STestTask: GPS shared memory read test --" << std::endl; + time_t timeRaw = gps->fix.time.tv_sec; + std::tm* time = gmtime(&timeRaw); + sif::info << "Time: " << std::put_time(time, "%c %Z") << std::endl; + sif::info << "Visible satellites: " << gps->satellites_visible << std::endl; + sif::info << "Satellites used: " << gps->satellites_used << std::endl; + sif::info << "Fix (0:Not Seen|1:No Fix|2:2D|3:3D): " << gps->fix.mode << std::endl; + sif::info << "Latitude: " << gps->fix.latitude << std::endl; + sif::info << "Longitude: " << gps->fix.longitude << std::endl; + sif::info << "Altitude(MSL): " << gps->fix.altMSL << std::endl; + sif::info << "Speed(m/s): " << gps->fix.speed << std::endl; } 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; - } - FileSystemHandler::FsCommandCfg cfg = {}; - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + auto fsHandler = ObjectManager::instance()->get(objects::FILE_SYSTEM_HANDLER); + if (fsHandler == nullptr) { + sif::warning << "Q7STestTask::testFileSystemHandlerDirect: No FS handler running.." + << std::endl; + } + FileSystemHandler::FsCommandCfg cfg = {}; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - // Lambda for common code - auto createNonEmptyTmpDir = [&]() { - if(not std::filesystem::exists("/tmp/test")) { - result = fsHandler->createDirectory("/tmp/test", &cfg); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - } - // Creating sample files - sif::info << "Creating sample files in directory" << std::endl; - result = fsHandler->createFile("/tmp/test", "test1.txt", nullptr, 0, &cfg); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - result = fsHandler->createFile("/tmp/test", "test2.txt", nullptr, 0, &cfg); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + // Lambda for common code + auto createNonEmptyTmpDir = [&]() { + if (not std::filesystem::exists("/tmp/test")) { + result = fsHandler->createDirectory("/tmp", "test", false, &cfg); + if (result != HasReturnvaluesIF::RETURN_OK) { return result; - }; + } + } + // Creating sample files + sif::info << "Creating sample files in directory" << std::endl; + result = fsHandler->createFile("/tmp/test", "test1.txt", nullptr, 0, &cfg); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = fsHandler->createFile("/tmp/test", "test2.txt", nullptr, 0, &cfg); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return result; + }; - - 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; + 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; - 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; + 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; } - 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", &cfg); - if(result == HasReturnvaluesIF::RETURN_OK) { - sif::info << "Directory created successfully" << std::endl; - } - else { - sif::warning << "Directory creation failed!" << std::endl; - } - 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; + } + 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", &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; + 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; } - 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; + 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; } - 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; - } + 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; } + 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 b0153ce9..b7aa791e 100644 --- a/bsp_q7s/boardtest/Q7STestTask.h +++ b/bsp_q7s/boardtest/Q7STestTask.h @@ -3,33 +3,44 @@ #include "test/testtasks/TestTask.h" -class Q7STestTask: public TestTask { -public: - Q7STestTask(object_id_t objectId); +class CoreController; - ReturnValue_t initialize() override; -private: - CoreController* coreController = nullptr; - ReturnValue_t performOneShotAction() override; +class Q7STestTask : public TestTask { + public: + Q7STestTask(object_id_t objectId); - void testSdCard(); - void fileTests(); + ReturnValue_t initialize() override; - void testScratchApi(); - void testJsonLibDirect(); - void testDummyParams(); - void testProtHandler(); + private: + bool doTestSdCard = false; + bool doTestScratchApi = false; + bool doTestGps = false; - enum FsOpCodes { - CREATE_EMPTY_FILE_IN_TMP, - REMOVE_TMP_FILE, - CREATE_DIR_IN_TMP, - REMOVE_EMPTY_DIR_IN_TMP, - ATTEMPT_DIR_REMOVAL_NON_EMPTY, - REMOVE_FILLED_DIR_IN_TMP, - }; - void testFileSystemHandlerDirect(FsOpCodes opCode); + CoreController* coreController = nullptr; + ReturnValue_t performOneShotAction() override; + ReturnValue_t performPeriodicAction() override; + + void testGpsDaemon(); + + void testSdCard(); + void fileTests(); + + void testScratchApi(); + void testJsonLibDirect(); + void testDummyParams(); + void testProtHandler(); + + enum FsOpCodes { + CREATE_EMPTY_FILE_IN_TMP, + REMOVE_TMP_FILE, + CREATE_DIR_IN_TMP, + REMOVE_EMPTY_DIR_IN_TMP, + ATTEMPT_DIR_REMOVAL_NON_EMPTY, + REMOVE_FILLED_DIR_IN_TMP, + RENAME_FILE, + APPEND_TO_FILE, + }; + void testFileSystemHandlerDirect(FsOpCodes opCode); }; - #endif /* BSP_Q7S_BOARDTEST_Q7STESTTASK_H_ */ diff --git a/bsp_q7s/callbacks/CMakeLists.txt b/bsp_q7s/callbacks/CMakeLists.txt index 8c83e26f..a4462937 100644 --- a/bsp_q7s/callbacks/CMakeLists.txt +++ b/bsp_q7s/callbacks/CMakeLists.txt @@ -1,4 +1,6 @@ -target_sources(${TARGET_NAME} PRIVATE +target_sources(${OBSW_NAME} PRIVATE rwSpiCallback.cpp gnssCallback.cpp + pcduSwitchCb.cpp + gpioCallbacks.cpp ) diff --git a/bsp_q7s/callbacks/gnssCallback.cpp b/bsp_q7s/callbacks/gnssCallback.cpp index 479f4a2b..d5dbc3b0 100644 --- a/bsp_q7s/callbacks/gnssCallback.cpp +++ b/bsp_q7s/callbacks/gnssCallback.cpp @@ -1,26 +1,25 @@ #include "gnssCallback.h" -#include "devices/gpioIds.h" +#include "devices/gpioIds.h" #include "fsfw/tasks/TaskFactory.h" -ReturnValue_t gps::triggerGpioResetPin(void *args) { - ResetArgs* resetArgs = reinterpret_cast(args); - if(args == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - if (resetArgs->gpioComIF == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - gpioId_t gpioId; - if(resetArgs->gnss1) { - gpioId = gpioIds::GNSS_1_NRESET; +ReturnValue_t gps::triggerGpioResetPin(void* args) { + ResetArgs* resetArgs = reinterpret_cast(args); + if (args == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + if (resetArgs->gpioComIF == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + gpioId_t gpioId; + if (resetArgs->gnss1) { + gpioId = gpioIds::GNSS_1_NRESET; - } - else { - gpioId = gpioIds::GNSS_0_NRESET; - } - resetArgs->gpioComIF->pullLow(gpioId); - TaskFactory::delayTask(resetArgs->waitPeriodMs); - resetArgs->gpioComIF->pullHigh(gpioId); - return HasReturnvaluesIF::RETURN_OK; + } else { + gpioId = gpioIds::GNSS_0_NRESET; + } + resetArgs->gpioComIF->pullLow(gpioId); + TaskFactory::delayTask(resetArgs->waitPeriodMs); + resetArgs->gpioComIF->pullHigh(gpioId); + return HasReturnvaluesIF::RETURN_OK; } diff --git a/bsp_q7s/callbacks/gnssCallback.h b/bsp_q7s/callbacks/gnssCallback.h index 9cbb6669..3e769899 100644 --- a/bsp_q7s/callbacks/gnssCallback.h +++ b/bsp_q7s/callbacks/gnssCallback.h @@ -1,13 +1,13 @@ #ifndef BSP_Q7S_CALLBACKS_GNSSCALLBACK_H_ #define BSP_Q7S_CALLBACKS_GNSSCALLBACK_H_ -#include "fsfw_hal/linux/gpio/LinuxLibgpioIF.h" #include "fsfw/returnvalues/HasReturnvaluesIF.h" +#include "fsfw_hal/linux/gpio/LinuxLibgpioIF.h" struct ResetArgs { - bool gnss1 = false; - LinuxLibgpioIF* gpioComIF = nullptr; - uint32_t waitPeriodMs = 100; + bool gnss1 = false; + LinuxLibgpioIF* gpioComIF = nullptr; + uint32_t waitPeriodMs = 100; }; namespace gps { diff --git a/bsp_q7s/callbacks/gpioCallbacks.cpp b/bsp_q7s/callbacks/gpioCallbacks.cpp new file mode 100644 index 00000000..e5fd877a --- /dev/null +++ b/bsp_q7s/callbacks/gpioCallbacks.cpp @@ -0,0 +1,487 @@ +#include "gpioCallbacks.h" + +#include +#include +#include +#include + +#include "busConf.h" + +namespace gpioCallbacks { + +GpioIF* gpioComInterface; + +void initSpiCsDecoder(GpioIF* gpioComIF) { + using namespace gpio; + ReturnValue_t result; + + if (gpioComIF == nullptr) { + sif::debug << "initSpiCsDecoder: Invalid gpioComIF" << std::endl; + return; + } + + gpioComInterface = gpioComIF; + + GpioCookie* spiMuxGpios = new GpioCookie; + + GpiodRegularByLineName* spiMuxBit = nullptr; + /** Setting mux bit 1 to low will disable IC21 on the interface board */ + spiMuxBit = new GpiodRegularByLineName(q7s::gpioNames::SPI_MUX_BIT_0_PIN, "SPI Mux Bit 1", + Direction::OUT, Levels::HIGH); + spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_0, spiMuxBit); + /** Setting mux bit 2 to low disables IC1 on the TCS board */ + spiMuxBit = new GpiodRegularByLineName(q7s::gpioNames::SPI_MUX_BIT_1_PIN, "SPI Mux Bit 2", + Direction::OUT, Levels::HIGH); + spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_1, spiMuxBit); + /** Setting mux bit 3 to low disables IC2 on the TCS board and IC22 on the interface board */ + spiMuxBit = new GpiodRegularByLineName(q7s::gpioNames::SPI_MUX_BIT_2_PIN, "SPI Mux Bit 3", + Direction::OUT, Levels::LOW); + spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_2, spiMuxBit); + + /** The following gpios can take arbitrary initial values */ + spiMuxBit = new GpiodRegularByLineName(q7s::gpioNames::SPI_MUX_BIT_3_PIN, "SPI Mux Bit 4", + Direction::OUT, Levels::LOW); + spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_3, spiMuxBit); + spiMuxBit = new GpiodRegularByLineName(q7s::gpioNames::SPI_MUX_BIT_4_PIN, "SPI Mux Bit 5", + Direction::OUT, Levels::LOW); + spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_4, spiMuxBit); + spiMuxBit = new GpiodRegularByLineName(q7s::gpioNames::SPI_MUX_BIT_5_PIN, "SPI Mux Bit 6", + Direction::OUT, Levels::LOW); + spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_5, spiMuxBit); + GpiodRegularByLineName* enRwDecoder = new GpiodRegularByLineName( + q7s::gpioNames::EN_RW_CS, "EN_RW_CS", Direction::OUT, Levels::HIGH); + spiMuxGpios->addGpio(gpioIds::EN_RW_CS, enRwDecoder); + + result = gpioComInterface->addGpios(spiMuxGpios); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "initSpiCsDecoder: Failed to add mux bit gpios to gpioComIF" << std::endl; + return; + } +} + +void spiCsDecoderCallback(gpioId_t gpioId, gpio::GpioOperation gpioOp, gpio::Levels value, + void* args) { + using namespace gpio; + if (gpioComInterface == nullptr) { + sif::debug << "spiCsDecoderCallback: No gpioComIF specified. Call initSpiCsDecoder " + << "to specify gpioComIF" << std::endl; + return; + } + + /* Reading is not supported by the callback function */ + if (gpioOp == gpio::GpioOperation::READ) { + return; + } + + if (value == Levels::HIGH) { + switch (gpioId) { + case (gpioIds::RTD_IC_3): { + disableDecoderTcsIc1(); + break; + } + case (gpioIds::RTD_IC_4): { + disableDecoderTcsIc1(); + break; + } + case (gpioIds::RTD_IC_5): { + disableDecoderTcsIc1(); + break; + } + case (gpioIds::RTD_IC_6): { + disableDecoderTcsIc1(); + break; + } + case (gpioIds::RTD_IC_7): { + disableDecoderTcsIc1(); + break; + } + case (gpioIds::RTD_IC_8): { + disableDecoderTcsIc1(); + break; + } + case (gpioIds::RTD_IC_9): { + disableDecoderTcsIc1(); + break; + } + case (gpioIds::RTD_IC_10): { + disableDecoderTcsIc1(); + break; + } + case (gpioIds::RTD_IC_11): { + disableDecoderTcsIc2(); + break; + } + case (gpioIds::RTD_IC_12): { + disableDecoderTcsIc2(); + break; + } + case (gpioIds::RTD_IC_13): { + disableDecoderTcsIc2(); + break; + } + case (gpioIds::RTD_IC_14): { + disableDecoderTcsIc2(); + break; + } + case (gpioIds::RTD_IC_15): { + disableDecoderTcsIc2(); + break; + } + case (gpioIds::RTD_IC_16): { + disableDecoderTcsIc2(); + break; + } + case (gpioIds::RTD_IC_17): { + disableDecoderTcsIc2(); + break; + } + case (gpioIds::RTD_IC_18): { + disableDecoderTcsIc2(); + break; + } + case (gpioIds::CS_SUS_0): { + disableDecoderInterfaceBoardIc1(); + break; + } + case (gpioIds::CS_SUS_1): { + disableDecoderInterfaceBoardIc1(); + break; + } + case (gpioIds::CS_SUS_2): { + disableDecoderInterfaceBoardIc1(); + break; + } + case (gpioIds::CS_SUS_3): { + disableDecoderInterfaceBoardIc1(); + break; + } + case (gpioIds::CS_SUS_4): { + disableDecoderInterfaceBoardIc1(); + break; + } + case (gpioIds::CS_SUS_5): { + disableDecoderInterfaceBoardIc1(); + break; + } + case (gpioIds::CS_SUS_6): { + disableDecoderInterfaceBoardIc2(); + break; + } + case (gpioIds::CS_SUS_7): { + disableDecoderInterfaceBoardIc2(); + break; + } + case (gpioIds::CS_SUS_8): { + disableDecoderInterfaceBoardIc2(); + break; + } + case (gpioIds::CS_SUS_9): { + disableDecoderInterfaceBoardIc2(); + break; + } + case (gpioIds::CS_SUS_10): { + disableDecoderInterfaceBoardIc2(); + break; + } + case (gpioIds::CS_SUS_11): { + disableDecoderInterfaceBoardIc2(); + break; + } + case (gpioIds::CS_RW1): { + disableRwDecoder(); + break; + } + case (gpioIds::CS_RW2): { + disableRwDecoder(); + break; + } + case (gpioIds::CS_RW3): { + disableRwDecoder(); + break; + } + case (gpioIds::CS_RW4): { + disableRwDecoder(); + break; + } + default: + sif::debug << "spiCsDecoderCallback: Invalid gpio id " << gpioId << std::endl; + } + } else if (value == Levels::LOW) { + switch (gpioId) { + case (gpioIds::RTD_IC_3): { + selectY7(); + enableDecoderTcsIc1(); + break; + } + case (gpioIds::RTD_IC_4): { + selectY6(); + enableDecoderTcsIc1(); + break; + } + case (gpioIds::RTD_IC_5): { + selectY5(); + enableDecoderTcsIc1(); + break; + } + case (gpioIds::RTD_IC_6): { + selectY4(); + enableDecoderTcsIc1(); + break; + } + case (gpioIds::RTD_IC_7): { + selectY3(); + enableDecoderTcsIc1(); + break; + } + case (gpioIds::RTD_IC_8): { + selectY2(); + enableDecoderTcsIc1(); + break; + } + case (gpioIds::RTD_IC_9): { + selectY1(); + enableDecoderTcsIc1(); + break; + } + case (gpioIds::RTD_IC_10): { + selectY0(); + enableDecoderTcsIc1(); + break; + } + case (gpioIds::RTD_IC_11): { + selectY7(); + enableDecoderTcsIc2(); + break; + } + case (gpioIds::RTD_IC_12): { + selectY6(); + enableDecoderTcsIc2(); + break; + } + case (gpioIds::RTD_IC_13): { + selectY5(); + enableDecoderTcsIc2(); + break; + } + case (gpioIds::RTD_IC_14): { + selectY4(); + enableDecoderTcsIc2(); + break; + } + case (gpioIds::RTD_IC_15): { + selectY3(); + enableDecoderTcsIc2(); + break; + } + case (gpioIds::RTD_IC_16): { + selectY2(); + enableDecoderTcsIc2(); + break; + } + case (gpioIds::RTD_IC_17): { + selectY1(); + enableDecoderTcsIc2(); + break; + } + case (gpioIds::RTD_IC_18): { + selectY0(); + enableDecoderTcsIc2(); + break; + } + case (gpioIds::CS_SUS_0): { + selectY0(); + enableDecoderInterfaceBoardIc1(); + break; + } + case (gpioIds::CS_SUS_1): { + selectY1(); + enableDecoderInterfaceBoardIc1(); + break; + } + case (gpioIds::CS_SUS_2): { + selectY2(); + enableDecoderInterfaceBoardIc1(); + break; + } + case (gpioIds::CS_SUS_3): { + selectY3(); + enableDecoderInterfaceBoardIc1(); + break; + } + case (gpioIds::CS_SUS_4): { + selectY4(); + enableDecoderInterfaceBoardIc1(); + break; + } + case (gpioIds::CS_SUS_5): { + selectY5(); + enableDecoderInterfaceBoardIc1(); + break; + } + case (gpioIds::CS_SUS_6): { + selectY0(); + enableDecoderInterfaceBoardIc2(); + break; + } + case (gpioIds::CS_SUS_7): { + selectY1(); + enableDecoderInterfaceBoardIc2(); + break; + } + case (gpioIds::CS_SUS_8): { + selectY2(); + enableDecoderInterfaceBoardIc2(); + break; + } + case (gpioIds::CS_SUS_9): { + selectY3(); + enableDecoderInterfaceBoardIc2(); + break; + } + case (gpioIds::CS_SUS_10): { + selectY4(); + enableDecoderInterfaceBoardIc2(); + break; + } + case (gpioIds::CS_SUS_11): { + selectY5(); + enableDecoderInterfaceBoardIc2(); + break; + } + case (gpioIds::CS_RW1): { + selectY0(); + enableRwDecoder(); + break; + } + case (gpioIds::CS_RW2): { + selectY1(); + enableRwDecoder(); + break; + } + case (gpioIds::CS_RW3): { + selectY2(); + enableRwDecoder(); + break; + } + case (gpioIds::CS_RW4): { + selectY3(); + enableRwDecoder(); + break; + } + default: + sif::debug << "spiCsDecoderCallback: Invalid gpio id " << gpioId << std::endl; + } + } else { + sif::debug << "spiCsDecoderCallback: Invalid value. Must be 0 or 1" << std::endl; + } +} + +void enableDecoderTcsIc1() { + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_0); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_1); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_2); +} + +void enableDecoderTcsIc2() { + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_2); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_0); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_1); +} + +void enableDecoderInterfaceBoardIc1() { + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_0); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_1); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_2); +} + +void enableDecoderInterfaceBoardIc2() { + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_0); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_1); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_2); +} + +void disableDecoderTcsIc1() { + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_0); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_1); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_2); +} + +void disableDecoderTcsIc2() { + // DO NOT CHANGE THE ORDER HERE + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_0); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_2); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_1); +} + +void disableDecoderInterfaceBoardIc1() { + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_0); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_1); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_2); +} + +void disableDecoderInterfaceBoardIc2() { + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_0); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_1); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_2); +} + +void enableRwDecoder() { gpioComInterface->pullHigh(gpioIds::EN_RW_CS); } + +void disableRwDecoder() { gpioComInterface->pullLow(gpioIds::EN_RW_CS); } + +void selectY0() { + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_3); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_4); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_5); +} + +void selectY1() { + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_3); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_4); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_5); +} + +void selectY2() { + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_3); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_4); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_5); +} + +void selectY3() { + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_3); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_4); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_5); +} + +void selectY4() { + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_3); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_4); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_5); +} + +void selectY5() { + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_3); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_4); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_5); +} + +void selectY6() { + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_3); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_4); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_5); +} + +void selectY7() { + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_3); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_4); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_5); +} + +void disableAllDecoder() { + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_2); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_0); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_1); + gpioComInterface->pullLow(gpioIds::EN_RW_CS); +} + +} // namespace gpioCallbacks diff --git a/bsp_q7s/callbacks/gpioCallbacks.h b/bsp_q7s/callbacks/gpioCallbacks.h new file mode 100644 index 00000000..6b4e99bf --- /dev/null +++ b/bsp_q7s/callbacks/gpioCallbacks.h @@ -0,0 +1,73 @@ +#ifndef LINUX_GPIO_GPIOCALLBACKS_H_ +#define LINUX_GPIO_GPIOCALLBACKS_H_ + +#include +#include + +namespace gpioCallbacks { + +/** + * @brief This function initializes the GPIOs used to control the SN74LVC138APWR decoders on + * the TCS Board and the interface board. + */ +void initSpiCsDecoder(GpioIF* gpioComIF); + +/** + * @brief This function implements the decoding to multiply gpios by using the decoder + * chips SN74LVC138APWR on the TCS board and the interface board. + */ +void spiCsDecoderCallback(gpioId_t gpioId, gpio::GpioOperation gpioOp, gpio::Levels value, + void* args); + +/** + * @brief This function sets mux bits 1-3 to a state which will only enable the decoder + * on the TCS board which is named to IC1 in the schematic. + */ +void enableDecoderTcsIc1(); + +/** + * @brief This function sets mux bits 1-3 to a state which will only enable the decoder + * on the TCS board which is named to IC2 in the schematic. + */ +void enableDecoderTcsIc2(); + +/** + * @brief This function sets mux bits 1-3 to a state which will only enable the decoder + * on the inteface board board which is named to IC21 in the schematic. + */ +void enableDecoderInterfaceBoardIc1(); + +/** + * @brief This function sets mux bits 1-3 to a state which will only enable the decoder + * on the inteface board board which is named to IC22 in the schematic. + */ +void enableDecoderInterfaceBoardIc2(); + +void disableDecoderTcsIc1(); +void disableDecoderTcsIc2(); +void disableDecoderInterfaceBoardIc1(); +void disableDecoderInterfaceBoardIc2(); + +/** + * @brief Enables the reaction wheel chip select decoder (IC3). + */ +void enableRwDecoder(); +void disableRwDecoder(); + +/** + * @brief This function disables all decoder. + */ +void disableAllDecoder(); + +/** The following functions enable the appropriate channel of the currently enabled decoder */ +void selectY0(); +void selectY1(); +void selectY2(); +void selectY3(); +void selectY4(); +void selectY5(); +void selectY6(); +void selectY7(); +} // namespace gpioCallbacks + +#endif /* LINUX_GPIO_GPIOCALLBACKS_H_ */ diff --git a/bsp_q7s/callbacks/pcduSwitchCb.cpp b/bsp_q7s/callbacks/pcduSwitchCb.cpp new file mode 100644 index 00000000..ec5f4dc5 --- /dev/null +++ b/bsp_q7s/callbacks/pcduSwitchCb.cpp @@ -0,0 +1,32 @@ +#include "pcduSwitchCb.h" + +#include + +#include "devices/gpioIds.h" + +void pcdu::switchCallback(GOMSPACE::Pdu pdu, uint8_t channel, bool state, void* args) { + LinuxLibgpioIF* gpioComIF = reinterpret_cast(args); + if (gpioComIF == nullptr) { + return; + } + if (pdu == GOMSPACE::Pdu::PDU1) { + PDU1::SwitchChannels typedChannel = static_cast(channel); + if (typedChannel == PDU1::SwitchChannels::ACS_A_SIDE) { + if (state) { + gpioComIF->pullHigh(gpioIds::GNSS_0_NRESET); + } else { + gpioComIF->pullLow(gpioIds::GNSS_0_NRESET); + } + } + + } else if (pdu == GOMSPACE::Pdu::PDU2) { + PDU2::SwitchChannels typedChannel = static_cast(channel); + if (typedChannel == PDU2::SwitchChannels::ACS_B_SIDE) { + if (state) { + gpioComIF->pullHigh(gpioIds::GNSS_1_NRESET); + } else { + gpioComIF->pullLow(gpioIds::GNSS_1_NRESET); + } + } + } +} diff --git a/bsp_q7s/callbacks/pcduSwitchCb.h b/bsp_q7s/callbacks/pcduSwitchCb.h new file mode 100644 index 00000000..d0f2b748 --- /dev/null +++ b/bsp_q7s/callbacks/pcduSwitchCb.h @@ -0,0 +1,14 @@ +#ifndef BSP_Q7S_CALLBACKS_PCDUSWITCHCB_H_ +#define BSP_Q7S_CALLBACKS_PCDUSWITCHCB_H_ + +#include + +#include "mission/devices/devicedefinitions/GomspaceDefinitions.h" + +namespace pcdu { + +void switchCallback(GOMSPACE::Pdu pdu, uint8_t channel, bool state, void* args); + +} + +#endif /* BSP_Q7S_CALLBACKS_PCDUSWITCHCB_H_ */ diff --git a/bsp_q7s/callbacks/rwSpiCallback.cpp b/bsp_q7s/callbacks/rwSpiCallback.cpp index 73516fb4..3ca3c181 100644 --- a/bsp_q7s/callbacks/rwSpiCallback.cpp +++ b/bsp_q7s/callbacks/rwSpiCallback.cpp @@ -1,237 +1,232 @@ #include "rwSpiCallback.h" -#include "devices/gpioIds.h" -#include "mission/devices/RwHandler.h" -#include "fsfw_hal/linux/spi/SpiCookie.h" -#include "fsfw_hal/linux/UnixFileGuard.h" +#include "devices/gpioIds.h" #include "fsfw/serviceinterface/ServiceInterface.h" +#include "fsfw_hal/linux/UnixFileGuard.h" +#include "fsfw_hal/linux/spi/SpiCookie.h" +#include "mission/devices/RwHandler.h" namespace rwSpiCallback { -ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie *cookie, const uint8_t *sendData, - size_t sendLen, void* args) { +ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie* cookie, const uint8_t* sendData, + size_t sendLen, void* args) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + RwHandler* handler = reinterpret_cast(args); + if (handler == nullptr) { + sif::error << "rwSpiCallback::spiCallback: Pointer to handler is invalid" << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } - RwHandler* handler = reinterpret_cast(args); - if(handler == nullptr) { - sif::error << "rwSpiCallback::spiCallback: Pointer to handler is invalid" - << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; + 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); + 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); + 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; } + } - uint8_t writeBuffer[2]; - uint8_t writeSize = 0; + if (write(fileDescriptor, writeBuffer, writeSize) != static_cast(writeSize)) { + sif::error << "rwSpiCallback::spiCallback: Write failed!" << std::endl; + closeSpi(gpioId, gpioIF, mutex); + return RwHandler::SPI_WRITE_FAILURE; + } - 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; + /** Encoding and sending command */ + size_t idx = 0; + while (idx < sendLen) { + switch (*(sendData + idx)) { + case 0x7E: + writeBuffer[0] = 0x7D; + writeBuffer[1] = 0x5E; + writeSize = 2; + break; + case 0x7D: + writeBuffer[0] = 0x7D; + writeBuffer[1] = 0x5D; + writeSize = 2; + break; + default: + writeBuffer[0] = *(sendData + idx); + writeSize = 1; + break; } - spi::SpiModes spiMode = spi::SpiModes::MODE_0; - uint32_t spiSpeed = 0; - cookie->getSpiParameters(spiMode, spiSpeed, nullptr); - comIf->setSpiSpeedAndMode(fileDescriptor, spiMode, spiSpeed); - - 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); - if(mutex == nullptr or gpioIF == nullptr) { - sif::debug << "rwSpiCallback::spiCallback: Mutex or GPIO interface invalid" << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; - } - - result = mutex->lockMutex(timeoutType, timeoutMs); - if (result != HasReturnvaluesIF::RETURN_OK) { - sif::debug << "rwSpiCallback::spiCallback: Failed to lock mutex" << std::endl; - return result; - } - - /** Disconnect PS SPI peripheral and select AXI SPI core */ - if(gpioIF->pullHigh(gpioIds::SPI_MUX) != HasReturnvaluesIF::RETURN_OK) { - sif::error << "rwSpiCallback::spiCallback: Failed to pull spi mux gpio high" << std::endl; - } - - /** 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; - } - } - if (write(fileDescriptor, writeBuffer, writeSize) != static_cast(writeSize)) { - sif::error << "rwSpiCallback::spiCallback: Write failed!" << std::endl; + sif::error << "rwSpiCallback::spiCallback: Write failed!" << std::endl; + closeSpi(gpioId, gpioIF, mutex); + return RwHandler::SPI_WRITE_FAILURE; + } + idx++; + } + + /** Sending frame end sign */ + writeBuffer[0] = 0x7E; + writeSize = 1; + + if (write(fileDescriptor, writeBuffer, writeSize) != static_cast(writeSize)) { + sif::error << "rwSpiCallback::spiCallback: Write failed!" << std::endl; + closeSpi(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); + return result; + } + + size_t replyBufferSize = cookie->getMaxBufferSize(); + + /** There must be a delay of at least 20 ms after sending the command */ + usleep(RwDefinitions::SPI_REPLY_DELAY); + + /** + * The reaction wheel responds with empty frames while preparing the reply data. + * However, receiving more than 5 empty frames will be interpreted as an error. + */ + uint8_t byteRead = 0; + 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); + 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); - return RwHandler::SPI_WRITE_FAILURE; + return RwHandler::NO_START_MARKER; + } } - /** Encoding and sending command */ - size_t idx = 0; - while(idx < sendLen) { - switch(*(sendData + idx)) { - case 0x7E: - writeBuffer[0] = 0x7D; - writeBuffer[1] = 0x5E; - writeSize = 2; - break; - case 0x7D: - writeBuffer[0] = 0x7D; - writeBuffer[1] = 0x5D; - writeSize = 2; - break; - default: - writeBuffer[0] = *(sendData + idx); - writeSize = 1; - break; - } - if (write(fileDescriptor, writeBuffer, writeSize) != static_cast(writeSize)) { - sif::error << "rwSpiCallback::spiCallback: Write failed!" << std::endl; - closeSpi(gpioId, gpioIF, mutex); - return RwHandler::SPI_WRITE_FAILURE; - } - idx++; + if (byteRead != FLAG_BYTE) { + break; } - /** Sending frame end sign */ - writeBuffer[0] = 0x7E; - writeSize = 1; + if (idx == 9) { + sif::error << "rwSpiCallback::spiCallback: Empty frame timeout" << std::endl; + closeSpi(gpioId, gpioIF, mutex); + return RwHandler::NO_REPLY; + } + } - if (write(fileDescriptor, writeBuffer, writeSize) != static_cast(writeSize)) { - sif::error << "rwSpiCallback::spiCallback: Write failed!" << std::endl; +#if FSFW_HAL_SPI_WIRETAPPING == 1 + sif::info << "RW start marker detected" << std::endl; +#endif + + size_t decodedFrameLen = 0; + while (decodedFrameLen < replyBufferSize) { + /** First byte already read in */ + if (decodedFrameLen != 0) { + byteRead = 0; + if (read(fileDescriptor, &byteRead, 1) != 1) { + sif::error << "rwSpiCallback::spiCallback: Read failed" << std::endl; + result = RwHandler::SPI_READ_FAILURE; + break; + } + } + + if (byteRead == FLAG_BYTE) { + /** Reached end of frame */ + break; + } else if (byteRead == 0x7D) { + if (read(fileDescriptor, &byteRead, 1) != 1) { + sif::error << "rwSpiCallback::spiCallback: Read failed" << std::endl; + result = RwHandler::SPI_READ_FAILURE; + break; + } + if (byteRead == 0x5E) { + *(rxBuf + decodedFrameLen) = 0x7E; + decodedFrameLen++; + continue; + } else if (byteRead == 0x5D) { + *(rxBuf + decodedFrameLen) = 0x7D; + decodedFrameLen++; + continue; + } else { + sif::error << "rwSpiCallback::spiCallback: Invalid substitute" << std::endl; closeSpi(gpioId, gpioIF, mutex); - return RwHandler::SPI_WRITE_FAILURE; + result = RwHandler::INVALID_SUBSTITUTE; + break; + } + } else { + *(rxBuf + decodedFrameLen) = byteRead; + decodedFrameLen++; + continue; } - uint8_t* rxBuf = nullptr; - result = comIf->getReadBuffer(cookie->getSpiAddress(), &rxBuf); - if(result != HasReturnvaluesIF::RETURN_OK) { - closeSpi(gpioId, gpioIF, mutex); - return result; - } - - size_t replyBufferSize = cookie->getMaxBufferSize(); - - /** There must be a delay of 20 ms after sending the command */ - usleep(RwDefinitions::SPI_REPLY_DELAY); - /** - * The reaction wheel responds with empty frames while preparing the reply data. - * However, receiving more than 5 empty frames will be interpreted as an error. + * There might be the unlikely case that each byte in a get-telemetry reply has been + * replaced by its substitute. Than the next byte must correspond to the end sign 0x7E. + * Otherwise there might be something wrong. */ - uint8_t byteRead = 0; - 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); - return RwHandler::SPI_READ_FAILURE; - } - - if (byteRead != 0x7E) { - break; - } - - if (idx == 9) { - sif::error << "rwSpiCallback::spiCallback: Empty frame timeout" << std::endl; - closeSpi(gpioId, gpioIF, mutex); - return RwHandler::NO_REPLY; - } + if (decodedFrameLen == replyBufferSize) { + if (read(fileDescriptor, &byteRead, 1) != 1) { + sif::error << "rwSpiCallback::spiCallback: Failed to read last byte" << std::endl; + result = RwHandler::SPI_READ_FAILURE; + break; + } + if (byteRead != 0x7E) { + sif::error << "rwSpiCallback::spiCallback: Missing end sign 0x7E" << std::endl; + decodedFrameLen--; + result = RwHandler::MISSING_END_SIGN; + break; + } } + result = HasReturnvaluesIF::RETURN_OK; + } - size_t decodedFrameLen = 0; - while(decodedFrameLen < replyBufferSize) { + cookie->setTransferSize(decodedFrameLen); - /** First byte already read in */ - if (decodedFrameLen != 0) { - byteRead = 0; - if(read(fileDescriptor, &byteRead, 1) != 1) { - sif::error << "rwSpiCallback::spiCallback: Read failed" << std::endl; - result = RwHandler::SPI_READ_FAILURE; - break; - } - } + closeSpi(gpioId, gpioIF, mutex); - if (byteRead == 0x7E) { - /** Reached end of frame */ - break; - } - else if (byteRead == 0x7D) { - if(read(fileDescriptor, &byteRead, 1) != 1) { - sif::error << "rwSpiCallback::spiCallback: Read failed" << std::endl; - result = RwHandler::SPI_READ_FAILURE; - break; - } - if (byteRead == 0x5E) { - *(rxBuf + decodedFrameLen) = 0x7E; - decodedFrameLen++; - continue; - } - else if (byteRead == 0x5D) { - *(rxBuf + decodedFrameLen) = 0x7D; - decodedFrameLen++; - continue; - } - else { - sif::error << "rwSpiCallback::spiCallback: Invalid substitute" << std::endl; - closeSpi(gpioId, gpioIF, mutex); - result = RwHandler::INVALID_SUBSTITUTE; - break; - } - } - else { - *(rxBuf + decodedFrameLen) = byteRead; - decodedFrameLen++; - continue; - } - - /** - * There might be the unlikely case that each byte in a get-telemetry reply has been - * replaced by its substitute. Than the next byte must correspond to the end sign 0x7E. - * Otherwise there might be something wrong. - */ - if (decodedFrameLen == replyBufferSize) { - if(read(fileDescriptor, &byteRead, 1) != 1) { - sif::error << "rwSpiCallback::spiCallback: Failed to read last byte" << std::endl; - result = RwHandler::SPI_READ_FAILURE; - break; - } - if (byteRead != 0x7E) { - sif::error << "rwSpiCallback::spiCallback: Missing end sign 0x7E" << std::endl; - decodedFrameLen--; - result = RwHandler::MISSING_END_SIGN; - break; - } - } - result = HasReturnvaluesIF::RETURN_OK; - } - - cookie->setTransferSize(decodedFrameLen); - - closeSpi(gpioId, gpioIF, mutex); - - return result; + return result; } -void closeSpi (gpioId_t gpioId, GpioIF* gpioIF, MutexIF* mutex) { - if(gpioId != gpio::NO_GPIO) { - if (gpioIF->pullHigh(gpioId) != HasReturnvaluesIF::RETURN_OK) { - sif::error << "closeSpi: Failed to pull chip select high" << std::endl; - } - } - if(mutex->unlockMutex() != HasReturnvaluesIF::RETURN_OK) { - sif::error << "rwSpiCallback::closeSpi: Failed to unlock mutex" << std::endl;; - } - - /** Route SPI interface again to PS SPI peripheral */ - if(gpioIF->pullLow(gpioIds::SPI_MUX) != HasReturnvaluesIF::RETURN_OK) { - sif::error << "rwSpiCallback::spiCallback: Failed to pull spi mux gpio low" << std::endl; +void closeSpi(gpioId_t gpioId, GpioIF* gpioIF, MutexIF* mutex) { + if (gpioId != gpio::NO_GPIO) { + if (gpioIF->pullHigh(gpioId) != HasReturnvaluesIF::RETURN_OK) { + sif::error << "closeSpi: Failed to pull chip select high" << std::endl; } + } + if (mutex->unlockMutex() != HasReturnvaluesIF::RETURN_OK) { + sif::error << "rwSpiCallback::closeSpi: Failed to unlock mutex" << std::endl; + ; + } } -} +} // namespace rwSpiCallback diff --git a/bsp_q7s/callbacks/rwSpiCallback.h b/bsp_q7s/callbacks/rwSpiCallback.h index cc7c6cbe..843d5b80 100644 --- a/bsp_q7s/callbacks/rwSpiCallback.h +++ b/bsp_q7s/callbacks/rwSpiCallback.h @@ -2,12 +2,14 @@ #define BSP_Q7S_RW_SPI_CALLBACK_H_ #include "fsfw/returnvalues/HasReturnvaluesIF.h" -#include "fsfw_hal/linux/spi/SpiComIF.h" #include "fsfw_hal/common/gpio/GpioCookie.h" - +#include "fsfw_hal/linux/spi/SpiComIF.h" namespace rwSpiCallback { +//! This is the end and start marker of the frame datalinklayer +static constexpr uint8_t FLAG_BYTE = 0x7E; + /** * @brief This is the callback function to send commands to the nano avionics reaction wheels and * receive the replies. @@ -28,8 +30,8 @@ namespace rwSpiCallback { * To switch between the to SPI peripherals, an EMIO is used which will also be controlled * by this function. */ -ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie *cookie, const uint8_t *sendData, - size_t sendLen, void* args); +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 @@ -40,5 +42,5 @@ ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie *cookie, const uint8_t *sen */ 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 0599b73f..fe4910f2 100644 --- a/bsp_q7s/comIF/CMakeLists.txt +++ b/bsp_q7s/comIF/CMakeLists.txt @@ -1,4 +1,4 @@ -target_sources(${TARGET_NAME} PRIVATE +target_sources(${OBSW_NAME} PRIVATE ) diff --git a/bsp_q7s/core/CMakeLists.txt b/bsp_q7s/core/CMakeLists.txt index fc397f2f..8731b7a3 100644 --- a/bsp_q7s/core/CMakeLists.txt +++ b/bsp_q7s/core/CMakeLists.txt @@ -1,6 +1,10 @@ -target_sources(${TARGET_NAME} PRIVATE +target_sources(${OBSW_NAME} PRIVATE CoreController.cpp obsw.cpp InitMission.cpp ObjectFactory.cpp ) + +target_sources(${SIMPLE_OBSW_NAME} PRIVATE + InitMission.cpp +) diff --git a/bsp_q7s/core/CoreController.cpp b/bsp_q7s/core/CoreController.cpp index b899e60f..b1783054 100644 --- a/bsp_q7s/core/CoreController.cpp +++ b/bsp_q7s/core/CoreController.cpp @@ -1,1172 +1,1647 @@ #include "CoreController.h" + +#include + #include "OBSWConfig.h" #include "OBSWVersion.h" -#include "watchdogConf.h" - #include "fsfw/FSFWVersion.h" -#include "fsfw/timemanager/Stopwatch.h" #include "fsfw/serviceinterface/ServiceInterface.h" -#include "fsfw/osal/linux/Timer.h" +#include "fsfw/timemanager/Stopwatch.h" +#include "watchdogConf.h" #if OBSW_USE_TMTC_TCP_BRIDGE == 0 #include "fsfw/osal/common/UdpTmTcBridge.h" #else #include "fsfw/osal/common/TcpTmTcServer.h" #endif -#include "bsp_q7s/memory/scratchApi.h" -#include "bsp_q7s/memory/SdCardManager.h" - #include #include #include -CoreController::Chip CoreController::CURRENT_CHIP = Chip::NO_CHIP; -CoreController::Copy CoreController::CURRENT_COPY = Copy::NO_COPY; +#include "bsp_q7s/memory/SdCardManager.h" +#include "bsp_q7s/memory/scratchApi.h" -CoreController::CoreController(object_id_t objectId): - ExtendedControllerBase(objectId, objects::NO_OBJECT, 5), opDivider(5) { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - try { - result = initWatchdogFifo(); - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::warning << "CoreController::CoreController: Watchdog FIFO init failed" << - std::endl; - } - sdcMan = SdCardManager::instance(); - if(sdcMan == nullptr) { - sif::error << "CoreController::CoreController: SD card manager invalid!" << std::endl; - } +xsc::Chip CoreController::CURRENT_CHIP = xsc::Chip::NO_CHIP; +xsc::Copy CoreController::CURRENT_COPY = xsc::Copy::NO_COPY; - if(not BLOCKING_SD_INIT) { - sdcMan->setBlocking(false); - } - sdStateMachine(); - - result = initBootCopy(); - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::warning << "CoreController::CoreController: Boot copy init" << std::endl; - } +CoreController::CoreController(object_id_t objectId) + : ExtendedControllerBase(objectId, objects::NO_OBJECT, 5), opDivider(5) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + try { + result = initWatchdogFifo(); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "CoreController::CoreController: Watchdog FIFO init failed" << std::endl; } - catch(const std::filesystem::filesystem_error& e) { - sif::error << "CoreController::CoreController: Failed with exception " << - e.what() << std::endl; + sdcMan = SdCardManager::instance(); + if (sdcMan == nullptr) { + sif::error << "CoreController::CoreController: SD card manager invalid!" << std::endl; } + + if (not BLOCKING_SD_INIT) { + sdcMan->setBlocking(false); + } + sdStateMachine(); + + result = initBootCopy(); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "CoreController::CoreController: Boot copy init" << std::endl; + } + } catch (const std::filesystem::filesystem_error &e) { + sif::error << "CoreController::CoreController: Failed with exception " << e.what() << std::endl; + } } ReturnValue_t CoreController::handleCommandMessage(CommandMessage *message) { - return ExtendedControllerBase::handleCommandMessage(message); + return ExtendedControllerBase::handleCommandMessage(message); } void CoreController::performControlOperation() { - performWatchdogControlOperation(); - sdStateMachine(); + performWatchdogControlOperation(); + sdStateMachine(); + performMountedSdCardOperations(); } ReturnValue_t CoreController::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, - LocalDataPoolManager &poolManager) { - return HasReturnvaluesIF::RETURN_OK; + LocalDataPoolManager &poolManager) { + return HasReturnvaluesIF::RETURN_OK; } -LocalPoolDataSetBase* CoreController::getDataSetHandle(sid_t sid) { - return nullptr; -} +LocalPoolDataSetBase *CoreController::getDataSetHandle(sid_t sid) { return nullptr; } ReturnValue_t CoreController::initialize() { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - result = scratch::writeNumber(scratch::ALLOC_FAILURE_COUNT, 0); - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::warning << "CoreController::initialize: Setting up alloc failure " - "count failed" << std::endl; - } + result = scratch::writeNumber(scratch::ALLOC_FAILURE_COUNT, 0); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "CoreController::initialize: Setting up alloc failure " + "count failed" + << std::endl; + } - sdStateMachine(); - return ExtendedControllerBase::initialize(); + sdStateMachine(); + + triggerEvent(REBOOT_SW, CURRENT_CHIP, CURRENT_COPY); + return ExtendedControllerBase::initialize(); } ReturnValue_t CoreController::initializeAfterTaskCreation() { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - if(BLOCKING_SD_INIT) { - ReturnValue_t result = initSdCardBlocking(); - if(result != HasReturnvaluesIF::RETURN_OK and result != SdCardManager::ALREADY_MOUNTED) { - sif::warning << "CoreController::CoreController: SD card init failed" << std::endl; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + if (BLOCKING_SD_INIT) { + ReturnValue_t result = initSdCardBlocking(); + if (result != HasReturnvaluesIF::RETURN_OK and result != SdCardManager::ALREADY_MOUNTED) { + sif::warning << "CoreController::CoreController: SD card init failed" << std::endl; + } + } + sdStateMachine(); + performMountedSdCardOperations(); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "CoreController::initialize: Version initialization failed" << std::endl; + } + // Add script folder to path + char *currentEnvPath = getenv("PATH"); + std::string updatedEnvPath = std::string(currentEnvPath) + ":/home/root/scripts"; + setenv("PATH", updatedEnvPath.c_str(), true); + updateProtInfo(); + initPrint(); + return result; +} + +ReturnValue_t CoreController::executeAction(ActionId_t actionId, MessageQueueId_t commandedBy, + const uint8_t *data, size_t size) { + switch (actionId) { + case (LIST_DIRECTORY_INTO_FILE): { + return actionListDirectoryIntoFile(actionId, commandedBy, data, size); + } + case (SWITCH_REBOOT_FILE_HANDLING): { + if (size < 1) { + return HasActionsIF::INVALID_PARAMETERS; + } + std::string path = sdcMan->getCurrentMountPrefix(sdInfo.pref) + REBOOT_FILE; + // Disable the reboot file mechanism + parseRebootFile(path, rebootFile); + if (data[0] == 0) { + rebootFile.enabled = false; + rewriteRebootFile(rebootFile); + } else if (data[0] == 1) { + rebootFile.enabled = true; + rewriteRebootFile(rebootFile); + } else { + return HasActionsIF::INVALID_PARAMETERS; + } + return HasActionsIF::EXECUTION_FINISHED; + } + case (RESET_REBOOT_COUNTERS): { + if (size == 0) { + resetRebootCount(xsc::ALL_CHIP, xsc::ALL_COPY); + } else if (size == 2) { + if (data[0] > 1 or data[1] > 1) { + return HasActionsIF::INVALID_PARAMETERS; } + resetRebootCount(static_cast(data[0]), static_cast(data[1])); + } + return HasActionsIF::EXECUTION_FINISHED; } - sdStateMachine(); - result = initVersionFile(); - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::warning << "CoreController::initialize: Version initialization failed" << std::endl; + case (SWITCH_IMG_LOCK): { + if (size != 3) { + return HasActionsIF::INVALID_PARAMETERS; + } + if (data[1] > 1 or data[2] > 1) { + return HasActionsIF::INVALID_PARAMETERS; + } + setRebootMechanismLock(data[0], static_cast(data[1]), + static_cast(data[2])); + return HasActionsIF::EXECUTION_FINISHED; } - // Add script folder to path - char* currentEnvPath = getenv("PATH"); - std::string updatedEnvPath = std::string(currentEnvPath) + ":/home/root/scripts"; - setenv("PATH", updatedEnvPath.c_str(), true); - updateProtInfo(); - initPrint(); - return result; + case (SET_MAX_REBOOT_CNT): { + if (size < 1) { + return HasActionsIF::INVALID_PARAMETERS; + } + std::string path = sdcMan->getCurrentMountPrefix(sdInfo.pref) + REBOOT_FILE; + // Disable the reboot file mechanism + parseRebootFile(path, rebootFile); + rebootFile.maxCount = data[0]; + rewriteRebootFile(rebootFile); + return HasActionsIF::EXECUTION_FINISHED; + } + case (REBOOT_OBC): { + return actionPerformReboot(data, size); + } + default: { + return HasActionsIF::INVALID_ACTION_ID; + } + } } ReturnValue_t CoreController::checkModeCommand(Mode_t mode, Submode_t submode, - uint32_t *msToReachTheMode) { - return HasReturnvaluesIF::RETURN_OK; + uint32_t *msToReachTheMode) { + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t CoreController::initSdCardBlocking() { - // Create update status file - ReturnValue_t result = sdcMan->updateSdCardStateFile(); - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::warning << "CoreController::initialize: Updating SD card state file failed" - << std::endl; - } + // Create update status file + ReturnValue_t result = sdcMan->updateSdCardStateFile(); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "CoreController::initialize: Updating SD card state file failed" << std::endl; + } #if Q7S_SD_CARD_CONFIG == Q7S_SD_NONE - sif::info << "No SD card initialization will be performed" << std::endl; - return HasReturnvaluesIF::RETURN_OK; + sif::info << "No SD card initialization will be performed" << std::endl; + return HasReturnvaluesIF::RETURN_OK; #else - result = sdcMan->getSdCardActiveStatus(sdInfo.currentState); - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::warning << "Getting SD card activity status failed" << std::endl; - } + result = sdcMan->getSdCardActiveStatus(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; - result = sdColdRedundantBlockingInit(); - // Update status file - sdcMan->updateSdCardStateFile(); - return result; + determinePreferredSdCard(); + updateSdInfoOther(); + sif::info << "Cold redundant SD card configuration, preferred SD card: " + << static_cast(sdInfo.pref) << std::endl; + result = sdColdRedundantBlockingInit(); + // Update status file + sdcMan->updateSdCardStateFile(); + return result; #elif Q7S_SD_CARD_CONFIG == Q7S_SD_HOT_REDUNDANT - sif::info << "Hot redundant SD card configuration" << std::endl; - sdCardSetup(sd::SdCard::SLOT_0, sd::SdState::MOUNTED, "0", false); - sdCardSetup(sd::SdCard::SLOT_1, sd::SdState::MOUNTED, "1", false); - // Update status file - sdcMan->updateSdCardStateFile(); - return HasReturnvaluesIF::RETURN_OK; + sif::info << "Hot redundant SD card configuration" << std::endl; + sdCardSetup(sd::SdCard::SLOT_0, sd::SdState::MOUNTED, "0", false); + sdCardSetup(sd::SdCard::SLOT_1, sd::SdState::MOUNTED, "1", false); + // Update status file + sdcMan->updateSdCardStateFile(); + return HasReturnvaluesIF::RETURN_OK; #endif #endif /* Q7S_SD_CARD_CONFIG != Q7S_SD_NONE */ - } ReturnValue_t CoreController::sdStateMachine() { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - SdCardManager::Operations operation; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + SdCardManager::Operations operation; - if(sdInfo.state == SdStates::IDLE) { - // Nothing to do - return result; - } + if (sdInfo.state == SdStates::IDLE) { + // Nothing to do + return result; + } - if(sdInfo.state == SdStates::START) { - // Init will be performed by separate function - if(BLOCKING_SD_INIT) { - sdInfo.state = SdStates::IDLE; - sdInfo.initFinished = true; - return result; - } - else { - // Still update SD state file + if (sdInfo.state == SdStates::START) { + // Init will be performed by separate function + if (BLOCKING_SD_INIT) { + sdInfo.state = SdStates::IDLE; + sdInfo.initFinished = true; + return result; + } else { + // Still update SD state file #if Q7S_SD_CARD_CONFIG == Q7S_SD_NONE - sdInfo.state = SdStates::UPDATE_INFO; + sdInfo.state = SdStates::UPDATE_INFO; #else - sdInfo.cycleCount = 0; - sdInfo.commandExecuted = false; - sdInfo.state = SdStates::GET_INFO; + sdInfo.cycleCount = 0; + sdInfo.commandExecuted = false; + sdInfo.state = SdStates::GET_INFO; #endif - } } + } - // This lambda checks the non-blocking operation and assigns the new state on success. - // It returns true for an operation success and false otherwise - auto nonBlockingOpChecking = [&](SdStates newStateOnSuccess, - uint16_t maxCycleCount, std::string opPrintout) { - SdCardManager::OpStatus status = sdcMan->checkCurrentOp(operation); - if(status == SdCardManager::OpStatus::SUCCESS) { - sdInfo.state = newStateOnSuccess; - sdInfo.commandExecuted = false; - sdInfo.cycleCount = 0; - return true; - } - else if(sdInfo.cycleCount > 4) { - sif::warning << "CoreController::sdInitStateMachine: " << opPrintout << - " takes too long" << std::endl; - return false; - } - return false; - }; - - if(sdInfo.state == SdStates::GET_INFO) { - if(not sdInfo.commandExecuted) { - // Create update status file - result = sdcMan->updateSdCardStateFile(); - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::warning << "CoreController::initialize: Updating SD card state file failed" - << std::endl; - } - sdInfo.commandExecuted = true; - } - else { - nonBlockingOpChecking(SdStates::SET_STATE_SELF, 4, "Updating SDC file"); - } + // This lambda checks the non-blocking operation and assigns the new state on success. + // It returns true for an operation success and false otherwise + auto nonBlockingOpChecking = [&](SdStates newStateOnSuccess, uint16_t maxCycleCount, + std::string opPrintout) { + SdCardManager::OpStatus status = sdcMan->checkCurrentOp(operation); + if (status == SdCardManager::OpStatus::SUCCESS) { + sdInfo.state = newStateOnSuccess; + sdInfo.commandExecuted = false; + sdInfo.cycleCount = 0; + return true; + } else if (sdInfo.cycleCount > 4) { + sif::warning << "CoreController::sdInitStateMachine: " << opPrintout << " takes too long" + << std::endl; + return false; } + return false; + }; - if(sdInfo.state == SdStates::SET_STATE_SELF) { - if(not sdInfo.commandExecuted) { - result = sdcMan->getSdCardActiveStatus(sdInfo.currentState); - determinePreferredSdCard(); - 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; - sdInfo.pref = sd::SdCard::SLOT_0; - } - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::warning << "Getting SD card activity status failed" << std::endl; - } + if (sdInfo.state == SdStates::GET_INFO) { + if (not sdInfo.commandExecuted) { + // Create update status file + result = sdcMan->updateSdCardStateFile(); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "CoreController::initialize: Updating SD card state file failed" + << std::endl; + } + sdInfo.commandExecuted = true; + } else { + nonBlockingOpChecking(SdStates::SET_STATE_SELF, 4, "Updating SDC file"); + } + } + + if (sdInfo.state == SdStates::SET_STATE_SELF) { + if (not sdInfo.commandExecuted) { + result = sdcMan->getSdCardActiveStatus(sdInfo.currentState); + determinePreferredSdCard(); + 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; + sdInfo.pref = sd::SdCard::SLOT_0; + } + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "Getting SD card activity status failed" << std::endl; + } #if Q7S_SD_CARD_CONFIG == Q7S_SD_COLD_REDUNDANT - sif::info << "Cold redundant SD card configuration, preferred SD card: " << - static_cast(sdInfo.pref) << std::endl; + sif::info << "Cold redundant SD card configuration, preferred SD card: " + << static_cast(sdInfo.pref) << std::endl; #endif - if(sdInfo.prefState == sd::SdState::MOUNTED) { + if (sdInfo.prefState == sd::SdState::MOUNTED) { #if OBSW_VERBOSE_LEVEL >= 1 - std::string mountString; - if(sdInfo.pref == sd::SdCard::SLOT_0) { - mountString = SdCardManager::SD_0_MOUNT_POINT; - } - else { - mountString = SdCardManager::SD_1_MOUNT_POINT; - } - sif::info << "SD card " << sdInfo.prefChar << " already on and mounted at " << - mountString << std::endl; + std::string mountString; + if (sdInfo.pref == sd::SdCard::SLOT_0) { + mountString = SdCardManager::SD_0_MOUNT_POINT; + } else { + mountString = SdCardManager::SD_1_MOUNT_POINT; + } + sif::info << "SD card " << sdInfo.prefChar << " already on and mounted at " << mountString + << std::endl; #endif - sdInfo.state = SdStates::DETERMINE_OTHER; - } - else if(sdInfo.prefState == sd::SdState::OFF) { - sdCardSetup(sdInfo.pref, sd::SdState::ON, sdInfo.prefChar, false); - sdInfo.commandExecuted = true; - } - else if(sdInfo.prefState == sd::SdState::ON) { - sdInfo.state = SdStates::MOUNT_SELF; - } - } - else { - if(nonBlockingOpChecking(SdStates::MOUNT_SELF, 10, "Setting SDC state")) { - sdInfo.prefState = sd::SdState::ON; - currentStateSetter(sdInfo.pref, sd::SdState::ON); - } - } + sdInfo.state = SdStates::DETERMINE_OTHER; + } else if (sdInfo.prefState == sd::SdState::OFF) { + sdCardSetup(sdInfo.pref, sd::SdState::ON, sdInfo.prefChar, false); + sdInfo.commandExecuted = true; + } else if (sdInfo.prefState == sd::SdState::ON) { + sdInfo.state = SdStates::MOUNT_SELF; + } + } else { + if (nonBlockingOpChecking(SdStates::MOUNT_SELF, 10, "Setting SDC state")) { + sdInfo.prefState = sd::SdState::ON; + currentStateSetter(sdInfo.pref, sd::SdState::ON); + } } + } - if(sdInfo.state == SdStates::MOUNT_SELF) { - if(not sdInfo.commandExecuted) { - result = sdCardSetup(sdInfo.pref, sd::SdState::MOUNTED, sdInfo.prefChar); - sdInfo.commandExecuted = true; - } - else { - if(nonBlockingOpChecking(SdStates::DETERMINE_OTHER, 5, "Mounting SD card")) { - sdInfo.prefState = sd::SdState::MOUNTED; - currentStateSetter(sdInfo.pref, sd::SdState::MOUNTED); - } - } + if (sdInfo.state == SdStates::MOUNT_SELF) { + if (not sdInfo.commandExecuted) { + result = sdCardSetup(sdInfo.pref, sd::SdState::MOUNTED, sdInfo.prefChar); + sdInfo.commandExecuted = true; + } else { + if (nonBlockingOpChecking(SdStates::DETERMINE_OTHER, 5, "Mounting SD card")) { + sdInfo.prefState = sd::SdState::MOUNTED; + currentStateSetter(sdInfo.pref, sd::SdState::MOUNTED); + } } + } - if(sdInfo.state == SdStates::DETERMINE_OTHER) { - // Determine whether any additional operations have to be done for the other SD card - // 1. Cold redundant case: Other SD card needs to be unmounted and switched off - // 2. Hot redundant case: Other SD card needs to be mounted and switched on + if (sdInfo.state == SdStates::DETERMINE_OTHER) { + // Determine whether any additional operations have to be done for the other SD card + // 1. Cold redundant case: Other SD card needs to be unmounted and switched off + // 2. Hot redundant case: Other SD card needs to be mounted and switched on #if Q7S_SD_CARD_CONFIG == Q7S_SD_COLD_REDUNDANT - if(sdInfo.otherState == sd::SdState::ON) { - sdInfo.state = SdStates::SET_STATE_OTHER; - } - else if(sdInfo.otherState == sd::SdState::MOUNTED) { - sdInfo.state = SdStates::MOUNT_UNMOUNT_OTHER; - } - else { - // Is already off, update info, but with a small delay - sdInfo.state = SdStates::SKIP_CYCLE_BEFORE_INFO_UPDATE; - } -#elif Q7S_SD_CARD_CONFIG == Q7S_SD_HOT_REDUNDANT - if(sdInfo.otherState == sd::SdState::OFF) { - sdInfo.state = SdStates::SET_STATE_OTHER; - } - else if(sdInfo.otherState == sd::SdState::ON) { - sdInfo.state = SdStates::MOUNT_UNMOUNT_OTHER; - } - else { - // Is already on and mounted, update info - sdInfo.state = SdStates::SKIP_CYCLE_BEFORE_INFO_UPDATE; - } -#endif + if (sdInfo.otherState == sd::SdState::ON) { + sdInfo.state = SdStates::SET_STATE_OTHER; + } else if (sdInfo.otherState == sd::SdState::MOUNTED) { + sdInfo.state = SdStates::MOUNT_UNMOUNT_OTHER; + } else { + // Is already off, update info, but with a small delay + sdInfo.state = SdStates::SKIP_CYCLE_BEFORE_INFO_UPDATE; } +#elif Q7S_SD_CARD_CONFIG == Q7S_SD_HOT_REDUNDANT + if (sdInfo.otherState == sd::SdState::OFF) { + sdInfo.state = SdStates::SET_STATE_OTHER; + } else if (sdInfo.otherState == sd::SdState::ON) { + sdInfo.state = SdStates::MOUNT_UNMOUNT_OTHER; + } else { + // Is already on and mounted, update info + sdInfo.state = SdStates::SKIP_CYCLE_BEFORE_INFO_UPDATE; + } +#endif + } - if(sdInfo.state == SdStates::SET_STATE_OTHER) { - // Set state of other SD card to ON or OFF, depending on redundancy mode + if (sdInfo.state == SdStates::SET_STATE_OTHER) { + // Set state of other SD card to ON or OFF, depending on redundancy mode #if Q7S_SD_CARD_CONFIG == Q7S_SD_COLD_REDUNDANT - if(not sdInfo.commandExecuted) { - result = sdCardSetup(sdInfo.other, sd::SdState::OFF, sdInfo.otherChar, false); - sdInfo.commandExecuted = true; - } - else { - if(nonBlockingOpChecking(SdStates::SKIP_CYCLE_BEFORE_INFO_UPDATE, 10, - "Switching off other SD card")) { - sdInfo.otherState = sd::SdState::OFF; - currentStateSetter(sdInfo.other, sd::SdState::OFF); - } - } -#elif Q7S_SD_CARD_CONFIG == Q7S_SD_HOT_REDUNDANT - if(not sdInfo.commandExecuted) { - result = sdCardSetup(sdInfo.other, sd::SdState::ON, sdInfo.otherChar, false); - sdInfo.commandExecuted = true; - } - else { - if(nonBlockingOpChecking(SdStates::MOUNT_UNMOUNT_OTHER, 10, - "Switching on other SD card")) { - sdInfo.otherState = sd::SdState::ON; - currentStateSetter(sdInfo.other, sd::SdState::ON); - } - } -#endif + if (not sdInfo.commandExecuted) { + result = sdCardSetup(sdInfo.other, sd::SdState::OFF, sdInfo.otherChar, false); + sdInfo.commandExecuted = true; + } else { + if (nonBlockingOpChecking(SdStates::SKIP_CYCLE_BEFORE_INFO_UPDATE, 10, + "Switching off other SD card")) { + sdInfo.otherState = sd::SdState::OFF; + currentStateSetter(sdInfo.other, sd::SdState::OFF); + } } +#elif Q7S_SD_CARD_CONFIG == Q7S_SD_HOT_REDUNDANT + if (not sdInfo.commandExecuted) { + result = sdCardSetup(sdInfo.other, sd::SdState::ON, sdInfo.otherChar, false); + sdInfo.commandExecuted = true; + } else { + if (nonBlockingOpChecking(SdStates::MOUNT_UNMOUNT_OTHER, 10, "Switching on other SD card")) { + sdInfo.otherState = sd::SdState::ON; + currentStateSetter(sdInfo.other, sd::SdState::ON); + } + } +#endif + } - if(sdInfo.state == SdStates::MOUNT_UNMOUNT_OTHER) { - // Mount or unmount other SD card, depending on redundancy mode + if (sdInfo.state == SdStates::MOUNT_UNMOUNT_OTHER) { + // Mount or unmount other SD card, depending on redundancy mode #if Q7S_SD_CARD_CONFIG == Q7S_SD_COLD_REDUNDANT - if(not sdInfo.commandExecuted) { - result = sdCardSetup(sdInfo.other, sd::SdState::ON, sdInfo.otherChar); - sdInfo.commandExecuted = true; - } - else { - if(nonBlockingOpChecking(SdStates::SET_STATE_OTHER, 10, "Unmounting other SD card")) { - sdInfo.otherState = sd::SdState::ON; - currentStateSetter(sdInfo.other, sd::SdState::ON); - } - } + if (not sdInfo.commandExecuted) { + result = sdCardSetup(sdInfo.other, sd::SdState::ON, sdInfo.otherChar); + sdInfo.commandExecuted = true; + } else { + if (nonBlockingOpChecking(SdStates::SET_STATE_OTHER, 10, "Unmounting other SD card")) { + sdInfo.otherState = sd::SdState::ON; + currentStateSetter(sdInfo.other, sd::SdState::ON); + } + } #elif Q7S_SD_CARD_CONFIG == Q7S_SD_HOT_REDUNDANT - if(not sdInfo.commandExecuted) { - result = sdCardSetup(sdInfo.other, sd::SdState::MOUNTED, sdInfo.otherChar); - sdInfo.commandExecuted = true; - } - else { - if(nonBlockingOpChecking(SdStates::UPDATE_INFO, 4, "Mounting other SD card")) { - sdInfo.otherState = sd::SdState::MOUNTED; - currentStateSetter(sdInfo.other, sd::SdState::MOUNTED); - } - } + if (not sdInfo.commandExecuted) { + result = sdCardSetup(sdInfo.other, sd::SdState::MOUNTED, sdInfo.otherChar); + sdInfo.commandExecuted = true; + } else { + if (nonBlockingOpChecking(SdStates::UPDATE_INFO, 4, "Mounting other SD card")) { + sdInfo.otherState = sd::SdState::MOUNTED; + currentStateSetter(sdInfo.other, sd::SdState::MOUNTED); + } + } #endif - } + } - if(sdInfo.state == SdStates::SKIP_CYCLE_BEFORE_INFO_UPDATE) { - sdInfo.state = SdStates::UPDATE_INFO; + if (sdInfo.state == SdStates::SKIP_CYCLE_BEFORE_INFO_UPDATE) { + sdInfo.state = SdStates::UPDATE_INFO; + } else if (sdInfo.state == SdStates::UPDATE_INFO) { + // It is assumed that all tasks are running by the point this section is reached. + // Therefore, perform this operation in blocking mode because it does not take long + // and the ready state of the SD card is available sooner + sdcMan->setBlocking(true); + // Update status file + result = sdcMan->updateSdCardStateFile(); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "CoreController::initialize: Updating SD card state file failed" << std::endl; } - else if(sdInfo.state == SdStates::UPDATE_INFO) { - // It is assumed that all tasks are running by the point this section is reached. - // Therefore, perform this operation in blocking mode because it does not take long - // and the ready state of the SD card is available sooner - sdcMan->setBlocking(true); - // Update status file - result = sdcMan->updateSdCardStateFile(); - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::warning << "CoreController::initialize: Updating SD card state file failed" - << std::endl; - } - sdInfo.commandExecuted = false; - sdInfo.state = SdStates::IDLE; - sdInfo.cycleCount = 0; - sdcMan->setBlocking(false); - sdcMan->getSdCardActiveStatus(sdInfo.currentState); - if(not sdInfo.initFinished) { - updateSdInfoOther(); - sdInfo.initFinished = true; - sif::info << "SD card initialization finished" << std::endl; - } + sdInfo.commandExecuted = false; + sdInfo.state = SdStates::IDLE; + sdInfo.cycleCount = 0; + sdcMan->setBlocking(false); + sdcMan->getSdCardActiveStatus(sdInfo.currentState); + if (not sdInfo.initFinished) { + updateSdInfoOther(); + sdInfo.initFinished = true; + sif::info << "SD card initialization finished" << std::endl; } + } - if(sdInfo.state == SdStates::SET_STATE_FROM_COMMAND) { - if(not sdInfo.commandExecuted) { - executeNextExternalSdCommand(); - } - else { - checkExternalSdCommandStatus(); - } + if (sdInfo.state == SdStates::SET_STATE_FROM_COMMAND) { + if (not sdInfo.commandExecuted) { + executeNextExternalSdCommand(); + } else { + checkExternalSdCommandStatus(); } + } - sdInfo.cycleCount++; - return HasReturnvaluesIF::RETURN_OK; + sdInfo.cycleCount++; + return HasReturnvaluesIF::RETURN_OK; } void CoreController::executeNextExternalSdCommand() { - std::string sdChar; - sd::SdState currentStateOfCard = sd::SdState::OFF; - if(sdInfo.commandedCard == sd::SdCard::SLOT_0) { - sdChar = "0"; - currentStateOfCard = sdInfo.currentState.first; + std::string sdChar; + sd::SdState currentStateOfCard = sd::SdState::OFF; + if (sdInfo.commandedCard == sd::SdCard::SLOT_0) { + sdChar = "0"; + currentStateOfCard = sdInfo.currentState.first; + } else { + sdChar = "1"; + currentStateOfCard = sdInfo.currentState.second; + } + if (currentStateOfCard == sd::SdState::OFF) { + if (sdInfo.commandedState == sd::SdState::ON) { + sdInfo.currentlyCommandedState = sdInfo.commandedState; + } else if (sdInfo.commandedState == sd::SdState::MOUNTED) { + sdInfo.currentlyCommandedState = sd::SdState::ON; + } else { + // SD card is already on target state + sdInfo.commandFinished = true; + sdInfo.state = SdStates::IDLE; } - else { - sdChar = "1"; - currentStateOfCard = sdInfo.currentState.second; + } else if (currentStateOfCard == sd::SdState::ON) { + if (sdInfo.commandedState == sd::SdState::OFF or + sdInfo.commandedState == sd::SdState::MOUNTED) { + sdInfo.currentlyCommandedState = sdInfo.commandedState; + } else { + // Already on target state + sdInfo.commandFinished = true; + sdInfo.state = SdStates::IDLE; } - if(currentStateOfCard == sd::SdState::OFF) { - if(sdInfo.commandedState == sd::SdState::ON) { - sdInfo.currentlyCommandedState = sdInfo.commandedState; - } - else if(sdInfo.commandedState == sd::SdState::MOUNTED) { - sdInfo.currentlyCommandedState = sd::SdState::ON; - } - else { - // SD card is already on target state - sdInfo.commandFinished = true; - sdInfo.state = SdStates::IDLE; - } + } else if (currentStateOfCard == sd::SdState::MOUNTED) { + if (sdInfo.commandedState == sd::SdState::ON) { + sdInfo.currentlyCommandedState = sdInfo.commandedState; + } else if (sdInfo.commandedState == sd::SdState::OFF) { + // This causes an unmount in sdCardSetup + sdInfo.currentlyCommandedState = sd::SdState::ON; + } else { + sdInfo.commandFinished = true; } - else if(currentStateOfCard == sd::SdState::ON) { - if(sdInfo.commandedState == sd::SdState::OFF or - sdInfo.commandedState == sd::SdState::MOUNTED) { - sdInfo.currentlyCommandedState = sdInfo.commandedState; - } - else { - // Already on target state - sdInfo.commandFinished = true; - sdInfo.state = SdStates::IDLE; - } - } - else if(currentStateOfCard == sd::SdState::MOUNTED) { - if(sdInfo.commandedState == sd::SdState::ON) { - sdInfo.currentlyCommandedState = sdInfo.commandedState; - } - else if(sdInfo.commandedState == sd::SdState::OFF) { - // This causes an unmount in sdCardSetup - sdInfo.currentlyCommandedState = sd::SdState::ON; - } - else { - sdInfo.commandFinished = true; - } - } - sdCardSetup(sdInfo.commandedCard, sdInfo.commandedState, sdChar); - sdInfo.commandExecuted = true; + } + sdCardSetup(sdInfo.commandedCard, sdInfo.commandedState, sdChar); + sdInfo.commandExecuted = true; } void CoreController::checkExternalSdCommandStatus() { - SdCardManager::Operations operation; - SdCardManager::OpStatus status = sdcMan->checkCurrentOp(operation); - if(status == SdCardManager::OpStatus::SUCCESS) { - if(sdInfo.currentlyCommandedState == sdInfo.commandedState) { - sdInfo.state = SdStates::SKIP_CYCLE_BEFORE_INFO_UPDATE; - sdInfo.commandFinished = true; - } - else { - // stay on same state machine state because the target state was not reached yet. - sdInfo.cycleCount = 0; - } - currentStateSetter(sdInfo.commandedCard, sdInfo.currentlyCommandedState); - sdInfo.commandExecuted = false; - } - else if(sdInfo.cycleCount > 4) { - sif::warning << "CoreController::sdStateMachine: Commanding SD state " - "takes too long" << std::endl; + SdCardManager::Operations operation; + SdCardManager::OpStatus status = sdcMan->checkCurrentOp(operation); + if (status == SdCardManager::OpStatus::SUCCESS) { + if (sdInfo.currentlyCommandedState == sdInfo.commandedState) { + sdInfo.state = SdStates::SKIP_CYCLE_BEFORE_INFO_UPDATE; + sdInfo.commandFinished = true; + } else { + // stay on same state machine state because the target state was not reached yet. + sdInfo.cycleCount = 0; } + currentStateSetter(sdInfo.commandedCard, sdInfo.currentlyCommandedState); + sdInfo.commandExecuted = false; + } else if (sdInfo.cycleCount > 4) { + sif::warning << "CoreController::sdStateMachine: Commanding SD state " + "takes too long" + << std::endl; + } } void CoreController::currentStateSetter(sd::SdCard sdCard, sd::SdState newState) { - if(sdCard == sd::SdCard::SLOT_0) { - sdInfo.currentState.first = newState; - } - else { - sdInfo.currentState.second = newState; - } + if (sdCard == sd::SdCard::SLOT_0) { + sdInfo.currentState.first = newState; + } else { + sdInfo.currentState.second = newState; + } } ReturnValue_t CoreController::sdCardSetup(sd::SdCard sdCard, sd::SdState targetState, - std::string sdChar, bool printOutput) { - std::string mountString; - sdcMan->setPrintCommandOutput(printOutput); - if(sdCard == sd::SdCard::SLOT_0) { - mountString = SdCardManager::SD_0_MOUNT_POINT; - } - else { - mountString = SdCardManager::SD_1_MOUNT_POINT; - } + std::string sdChar, bool printOutput) { + std::string mountString; + sdcMan->setPrintCommandOutput(printOutput); + if (sdCard == sd::SdCard::SLOT_0) { + mountString = SdCardManager::SD_0_MOUNT_POINT; + } else { + mountString = SdCardManager::SD_1_MOUNT_POINT; + } - sd::SdState state = sd::SdState::OFF; - if(sdCard == sd::SdCard::SLOT_0) { - state = sdInfo.currentState.first; - } - else { - state = sdInfo.currentState.second; - } - if(state == sd::SdState::MOUNTED) { - if(targetState == sd::SdState::OFF) { - sif::info << "Switching off SD card " << sdChar << std::endl; - return sdcMan->switchOffSdCard(sdCard, true, &sdInfo.currentState); - } - else if(targetState == sd::SdState::ON) { - sif::info << "Unmounting SD card " << sdChar << std::endl; - return sdcMan->unmountSdCard(sdCard); - } - else { - if(std::filesystem::exists(mountString)) { - sif::info << "SD card " << sdChar << " already on and mounted at " << - mountString << std::endl; - return SdCardManager::ALREADY_MOUNTED; - } - sif::error << "SD card mounted but expected mount point " << - mountString << " not found!" << std::endl; - return SdCardManager::MOUNT_ERROR; - } + sd::SdState state = sd::SdState::OFF; + if (sdCard == sd::SdCard::SLOT_0) { + state = sdInfo.currentState.first; + } else { + state = sdInfo.currentState.second; + } + if (state == sd::SdState::MOUNTED) { + if (targetState == sd::SdState::OFF) { + sif::info << "Switching off SD card " << sdChar << std::endl; + return sdcMan->switchOffSdCard(sdCard, true, &sdInfo.currentState); + } else if (targetState == sd::SdState::ON) { + sif::info << "Unmounting SD card " << sdChar << std::endl; + return sdcMan->unmountSdCard(sdCard); + } else { + if (std::filesystem::exists(mountString)) { + sif::info << "SD card " << sdChar << " already on and mounted at " << mountString + << std::endl; + return SdCardManager::ALREADY_MOUNTED; + } + sif::error << "SD card mounted but expected mount point " << mountString << " not found!" + << std::endl; + return SdCardManager::MOUNT_ERROR; } + } - if(state == sd::SdState::OFF) { - if(targetState == sd::SdState::MOUNTED) { - sif::info << "Switching on and mounting SD card " << sdChar << " at " << - mountString << std::endl; - return sdcMan->switchOnSdCard(sdCard, true, &sdInfo.currentState); - } - else if(targetState == sd::SdState::ON) { - sif::info << "Switching on SD card " << sdChar << std::endl; - return sdcMan->switchOnSdCard(sdCard, false, &sdInfo.currentState); - } + if (state == sd::SdState::OFF) { + if (targetState == sd::SdState::MOUNTED) { + sif::info << "Switching on and mounting SD card " << sdChar << " at " << mountString + << std::endl; + return sdcMan->switchOnSdCard(sdCard, true, &sdInfo.currentState); + } else if (targetState == sd::SdState::ON) { + sif::info << "Switching on SD card " << sdChar << std::endl; + return sdcMan->switchOnSdCard(sdCard, false, &sdInfo.currentState); } + } - else if(state == sd::SdState::ON) { - if(targetState == sd::SdState::MOUNTED) { - sif::info << "Mounting SD card " << sdChar << " at " << mountString << std::endl; - return sdcMan->mountSdCard(sdCard); - } - else if(targetState == sd::SdState::OFF) { - sif::info << "Switching off SD card " << sdChar << std::endl; - return sdcMan->switchOffSdCard(sdCard, false, &sdInfo.currentState); - } - } - else { - sif::warning << "CoreController::sdCardSetup: Invalid state for this call" << std::endl; - } - return HasReturnvaluesIF::RETURN_OK; -} - - -ReturnValue_t CoreController::executeAction(ActionId_t actionId, MessageQueueId_t commandedBy, - const uint8_t *data, size_t size) { - switch(actionId) { - case(LIST_DIRECTORY_INTO_FILE): { - return actionListDirectoryIntoFile(actionId, commandedBy, data, size); - } - case(REBOOT_OBC): { - return actionPerformReboot(data, size); - } - default: { - return HasActionsIF::INVALID_ACTION_ID; - } + else if (state == sd::SdState::ON) { + if (targetState == sd::SdState::MOUNTED) { + sif::info << "Mounting SD card " << sdChar << " at " << mountString << std::endl; + return sdcMan->mountSdCard(sdCard); + } else if (targetState == sd::SdState::OFF) { + sif::info << "Switching off SD card " << sdChar << std::endl; + return sdcMan->switchOffSdCard(sdCard, false, &sdInfo.currentState); } + } else { + sif::warning << "CoreController::sdCardSetup: Invalid state for this call" << std::endl; + } + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t CoreController::sdColdRedundantBlockingInit() { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - result = sdCardSetup(sdInfo.pref, sd::SdState::MOUNTED, sdInfo.prefChar); - if(result != SdCardManager::ALREADY_MOUNTED and result != HasReturnvaluesIF::RETURN_OK) { - sif::warning << "Setting up preferred card " << sdInfo.otherChar << - " in cold redundant mode failed" << std::endl; - // Try other SD card and mark set up operation as failed - sdCardSetup(sdInfo.pref, sd::SdState::MOUNTED, sdInfo.prefChar); - result = HasReturnvaluesIF::RETURN_FAILED; - } + result = sdCardSetup(sdInfo.pref, sd::SdState::MOUNTED, sdInfo.prefChar); + if (result != SdCardManager::ALREADY_MOUNTED and result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "Setting up preferred card " << sdInfo.otherChar + << " in cold redundant mode failed" << std::endl; + // Try other SD card and mark set up operation as failed + sdCardSetup(sdInfo.pref, sd::SdState::MOUNTED, sdInfo.prefChar); + result = HasReturnvaluesIF::RETURN_FAILED; + } - if(result != HasReturnvaluesIF::RETURN_FAILED and sdInfo.otherState != sd::SdState::OFF) { - sif::info << "Switching off secondary SD card " << sdInfo.otherChar << std::endl; - // Switch off other SD card in cold redundant mode if setting up preferred one worked - // without issues - ReturnValue_t result2 = sdcMan->switchOffSdCard(sdInfo.other, - sdInfo.otherState, &sdInfo.currentState); - if(result2 != HasReturnvaluesIF::RETURN_OK and result2 != SdCardManager::ALREADY_OFF) { - sif::warning << "Switching off secondary SD card " << sdInfo.otherChar << - " in cold redundant mode failed" << std::endl; - } + if (result != HasReturnvaluesIF::RETURN_FAILED and sdInfo.otherState != sd::SdState::OFF) { + sif::info << "Switching off secondary SD card " << sdInfo.otherChar << std::endl; + // Switch off other SD card in cold redundant mode if setting up preferred one worked + // without issues + ReturnValue_t result2 = + sdcMan->switchOffSdCard(sdInfo.other, sdInfo.otherState, &sdInfo.currentState); + if (result2 != HasReturnvaluesIF::RETURN_OK and result2 != SdCardManager::ALREADY_OFF) { + sif::warning << "Switching off secondary SD card " << sdInfo.otherChar + << " in cold redundant mode failed" << std::endl; } - return result; + } + return result; } ReturnValue_t CoreController::incrementAllocationFailureCount() { - uint32_t count = 0; - ReturnValue_t result = scratch::readNumber(scratch::ALLOC_FAILURE_COUNT, count); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - count++; - return scratch::writeNumber(scratch::ALLOC_FAILURE_COUNT, count); + uint32_t count = 0; + ReturnValue_t result = scratch::readNumber(scratch::ALLOC_FAILURE_COUNT, count); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + count++; + return scratch::writeNumber(scratch::ALLOC_FAILURE_COUNT, count); } ReturnValue_t CoreController::initVersionFile() { + std::string unameFileName = "/tmp/uname_version.txt"; + // TODO: No -v flag for now. If the kernel version is used, need to cut off first few letters + std::string unameCmd = "uname -mnrso > " + unameFileName; + int result = std::system(unameCmd.c_str()); + if (result != 0) { + utility::handleSystemError(result, "CoreController::versionFileInit"); + } + std::ifstream unameFile(unameFileName); + std::string unameLine; + if (not std::getline(unameFile, unameLine)) { + sif::warning << "CoreController::versionFileInit: Retrieving uname line failed" << std::endl; + } - std::string unameFileName = "/tmp/uname_version.txt"; - // TODO: No -v flag for now. If the kernel version is used, need to cut off first few letters - std::string unameCmd = "uname -mnrso > " + unameFileName; - int result = std::system(unameCmd.c_str()); - if(result != 0) { - utility::handleSystemError(result, "CoreController::versionFileInit"); - } - std::ifstream unameFile(unameFileName); - std::string unameLine; - if(not std::getline(unameFile, unameLine)) { - sif::warning << "CoreController::versionFileInit: Retrieving uname line failed" - << std::endl; - } - - std::string fullObswVersionString = "OBSW: v" + std::to_string(SW_VERSION) + "." + - std::to_string(SW_SUBVERSION) + "." + std::to_string(SW_REVISION); - std::string fullFsfwVersionString = "FSFW: v" + std::to_string(FSFW_VERSION) + "." + - std::to_string(FSFW_SUBVERSION) + "." + std::to_string(FSFW_REVISION); - std::string systemString = "System: " + unameLine; - std::string mountPrefix = SdCardManager::instance()->getCurrentMountPrefix(); - std::string versionFilePath = mountPrefix + VERSION_FILE; - std::fstream versionFile; - - if(not std::filesystem::exists(versionFilePath)) { - sif::info << "Writing version file " << versionFilePath << ".." << std::endl; - versionFile.open(versionFilePath, std::ios_base::out); - versionFile << fullObswVersionString << std::endl; - versionFile << fullFsfwVersionString << std::endl; - versionFile << systemString << std::endl; - return HasReturnvaluesIF::RETURN_OK; - } - - // Check whether any version has changed - bool createNewFile = false; - versionFile.open(versionFilePath); - std::string currentVersionString; - uint8_t idx = 0; - while(std::getline(versionFile, currentVersionString)) { - if(idx == 0) { - if(currentVersionString != fullObswVersionString) { - sif::info << "OBSW version changed" << std::endl; - sif::info << "From " << currentVersionString << " to " << - fullObswVersionString << std::endl; - createNewFile = true; - } - } - else if(idx == 1) { - if(currentVersionString != fullFsfwVersionString) { - sif::info << "FSFW version changed" << std::endl; - sif::info << "From " << currentVersionString << " to " << - fullFsfwVersionString << std::endl; - createNewFile = true; - } - } - else if(idx == 2) { - if(currentVersionString != systemString) { - sif::info << "System version changed" << std::endl; - sif::info << "Old: " << currentVersionString << std::endl; - sif::info << "New: " << systemString << std::endl; - createNewFile = true; - } - } - else { - sif::warning << "Invalid version file! Rewriting it.." << std::endl; - createNewFile = true; - } - idx++; - } - - // Overwrite file if necessary - if(createNewFile) { - sif::info << "Rewriting version.txt file with updated versions.." << std::endl; - versionFile.close(); - versionFile.open(versionFilePath, std::ios_base::out | std::ios_base::trunc); - versionFile << fullObswVersionString << std::endl; - versionFile << fullFsfwVersionString << std::endl; - versionFile << systemString << std::endl; - } + std::string fullObswVersionString = "OBSW: v" + std::to_string(SW_VERSION) + "." + + std::to_string(SW_SUBVERSION) + "." + + std::to_string(SW_REVISION); + std::string fullFsfwVersionString = "FSFW: v" + std::to_string(FSFW_VERSION) + "." + + std::to_string(FSFW_SUBVERSION) + "." + + std::to_string(FSFW_REVISION); + std::string systemString = "System: " + unameLine; + std::string mountPrefix = SdCardManager::instance()->getCurrentMountPrefix(); + std::string versionFilePath = mountPrefix + VERSION_FILE; + std::fstream versionFile; + if (not std::filesystem::exists(versionFilePath)) { + sif::info << "Writing version file " << versionFilePath << ".." << std::endl; + versionFile.open(versionFilePath, std::ios_base::out); + versionFile << fullObswVersionString << std::endl; + versionFile << fullFsfwVersionString << std::endl; + versionFile << systemString << std::endl; return HasReturnvaluesIF::RETURN_OK; + } + + // Check whether any version has changed + bool createNewFile = false; + versionFile.open(versionFilePath); + std::string currentVersionString; + uint8_t idx = 0; + while (std::getline(versionFile, currentVersionString)) { + if (idx == 0) { + if (currentVersionString != fullObswVersionString) { + sif::info << "OBSW version changed" << std::endl; + sif::info << "From " << currentVersionString << " to " << fullObswVersionString + << std::endl; + createNewFile = true; + } + } else if (idx == 1) { + if (currentVersionString != fullFsfwVersionString) { + sif::info << "FSFW version changed" << std::endl; + sif::info << "From " << currentVersionString << " to " << fullFsfwVersionString + << std::endl; + createNewFile = true; + } + } else if (idx == 2) { + if (currentVersionString != systemString) { + sif::info << "System version changed" << std::endl; + sif::info << "Old: " << currentVersionString << std::endl; + sif::info << "New: " << systemString << std::endl; + createNewFile = true; + } + } else { + sif::warning << "Invalid version file! Rewriting it.." << std::endl; + createNewFile = true; + } + idx++; + } + + // Overwrite file if necessary + if (createNewFile) { + sif::info << "Rewriting version.txt file with updated versions.." << std::endl; + versionFile.close(); + versionFile.open(versionFilePath, std::ios_base::out | std::ios_base::trunc); + versionFile << fullObswVersionString << std::endl; + versionFile << fullFsfwVersionString << std::endl; + versionFile << systemString << std::endl; + } + + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t CoreController::actionListDirectoryIntoFile(ActionId_t actionId, - MessageQueueId_t commandedBy, const uint8_t *data, size_t size) { - // TODO: Packet definition for clean deserialization - // 2 bytes for a and R flag, at least 5 bytes for minimum valid path /tmp with - // null termination, at least 7 bytes for minimum target file name /tmp/a with - // null termination. - if(size < 14) { - return HasActionsIF::INVALID_PARAMETERS; - } - // We could also make -l optional, but I can't think of a reason why to not use -l.. + MessageQueueId_t commandedBy, + const uint8_t *data, size_t size) { + // TODO: Packet definition for clean deserialization + // 2 bytes for a and R flag, at least 5 bytes for minimum valid path /tmp with + // null termination, at least 7 bytes for minimum target file name /tmp/a with + // null termination. + if (size < 14) { + return HasActionsIF::INVALID_PARAMETERS; + } + // We could also make -l optional, but I can't think of a reason why to not use -l.. - // This flag specifies to run ls with -a - bool aFlag = data[0]; - data += 1; - // This flag specifies to run ls with -R - bool RFlag = data[1]; - data += 1; + // This flag specifies to run ls with -a + bool aFlag = data[0]; + data += 1; + // This flag specifies to run ls with -R + bool RFlag = data[1]; + data += 1; - size_t remainingSize = size - 2; - // One larger for null termination, which prevents undefined behaviour if the sent - // strings are not 0 terminated properly - std::vector repoAndTargetFileBuffer(remainingSize + 1, 0); - std::memcpy(repoAndTargetFileBuffer.data(), data, remainingSize); - const char* currentCharPtr = reinterpret_cast(repoAndTargetFileBuffer.data()); - // Full target file name - std::string repoName(currentCharPtr); - size_t repoLength = repoName.length(); - // The other string needs to be at least one letter plus NULL termination to be valid at all - // The first string also needs to be NULL terminated, but the termination is not included - // in the string length, so this is subtracted from the remaining size as well - if(repoLength > remainingSize - 3) { - return HasActionsIF::INVALID_PARAMETERS; - } - // The file length will not include the NULL termination, so we skip it - currentCharPtr += repoLength + 1; - std::string targetFileName(currentCharPtr); - std::ostringstream oss; - oss << "ls -l"; - if(aFlag) { - oss << "a"; - } - if(RFlag) { - oss << "R"; - } + size_t remainingSize = size - 2; + // One larger for null termination, which prevents undefined behaviour if the sent + // strings are not 0 terminated properly + std::vector repoAndTargetFileBuffer(remainingSize + 1, 0); + std::memcpy(repoAndTargetFileBuffer.data(), data, remainingSize); + const char *currentCharPtr = reinterpret_cast(repoAndTargetFileBuffer.data()); + // Full target file name + std::string repoName(currentCharPtr); + size_t repoLength = repoName.length(); + // The other string needs to be at least one letter plus NULL termination to be valid at all + // The first string also needs to be NULL terminated, but the termination is not included + // in the string length, so this is subtracted from the remaining size as well + if (repoLength > remainingSize - 3) { + return HasActionsIF::INVALID_PARAMETERS; + } + // The file length will not include the NULL termination, so we skip it + currentCharPtr += repoLength + 1; + std::string targetFileName(currentCharPtr); + std::ostringstream oss; + oss << "ls -l"; + if (aFlag) { + oss << "a"; + } + if (RFlag) { + oss << "R"; + } - oss << " " << repoName << " > " << targetFileName; - int result = std::system(oss.str().c_str()); - if(result != 0) { - utility::handleSystemError(result, "CoreController::actionListDirectoryIntoFile"); - actionHelper.finish(false, commandedBy, actionId); - } - return HasReturnvaluesIF::RETURN_OK; + oss << " " << repoName << " > " << targetFileName; + int result = std::system(oss.str().c_str()); + if (result != 0) { + utility::handleSystemError(result, "CoreController::actionListDirectoryIntoFile"); + actionHelper.finish(false, commandedBy, actionId); + } + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t CoreController::initBootCopy() { - if(not std::filesystem::exists(CURR_COPY_FILE)) { - // Thils file is created by the systemd service eive-early-config so this should - // not happen normally - std::string cmd = "xsc_boot_copy > " + std::string(CURR_COPY_FILE); - int result = std::system(cmd.c_str()); - if(result != 0) { - utility::handleSystemError(result, "CoreController::initBootCopy"); - } + if (not std::filesystem::exists(CURR_COPY_FILE)) { + // This file is created by the systemd service eive-early-config so this should + // not happen normally + std::string cmd = "xsc_boot_copy > " + std::string(CURR_COPY_FILE); + int result = std::system(cmd.c_str()); + if (result != 0) { + utility::handleSystemError(result, "CoreController::initBootCopy"); } - std::ifstream file(CURR_COPY_FILE); - std::string line; - std::getline(file, line); - std::istringstream iss(line); - int value = 0; - iss >> value; - CURRENT_CHIP = static_cast(value); - iss >> value; - CURRENT_COPY = static_cast(value); - return HasReturnvaluesIF::RETURN_OK; + } + + getCurrentBootCopy(CURRENT_CHIP, CURRENT_COPY); + return HasReturnvaluesIF::RETURN_OK; } -void CoreController::getCurrentBootCopy(Chip &chip, Copy ©) { - // Not really thread-safe but it does not need to be - chip = CURRENT_CHIP; - copy = CURRENT_COPY; +void CoreController::getCurrentBootCopy(xsc::Chip &chip, xsc::Copy ©) { + xsc_libnor_chip_t xscChip; + xsc_libnor_copy_t xscCopy; + xsc_boot_get_chip_copy(&xscChip, &xscCopy); + // Not really thread-safe but it does not need to be + chip = static_cast(xscChip); + copy = static_cast(xscCopy); } ReturnValue_t CoreController::initWatchdogFifo() { - if(not std::filesystem::exists(watchdog::FIFO_NAME)) { - // Still return RETURN_OK for now - sif::info << "Watchdog FIFO " << watchdog::FIFO_NAME << " does not exist, can't initiate" << - " watchdog" << std::endl; - return HasReturnvaluesIF::RETURN_OK; - } - // Open FIFO write only and non-blocking to prevent SW from killing itself. - watchdogFifoFd = open(watchdog::FIFO_NAME.c_str(), O_WRONLY | O_NONBLOCK); - if(watchdogFifoFd < 0) { - if(errno == ENXIO) { - watchdogFifoFd = RETRY_FIFO_OPEN; - sif::info << "eive-watchdog not running. FIFO can not be opened" << std::endl; - } - else { - sif::error << "Opening pipe " << watchdog::FIFO_NAME << " write-only failed with " << - errno << ": " << strerror(errno) << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; - } - } + if (not std::filesystem::exists(watchdog::FIFO_NAME)) { + // Still return RETURN_OK for now + sif::info << "Watchdog FIFO " << watchdog::FIFO_NAME << " does not exist, can't initiate" + << " watchdog" << std::endl; return HasReturnvaluesIF::RETURN_OK; + } + // Open FIFO write only and non-blocking to prevent SW from killing itself. + watchdogFifoFd = open(watchdog::FIFO_NAME.c_str(), O_WRONLY | O_NONBLOCK); + if (watchdogFifoFd < 0) { + if (errno == ENXIO) { + watchdogFifoFd = RETRY_FIFO_OPEN; + sif::info << "eive-watchdog not running. FIFO can not be opened" << std::endl; + } else { + sif::error << "Opening pipe " << watchdog::FIFO_NAME << " write-only failed with " << errno + << ": " << strerror(errno) << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } + } + return HasReturnvaluesIF::RETURN_OK; } void CoreController::initPrint() { #if OBSW_VERBOSE_LEVEL >= 1 - if(watchdogFifoFd > 0) { - sif::info << "Opened watchdog FIFO successfully.." << std::endl; - } + if (watchdogFifoFd > 0) { + sif::info << "Opened watchdog FIFO successfully.." << std::endl; + } #endif } ReturnValue_t CoreController::actionPerformReboot(const uint8_t *data, size_t size) { - if(size < 1) { - return HasActionsIF::INVALID_PARAMETERS; - } - bool rebootSameBootCopy = data[0]; - bool protOpPerformed; - if(rebootSameBootCopy) { + if (size < 1) { + return HasActionsIF::INVALID_PARAMETERS; + } + bool rebootSameBootCopy = data[0]; + bool protOpPerformed; + if (rebootSameBootCopy) { #if OBSW_VERBOSE_LEVEL >= 1 - sif::info << "CoreController::actionPerformReboot: Rebooting on current image" << std::endl; + 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(Chip::SELF_CHIP, Copy::SELF_COPY, - true, protOpPerformed, false); - if(retval == HasReturnvaluesIF::RETURN_OK and protOpPerformed) { - sif::info << "Running slot was writeprotected before reboot" << std::endl; - } - int result = std::system("xsc_boot_copy -r"); - if(result != 0) { - utility::handleSystemError(result, "CoreController::executeAction"); - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasActionsIF::EXECUTION_FINISHED; + // 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; } - if(size < 3) { - return HasActionsIF::INVALID_PARAMETERS; - } -#if OBSW_VERBOSE_LEVEL >= 1 - sif::info << "CoreController::actionPerformReboot: Rebooting on " << - static_cast(data[1]) << " " << static_cast(data[2]) << std::endl; -#endif - - // Check that the target chip and copy is writeprotected first - generateChipStateFile(); - // If any boot copies are unprotected, protect them here - 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; - } - - // The second byte in data is the target chip, the third byte is the target copy - std::string cmdString = "xsc_boot_copy " + std::to_string(data[1]) + " " + - std::to_string(data[2]); - int result = std::system(cmdString.c_str()); - if(result != 0) { - utility::handleSystemError(result, "CoreController::executeAction"); - return HasReturnvaluesIF::RETURN_FAILED; + int result = std::system("xsc_boot_copy -r"); + if (result != 0) { + utility::handleSystemError(result, "CoreController::executeAction"); + return HasReturnvaluesIF::RETURN_FAILED; } return HasActionsIF::EXECUTION_FINISHED; + } + if (size < 3 or (data[1] > 1 or data[2] > 1)) { + return HasActionsIF::INVALID_PARAMETERS; + } +#if OBSW_VERBOSE_LEVEL >= 1 + sif::info << "CoreController::actionPerformReboot: Rebooting on " << static_cast(data[1]) + << " " << static_cast(data[2]) << std::endl; +#endif + + // Check that the target chip and copy is writeprotected first + generateChipStateFile(); + // If any boot copies are unprotected, protect them here + 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; + } + + switch (tgtChip) { + case (xsc::Chip::CHIP_0): { + switch (tgtCopy) { + case (xsc::Copy::COPY_0): { + xsc_boot_copy(XSC_LIBNOR_CHIP_0, XSC_LIBNOR_COPY_NOMINAL); + break; + } + case (xsc::Copy::COPY_1): { + xsc_boot_copy(XSC_LIBNOR_CHIP_0, XSC_LIBNOR_COPY_GOLD); + break; + } + default: { + break; + } + } + break; + } + case (xsc::Chip::CHIP_1): { + switch (tgtCopy) { + case (xsc::Copy::COPY_0): { + xsc_boot_copy(XSC_LIBNOR_CHIP_1, XSC_LIBNOR_COPY_NOMINAL); + break; + } + case (xsc::Copy::COPY_1): { + xsc_boot_copy(XSC_LIBNOR_CHIP_1, XSC_LIBNOR_COPY_GOLD); + break; + } + default: { + break; + } + } + break; + } + default: + break; + } + return HasReturnvaluesIF::RETURN_FAILED; } -CoreController::~CoreController() { -} +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; - } - } + 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; + } } + } } void CoreController::updateSdInfoOther() { - if(sdInfo.pref == sd::SdCard::SLOT_0) { - sdInfo.prefChar = "0"; - sdInfo.otherChar = "1"; - sdInfo.otherState = sdInfo.currentState.second; - sdInfo.prefState = sdInfo.currentState.first; - sdInfo.other = sd::SdCard::SLOT_1; + if (sdInfo.pref == sd::SdCard::SLOT_0) { + sdInfo.prefChar = "0"; + sdInfo.otherChar = "1"; + sdInfo.otherState = sdInfo.currentState.second; + sdInfo.prefState = sdInfo.currentState.first; + sdInfo.other = sd::SdCard::SLOT_1; - } - else if(sdInfo.pref == sd::SdCard::SLOT_1) { - sdInfo.prefChar = "1"; - sdInfo.otherChar = "0"; - sdInfo.otherState = sdInfo.currentState.first; - sdInfo.prefState = sdInfo.currentState.second; - sdInfo.other = sd::SdCard::SLOT_0; - } - else { - sif::warning << "CoreController::updateSdInfoOther: Invalid SD card passed" << std::endl; - } + } else if (sdInfo.pref == sd::SdCard::SLOT_1) { + sdInfo.prefChar = "1"; + sdInfo.otherChar = "0"; + sdInfo.otherState = sdInfo.currentState.first; + sdInfo.prefState = sdInfo.currentState.second; + sdInfo.other = sd::SdCard::SLOT_0; + } else { + sif::warning << "CoreController::updateSdInfoOther: Invalid SD card passed" << std::endl; + } } -bool CoreController::sdInitFinished() const { - return sdInfo.initFinished; -} +bool CoreController::sdInitFinished() const { return sdInfo.initFinished; } ReturnValue_t CoreController::generateChipStateFile() { - int result = std::system(CHIP_PROT_SCRIPT); - if(result != 0) { - utility::handleSystemError(result, "CoreController::generateChipStateFile"); - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_OK; + int result = std::system(CHIP_PROT_SCRIPT); + if (result != 0) { + utility::handleSystemError(result, "CoreController::generateChipStateFile"); + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t CoreController::setBootCopyProtection(Chip targetChip, Copy targetCopy, - bool protect, bool& protOperationPerformed, bool updateProtFile) { - bool allChips = false; - bool allCopies = false; - bool selfChip = false; - bool selfCopy = false; - protOperationPerformed = false; +ReturnValue_t CoreController::setBootCopyProtection(xsc::Chip targetChip, xsc::Copy targetCopy, + bool protect, bool &protOperationPerformed, + bool updateProtFile) { + bool allChips = false; + bool allCopies = false; + bool selfChip = false; + bool selfCopy = false; + protOperationPerformed = false; - switch(targetChip) { - case(Chip::ALL_CHIP): { - allChips = true; - break; + switch (targetChip) { + case (xsc::Chip::ALL_CHIP): { + allChips = true; + break; } - case(Chip::NO_CHIP): { - return HasReturnvaluesIF::RETURN_OK; + case (xsc::Chip::NO_CHIP): { + return HasReturnvaluesIF::RETURN_OK; } - case(Chip::SELF_CHIP): { - selfChip = true; - targetChip = CURRENT_CHIP; - break; + case (xsc::Chip::SELF_CHIP): { + selfChip = true; + targetChip = CURRENT_CHIP; + break; } default: { - break; + break; } + } + switch (targetCopy) { + case (xsc::Copy::ALL_COPY): { + allCopies = true; + break; } - switch(targetCopy) { - case(Copy::ALL_COPY): { - allCopies = true; - break; + case (xsc::Copy::NO_COPY): { + return HasReturnvaluesIF::RETURN_OK; } - case(Copy::NO_COPY): { - return HasReturnvaluesIF::RETURN_OK; - } - case(Copy::SELF_COPY): { - selfCopy = true; - targetCopy = CURRENT_COPY; - break; + case (xsc::Copy::SELF_COPY): { + selfCopy = true; + targetCopy = CURRENT_COPY; + break; } default: { - break; - } + break; } + } - for(uint8_t arrIdx = 0; arrIdx < protArray.size(); arrIdx++) { - int result = handleBootCopyProtAtIndex(targetChip, targetCopy, protect, - protOperationPerformed, selfChip, selfCopy, allChips, allCopies, arrIdx); - if(result != 0) { - break; - } + for (uint8_t arrIdx = 0; arrIdx < protArray.size(); arrIdx++) { + int result = handleBootCopyProtAtIndex(targetChip, targetCopy, protect, protOperationPerformed, + selfChip, selfCopy, allChips, allCopies, arrIdx); + if (result != 0) { + break; } - if(protOperationPerformed and updateProtFile) { - updateProtInfo(); - } - return HasReturnvaluesIF::RETURN_OK; + } + if (protOperationPerformed and updateProtFile) { + updateProtInfo(); + } + return HasReturnvaluesIF::RETURN_OK; } -int CoreController::handleBootCopyProtAtIndex(Chip targetChip, Copy targetCopy, bool protect, - bool &protOperationPerformed, bool selfChip, bool selfCopy, bool allChips, - bool allCopies, uint8_t arrIdx) { - bool currentProt = protArray[arrIdx]; - std::ostringstream oss; - bool performOp = false; - if(protect == currentProt) { - return 0; - } - if(protOperationPerformed) { - if((selfChip and selfCopy) or (not allCopies and not allChips)) { - // No need to continue, only one operation was requested - return 1; - } - } - Chip currentChip; - Copy currentCopy; - oss << "writeprotect "; - if(arrIdx == 0 or arrIdx == 1) { - oss << "0 "; - currentChip = Chip::CHIP_0; - } - else { - oss << "1 "; - currentChip = Chip::CHIP_1; - } - if(arrIdx == 0 or arrIdx == 2) { - oss << "0 "; - currentCopy = Copy::COPY_0; - } - else { - oss << "1 "; - currentCopy = Copy::COPY_1; - } - if(protect) { - oss << "1"; - } - else { - oss << "0"; - } - - int result = 0; - if(allChips and allCopies) { - performOp = true; - } - else if(allChips) { - if((selfCopy and CURRENT_COPY == targetCopy) or - (currentCopy == targetCopy)) { - performOp = true; - } - } - else if(allCopies) { - if((selfChip and CURRENT_COPY == targetCopy) or - (currentChip == targetChip)) { - performOp = true; - } - } - else if(selfChip and (currentChip == targetChip)) { - if(selfCopy) { - if(currentCopy == targetCopy) { - performOp = true; - } - } - else { - performOp = true; - } - - } - else if(selfCopy and (currentCopy == targetCopy)) { - if(selfChip) { - if(currentChip == targetChip) { - performOp = true; - } - } - else { - performOp = true; - } - } - else if((targetChip == currentChip) and (targetCopy == currentCopy)) { - performOp = true; - } - if(result != 0) { - utility::handleSystemError(result, "CoreController::checkAndSetBootCopyProtection"); - } - if(performOp) { - // TODO: Lock operation take a long time. Use command executor? That would require a - // new state machine.. - protOperationPerformed = true; - sif::info << "Executing command: " << oss.str() << std::endl; - result = std::system(oss.str().c_str()); - } +int CoreController::handleBootCopyProtAtIndex(xsc::Chip targetChip, xsc::Copy targetCopy, + bool protect, bool &protOperationPerformed, + bool selfChip, bool selfCopy, bool allChips, + bool allCopies, uint8_t arrIdx) { + bool currentProt = protArray[arrIdx]; + std::ostringstream oss; + bool performOp = false; + if (protect == currentProt) { return 0; + } + if (protOperationPerformed) { + if ((selfChip and selfCopy) or (not allCopies and not allChips)) { + // No need to continue, only one operation was requested + return 1; + } + } + xsc::Chip currentChip; + xsc::Copy currentCopy; + oss << "writeprotect "; + if (arrIdx == 0 or arrIdx == 1) { + oss << "0 "; + currentChip = xsc::Chip::CHIP_0; + } else { + oss << "1 "; + currentChip = xsc::Chip::CHIP_1; + } + if (arrIdx == 0 or arrIdx == 2) { + oss << "0 "; + currentCopy = xsc::Copy::COPY_0; + } else { + oss << "1 "; + currentCopy = xsc::Copy::COPY_1; + } + if (protect) { + oss << "1"; + } else { + oss << "0"; + } + + int result = 0; + if (allChips and allCopies) { + performOp = true; + } else if (allChips) { + if ((selfCopy and CURRENT_COPY == targetCopy) or (currentCopy == targetCopy)) { + performOp = true; + } + } else if (allCopies) { + if ((selfChip and CURRENT_COPY == targetCopy) or (currentChip == targetChip)) { + performOp = true; + } + } else if (selfChip and (currentChip == targetChip)) { + if (selfCopy) { + if (currentCopy == targetCopy) { + performOp = true; + } + } else { + performOp = true; + } + + } else if (selfCopy and (currentCopy == targetCopy)) { + if (selfChip) { + if (currentChip == targetChip) { + performOp = true; + } + } else { + performOp = true; + } + } else if ((targetChip == currentChip) and (targetCopy == currentCopy)) { + performOp = true; + } + if (result != 0) { + utility::handleSystemError(result, "CoreController::checkAndSetBootCopyProtection"); + } + if (performOp) { + // TODO: Lock operation take a long time. Use command executor? That would require a + // new state machine.. + protOperationPerformed = true; + sif::info << "Executing command: " << oss.str() << std::endl; + result = std::system(oss.str().c_str()); + } + return 0; } ReturnValue_t CoreController::updateProtInfo(bool regenerateChipStateFile) { - using namespace std; - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - if(regenerateChipStateFile) { - result = generateChipStateFile(); - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::warning << "CoreController::updateProtInfo: Generating chip state file failed" << - std::endl; - return result; - } + using namespace std; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + if (regenerateChipStateFile) { + result = generateChipStateFile(); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "CoreController::updateProtInfo: Generating chip state file failed" + << std::endl; + return result; } - if(not filesystem::exists(CHIP_STATE_FILE)) { - return HasReturnvaluesIF::RETURN_FAILED; + } + if (not filesystem::exists(CHIP_STATE_FILE)) { + return HasReturnvaluesIF::RETURN_FAILED; + } + ifstream chipStateFile(CHIP_STATE_FILE); + if (not chipStateFile.good()) { + return HasReturnvaluesIF::RETURN_FAILED; + } + string nextLine; + uint8_t lineCounter = 0; + string word; + while (getline(chipStateFile, nextLine)) { + ReturnValue_t result = handleProtInfoUpdateLine(nextLine); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "CoreController::updateProtInfo: Protection info update failed!" << std::endl; + return result; } - ifstream chipStateFile(CHIP_STATE_FILE); - if(not chipStateFile.good()) { - return HasReturnvaluesIF::RETURN_FAILED; + ++lineCounter; + if (lineCounter > 4) { + sif::warning << "CoreController::checkAndProtectBootCopy: " + "Line counter larger than 4" + << std::endl; } - string nextLine; - uint8_t lineCounter = 0; - string word; - while(getline(chipStateFile, nextLine)) { - ReturnValue_t result = handleProtInfoUpdateLine(nextLine); - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::warning << "CoreController::updateProtInfo: Protection info update failed!" << - std::endl; - return result; - } - ++lineCounter; - if(lineCounter > 4) { - sif::warning << "CoreController::checkAndProtectBootCopy: " - "Line counter larger than 4" << std::endl; - } - } - return HasReturnvaluesIF::RETURN_OK; + } + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t CoreController::handleProtInfoUpdateLine(std::string nextLine) { - using namespace std; - string word; - uint8_t wordIdx = 0; - uint8_t arrayIdx = 0; - istringstream iss(nextLine); - Chip currentChip; - Copy currentCopy; - while(iss >> word) { - if(wordIdx == 1) { - currentChip = static_cast(stoi(word)); - } - if(wordIdx == 3) { - currentCopy = static_cast(stoi(word)); - } - - if(wordIdx == 3) { - if(currentChip == Chip::CHIP_0) { - if(currentCopy == Copy::COPY_0) { - arrayIdx = 0; - } - else if(currentCopy == Copy::COPY_1) { - arrayIdx = 1; - } - } - - else if(currentChip == Chip::CHIP_1) { - if(currentCopy == Copy::COPY_0) { - arrayIdx = 2; - } - else if(currentCopy == Copy::COPY_1) { - arrayIdx = 3; - } - } - } - if(wordIdx == 5) { - if(word == "unlocked.") { - protArray[arrayIdx] = false; - } - else { - protArray[arrayIdx] = true; - } - } - wordIdx++; + using namespace std; + string word; + uint8_t wordIdx = 0; + uint8_t arrayIdx = 0; + istringstream iss(nextLine); + xsc::Chip currentChip = xsc::Chip::CHIP_0; + xsc::Copy currentCopy = xsc::Copy::COPY_0; + while (iss >> word) { + if (wordIdx == 1) { + currentChip = static_cast(stoi(word)); } - return HasReturnvaluesIF::RETURN_OK; + if (wordIdx == 3) { + currentCopy = static_cast(stoi(word)); + } + + if (wordIdx == 3) { + if (currentChip == xsc::Chip::CHIP_0) { + if (currentCopy == xsc::Copy::COPY_0) { + arrayIdx = 0; + } else if (currentCopy == xsc::Copy::COPY_1) { + arrayIdx = 1; + } + } + + else if (currentChip == xsc::Chip::CHIP_1) { + if (currentCopy == xsc::Copy::COPY_0) { + arrayIdx = 2; + } else if (currentCopy == xsc::Copy::COPY_1) { + arrayIdx = 3; + } + } + } + if (wordIdx == 5) { + if (word == "unlocked.") { + protArray[arrayIdx] = false; + } else { + protArray[arrayIdx] = true; + } + } + wordIdx++; + } + return HasReturnvaluesIF::RETURN_OK; } void CoreController::performWatchdogControlOperation() { - // Only perform each fifth iteration - if(watchdogFifoFd != 0 and opDivider.checkAndIncrement()) { - if(watchdogFifoFd == RETRY_FIFO_OPEN) { - // Open FIFO write only and non-blocking - watchdogFifoFd = open(watchdog::FIFO_NAME.c_str(), O_WRONLY | O_NONBLOCK); - if(watchdogFifoFd < 0) { - if(errno == ENXIO) { - watchdogFifoFd = RETRY_FIFO_OPEN; - // No printout for now, would be spam - return; - } - else { - sif::error << "Opening pipe " << watchdog::FIFO_NAME << - " write-only failed with " << errno << ": " << - strerror(errno) << std::endl; - return; - } - } - sif::info << "Opened " << watchdog::FIFO_NAME << " successfully" << std::endl; - } - else if(watchdogFifoFd > 0) { - // Write to OBSW watchdog FIFO here - const char writeChar = 'a'; - ssize_t writtenBytes = write(watchdogFifoFd, &writeChar, 1); - if(writtenBytes < 0) { - sif::error << "Errors writing to watchdog FIFO, code " << errno << ": " << - strerror(errno) << std::endl; - } + // Only perform each fifth iteration + if (watchdogFifoFd != 0 and opDivider.checkAndIncrement()) { + if (watchdogFifoFd == RETRY_FIFO_OPEN) { + // Open FIFO write only and non-blocking + watchdogFifoFd = open(watchdog::FIFO_NAME.c_str(), O_WRONLY | O_NONBLOCK); + if (watchdogFifoFd < 0) { + if (errno == ENXIO) { + watchdogFifoFd = RETRY_FIFO_OPEN; + // No printout for now, would be spam + return; + } else { + sif::error << "Opening pipe " << watchdog::FIFO_NAME << " write-only failed with " + << errno << ": " << strerror(errno) << std::endl; + return; } + } + sif::info << "Opened " << watchdog::FIFO_NAME << " successfully" << std::endl; + } else if (watchdogFifoFd > 0) { + // Write to OBSW watchdog FIFO here + const char writeChar = 'a'; + ssize_t writtenBytes = write(watchdogFifoFd, &writeChar, 1); + if (writtenBytes < 0) { + sif::error << "Errors writing to watchdog FIFO, code " << errno << ": " << strerror(errno) + << std::endl; + } } - + } +} + +void CoreController::performMountedSdCardOperations() { + if (doPerformMountedSdCardOps) { + bool sdCardMounted = false; + sdCardMounted = sdcMan->isSdCardMounted(sdInfo.pref); + if (sdCardMounted) { + std::string path = sdcMan->getCurrentMountPrefix(sdInfo.pref) + "/" + CONF_FOLDER; + if (not std::filesystem::exists(path)) { + std::filesystem::create_directory(path); + } + initVersionFile(); + performRebootFileHandling(false); + doPerformMountedSdCardOps = false; + } + } +} + +void CoreController::performRebootFileHandling(bool recreateFile) { + using namespace std; + std::string path = sdcMan->getCurrentMountPrefix(sdInfo.pref) + REBOOT_FILE; + if (not std::filesystem::exists(path) or recreateFile) { +#if OBSW_VERBOSE_LEVEL >= 1 + sif::info << "CoreController::performRebootFileHandling: Recreating reboot file" << std::endl; +#endif + rebootFile.enabled = true; + rebootFile.img00Cnt = 0; + rebootFile.img01Cnt = 0; + rebootFile.img10Cnt = 0; + rebootFile.img11Cnt = 0; + rebootFile.lastChip = xsc::Chip::CHIP_0; + rebootFile.lastCopy = xsc::Copy::COPY_0; + rebootFile.img00Lock = false; + rebootFile.img01Lock = false; + rebootFile.img10Lock = false; + rebootFile.img11Lock = false; + rebootFile.mechanismNextChip = xsc::Chip::NO_CHIP; + rebootFile.mechanismNextCopy = xsc::Copy::NO_COPY; + rebootFile.bootFlag = false; + rewriteRebootFile(rebootFile); + } else { + if (not parseRebootFile(path, rebootFile)) { + performRebootFileHandling(true); + } + } + + if (CURRENT_CHIP == xsc::CHIP_0) { + if (CURRENT_COPY == xsc::COPY_0) { + rebootFile.img00Cnt++; + } else { + rebootFile.img01Cnt++; + } + } else { + if (CURRENT_COPY == xsc::COPY_0) { + rebootFile.img10Cnt++; + } else { + rebootFile.img11Cnt++; + } + } + + if (rebootFile.bootFlag) { + // Trigger event to inform ground that a reboot was triggered + uint32_t p1 = rebootFile.lastChip << 16 | rebootFile.lastCopy; + uint32_t p2 = rebootFile.img00Cnt << 24 | rebootFile.img01Cnt << 16 | rebootFile.img10Cnt << 8 | + rebootFile.img11Cnt; + triggerEvent(REBOOT_MECHANISM_TRIGGERED, p1, p2); + // Clear the boot flag + rebootFile.bootFlag = false; + } + + if (rebootFile.mechanismNextChip != xsc::NO_CHIP and + rebootFile.mechanismNextCopy != xsc::NO_COPY) { + if (CURRENT_CHIP != rebootFile.mechanismNextChip or + CURRENT_COPY != rebootFile.mechanismNextCopy) { + std::string infoString = std::to_string(rebootFile.mechanismNextChip) + " " + + std::to_string(rebootFile.mechanismNextCopy); + sif::warning << "CoreController::performRebootFileHandling: Expected to be on image " + << infoString << " but currently on other image. Locking " << infoString + << std::endl; + // Firmware or other component might be corrupt and we are on another image then the target + // image specified by the mechanism. We can't really trust the target image anymore. + // Lock it for now + if (rebootFile.mechanismNextChip == xsc::CHIP_0) { + if (rebootFile.mechanismNextCopy == xsc::COPY_0) { + rebootFile.img00Lock = true; + } else { + rebootFile.img01Lock = true; + } + } else { + if (rebootFile.mechanismNextCopy == xsc::COPY_0) { + rebootFile.img10Lock = true; + } else { + rebootFile.img11Lock = true; + } + } + } + } + + rebootFile.lastChip = CURRENT_CHIP; + rebootFile.lastCopy = CURRENT_COPY; + // Only reboot if the reboot functionality is enabled. + // The handler will still increment the boot counts + if (rebootFile.enabled and (*rebootFile.relevantBootCnt >= rebootFile.maxCount)) { + // Reboot to other image + bool doReboot = false; + xsc::Chip tgtChip = xsc::NO_CHIP; + xsc::Copy tgtCopy = xsc::NO_COPY; + determineAndExecuteReboot(rebootFile, doReboot, tgtChip, tgtCopy); + if (doReboot) { + rebootFile.bootFlag = true; +#if OBSW_VERBOSE_LEVEL >= 1 + sif::info << "Boot counter for image " << CURRENT_CHIP << " " << CURRENT_COPY + << " too high. Rebooting to " << tgtChip << " " << tgtCopy << std::endl; +#endif + rebootFile.mechanismNextChip = tgtChip; + rebootFile.mechanismNextCopy = tgtCopy; + rewriteRebootFile(rebootFile); + xsc_boot_copy(static_cast(tgtChip), + static_cast(tgtCopy)); + } + } else { + rebootFile.mechanismNextChip = xsc::NO_CHIP; + rebootFile.mechanismNextCopy = xsc::NO_COPY; + } + rewriteRebootFile(rebootFile); +} + +void CoreController::determineAndExecuteReboot(RebootFile &rf, bool &needsReboot, + xsc::Chip &tgtChip, xsc::Copy &tgtCopy) { + tgtChip = xsc::CHIP_0; + tgtCopy = xsc::COPY_0; + needsReboot = false; + if ((CURRENT_CHIP == xsc::CHIP_0) and (CURRENT_COPY == xsc::COPY_0) and + (rf.img00Cnt >= rf.maxCount)) { + needsReboot = true; + if (rf.img01Cnt < rf.maxCount and not rf.img01Lock) { + tgtCopy = xsc::COPY_1; + return; + } + if (rf.img10Cnt < rf.maxCount and not rf.img10Lock) { + tgtChip = xsc::CHIP_1; + return; + } + if (rf.img11Cnt < rf.maxCount and not rf.img11Lock) { + tgtChip = xsc::CHIP_1; + tgtCopy = xsc::COPY_1; + return; + } + // Can't really do much here. Stay on image + sif::warning + << "All reboot counts too high or all fallback images locked, already on fallback image" + << std::endl; + needsReboot = false; + return; + } + if ((CURRENT_CHIP == xsc::CHIP_0) and (CURRENT_COPY == xsc::COPY_1) and + (rf.img01Cnt >= rf.maxCount)) { + needsReboot = true; + if (rf.img00Cnt < rf.maxCount and not rf.img00Lock) { + // Reboot on fallback image + return; + } + if (rf.img10Cnt < rf.maxCount and not rf.img10Lock) { + tgtChip = xsc::CHIP_1; + return; + } + if (rf.img11Cnt < rf.maxCount and not rf.img11Lock) { + tgtChip = xsc::CHIP_1; + tgtCopy = xsc::COPY_1; + } + if (rf.img00Lock) { + needsReboot = false; + } + // Reboot to fallback image + } + if ((CURRENT_CHIP == xsc::CHIP_1) and (CURRENT_COPY == xsc::COPY_0) and + (rf.img10Cnt >= rf.maxCount)) { + needsReboot = true; + if (rf.img11Cnt < rf.maxCount and not rf.img11Lock) { + tgtChip = xsc::CHIP_1; + tgtCopy = xsc::COPY_1; + return; + } + if (rf.img00Cnt < rf.maxCount and not rf.img00Lock) { + return; + } + if (rf.img01Cnt < rf.maxCount and not rf.img01Lock) { + tgtCopy = xsc::COPY_1; + return; + } + if (rf.img00Lock) { + needsReboot = false; + } + // Reboot to fallback image + } + if ((CURRENT_CHIP == xsc::CHIP_1) and (CURRENT_COPY == xsc::COPY_1) and + (rf.img11Cnt >= rf.maxCount)) { + needsReboot = true; + if (rf.img10Cnt < rf.maxCount and not rf.img10Lock) { + tgtChip = xsc::CHIP_1; + return; + } + if (rf.img00Cnt < rf.maxCount and not rf.img00Lock) { + return; + } + if (rf.img01Cnt < rf.maxCount and not rf.img01Lock) { + tgtCopy = xsc::COPY_1; + return; + } + if (rf.img00Lock) { + needsReboot = false; + } + // Reboot to fallback image + } +} + +bool CoreController::parseRebootFile(std::string path, RebootFile &rf) { + using namespace std; + std::string selfMatch; + if (CURRENT_CHIP == xsc::CHIP_0) { + if (CURRENT_COPY == xsc::COPY_0) { + selfMatch = "00"; + } else { + selfMatch = "01"; + } + } else { + if (CURRENT_COPY == xsc::COPY_0) { + selfMatch = "10"; + } else { + selfMatch = "11"; + } + } + ifstream file(path); + string word; + string line; + uint8_t lineIdx = 0; + while (std::getline(file, line)) { + istringstream iss(line); + switch (lineIdx) { + case 0: { + iss >> word; + if (word.find("on:") == string::npos) { + // invalid file + return false; + } + iss >> rf.enabled; + break; + } + case 1: { + iss >> word; + if (word.find("maxcnt:") == string::npos) { + return false; + } + iss >> rf.maxCount; + break; + } + case 2: { + iss >> word; + if (word.find("img00:") == string::npos) { + return false; + } + iss >> rf.img00Cnt; + if (word.find(selfMatch) != string::npos) { + rf.relevantBootCnt = &rf.img00Cnt; + } + break; + } + case 3: { + iss >> word; + if (word.find("img01:") == string::npos) { + return false; + } + iss >> rf.img01Cnt; + if (word.find(selfMatch) != string::npos) { + rf.relevantBootCnt = &rf.img01Cnt; + } + break; + } + case 4: { + iss >> word; + if (word.find("img10:") == string::npos) { + return false; + } + iss >> rf.img10Cnt; + if (word.find(selfMatch) != string::npos) { + rf.relevantBootCnt = &rf.img10Cnt; + } + break; + } + case 5: { + iss >> word; + if (word.find("img11:") == string::npos) { + return false; + } + iss >> rf.img11Cnt; + if (word.find(selfMatch) != string::npos) { + rf.relevantBootCnt = &rf.img11Cnt; + } + break; + } + case 6: { + iss >> word; + if (word.find("img00lock:") == string::npos) { + return false; + } + iss >> rf.img00Lock; + break; + } + case 7: { + iss >> word; + if (word.find("img01lock:") == string::npos) { + return false; + } + iss >> rf.img01Lock; + break; + } + case 8: { + iss >> word; + if (word.find("img10lock:") == string::npos) { + return false; + } + iss >> rf.img10Lock; + break; + } + case 9: { + iss >> word; + if (word.find("img11lock:") == string::npos) { + return false; + } + iss >> rf.img11Lock; + break; + } + case 10: { + iss >> word; + if (word.find("bootflag:") == string::npos) { + return false; + } + iss >> rf.bootFlag; + break; + } + case 11: { + iss >> word; + int copyRaw = 0; + int chipRaw = 0; + if (word.find("last:") == string::npos) { + return false; + } + iss >> chipRaw; + if (iss.fail()) { + return false; + } + iss >> copyRaw; + if (iss.fail()) { + return false; + } + + if (chipRaw > 1 or copyRaw > 1) { + return false; + } + rf.lastChip = static_cast(chipRaw); + rf.lastCopy = static_cast(copyRaw); + break; + } + case 12: { + iss >> word; + int copyRaw = 0; + int chipRaw = 0; + if (word.find("next:") == string::npos) { + return false; + } + iss >> chipRaw; + if (iss.fail()) { + return false; + } + iss >> copyRaw; + if (iss.fail()) { + return false; + } + + if (chipRaw > 2 or copyRaw > 2) { + return false; + } + rf.mechanismNextChip = static_cast(chipRaw); + rf.mechanismNextCopy = static_cast(copyRaw); + break; + } + } + if (iss.fail()) { + return false; + } + lineIdx++; + } + if (lineIdx < 12) { + return false; + } + return true; +} + +void CoreController::resetRebootCount(xsc::Chip tgtChip, xsc::Copy tgtCopy) { + std::string path = sdcMan->getCurrentMountPrefix(sdInfo.pref) + REBOOT_FILE; + // Disable the reboot file mechanism + parseRebootFile(path, rebootFile); + if (tgtChip == xsc::ALL_CHIP and tgtCopy == xsc::ALL_COPY) { + rebootFile.img00Cnt = 0; + rebootFile.img01Cnt = 0; + rebootFile.img10Cnt = 0; + rebootFile.img11Cnt = 0; + } else { + if (tgtChip == xsc::CHIP_0) { + if (tgtCopy == xsc::COPY_0) { + rebootFile.img00Cnt = 0; + } else { + rebootFile.img01Cnt = 0; + } + } else { + if (tgtCopy == xsc::COPY_0) { + rebootFile.img10Cnt = 0; + } else { + rebootFile.img11Cnt = 0; + } + } + } + rewriteRebootFile(rebootFile); +} + +void CoreController::rewriteRebootFile(RebootFile file) { + std::string path = sdcMan->getCurrentMountPrefix(sdInfo.pref) + REBOOT_FILE; + std::ofstream rebootFile(path); + if (rebootFile.is_open()) { + // Initiate reboot file first. Reboot handling will be on on initialization + rebootFile << "on: " << file.enabled << "\nmaxcnt: " << file.maxCount + << "\nimg00: " << file.img00Cnt << "\nimg01: " << file.img01Cnt + << "\nimg10: " << file.img10Cnt << "\nimg11: " << file.img11Cnt + << "\nimg00lock: " << file.img00Lock << "\nimg01lock: " << file.img01Lock + << "\nimg10lock: " << file.img10Lock << "\nimg11lock: " << file.img11Lock + << "\nbootflag: " << file.bootFlag << "\nlast: " << static_cast(file.lastChip) + << " " << static_cast(file.lastCopy) + << "\nnext: " << static_cast(file.mechanismNextChip) << " " + << static_cast(file.mechanismNextCopy) << "\n"; + } +} + +void CoreController::setRebootMechanismLock(bool lock, xsc::Chip tgtChip, xsc::Copy tgtCopy) { + std::string path = sdcMan->getCurrentMountPrefix(sdInfo.pref) + REBOOT_FILE; + // Disable the reboot file mechanism + parseRebootFile(path, rebootFile); + if (tgtChip == xsc::CHIP_0) { + if (tgtCopy == xsc::COPY_0) { + rebootFile.img00Lock = lock; + } else { + rebootFile.img01Lock = lock; + } + } else { + if (tgtCopy == xsc::COPY_0) { + rebootFile.img10Lock = lock; + } else { + rebootFile.img11Lock = lock; + } + } + rewriteRebootFile(rebootFile); } diff --git a/bsp_q7s/core/CoreController.h b/bsp_q7s/core/CoreController.h index 74702441..48bc9b7f 100644 --- a/bsp_q7s/core/CoreController.h +++ b/bsp_q7s/core/CoreController.h @@ -2,183 +2,224 @@ #define BSP_Q7S_CORE_CORECONTROLLER_H_ #include -#include "fsfw/controller/ExtendedControllerBase.h" +#include + +#include + #include "bsp_q7s/memory/SdCardManager.h" - #include "events/subsystemIdRanges.h" - +#include "fsfw/controller/ExtendedControllerBase.h" class Timer; class SdCardManager; -class CoreController: public ExtendedControllerBase { -public: - enum Chip: uint8_t { - CHIP_0, - CHIP_1, - NO_CHIP, - SELF_CHIP, - ALL_CHIP - }; +namespace xsc { - enum Copy: uint8_t { - COPY_0, - COPY_1, - NO_COPY, - SELF_COPY, - ALL_COPY - }; +enum Chip : int { CHIP_0, CHIP_1, NO_CHIP, SELF_CHIP, ALL_CHIP }; +enum Copy : int { COPY_0, COPY_1, NO_COPY, SELF_COPY, ALL_COPY }; - static constexpr char CHIP_PROT_SCRIPT[] = "/home/root/scripts/get-chip-prot-status.sh"; - static constexpr char CHIP_STATE_FILE[] = "/tmp/chip_prot_status.txt"; - static constexpr char CURR_COPY_FILE[] = "/tmp/curr_copy.txt"; - static constexpr char VERSION_FILE[] = "/conf/sd_status"; +} // namespace xsc - static constexpr ActionId_t LIST_DIRECTORY_INTO_FILE = 0; - static constexpr ActionId_t REBOOT_OBC = 32; - static constexpr ActionId_t MOUNT_OTHER_COPY = 33; +struct RebootFile { + static constexpr uint8_t DEFAULT_MAX_BOOT_CNT = 10; + bool enabled = true; + size_t maxCount = DEFAULT_MAX_BOOT_CNT; + uint32_t img00Cnt = 0; + uint32_t img01Cnt = 0; + uint32_t img10Cnt = 0; + uint32_t img11Cnt = 0; + bool img00Lock = false; + bool img01Lock = false; + bool img10Lock = false; + bool img11Lock = false; + uint32_t* relevantBootCnt = &img00Cnt; + bool bootFlag = false; + xsc::Chip lastChip = xsc::Chip::CHIP_0; + xsc::Copy lastCopy = xsc::Copy::COPY_0; + xsc::Chip mechanismNextChip = xsc::Chip::NO_CHIP; + xsc::Copy mechanismNextCopy = xsc::Copy::NO_COPY; +}; - static constexpr uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::CORE; +class CoreController : public ExtendedControllerBase { + public: + static xsc::Chip CURRENT_CHIP; + static xsc::Copy CURRENT_COPY; - static constexpr Event ALLOC_FAILURE = event::makeEvent(SUBSYSTEM_ID, 0, severity::MEDIUM); + static constexpr char CHIP_PROT_SCRIPT[] = "/home/root/scripts/get-chip-prot-status.sh"; + static constexpr char CHIP_STATE_FILE[] = "/tmp/chip_prot_status.txt"; + static constexpr char CURR_COPY_FILE[] = "/tmp/curr_copy.txt"; + static constexpr char CONF_FOLDER[] = "conf"; + static constexpr char VERSION_FILE_NAME[] = "version.txt"; + static constexpr char REBOOT_FILE_NAME[] = "reboot.txt"; + const std::string VERSION_FILE = + "/" + std::string(CONF_FOLDER) + "/" + std::string(VERSION_FILE_NAME); + const std::string REBOOT_FILE = + "/" + std::string(CONF_FOLDER) + "/" + std::string(REBOOT_FILE_NAME); + static constexpr ActionId_t LIST_DIRECTORY_INTO_FILE = 0; + static constexpr ActionId_t SWITCH_REBOOT_FILE_HANDLING = 5; + static constexpr ActionId_t RESET_REBOOT_COUNTERS = 6; + static constexpr ActionId_t SWITCH_IMG_LOCK = 7; + static constexpr ActionId_t SET_MAX_REBOOT_CNT = 8; - CoreController(object_id_t objectId); - virtual~ CoreController(); + static constexpr ActionId_t REBOOT_OBC = 32; + static constexpr ActionId_t MOUNT_OTHER_COPY = 33; - ReturnValue_t initialize() override; + static constexpr uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::CORE; - ReturnValue_t initializeAfterTaskCreation() override; + static constexpr Event ALLOC_FAILURE = event::makeEvent(SUBSYSTEM_ID, 0, severity::MEDIUM); + //! [EXPORT] : [COMMENT] Software reboot occured. 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. + //! P1: First 16 bits: Last Chip, Last 16 bits: Last Copy, + //! P2: Each byte is the respective reboot count for the slots + static constexpr Event REBOOT_MECHANISM_TRIGGERED = + event::makeEvent(SUBSYSTEM_ID, 2, severity::MEDIUM); + //! Trying to find a way how to determine that the reboot came from ProASIC3 or PCDU.. + static constexpr Event REBOOT_HW = event::makeEvent(SUBSYSTEM_ID, 3, severity::MEDIUM); - ReturnValue_t executeAction(ActionId_t actionId, - MessageQueueId_t commandedBy, const uint8_t *data, size_t size) override; + CoreController(object_id_t objectId); + virtual ~CoreController(); - ReturnValue_t handleCommandMessage(CommandMessage *message) override; - void performControlOperation() override; + ReturnValue_t initialize() override; - /** - * Generate a file containing the chip lock/unlock states inside /tmp/chip_prot_status.txt - * @return - */ - static ReturnValue_t generateChipStateFile(); - static ReturnValue_t incrementAllocationFailureCount(); - static void getCurrentBootCopy(Chip& chip, Copy& copy); + ReturnValue_t initializeAfterTaskCreation() override; - ReturnValue_t updateProtInfo(bool regenerateChipStateFile = true); + ReturnValue_t executeAction(ActionId_t actionId, MessageQueueId_t commandedBy, + const uint8_t* data, size_t size) override; - /** - * Checks whether the target chip and copy are write protected and protect set them to a target - * state where applicable. - * @param targetChip - * @param targetCopy - * @param protect Target state - * @param protOperationPerformed [out] Can be used to determine whether any operation - * was performed - * @param updateProtFile Specify whether the protection info file is updated - * @return - */ - ReturnValue_t setBootCopyProtection(Chip targetChip, Copy targetCopy, - bool protect, bool& protOperationPerformed, bool updateProtFile = true); + ReturnValue_t handleCommandMessage(CommandMessage* message) override; + void performControlOperation() override; - bool sdInitFinished() const; + /** + * Generate a file containing the chip lock/unlock states inside /tmp/chip_prot_status.txt + * @return + */ + static ReturnValue_t generateChipStateFile(); + static ReturnValue_t incrementAllocationFailureCount(); + static void getCurrentBootCopy(xsc::Chip& chip, xsc::Copy& copy); -private: - static Chip CURRENT_CHIP; - static Copy CURRENT_COPY; + ReturnValue_t updateProtInfo(bool regenerateChipStateFile = true); - // Designated value for rechecking FIFO open - static constexpr int RETRY_FIFO_OPEN = -2; - int watchdogFifoFd = 0; + /** + * Checks whether the target chip and copy are write protected and protect set them to a target + * state where applicable. + * @param targetChip + * @param targetCopy + * @param protect Target state + * @param protOperationPerformed [out] Can be used to determine whether any operation + * was performed + * @param updateProtFile Specify whether the protection info file is updated + * @return + */ + ReturnValue_t setBootCopyProtection(xsc::Chip targetChip, xsc::Copy targetCopy, bool protect, + bool& protOperationPerformed, bool updateProtFile = true); - // States for SD state machine, which is used in non-blocking mode - enum class SdStates { - NONE, - START, - GET_INFO, - SET_STATE_SELF, - MOUNT_SELF, - // Determine operations for other SD card, depending on redundancy configuration - DETERMINE_OTHER, - SET_STATE_OTHER, - // Mount or unmount other - MOUNT_UNMOUNT_OTHER, - // Skip period because the shell command used to generate the info file sometimes is - // missing the last performed operation if executed too early - SKIP_CYCLE_BEFORE_INFO_UPDATE, - UPDATE_INFO, - // SD initialization done - IDLE, - // Used if SD switches or mount commands are issued via telecommand - SET_STATE_FROM_COMMAND, - }; - static constexpr bool BLOCKING_SD_INIT = false; + bool sdInitFinished() const; - SdCardManager* sdcMan = nullptr; + private: + // Designated value for rechecking FIFO open + static constexpr int RETRY_FIFO_OPEN = -2; + int watchdogFifoFd = 0; - struct SdInfo { - sd::SdCard pref = sd::SdCard::NONE; - sd::SdState prefState = sd::SdState::OFF; - sd::SdCard other = sd::SdCard::NONE; - sd::SdState otherState = sd::SdState::OFF; - std::string prefChar = "0"; - std::string otherChar = "1"; - SdStates state = SdStates::START; - // Used to track whether a command was executed - bool commandExecuted = true; - bool initFinished = false; - SdCardManager::SdStatePair currentState; - uint16_t cycleCount = 0; - // These two flags are related to external commanding - bool commandIssued = false; - bool commandFinished = false; - sd::SdState currentlyCommandedState = sd::SdState::OFF; - sd::SdCard commandedCard = sd::SdCard::NONE; - sd::SdState commandedState = sd::SdState::OFF; - }; - SdInfo sdInfo; + // States for SD state machine, which is used in non-blocking mode + enum class SdStates { + NONE, + START, + GET_INFO, + SET_STATE_SELF, + MOUNT_SELF, + // Determine operations for other SD card, depending on redundancy configuration + DETERMINE_OTHER, + SET_STATE_OTHER, + // Mount or unmount other + MOUNT_UNMOUNT_OTHER, + // Skip period because the shell command used to generate the info file sometimes is + // missing the last performed operation if executed too early + SKIP_CYCLE_BEFORE_INFO_UPDATE, + UPDATE_INFO, + // SD initialization done + IDLE, + // Used if SD switches or mount commands are issued via telecommand + SET_STATE_FROM_COMMAND, + }; + static constexpr bool BLOCKING_SD_INIT = false; - /** - * Index 0: Chip 0 Copy 0 - * Index 1: Chip 0 Copy 1 - * Index 2: Chip 1 Copy 0 - * Index 3: Chip 1 Copy 1 - */ - std::array protArray; - PeriodicOperationDivider opDivider; + SdCardManager* sdcMan = nullptr; - ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, - LocalDataPoolManager& poolManager) override; - LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override; - ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode, - uint32_t *msToReachTheMode); + struct SdInfo { + sd::SdCard pref = sd::SdCard::NONE; + sd::SdState prefState = sd::SdState::OFF; + sd::SdCard other = sd::SdCard::NONE; + sd::SdState otherState = sd::SdState::OFF; + std::string prefChar = "0"; + std::string otherChar = "1"; + SdStates state = SdStates::START; + // Used to track whether a command was executed + bool commandExecuted = true; + bool initFinished = false; + SdCardManager::SdStatePair currentState; + uint16_t cycleCount = 0; + // These two flags are related to external commanding + bool commandIssued = false; + bool commandFinished = false; + sd::SdState currentlyCommandedState = sd::SdState::OFF; + sd::SdCard commandedCard = sd::SdCard::NONE; + sd::SdState commandedState = sd::SdState::OFF; + } sdInfo; + RebootFile rebootFile = {}; + bool doPerformMountedSdCardOps = true; - ReturnValue_t initVersionFile(); - ReturnValue_t initBootCopy(); - ReturnValue_t initWatchdogFifo(); - ReturnValue_t initSdCardBlocking(); - void initPrint(); + /** + * Index 0: Chip 0 Copy 0 + * Index 1: Chip 0 Copy 1 + * Index 2: Chip 1 Copy 0 + * Index 3: Chip 1 Copy 1 + */ + std::array protArray; + PeriodicOperationDivider opDivider; - ReturnValue_t sdStateMachine(); - void updateSdInfoOther(); - ReturnValue_t sdCardSetup(sd::SdCard sdCard, sd::SdState targetState, std::string sdChar, - bool printOutput = true); - ReturnValue_t sdColdRedundantBlockingInit(); - void currentStateSetter(sd::SdCard sdCard, sd::SdState newState); - void determinePreferredSdCard(); - void executeNextExternalSdCommand(); - void checkExternalSdCommandStatus(); + ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, + LocalDataPoolManager& poolManager) override; + 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 initBootCopy(); + ReturnValue_t initWatchdogFifo(); + ReturnValue_t initSdCardBlocking(); + void initPrint(); - 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 sdStateMachine(); + void updateSdInfoOther(); + ReturnValue_t sdCardSetup(sd::SdCard sdCard, sd::SdState targetState, std::string sdChar, + bool printOutput = true); + ReturnValue_t sdColdRedundantBlockingInit(); - void performWatchdogControlOperation(); + void currentStateSetter(sd::SdCard sdCard, sd::SdState newState); + void determinePreferredSdCard(); + void executeNextExternalSdCommand(); + void checkExternalSdCommandStatus(); + void performRebootFileHandling(bool recreateFile); - ReturnValue_t handleProtInfoUpdateLine(std::string nextLine); - int handleBootCopyProtAtIndex(Chip targetChip, Copy targetCopy, bool protect, - bool &protOperationPerformed, bool selfChip, bool selfCopy, bool allChips, - bool allCopies, uint8_t arrIdx); + 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); + + void performWatchdogControlOperation(); + + ReturnValue_t handleProtInfoUpdateLine(std::string nextLine); + int handleBootCopyProtAtIndex(xsc::Chip targetChip, xsc::Copy targetCopy, bool protect, + bool& protOperationPerformed, bool selfChip, bool selfCopy, + bool allChips, bool allCopies, uint8_t arrIdx); + void determineAndExecuteReboot(RebootFile& rf, bool& needsReboot, xsc::Chip& tgtChip, + xsc::Copy& tgtCopy); + void resetRebootCount(xsc::Chip tgtChip, xsc::Copy tgtCopy); + void setRebootMechanismLock(bool lock, xsc::Chip tgtChip, xsc::Copy tgtCopy); + bool parseRebootFile(std::string path, RebootFile& file); + void rewriteRebootFile(RebootFile file); }; #endif /* BSP_Q7S_CORE_CORECONTROLLER_H_ */ diff --git a/bsp_q7s/core/InitMission.cpp b/bsp_q7s/core/InitMission.cpp index e7d8779b..9d28e1d3 100644 --- a/bsp_q7s/core/InitMission.cpp +++ b/bsp_q7s/core/InitMission.cpp @@ -1,28 +1,27 @@ #include "InitMission.h" -#include "ObjectFactory.h" -#include "OBSWConfig.h" -#include "pollingsequence/pollingSequenceFactory.h" - -#include "mission/utility/InitMission.h" - -#include "fsfw/platform.h" -#include "fsfw/objectmanager/ObjectManagerIF.h" -#include "fsfw/returnvalues/HasReturnvaluesIF.h" -#include "fsfw/serviceinterface/ServiceInterfaceStream.h" -#include "fsfw/objectmanager/ObjectManager.h" -#include "fsfw/tasks/FixedTimeslotTaskIF.h" -#include "fsfw/tasks/PeriodicTaskIF.h" -#include "fsfw/tasks/TaskFactory.h" #include #include +#include "OBSWConfig.h" +#include "ObjectFactory.h" +#include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/objectmanager/ObjectManagerIF.h" +#include "fsfw/platform.h" +#include "fsfw/returnvalues/HasReturnvaluesIF.h" +#include "fsfw/serviceinterface/ServiceInterfaceStream.h" +#include "fsfw/tasks/FixedTimeslotTaskIF.h" +#include "fsfw/tasks/PeriodicTaskIF.h" +#include "fsfw/tasks/TaskFactory.h" +#include "mission/utility/InitMission.h" +#include "pollingsequence/pollingSequenceFactory.h" + /* This is configured for linux without CR */ #ifdef PLATFORM_UNIX ServiceInterfaceStream sif::debug("DEBUG"); ServiceInterfaceStream sif::info("INFO"); ServiceInterfaceStream sif::warning("WARNING"); -ServiceInterfaceStream sif::error("ERROR", false, false, true); +ServiceInterfaceStream sif::error("ERROR"); #else ServiceInterfaceStream sif::debug("DEBUG", true); ServiceInterfaceStream sif::info("INFO", true); @@ -30,288 +29,387 @@ ServiceInterfaceStream sif::warning("WARNING", true); ServiceInterfaceStream sif::error("ERROR", true, false, true); #endif -ObjectManagerIF *objectManager = nullptr; +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); + sif::info << "Initializing all objects.." << std::endl; + ObjectManager::instance()->initialize(); - sif::info << "Building global objects.." << std::endl; - /* Instantiate global object manager and also create all objects */ - ObjectManager::instance()->setObjectFactoryFunction(ObjectFactory::produce, nullptr); - sif::info << "Initializing all objects.." << std::endl; - ObjectManager::instance()->initialize(); - - /* This function creates and starts all tasks */ - initTasks(); + /* This function creates and starts all tasks */ + initTasks(); } void initmission::initTasks() { - TaskFactory* factory = TaskFactory::instance(); - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - if(factory == nullptr) { - /* Should never happen ! */ - return; - } + TaskFactory* factory = TaskFactory::instance(); + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + if (factory == nullptr) { + /* Should never happen ! */ + return; + } #if OBSW_PRINT_MISSED_DEADLINES == 1 - void (*missedDeadlineFunc) (void) = TaskFactory::printMissedDeadline; + void (*missedDeadlineFunc)(void) = TaskFactory::printMissedDeadline; #else - void (*missedDeadlineFunc) (void) = nullptr; + void (*missedDeadlineFunc)(void) = nullptr; #endif #if BOARD_TE0720 == 0 - PeriodicTaskIF* coreController = factory->createPeriodicTask( - "CORE_CTRL", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.4, missedDeadlineFunc); - result = coreController->addComponent(objects::CORE_CONTROLLER); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("CORE_CTRL", objects::CORE_CONTROLLER); - } + PeriodicTaskIF* coreController = factory->createPeriodicTask( + "CORE_CTRL", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.4, missedDeadlineFunc); + result = coreController->addComponent(objects::CORE_CONTROLLER); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("CORE_CTRL", objects::CORE_CONTROLLER); + } #endif - /* TMTC Distribution */ - PeriodicTaskIF* tmTcDistributor = factory->createPeriodicTask( - "DIST", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc); - result = tmTcDistributor->addComponent(objects::CCSDS_PACKET_DISTRIBUTOR); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("CCSDS_DISTRIB", objects::CCSDS_PACKET_DISTRIBUTOR); - } - result = tmTcDistributor->addComponent(objects::PUS_PACKET_DISTRIBUTOR); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("PUS_PACKET_DISTRIB", objects::PUS_PACKET_DISTRIBUTOR); - } - result = tmTcDistributor->addComponent(objects::TM_FUNNEL); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("TM_FUNNEL", objects::TM_FUNNEL); - } + /* TMTC Distribution */ + PeriodicTaskIF* tmTcDistributor = factory->createPeriodicTask( + "DIST", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc); + result = tmTcDistributor->addComponent(objects::CCSDS_PACKET_DISTRIBUTOR); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("CCSDS_DISTRIB", objects::CCSDS_PACKET_DISTRIBUTOR); + } + result = tmTcDistributor->addComponent(objects::PUS_PACKET_DISTRIBUTOR); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS_PACKET_DISTRIB", objects::PUS_PACKET_DISTRIBUTOR); + } + result = tmTcDistributor->addComponent(objects::TM_FUNNEL); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("TM_FUNNEL", objects::TM_FUNNEL); + } - /* UDP bridge */ - PeriodicTaskIF* tmtcBridgeTask = factory->createPeriodicTask( - "UDP_UNIX_BRIDGE", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc); - result = tmtcBridgeTask->addComponent(objects::TMTC_BRIDGE); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("UDP_BRIDGE", objects::TMTC_BRIDGE); - } - PeriodicTaskIF* tmtcPollingTask = factory->createPeriodicTask( - "UDP_POLLING", 80, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc); - result = tmtcPollingTask->addComponent(objects::TMTC_POLLING_TASK); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("UDP_POLLING", objects::TMTC_POLLING_TASK); - } +#if OBSW_ADD_TCPIP_BRIDGE == 1 + // TMTC bridge + PeriodicTaskIF* tmtcBridgeTask = factory->createPeriodicTask( + "TCPIP_TMTC_BRIDGE", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc); + result = tmtcBridgeTask->addComponent(objects::TMTC_BRIDGE); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("TMTC_BRIDGE", objects::TMTC_BRIDGE); + } + PeriodicTaskIF* tmtcPollingTask = factory->createPeriodicTask( + "TMTC_POLLING", 80, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc); + result = tmtcPollingTask->addComponent(objects::TMTC_POLLING_TASK); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("UDP_POLLING", objects::TMTC_POLLING_TASK); + } +#endif + +#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 */ + +#if OBSW_ADD_ACS_HANDLERS == 1 + PeriodicTaskIF* acsCtrl = factory->createPeriodicTask( + "ACS_CTRL", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, 0.4, missedDeadlineFunc); + result = acsCtrl->addComponent(objects::GPS_CONTROLLER); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("ACS_CTRL", objects::GPS_CONTROLLER); + } +#endif /* OBSW_ADD_ACS_HANDLERS */ + +#if BOARD_TE0720 == 0 + // FS task, task interval does not matter because it runs in permanent loop, priority low + // because it is a non-essential background task + PeriodicTaskIF* fsTask = factory->createPeriodicTask( + "FILE_SYSTEM_TASK", 25, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.4, missedDeadlineFunc); + result = fsTask->addComponent(objects::FILE_SYSTEM_HANDLER); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("FILE_SYSTEM_TASK", objects::FILE_SYSTEM_HANDLER); + } + +#if OBSW_ADD_STAR_TRACKER == 1 + PeriodicTaskIF* strHelperTask = factory->createPeriodicTask( + "STR_HELPER", 20, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc); + result = strHelperTask->addComponent(objects::STR_HELPER); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("STR_HELPER", objects::STR_HELPER); + } +#endif /* OBSW_ADD_STAR_TRACKER == 1 */ -# if BOARD_TE0720 == 0 - // FS task, task interval does not matter because it runs in permanent loop, priority low - // because it is a non-essential background task - PeriodicTaskIF* fsTask = factory->createPeriodicTask( - "FILE_SYSTEM_TASK", 25, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.4, missedDeadlineFunc); - result = fsTask->addComponent(objects::FILE_SYSTEM_HANDLER); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("FILE_SYSTEM_TASK", objects::FILE_SYSTEM_HANDLER); - } #endif /* BOARD_TE0720 */ #if OBSW_TEST_CCSDS_BRIDGE == 1 - PeriodicTaskIF* ptmeTestTask = factory->createPeriodicTask( - "PTME_TEST", 80, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc); - result = ptmeTestTask->addComponent(objects::CCSDS_IP_CORE_BRIDGE); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("PTME_TEST", objects::CCSDS_IP_CORE_BRIDGE); + PeriodicTaskIF* ptmeTestTask = factory->createPeriodicTask( + "PTME_TEST", 80, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc); + result = ptmeTestTask->addComponent(objects::CCSDS_IP_CORE_BRIDGE); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PTME_TEST", objects::CCSDS_IP_CORE_BRIDGE); + } +#endif + + std::vector pusTasks; + createPusTasks(*factory, missedDeadlineFunc, pusTasks); + std::vector pstTasks; + createPstTasks(*factory, missedDeadlineFunc, pstTasks); + +#if OBSW_ADD_TEST_CODE == 1 + std::vector testTasks; + createTestTasks(*factory, missedDeadlineFunc, testTasks); +#endif + + auto taskStarter = [](std::vector& taskVector, std::string name) { + for (const auto& task : taskVector) { + if (task != nullptr) { + task->startTask(); + } else { + sif::error << "Task in vector " << name << " is invalid!" << std::endl; + } } + }; + + sif::info << "Starting tasks.." << std::endl; + tmTcDistributor->startTask(); + +#if OBSW_ADD_TCPIP_BRIDGE == 1 + tmtcBridgeTask->startTask(); + tmtcPollingTask->startTask(); #endif - std::vector pusTasks; - createPusTasks(*factory, missedDeadlineFunc, pusTasks); - std::vector pstTasks; - createPstTasks(*factory, missedDeadlineFunc, pstTasks); +#if OBSW_USE_CCSDS_IP_CORE == 1 + ccsdsHandlerTask->startTask(); + pdecHandlerTask->startTask(); +#endif /* OBSW_USE_CCSDS_IP_CORE == 1 */ -#if OBSW_ADD_TEST_CODE == 1 - std::vector testTasks; - createTestTasks(*factory, missedDeadlineFunc, testTasks); -#endif - - auto taskStarter = [](std::vector& taskVector, std::string name) { - for(const auto& task: taskVector) { - if(task != nullptr) { - task->startTask(); - } - else { - sif::error << "Task in vector " << name << " is invalid!" << std::endl; - } - } - }; - - sif::info << "Starting tasks.." << std::endl; - tmTcDistributor->startTask(); - tmtcBridgeTask->startTask(); - tmtcPollingTask->startTask(); #if BOARD_TE0720 == 0 - coreController->startTask(); + coreController->startTask(); #endif - taskStarter(pstTasks, "PST task vector"); - taskStarter(pusTasks, "PUS task vector"); + taskStarter(pstTasks, "PST task vector"); + taskStarter(pusTasks, "PUS task vector"); #if OBSW_ADD_TEST_CODE == 1 - taskStarter(testTasks, "Test task vector"); + taskStarter(testTasks, "Test task vector"); #endif #if OBSW_TEST_CCSDS_BRIDGE == 1 - ptmeTestTask->startTask(); + ptmeTestTask->startTask(); #endif #if BOARD_TE0720 == 0 - fsTask->startTask(); + fsTask->startTask(); +#if OBSW_ADD_STAR_TRACKER == 1 + strHelperTask > startTask(); +#endif /* OBSW_ADD_STAR_TRACKER == 1 */ #endif - sif::info << "Tasks started.." << std::endl; +#if OBSW_ADD_ACS_HANDLERS == 1 + acsCtrl->startTask(); +#endif + + sif::info << "Tasks started.." << std::endl; } void initmission::createPstTasks(TaskFactory& factory, - TaskDeadlineMissedFunction missedDeadlineFunc, std::vector &taskVec) { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + TaskDeadlineMissedFunction missedDeadlineFunc, + std::vector& taskVec) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; #if BOARD_TE0720 == 0 - /* Polling Sequence Table Default */ + /* Polling Sequence Table Default */ #if OBSW_ADD_SPI_TEST_CODE == 0 - FixedTimeslotTaskIF* spiPst = factory.createFixedTimeslotTask( - "PST_TASK_DEFAULT", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 3.0, - missedDeadlineFunc); - result = pst::pstSpi(spiPst); - if (result != HasReturnvaluesIF::RETURN_OK) { - sif::error << "InitMission::initTasks: Creating PST failed!" << std::endl; + FixedTimeslotTaskIF* spiPst = factory.createFixedTimeslotTask( + "PST_TASK_DEFAULT", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 0.5, missedDeadlineFunc); + result = pst::pstSpi(spiPst); + if (result != HasReturnvaluesIF::RETURN_OK) { + if (result != FixedTimeslotTaskIF::SLOT_LIST_EMPTY) { + sif::error << "InitMission::initTasks: Creating PST failed!" << std::endl; } + } else { taskVec.push_back(spiPst); + } #endif - FixedTimeslotTaskIF* uartPst = factory.createFixedTimeslotTask( - "UART_PST", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 3.0, missedDeadlineFunc); - result = pst::pstUart(uartPst); - if (result != HasReturnvaluesIF::RETURN_OK) { - sif::error << "InitMission::initTasks: Creating PST failed!" << std::endl; - } - taskVec.push_back(uartPst); - FixedTimeslotTaskIF* gpioPst = factory.createFixedTimeslotTask( - "GPIO_PST", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 3.0, missedDeadlineFunc); - result = pst::pstGpio(gpioPst); - if (result != HasReturnvaluesIF::RETURN_OK) { - sif::error << "InitMission::initTasks: Creating PST failed!" << std::endl; - } - taskVec.push_back(gpioPst); - FixedTimeslotTaskIF* i2cPst = factory.createFixedTimeslotTask( - "I2C_PST", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 3.0, missedDeadlineFunc); - result = pst::pstI2c(i2cPst); - if (result != HasReturnvaluesIF::RETURN_OK) { - sif::error << "InitMission::initTasks: Creating PST failed!" << std::endl; - } + FixedTimeslotTaskIF* uartPst = factory.createFixedTimeslotTask( + "UART_PST", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 0.2, missedDeadlineFunc); + result = pst::pstUart(uartPst); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "InitMission::initTasks: Creating PST failed!" << std::endl; + } + taskVec.push_back(uartPst); + FixedTimeslotTaskIF* gpioPst = factory.createFixedTimeslotTask( + "GPIO_PST", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 0.2, missedDeadlineFunc); + result = pst::pstGpio(gpioPst); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "InitMission::initTasks: Creating PST failed!" << std::endl; + } + taskVec.push_back(gpioPst); - FixedTimeslotTaskIF* gomSpacePstTask = factory.createFixedTimeslotTask( - "GS_PST_TASK", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 1.0, missedDeadlineFunc); - result = pst::pstGompaceCan(gomSpacePstTask); - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::error << "InitMission::initTasks: GomSpace PST initialization failed!" << std::endl; - } - taskVec.push_back(gomSpacePstTask); -#else /* BOARD_TE7020 == 0 */ - FixedTimeslotTaskIF * pollingSequenceTaskTE0720 = factory.createFixedTimeslotTask( - "PST_TASK_TE0720", 30, PeriodicTaskIF::MINIMUM_STACK_SIZE * 8, 3.0, - missedDeadlineFunc); - result = pst::pollingSequenceTE0720(pollingSequenceTaskTE0720); - if (result != HasReturnvaluesIF::RETURN_OK) { - sif::error << "InitMission::initTasks: Creating TE0720 PST failed!" << std::endl; - } - taskVec.push_back(pollingSequenceTaskTE0720); +#if OBSW_ADD_I2C_TEST_CODE == 0 + FixedTimeslotTaskIF* i2cPst = factory.createFixedTimeslotTask( + "I2C_PST", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 0.2, missedDeadlineFunc); + result = pst::pstI2c(i2cPst); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "InitMission::initTasks: Creating PST failed!" << std::endl; + } + taskVec.push_back(i2cPst); +#endif + + FixedTimeslotTaskIF* gomSpacePstTask = factory.createFixedTimeslotTask( + "GS_PST_TASK", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 1.0, missedDeadlineFunc); + result = pst::pstGompaceCan(gomSpacePstTask); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "InitMission::initTasks: GomSpace PST initialization failed!" << std::endl; + } + taskVec.push_back(gomSpacePstTask); +#else /* BOARD_TE7020 == 0 */ + FixedTimeslotTaskIF* pollingSequenceTaskTE0720 = factory.createFixedTimeslotTask( + "PST_TASK_TE0720", 30, PeriodicTaskIF::MINIMUM_STACK_SIZE * 8, 3.0, missedDeadlineFunc); + result = pst::pollingSequenceTE0720(pollingSequenceTaskTE0720); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "InitMission::initTasks: Creating TE0720 PST failed!" << std::endl; + } + taskVec.push_back(pollingSequenceTaskTE0720); #endif /* BOARD_TE7020 == 1 */ } -void initmission::createPusTasks(TaskFactory &factory, - TaskDeadlineMissedFunction missedDeadlineFunc, std::vector &taskVec) { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - /* PUS Services */ - PeriodicTaskIF* pusVerification = factory.createPeriodicTask( - "PUS_VERIF", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); - result = pusVerification->addComponent(objects::PUS_SERVICE_1_VERIFICATION); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("PUS_VERIF", objects::PUS_SERVICE_1_VERIFICATION); - } - taskVec.push_back(pusVerification); +void initmission::createPusTasks(TaskFactory& factory, + TaskDeadlineMissedFunction missedDeadlineFunc, + std::vector& taskVec) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + /* PUS Services */ + PeriodicTaskIF* pusVerification = factory.createPeriodicTask( + "PUS_VERIF", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); + result = pusVerification->addComponent(objects::PUS_SERVICE_1_VERIFICATION); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS_VERIF", objects::PUS_SERVICE_1_VERIFICATION); + } + taskVec.push_back(pusVerification); - PeriodicTaskIF* pusEvents = factory.createPeriodicTask( - "PUS_EVENTS", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); - result = pusEvents->addComponent(objects::PUS_SERVICE_5_EVENT_REPORTING); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("PUS_EVENTS", objects::PUS_SERVICE_5_EVENT_REPORTING); - } - result = pusEvents->addComponent(objects::EVENT_MANAGER); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("PUS_MGMT", objects::EVENT_MANAGER); - } - taskVec.push_back(pusEvents); + PeriodicTaskIF* pusEvents = factory.createPeriodicTask( + "PUS_EVENTS", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); + result = pusEvents->addComponent(objects::PUS_SERVICE_5_EVENT_REPORTING); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS_EVENTS", objects::PUS_SERVICE_5_EVENT_REPORTING); + } + result = pusEvents->addComponent(objects::EVENT_MANAGER); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS_MGMT", objects::EVENT_MANAGER); + } + taskVec.push_back(pusEvents); - PeriodicTaskIF* pusHighPrio = factory.createPeriodicTask( - "PUS_HIGH_PRIO", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); - result = pusHighPrio->addComponent(objects::PUS_SERVICE_2_DEVICE_ACCESS); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("PUS_2", objects::PUS_SERVICE_2_DEVICE_ACCESS); - } - result = pusHighPrio->addComponent(objects::PUS_SERVICE_9_TIME_MGMT); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("PUS_9", objects::PUS_SERVICE_9_TIME_MGMT); - } - taskVec.push_back(pusHighPrio); + PeriodicTaskIF* pusHighPrio = factory.createPeriodicTask( + "PUS_HIGH_PRIO", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); + result = pusHighPrio->addComponent(objects::PUS_SERVICE_2_DEVICE_ACCESS); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS_2", objects::PUS_SERVICE_2_DEVICE_ACCESS); + } + result = pusHighPrio->addComponent(objects::PUS_SERVICE_9_TIME_MGMT); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS_9", objects::PUS_SERVICE_9_TIME_MGMT); + } + taskVec.push_back(pusHighPrio); - PeriodicTaskIF* pusMedPrio = factory.createPeriodicTask( - "PUS_MED_PRIO", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.8, missedDeadlineFunc); - 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); - if(result!=HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } - 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); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("PUS_20", objects::PUS_SERVICE_20_PARAMETERS); - } - taskVec.push_back(pusMedPrio); + PeriodicTaskIF* pusMedPrio = factory.createPeriodicTask( + "PUS_MED_PRIO", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.8, missedDeadlineFunc); + 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); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "Object add component failed" << std::endl; + } + 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); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS_20", objects::PUS_SERVICE_20_PARAMETERS); + } + taskVec.push_back(pusMedPrio); - PeriodicTaskIF* pusLowPrio = factory.createPeriodicTask( - "PUS_LOW_PRIO", 30, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.6, missedDeadlineFunc); - result = pusLowPrio->addComponent(objects::PUS_SERVICE_17_TEST); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("PUS_17", objects::PUS_SERVICE_17_TEST); - } - result = pusLowPrio->addComponent(objects::INTERNAL_ERROR_REPORTER); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("ERROR_REPORTER", objects::INTERNAL_ERROR_REPORTER); - } - taskVec.push_back(pusLowPrio); + PeriodicTaskIF* pusLowPrio = factory.createPeriodicTask( + "PUS_LOW_PRIO", 30, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.6, missedDeadlineFunc); + result = pusLowPrio->addComponent(objects::PUS_SERVICE_17_TEST); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS_17", objects::PUS_SERVICE_17_TEST); + } + result = pusLowPrio->addComponent(objects::INTERNAL_ERROR_REPORTER); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("ERROR_REPORTER", objects::INTERNAL_ERROR_REPORTER); + } + taskVec.push_back(pusLowPrio); } -void initmission::createTestTasks(TaskFactory& factory, TaskDeadlineMissedFunction missedDeadlineFunc, - std::vector& taskVec) { -#if OBSW_ADD_TEST_TASK == 1 || OBSW_ADD_SPI_TEST_CODE == 1 || (BOARD_TE0720 == 1 && OBSW_TEST_LIBGPIOD == 1) - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; -#endif - PeriodicTaskIF* testTask = factory.createPeriodicTask( - "TEST_TASK", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1, missedDeadlineFunc); -#if OBSW_ADD_TEST_TASK == 1 - result = testTask->addComponent(objects::TEST_TASK); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("TEST_TASK", objects::TEST_TASK); - } -#endif /* OBSW_ADD_TEST_TASK == 1 */ +void initmission::createTestTasks(TaskFactory& factory, + TaskDeadlineMissedFunction missedDeadlineFunc, + std::vector& taskVec) { +#if OBSW_ADD_TEST_TASK == 1 && OBSW_ADD_TEST_CODE == 1 + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + static_cast(result); // supress warning in case it is not used + + PeriodicTaskIF* testTask = factory.createPeriodicTask( + "TEST_TASK", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1, missedDeadlineFunc); + + result = testTask->addComponent(objects::TEST_TASK); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("TEST_TASK", objects::TEST_TASK); + } #if OBSW_ADD_SPI_TEST_CODE == 1 - result = testTask->addComponent(objects::SPI_TEST); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("SPI_TEST", objects::SPI_TEST); - } + result = testTask->addComponent(objects::SPI_TEST); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("SPI_TEST", objects::SPI_TEST); + } #endif +#if OBSW_ADD_I2C_TEST_CODE == 1 + result = testTask->addComponent(objects::I2C_TEST); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("I2C_TEST", objects::I2C_TEST); + } +#endif +#if OBSW_ADD_UART_TEST_CODE == 1 + result = testTask->addComponent(objects::UART_TEST); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("UART_TEST", objects::UART_TEST); + } +#endif + #if BOARD_TE0720 == 1 && OBSW_TEST_LIBGPIOD == 1 - result = testTask->addComponent(objects::LIBGPIOD_TEST); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("GPIOD_TEST", objects::LIBGPIOD_TEST); - } + result = testTask->addComponent(objects::LIBGPIOD_TEST); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("GPIOD_TEST", objects::LIBGPIOD_TEST); + } #endif /* BOARD_TE0720 == 1 && OBSW_TEST_LIBGPIOD == 1 */ - taskVec.push_back(testTask); + taskVec.push_back(testTask); + +#endif // OBSW_ADD_TEST_TASK == 1 && OBSW_ADD_TEST_CODE == 1 } + +/** + â–„ â–„ + ▌▒█ ▄▀▒▌ + ▌▒▒█ ▄▀▒▒▒■+ â–▄▀▒▒▀▀▀▀▄▄▄▀▒▒▒▒▒■+ ▄▄▀▒░▒▒▒▒▒▒▒▒▒█▒▒▄█▒■+ ▄▀▒▒▒░░░▒▒▒░░░▒▒▒▀██▀▒▌ + â–▒▒▒▄▄▒▒▒▒░░░▒▒▒▒▒▒▒▀▄▒▒▌ + ▌░░▌█▀▒▒▒▒▒▄▀█▄▒▒▒▒▒▒▒█▒■+ â–░░░▒▒▒▒▒▒▒▒▌██▀▒▒░░░▒▒▒▀▄▌ + ▌░▒▄██▄▒▒▒▒▒▒▒▒▒░░░░░░▒▒▒▒▌ + ▌▒▀â–▄█▄█▌▄░▀▒▒░░░░░░░░░░▒▒▒■+ â–â–’â–’â–â–€â–▀▒░▄▄▒▄▒▒▒▒▒▒░▒░▒░▒▒▒▒▌ + â–▒▒▒▀▀▄▄▒▒▒▄▒▒▒▒▒▒▒▒░▒░▒░▒▒■+ ▌▒▒▒▒▒▒▀▀▀▒▒▒▒▒▒░▒░▒░▒░▒▒▒▌ + â–â–’â–’â–’â–’â–’â–’â–’â–’â–’â–’â–’â–’â–’â–’â–‘â–’â–‘â–’â–‘â–’â–’â–„â–’â–’â– + ▀▄▒▒▒▒▒▒▒▒▒▒▒░▒░▒░▒▄▒▒▒▒▌ + ▀▄▒▒▒▒▒▒▒▒▒▒▄▄▄▀▒▒▒▒▄▀ + ▀▄▄▄▄▄▄▀▀▀▒▒▒▒▒▄▄▀ + ▒▒▒▒▒▒▒▒▒▒▀▀ + **/ diff --git a/bsp_q7s/core/InitMission.h b/bsp_q7s/core/InitMission.h index ffdfc11c..5c509b79 100644 --- a/bsp_q7s/core/InitMission.h +++ b/bsp_q7s/core/InitMission.h @@ -1,9 +1,10 @@ #ifndef BSP_Q7S_INITMISSION_H_ #define BSP_Q7S_INITMISSION_H_ -#include "fsfw/tasks/Typedef.h" #include +#include "fsfw/tasks/Typedef.h" + class PeriodicTaskIF; class TaskFactory; @@ -12,11 +13,11 @@ void initMission(); void initTasks(); void createPstTasks(TaskFactory& factory, TaskDeadlineMissedFunction missedDeadlineFunc, - std::vector& taskVec); + std::vector& taskVec); void createPusTasks(TaskFactory& factory, TaskDeadlineMissedFunction missedDeadlineFunc, - std::vector& taskVec); + std::vector& taskVec); void createTestTasks(TaskFactory& factory, TaskDeadlineMissedFunction missedDeadlineFunc, - std::vector& taskVec); -}; + std::vector& taskVec); +}; // namespace initmission #endif /* BSP_Q7S_INITMISSION_H_ */ diff --git a/bsp_q7s/core/ObjectFactory.cpp b/bsp_q7s/core/ObjectFactory.cpp index d956a392..519dec8f 100644 --- a/bsp_q7s/core/ObjectFactory.cpp +++ b/bsp_q7s/core/ObjectFactory.cpp @@ -1,931 +1,1329 @@ #include "ObjectFactory.h" + +#include +#include +#include +#include +#include + #include "OBSWConfig.h" -#include "devConf.h" -#include "busConf.h" -#include "tmtc/apid.h" -#include "devices/addresses.h" -#include "devices/gpioIds.h" -#include "tmtc/pusIds.h" -#include "devices/powerSwitcherList.h" -#include "bsp_q7s/gpio/gpioCallbacks.h" -#include "bsp_q7s/core/CoreController.h" #include "bsp_q7s/boardtest/Q7STestTask.h" -#include "bsp_q7s/memory/FileSystemHandler.h" +#include "bsp_q7s/callbacks/gnssCallback.h" +#include "bsp_q7s/callbacks/gpioCallbacks.h" +#include "bsp_q7s/callbacks/pcduSwitchCb.h" +#include "bsp_q7s/callbacks/rwSpiCallback.h" +#include "bsp_q7s/core/CoreController.h" +#include "bsp_q7s/devices/PlocMemoryDumper.h" #include "bsp_q7s/devices/PlocSupervisorHandler.h" #include "bsp_q7s/devices/PlocUpdater.h" -#include "bsp_q7s/devices/PlocMemoryDumper.h" -#include "bsp_q7s/callbacks/rwSpiCallback.h" -#include "bsp_q7s/callbacks/gnssCallback.h" - -#include "linux/devices/HeaterHandler.h" -#include "linux/devices/SolarArrayDeploymentHandler.h" -#include "linux/devices/devicedefinitions/SusDefinitions.h" -#include "linux/devices/SusHandler.h" -#include "linux/csp/CspCookie.h" -#include "linux/csp/CspComIF.h" -#include "linux/obc/CCSDSIPCoreBridge.h" - -#include "mission/core/GenericFactory.h" -#include "mission/devices/PDU1Handler.h" -#include "mission/devices/PDU2Handler.h" -#include "mission/devices/ACUHandler.h" -#include "mission/devices/PCDUHandler.h" -#include "mission/devices/P60DockHandler.h" -#include "mission/devices/Tmp1075Handler.h" -#include "mission/devices/Max31865PT1000Handler.h" -#include "mission/devices/GyroADIS16507Handler.h" -#include "mission/devices/IMTQHandler.h" -#include "mission/devices/SyrlinksHkHandler.h" -#include "mission/devices/PlocMPSoCHandler.h" -#include "mission/devices/RadiationSensorHandler.h" -#include "mission/devices/RwHandler.h" -#include "mission/devices/StarTrackerHandler.h" -#include "mission/devices/devicedefinitions/GomspaceDefinitions.h" -#include "mission/devices/devicedefinitions/SyrlinksDefinitions.h" -#include "mission/devices/devicedefinitions/PlocMPSoCDefinitions.h" -#include "mission/devices/devicedefinitions/RadSensorDefinitions.h" -#include "mission/devices/devicedefinitions/Max31865Definitions.h" -#include "mission/devices/devicedefinitions/RwDefinitions.h" -#include "mission/devices/devicedefinitions/StarTrackerDefinitions.h" -#include "mission/devices/GPSHyperionHandler.h" -#include "mission/utility/TmFunnel.h" - -#include "fsfw_hal/linux/uart/UartComIF.h" -#include "fsfw_hal/linux/uart/UartCookie.h" -#include "fsfw_hal/devicehandlers/MgmLIS3MDLHandler.h" -#include "fsfw_hal/devicehandlers/GyroL3GD20Handler.h" -#include "fsfw_hal/devicehandlers/MgmRM3100Handler.h" -#include "fsfw_hal/linux/i2c/I2cCookie.h" -#include "fsfw_hal/linux/i2c/I2cComIF.h" -#include "fsfw_hal/linux/spi/SpiCookie.h" -#include "fsfw_hal/linux/spi/SpiComIF.h" -#include "fsfw_hal/linux/gpio/LinuxLibgpioIF.h" -#include "fsfw_hal/common/gpio/GpioCookie.h" - -#include "fsfw/datapoollocal/LocalDataPoolManager.h" -#include "fsfw/tmtcservices/CommandingServiceBase.h" -#include "fsfw/tmtcservices/PusServiceBase.h" -#include "fsfw/tmtcpacket/pus/tm.h" - -#if OBSW_USE_TMTC_TCP_BRIDGE == 0 -// UDP server includes -#include "fsfw/osal/common/UdpTmTcBridge.h" -#include "fsfw/osal/common/UdpTcPollingTask.h" -#else -// TCP server includes -#include "fsfw/osal/common/TcpTmTcBridge.h" -#include "fsfw/osal/common/TcpTmTcServer.h" -#endif - +#include "bsp_q7s/memory/FileSystemHandler.h" +#include "busConf.h" +#include "ccsdsConfig.h" +#include "devConf.h" +#include "devices/addresses.h" +#include "devices/gpioIds.h" +#include "devices/powerSwitcherList.h" +#include "linux/boardtest/I2cTestClass.h" #include "linux/boardtest/SpiTestClass.h" +#include "linux/boardtest/UartTestClass.h" +#include "linux/csp/CspComIF.h" +#include "linux/csp/CspCookie.h" +#include "linux/devices/GPSHyperionLinuxController.h" +#include "linux/devices/devicedefinitions/StarTrackerDefinitions.h" +#include "linux/devices/startracker/StarTrackerHandler.h" +#include "linux/devices/startracker/StrHelper.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/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 "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/PlocMPSoCHandler.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/PlocMPSoCDefinitions.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/tmtc/CCSDSHandler.h" +#include "mission/tmtc/VirtualChannel.h" +#include "mission/utility/TmFunnel.h" + ResetArgs resetArgsGnss0; ResetArgs resetArgsGnss1; -void ObjectFactory::setStatics() { - Factory::setStaticFrameworkObjectIds(); -} +void ObjectFactory::setStatics() { Factory::setStaticFrameworkObjectIds(); } void Factory::setStaticFrameworkObjectIds() { - PusServiceBase::packetSource = objects::PUS_PACKET_DISTRIBUTOR; - PusServiceBase::packetDestination = objects::TM_FUNNEL; + PusServiceBase::packetSource = objects::PUS_PACKET_DISTRIBUTOR; + PusServiceBase::packetDestination = objects::TM_FUNNEL; - CommandingServiceBase::defaultPacketSource = objects::PUS_PACKET_DISTRIBUTOR; - CommandingServiceBase::defaultPacketDestination = objects::TM_FUNNEL; + CommandingServiceBase::defaultPacketSource = objects::PUS_PACKET_DISTRIBUTOR; + CommandingServiceBase::defaultPacketDestination = objects::TM_FUNNEL; - //DeviceHandlerBase::powerSwitcherId = objects::PCDU_HANDLER; - DeviceHandlerBase::powerSwitcherId = objects::NO_OBJECT; - TmFunnel::downlinkDestination = objects::TMTC_BRIDGE; - // No storage object for now. - TmFunnel::storageDestination = objects::NO_OBJECT; + // DeviceHandlerBase::powerSwitcherId = objects::PCDU_HANDLER; + DeviceHandlerBase::powerSwitcherId = objects::NO_OBJECT; - LocalDataPoolManager::defaultHkDestination = objects::PUS_SERVICE_3_HOUSEKEEPING; +#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; - VerificationReporter::messageReceiver = objects::PUS_SERVICE_1_VERIFICATION; - TmPacketBase::timeStamperId = objects::TIME_STAMPER; + 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(); - LinuxLibgpioIF* gpioComIF = nullptr; - UartComIF* uartComIF = nullptr; - SpiComIF* spiComIF = nullptr; - createCommunicationInterfaces(&gpioComIF, &uartComIF, &spiComIF); - createTmpComponents(); -#if BOARD_TE0720 == 0 - new CoreController(objects::CORE_CONTROLLER); + ObjectFactory::setStatics(); + ObjectFactory::produceGenericObjects(); - createPcduComponents(); - createRadSensorComponent(gpioComIF); - createSunSensorComponents(gpioComIF, spiComIF); + LinuxLibgpioIF* gpioComIF = nullptr; + UartComIF* uartComIF = nullptr; + SpiComIF* spiComIF = nullptr; + I2cComIF* i2cComIF = nullptr; + createCommunicationInterfaces(&gpioComIF, &uartComIF, &spiComIF, &i2cComIF); + createTmpComponents(); +#if BOARD_TE0720 == 0 + new CoreController(objects::CORE_CONTROLLER); + + gpioCallbacks::disableAllDecoder(); + createPcduComponents(gpioComIF); + createRadSensorComponent(gpioComIF); + createSunSensorComponents(gpioComIF, spiComIF); #if OBSW_ADD_ACS_BOARD == 1 - createAcsBoardComponents(gpioComIF, uartComIF); -#endif /* OBSW_ADD_ACS_BOARD == 1 */ - createHeaterComponents(); - createSolarArrayDeploymentComponents(); + createAcsBoardComponents(gpioComIF, uartComIF); +#endif + + createHeaterComponents(); + createSolarArrayDeploymentComponents(); + createPlPcduComponents(gpioComIF, spiComIF); #if OBSW_ADD_SYRLINKS == 1 - createSyrlinksComponents(); + createSyrlinksComponents(); #endif /* OBSW_ADD_SYRLINKS == 1 */ + createRtdComponents(gpioComIF); -#if OBSW_ADD_RTD_DEVICES == 1 - createRtdComponents(); -#endif /* OBSW_ADD_RTD_DEVICES == 1 */ +#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); + static_cast(imtqHandler); +#if OBSW_DEBUG_IMTQ == 1 + imtqHandler->setToGoToNormal(true); + imtqHandler->setStartUpImmediately(); +#else + (void)imtqHandler; +#endif +#endif + createReactionWheelComponents(gpioComIF); - I2cCookie* imtqI2cCookie = new I2cCookie(addresses::IMTQ, IMTQ::MAX_REPLY_SIZE, - q7s::I2C_DEFAULT_DEV); - new IMTQHandler(objects::IMTQ_HANDLER, objects::I2C_COM_IF, imtqI2cCookie); - 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); +#if OBSW_TEST_BPX_BATT == 1 + bpxHandler->setToGoToNormalMode(true); + bpxHandler->setStartUpImmediately(); +#else + static_cast(bpxHandler); +#endif +#endif #if OBSW_ADD_PLOC_MPSOC == 1 - UartCookie* plocMpsocCookie = new UartCookie(objects::PLOC_MPSOC_HANDLER, - q7s::UART_PLOC_MPSOC_DEV, UartModes::NON_CANONICAL, uart::PLOC_MPSOC_BAUD, - PLOC_MPSOC::MAX_REPLY_SIZE); - new PlocMPSoCHandler(objects::PLOC_MPSOC_HANDLER, objects::UART_COM_IF, plocMpsocCookie); + UartCookie* plocMpsocCookie = + new UartCookie(objects::PLOC_MPSOC_HANDLER, q7s::UART_PLOC_MPSOC_DEV, + UartModes::NON_CANONICAL, uart::PLOC_MPSOC_BAUD, PLOC_MPSOC::MAX_REPLY_SIZE); + new PlocMPSoCHandler(objects::PLOC_MPSOC_HANDLER, objects::UART_COM_IF, plocMpsocCookie); #endif /* OBSW_ADD_PLOC_MPSOC == 1 */ #if OBSW_ADD_PLOC_SUPERVISOR == 1 - UartCookie* plocSupervisorCookie = new UartCookie(objects::PLOC_SUPERVISOR_HANDLER, - q7s::UART_PLOC_SUPERVSIOR_DEV, UartModes::NON_CANONICAL, uart::PLOC_SUPERVISOR_BAUD, - PLOC_SPV::MAX_PACKET_SIZE * 20); - plocSupervisorCookie->setNoFixedSizeReply(); - PlocSupervisorHandler* plocSupervisor = new PlocSupervisorHandler( - objects::PLOC_SUPERVISOR_HANDLER, objects::UART_COM_IF, plocSupervisorCookie); - plocSupervisor->setStartUpImmediately(); + UartCookie* plocSupervisorCookie = new UartCookie( + objects::PLOC_SUPERVISOR_HANDLER, q7s::UART_PLOC_SUPERVSIOR_DEV, UartModes::NON_CANONICAL, + uart::PLOC_SUPERVISOR_BAUD, PLOC_SPV::MAX_PACKET_SIZE * 20); + plocSupervisorCookie->setNoFixedSizeReply(); + PlocSupervisorHandler* plocSupervisor = new PlocSupervisorHandler( + objects::PLOC_SUPERVISOR_HANDLER, objects::UART_COM_IF, plocSupervisorCookie); + plocSupervisor->setStartUpImmediately(); #endif /* OBSW_ADD_PLOC_SUPERVISOR == 1 */ - new FileSystemHandler(objects::FILE_SYSTEM_HANDLER); + new FileSystemHandler(objects::FILE_SYSTEM_HANDLER); #if OBSW_ADD_STAR_TRACKER == 1 - UartCookie* starTrackerCookie = new UartCookie(objects::START_TRACKER, - q7s::UART_STAR_TRACKER_DEV, UartModes::NON_CANONICAL, uart::STAR_TRACKER_BAUD, - StarTracker::MAX_FRAME_SIZE* 2 + 2); - starTrackerCookie->setNoFixedSizeReply(); - new StarTrackerHandler(objects::START_TRACKER, objects::UART_COM_IF, starTrackerCookie); + UartCookie* starTrackerCookie = + new UartCookie(objects::STAR_TRACKER, q7s::UART_STAR_TRACKER_DEV, UartModes::NON_CANONICAL, + uart::STAR_TRACKER_BAUD, StarTracker::MAX_FRAME_SIZE * 2 + 2); + starTrackerCookie->setNoFixedSizeReply(); + StrHelper* strHelper = new StrHelper(objects::STR_HELPER); + StarTrackerHandler* starTrackerHandler = new StarTrackerHandler( + objects::STAR_TRACKER, objects::UART_COM_IF, starTrackerCookie, strHelper); + starTrackerHandler->setStartUpImmediately(); + #endif /* OBSW_ADD_STAR_TRACKER == 1 */ -#endif /* TE7020 != 0 */ +#endif /* TE7020 == 0 */ -#if OBSW_USE_TMTC_TCP_BRIDGE == 0 - auto udpBridge = new UdpTmTcBridge(objects::TMTC_BRIDGE, objects::CCSDS_PACKET_DISTRIBUTOR); - new UdpTcPollingTask(objects::TMTC_POLLING_TASK, objects::TMTC_BRIDGE); - sif::info << "Created UDP server for TMTC commanding with listener port " << - udpBridge->getUdpPort() << std::endl; -#else - auto tmtcBridge = new TcpTmTcBridge(objects::TMTC_BRIDGE, objects::CCSDS_PACKET_DISTRIBUTOR); - tmtcBridge->setMaxNumberOfPacketsStored(50); - auto tcpServer = new TcpTmTcServer(objects::TMTC_POLLING_TASK, objects::TMTC_BRIDGE); - sif::info << "Created TCP server for TMTC commanding with listener port " - << tcpServer->getTcpPort() << std::endl; -#endif /* OBSW_USE_TMTC_TCP_BRIDGE == 0 */ +#if OBSW_USE_CCSDS_IP_CORE == 1 + createCcsdsComponents(gpioComIF); +#endif /* OBSW_USE_CCSDS_IP_CORE == 1 */ - /* Test Task */ + /* Test Task */ #if OBSW_ADD_TEST_CODE == 1 - createTestComponents(gpioComIF); + createTestComponents(gpioComIF); #endif /* OBSW_ADD_TEST_CODE == 1 */ - new PlocUpdater(objects::PLOC_UPDATER); - new PlocMemoryDumper(objects::PLOC_MEMORY_DUMPER); + new PlocUpdater(objects::PLOC_UPDATER); + new PlocMemoryDumper(objects::PLOC_MEMORY_DUMPER); } void ObjectFactory::createTmpComponents() { #if BOARD_TE0720 == 1 - 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")); #else - 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); + 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); #endif - /* 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; + /* 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) { - 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); +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); - new I2cComIF(objects::I2C_COM_IF); - *uartComIF = new UartComIF(objects::UART_COM_IF); -#if OBSW_ADD_SPI_TEST_CODE == 0 - *spiComIF = new SpiComIF(objects::SPI_COM_IF, *gpioComIF); -#endif /* Q7S_ADD_SPI_TEST_CODE == 0 */ + /* 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); #if BOARD_TE0720 == 0 - /* Adding gpios for chip select decoding to the gpioComIf */ - gpioCallbacks::initSpiCsDecoder(*gpioComIF); + /* Adding gpios for chip select decoding to the gpioComIf */ + gpioCallbacks::initSpiCsDecoder(*gpioComIF); #endif } -void ObjectFactory::createPcduComponents() { - 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); - /* Device Handler */ - P60DockHandler* p60dockhandler = new P60DockHandler(objects::P60DOCK_HANDLER, - objects::CSP_COM_IF, p60DockCspCookie); - PDU1Handler* pdu1handler = new PDU1Handler(objects::PDU1_HANDLER, objects::CSP_COM_IF, - pdu1CspCookie); - PDU2Handler* pdu2handler = new PDU2Handler(objects::PDU2_HANDLER, objects::CSP_COM_IF, - pdu2CspCookie); - ACUHandler* acuhandler = new ACUHandler(objects::ACU_HANDLER, objects::CSP_COM_IF, - acuCspCookie); - new PCDUHandler(objects::PCDU_HANDLER, 50); +void ObjectFactory::createPcduComponents(LinuxLibgpioIF* gpioComIF) { + 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); + /* Device Handler */ + P60DockHandler* p60dockhandler = + new P60DockHandler(objects::P60DOCK_HANDLER, objects::CSP_COM_IF, p60DockCspCookie); + PDU1Handler* pdu1handler = + new PDU1Handler(objects::PDU1_HANDLER, objects::CSP_COM_IF, pdu1CspCookie); + pdu1handler->assignChannelHookFunction(&pcdu::switchCallback, gpioComIF); + PDU2Handler* pdu2handler = + new PDU2Handler(objects::PDU2_HANDLER, objects::CSP_COM_IF, pdu2CspCookie); + pdu2handler->assignChannelHookFunction(&pcdu::switchCallback, gpioComIF); + ACUHandler* acuhandler = new ACUHandler(objects::ACU_HANDLER, objects::CSP_COM_IF, acuCspCookie); + 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(); + /** + * Setting PCDU devices to mode normal immediately after start up because PCDU is always + * running. + */ + p60dockhandler->setModeNormal(); + pdu1handler->setModeNormal(); + pdu2handler->setModeNormal(); + acuhandler->setModeNormal(); } void ObjectFactory::createRadSensorComponent(LinuxLibgpioIF* gpioComIF) { - GpioCookie* gpioCookieRadSensor = new GpioCookie; - auto chipSelectRadSensor = new GpiodRegularByLabel(q7s::GPIO_RAD_SENSOR_LABEL, - q7s::GPIO_RAD_SENSOR_CS, "Chip Select Radiation Sensor", gpio::OUT, gpio::HIGH); - gpioCookieRadSensor->addGpio(gpioIds::CS_RAD_SENSOR, chipSelectRadSensor); - gpioComIF->addGpios(gpioCookieRadSensor); + 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); - new RadiationSensorHandler(objects::RAD_SENSOR, objects::SPI_COM_IF, spiCookieRadSensor); + 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); +#if OBSW_TEST_RAD_SENSOR == 1 + radSensor->setStartUpImmediately(); + radSensor->setToGoToNormalModeImmediately(); +#endif } -void ObjectFactory::createSunSensorComponents(LinuxLibgpioIF *gpioComIF, SpiComIF* spiComIF) { - GpioCookie* gpioCookieSus = new GpioCookie(); - GpioCallback* susgpio = nullptr; +void ObjectFactory::createSunSensorComponents(LinuxLibgpioIF* gpioComIF, SpiComIF* spiComIF) { + using namespace gpio; + GpioCookie* gpioCookieSus = new GpioCookie(); + GpioCallback* susgpio = nullptr; - susgpio = new GpioCallback("Chip select SUS 1", gpio::OUT, 1, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - gpioCookieSus->addGpio(gpioIds::CS_SUS_1, susgpio); - susgpio = new GpioCallback("Chip select SUS 2", gpio::OUT, 1, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - gpioCookieSus->addGpio(gpioIds::CS_SUS_2, susgpio); - susgpio = new GpioCallback("Chip select SUS 3", gpio::OUT, 1, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - gpioCookieSus->addGpio(gpioIds::CS_SUS_3, susgpio); - susgpio = new GpioCallback("Chip select SUS 4", gpio::OUT, 1, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - gpioCookieSus->addGpio(gpioIds::CS_SUS_4, susgpio); - susgpio = new GpioCallback("Chip select SUS 5", gpio::OUT, 1, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - gpioCookieSus->addGpio(gpioIds::CS_SUS_5, susgpio); - susgpio = new GpioCallback("Chip select SUS 6", gpio::OUT, 1, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - gpioCookieSus->addGpio(gpioIds::CS_SUS_6, susgpio); - susgpio = new GpioCallback("Chip select SUS 7", gpio::OUT, 1, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - gpioCookieSus->addGpio(gpioIds::CS_SUS_7, susgpio); - susgpio = new GpioCallback("Chip select SUS 8", gpio::OUT, 1, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - gpioCookieSus->addGpio(gpioIds::CS_SUS_8, susgpio); - susgpio = new GpioCallback("Chip select SUS 9", gpio::OUT, 1, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - gpioCookieSus->addGpio(gpioIds::CS_SUS_9, susgpio); - susgpio = new GpioCallback("Chip select SUS 10", gpio::OUT, 1, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - gpioCookieSus->addGpio(gpioIds::CS_SUS_10, susgpio); - susgpio = new GpioCallback("Chip select SUS 11", gpio::OUT, 1, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - gpioCookieSus->addGpio(gpioIds::CS_SUS_11, susgpio); - susgpio = new GpioCallback("Chip select SUS 12", gpio::OUT, 1, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - gpioCookieSus->addGpio(gpioIds::CS_SUS_12, susgpio); - susgpio = new GpioCallback("Chip select SUS 13", gpio::OUT, 1, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - gpioCookieSus->addGpio(gpioIds::CS_SUS_13, susgpio); + susgpio = new GpioCallback("Chip select SUS 0", Direction::OUT, Levels::HIGH, + &gpioCallbacks::spiCsDecoderCallback, gpioComIF); + gpioCookieSus->addGpio(gpioIds::CS_SUS_0, susgpio); + susgpio = new GpioCallback("Chip select SUS 1", Direction::OUT, Levels::HIGH, + &gpioCallbacks::spiCsDecoderCallback, gpioComIF); + gpioCookieSus->addGpio(gpioIds::CS_SUS_1, susgpio); + susgpio = new GpioCallback("Chip select SUS 2", Direction::OUT, Levels::HIGH, + &gpioCallbacks::spiCsDecoderCallback, gpioComIF); + gpioCookieSus->addGpio(gpioIds::CS_SUS_2, susgpio); + susgpio = new GpioCallback("Chip select SUS 3", Direction::OUT, Levels::HIGH, + &gpioCallbacks::spiCsDecoderCallback, gpioComIF); + gpioCookieSus->addGpio(gpioIds::CS_SUS_3, susgpio); + susgpio = new GpioCallback("Chip select SUS 4", Direction::OUT, Levels::HIGH, + &gpioCallbacks::spiCsDecoderCallback, gpioComIF); + gpioCookieSus->addGpio(gpioIds::CS_SUS_4, susgpio); + susgpio = new GpioCallback("Chip select SUS 5", Direction::OUT, Levels::HIGH, + &gpioCallbacks::spiCsDecoderCallback, gpioComIF); + gpioCookieSus->addGpio(gpioIds::CS_SUS_5, susgpio); + susgpio = new GpioCallback("Chip select SUS 6", Direction::OUT, Levels::HIGH, + &gpioCallbacks::spiCsDecoderCallback, gpioComIF); + gpioCookieSus->addGpio(gpioIds::CS_SUS_6, susgpio); + susgpio = new GpioCallback("Chip select SUS 7", Direction::OUT, Levels::HIGH, + &gpioCallbacks::spiCsDecoderCallback, gpioComIF); + gpioCookieSus->addGpio(gpioIds::CS_SUS_7, susgpio); + susgpio = new GpioCallback("Chip select SUS 8", Direction::OUT, Levels::HIGH, + &gpioCallbacks::spiCsDecoderCallback, gpioComIF); + gpioCookieSus->addGpio(gpioIds::CS_SUS_8, susgpio); + susgpio = new GpioCallback("Chip select SUS 9", Direction::OUT, Levels::HIGH, + &gpioCallbacks::spiCsDecoderCallback, gpioComIF); + gpioCookieSus->addGpio(gpioIds::CS_SUS_9, susgpio); + susgpio = new GpioCallback("Chip select SUS 10", Direction::OUT, Levels::HIGH, + &gpioCallbacks::spiCsDecoderCallback, gpioComIF); + gpioCookieSus->addGpio(gpioIds::CS_SUS_10, susgpio); + susgpio = new GpioCallback("Chip select SUS 11", Direction::OUT, Levels::HIGH, + &gpioCallbacks::spiCsDecoderCallback, gpioComIF); + gpioCookieSus->addGpio(gpioIds::CS_SUS_11, susgpio); - gpioComIF->addGpios(gpioCookieSus); + gpioComIF->addGpios(gpioCookieSus); - SpiCookie* spiCookieSus1 = new SpiCookie(addresses::SUS_1, gpio::NO_GPIO, - std::string(q7s::SPI_DEFAULT_DEV), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE, - SUS::MAX1227_SPI_FREQ); - SpiCookie* spiCookieSus2 = new SpiCookie(addresses::SUS_2, gpio::NO_GPIO, - std::string(q7s::SPI_DEFAULT_DEV), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE, - SUS::MAX1227_SPI_FREQ); - SpiCookie* spiCookieSus3 = new SpiCookie(addresses::SUS_3, gpio::NO_GPIO, - std::string(q7s::SPI_DEFAULT_DEV), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE, - SUS::MAX1227_SPI_FREQ); - SpiCookie* spiCookieSus4 = new SpiCookie(addresses::SUS_4, gpio::NO_GPIO, - std::string(q7s::SPI_DEFAULT_DEV), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE, - SUS::MAX1227_SPI_FREQ); - SpiCookie* spiCookieSus5 = new SpiCookie(addresses::SUS_5, gpio::NO_GPIO, - std::string(q7s::SPI_DEFAULT_DEV), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE, - SUS::MAX1227_SPI_FREQ); - SpiCookie* spiCookieSus6 = new SpiCookie(addresses::SUS_6, gpio::NO_GPIO, - std::string(q7s::SPI_DEFAULT_DEV), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE, - SUS::MAX1227_SPI_FREQ); - SpiCookie* spiCookieSus7 = new SpiCookie(addresses::SUS_7, gpio::NO_GPIO, - std::string(q7s::SPI_DEFAULT_DEV), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE, - SUS::MAX1227_SPI_FREQ); - SpiCookie* spiCookieSus8 = new SpiCookie(addresses::SUS_8, gpio::NO_GPIO, - std::string(q7s::SPI_DEFAULT_DEV), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE, - SUS::MAX1227_SPI_FREQ); - SpiCookie* spiCookieSus9 = new SpiCookie(addresses::SUS_9, gpio::NO_GPIO, - std::string(q7s::SPI_DEFAULT_DEV), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE, - SUS::MAX1227_SPI_FREQ); - SpiCookie* spiCookieSus10 = new SpiCookie(addresses::SUS_10, gpio::NO_GPIO, - std::string(q7s::SPI_DEFAULT_DEV), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE, - SUS::MAX1227_SPI_FREQ); - SpiCookie* spiCookieSus11 = new SpiCookie(addresses::SUS_11, gpio::NO_GPIO, - std::string(q7s::SPI_DEFAULT_DEV), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE, - SUS::MAX1227_SPI_FREQ); - SpiCookie* spiCookieSus12 = new SpiCookie(addresses::SUS_12, gpio::NO_GPIO, - std::string(q7s::SPI_DEFAULT_DEV), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE, - SUS::MAX1227_SPI_FREQ); - SpiCookie* spiCookieSus13 = new SpiCookie(addresses::SUS_13, gpio::NO_GPIO, - std::string(q7s::SPI_DEFAULT_DEV), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE, - SUS::MAX1227_SPI_FREQ); +#if OBSW_ADD_SUN_SENSORS == 1 + SpiCookie* spiCookie = + new SpiCookie(addresses::SUS_0, gpioIds::CS_SUS_0, q7s::SPI_DEFAULT_DEV, SUS::MAX_CMD_SIZE, + spi::DEFAULT_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ); + SusHandler* susHandler0 = new SusHandler(objects::SUS_0, 0, objects::SPI_COM_IF, spiCookie); - new SusHandler(objects::SUS_1, objects::SPI_COM_IF, spiCookieSus1, gpioComIF, - gpioIds::CS_SUS_1); - new SusHandler(objects::SUS_2, objects::SPI_COM_IF, spiCookieSus2, gpioComIF, - gpioIds::CS_SUS_2); - new SusHandler(objects::SUS_3, objects::SPI_COM_IF, spiCookieSus3, gpioComIF, - gpioIds::CS_SUS_3); - new SusHandler(objects::SUS_4, objects::SPI_COM_IF, spiCookieSus4, gpioComIF, - gpioIds::CS_SUS_4); - new SusHandler(objects::SUS_5, objects::SPI_COM_IF, spiCookieSus5, gpioComIF, - gpioIds::CS_SUS_5); - new SusHandler(objects::SUS_6, objects::SPI_COM_IF, spiCookieSus6, gpioComIF, - gpioIds::CS_SUS_6); - new SusHandler(objects::SUS_7, objects::SPI_COM_IF, spiCookieSus7, gpioComIF, - gpioIds::CS_SUS_7); - new SusHandler(objects::SUS_8, objects::SPI_COM_IF, spiCookieSus8, gpioComIF, - gpioIds::CS_SUS_8); - new SusHandler(objects::SUS_9, objects::SPI_COM_IF, spiCookieSus9, gpioComIF, - gpioIds::CS_SUS_9); - new SusHandler(objects::SUS_10, objects::SPI_COM_IF, spiCookieSus10, gpioComIF, - gpioIds::CS_SUS_10); - new SusHandler(objects::SUS_11, objects::SPI_COM_IF, spiCookieSus11, gpioComIF, - gpioIds::CS_SUS_11); - new SusHandler(objects::SUS_12, objects::SPI_COM_IF, spiCookieSus12, gpioComIF, - gpioIds::CS_SUS_12); - new SusHandler(objects::SUS_13, objects::SPI_COM_IF, spiCookieSus13, gpioComIF, - gpioIds::CS_SUS_13); + spiCookie = + new SpiCookie(addresses::SUS_1, gpioIds::CS_SUS_1, q7s::SPI_DEFAULT_DEV, SUS::MAX_CMD_SIZE, + spi::DEFAULT_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ); + SusHandler* susHandler1 = new SusHandler(objects::SUS_1, 1, objects::SPI_COM_IF, spiCookie); + + spiCookie = + new SpiCookie(addresses::SUS_2, gpioIds::CS_SUS_2, q7s::SPI_DEFAULT_DEV, SUS::MAX_CMD_SIZE, + spi::DEFAULT_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ); + SusHandler* susHandler2 = new SusHandler(objects::SUS_2, 2, objects::SPI_COM_IF, spiCookie); + + spiCookie = + new SpiCookie(addresses::SUS_3, gpioIds::CS_SUS_3, std::string(q7s::SPI_DEFAULT_DEV), + SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ); + SusHandler* susHandler3 = new SusHandler(objects::SUS_3, 3, objects::SPI_COM_IF, spiCookie); + + spiCookie = + new SpiCookie(addresses::SUS_4, gpioIds::CS_SUS_4, std::string(q7s::SPI_DEFAULT_DEV), + SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ); + SusHandler* susHandler4 = new SusHandler(objects::SUS_4, 4, objects::SPI_COM_IF, spiCookie); + + spiCookie = + new SpiCookie(addresses::SUS_5, gpioIds::CS_SUS_5, std::string(q7s::SPI_DEFAULT_DEV), + SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ); + SusHandler* susHandler5 = new SusHandler(objects::SUS_5, 5, objects::SPI_COM_IF, spiCookie); + + spiCookie = + new SpiCookie(addresses::SUS_6, gpioIds::CS_SUS_6, q7s::SPI_DEFAULT_DEV, SUS::MAX_CMD_SIZE, + spi::DEFAULT_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ); + SusHandler* susHandler6 = new SusHandler(objects::SUS_6, 6, objects::SPI_COM_IF, spiCookie); + + spiCookie = + new SpiCookie(addresses::SUS_7, gpioIds::CS_SUS_7, q7s::SPI_DEFAULT_DEV, SUS::MAX_CMD_SIZE, + spi::DEFAULT_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ); + SusHandler* susHandler7 = new SusHandler(objects::SUS_7, 7, objects::SPI_COM_IF, spiCookie); + + spiCookie = + new SpiCookie(addresses::SUS_8, gpioIds::CS_SUS_8, q7s::SPI_DEFAULT_DEV, SUS::MAX_CMD_SIZE, + spi::DEFAULT_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ); + SusHandler* susHandler8 = new SusHandler(objects::SUS_8, 8, objects::SPI_COM_IF, spiCookie); + + spiCookie = + new SpiCookie(addresses::SUS_9, gpioIds::CS_SUS_9, q7s::SPI_DEFAULT_DEV, SUS::MAX_CMD_SIZE, + spi::DEFAULT_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ); + SusHandler* susHandler9 = new SusHandler(objects::SUS_9, 9, objects::SPI_COM_IF, spiCookie); + + spiCookie = + new SpiCookie(addresses::SUS_10, gpioIds::CS_SUS_10, q7s::SPI_DEFAULT_DEV, SUS::MAX_CMD_SIZE, + spi::DEFAULT_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ); + SusHandler* susHandler10 = new SusHandler(objects::SUS_10, 10, objects::SPI_COM_IF, spiCookie); + + spiCookie = + new SpiCookie(addresses::SUS_11, gpioIds::CS_SUS_11, q7s::SPI_DEFAULT_DEV, SUS::MAX_CMD_SIZE, + spi::DEFAULT_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ); + SusHandler* susHandler11 = new SusHandler(objects::SUS_11, 11, objects::SPI_COM_IF, spiCookie); + static_cast(susHandler0); + static_cast(susHandler1); + static_cast(susHandler2); + static_cast(susHandler3); + static_cast(susHandler4); + static_cast(susHandler5); + static_cast(susHandler6); + static_cast(susHandler7); + static_cast(susHandler8); + static_cast(susHandler9); + static_cast(susHandler10); + static_cast(susHandler11); +#if OBSW_TEST_SUS == 1 + susHandler0->setStartUpImmediately(); + susHandler1->setStartUpImmediately(); + susHandler2->setStartUpImmediately(); + susHandler3->setStartUpImmediately(); + susHandler4->setStartUpImmediately(); + susHandler5->setStartUpImmediately(); + susHandler6->setStartUpImmediately(); + susHandler7->setStartUpImmediately(); + susHandler8->setStartUpImmediately(); + susHandler9->setStartUpImmediately(); + susHandler10->setStartUpImmediately(); + susHandler11->setStartUpImmediately(); + susHandler0->setToGoToNormalMode(true); + susHandler1->setToGoToNormalMode(true); + susHandler2->setToGoToNormalMode(true); + susHandler3->setToGoToNormalMode(true); + susHandler4->setToGoToNormalMode(true); + susHandler5->setToGoToNormalMode(true); + susHandler6->setToGoToNormalMode(true); + susHandler7->setToGoToNormalMode(true); + susHandler8->setToGoToNormalMode(true); + susHandler9->setToGoToNormalMode(true); + susHandler10->setToGoToNormalMode(true); + susHandler11->setToGoToNormalMode(true); +#if OBSW_DEBUG_SUS == 1 + susHandler0->enablePeriodicPrintout(true, 3); + susHandler1->enablePeriodicPrintout(true, 3); + susHandler2->enablePeriodicPrintout(true, 3); + susHandler3->enablePeriodicPrintout(true, 3); + susHandler4->enablePeriodicPrintout(true, 3); + susHandler5->enablePeriodicPrintout(true, 3); + susHandler6->enablePeriodicPrintout(true, 3); + susHandler7->enablePeriodicPrintout(true, 3); + susHandler8->enablePeriodicPrintout(true, 3); + susHandler9->enablePeriodicPrintout(true, 3); + susHandler10->enablePeriodicPrintout(true, 3); + susHandler11->enablePeriodicPrintout(true, 3); +#endif +#endif + +#endif /* OBSW_ADD_SUN_SENSORS == 1 */ } -void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF *gpioComIF, UartComIF* uartComIF) { - GpioCookie* gpioCookieAcsBoard = new GpioCookie(); - GpiodRegularByLabel* gpio = nullptr; - gpio = new GpiodRegularByLabel(q7s::GPIO_GYRO_ADIS_LABEL, q7s::GPIO_GYRO_0_ADIS_CS, - "CS_GYRO_0_ADIS", gpio::OUT, gpio::HIGH); - gpioCookieAcsBoard->addGpio(gpioIds::GYRO_0_ADIS_CS, gpio); - gpio = new GpiodRegularByLabel(q7s::GPIO_ACS_BOARD_DEFAULT_LABEL, q7s::GPIO_GYRO_1_L3G_CS, - "CS_GYRO_1_L3G", gpio::OUT, gpio::HIGH); - gpioCookieAcsBoard->addGpio(gpioIds::GYRO_1_L3G_CS, gpio); - gpio = new GpiodRegularByLabel(q7s::GPIO_GYRO_ADIS_LABEL, q7s::GPIO_GYRO_2_ADIS_CS, - "CS_GYRO_2_ADIS", gpio::OUT, gpio::HIGH); - gpioCookieAcsBoard->addGpio(gpioIds::GYRO_2_ADIS_CS, gpio); - gpio = new GpiodRegularByLabel(q7s::GPIO_ACS_BOARD_DEFAULT_LABEL, q7s::GPIO_GYRO_3_L3G_CS, - "CS_GYRO_3_L3G", gpio::OUT, gpio::HIGH); - gpioCookieAcsBoard->addGpio(gpioIds::GYRO_3_L3G_CS, gpio); +void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, UartComIF* uartComIF) { + using namespace gpio; + GpioCookie* gpioCookieAcsBoard = new GpioCookie(); - gpio = new GpiodRegularByLabel(q7s::GPIO_ACS_BOARD_DEFAULT_LABEL, q7s::GPIO_MGM_0_LIS3_CS, - "CS_MGM_0_LIS3_A", gpio::OUT, gpio::HIGH); - gpioCookieAcsBoard->addGpio(gpioIds::MGM_0_LIS3_CS, gpio); - gpio = new GpiodRegularByLabel(q7s::GPIO_ACS_BOARD_DEFAULT_LABEL, q7s::GPIO_MGM_1_RM3100_CS, - "CS_MGM_1_RM3100_A", gpio::OUT, gpio::HIGH); - gpioCookieAcsBoard->addGpio(gpioIds::MGM_1_RM3100_CS, gpio); - auto gpioChip = new GpiodRegularByChip(q7s::GPIO_MGM2_LIS3_LABEL, q7s::GPIO_MGM_2_LIS3_CS, - "CS_MGM_2_LIS3_B", gpio::OUT, gpio::HIGH); - gpioCookieAcsBoard->addGpio(gpioIds::MGM_2_LIS3_CS, gpioChip); - gpio = new GpiodRegularByLabel(q7s::GPIO_ACS_BOARD_DEFAULT_LABEL, q7s::GPIO_MGM_3_RM3100_CS, - "CS_MGM_3_RM3100_B", gpio::OUT, gpio::HIGH); - gpioCookieAcsBoard->addGpio(gpioIds::MGM_3_RM3100_CS, gpio); + 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); - // GNSS reset pins are active low - gpio = new GpiodRegularByLabel(q7s::GPIO_ACS_BOARD_DEFAULT_LABEL, q7s::GPIO_RESET_GNSS_0, - "GNSS_0_NRESET", gpio::OUT, gpio::HIGH); - gpioCookieAcsBoard->addGpio(gpioIds::GNSS_0_NRESET, gpio); - gpio = new GpiodRegularByLabel(q7s::GPIO_ACS_BOARD_DEFAULT_LABEL, q7s::GPIO_RESET_GNSS_1, - "GNSS_1_NRESET", gpio::OUT, gpio::HIGH); - gpioCookieAcsBoard->addGpio(gpioIds::GNSS_1_NRESET, 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); - // Enable pins must be pulled low for regular operations - gpio = new GpiodRegularByLabel(q7s::GPIO_FLEX_OBC1F_B0, q7s::GPIO_GYRO_0_ENABLE, - "GYRO_0_ENABLE", gpio::OUT, gpio::LOW); - gpioCookieAcsBoard->addGpio(gpioIds::GYRO_0_ENABLE, gpio); - gpio = new GpiodRegularByLabel(q7s::GPIO_3V3_OBC1C, q7s::GPIO_GYRO_2_ENABLE, - "GYRO_2_ENABLE", gpio::OUT, gpio::LOW); - gpioCookieAcsBoard->addGpio(gpioIds::GYRO_2_ENABLE, 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); - // TODO: Add enable pins for GPS as soon as new interface board design is finished - gpioComIF->addGpios(gpioCookieAcsBoard); + 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); - 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); - mgmLis3Handler->setStartUpImmediately(); -#if FSFW_HAL_LIS3MDL_MGM_DEBUG == 1 - mgmLis3Handler->setToGoToNormalMode(true); + 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); + +#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); +#if OBSW_TEST_ACS == 1 + mgmLis3Handler->setStartUpImmediately(); + mgmLis3Handler->setToGoToNormalMode(true); +#if OBSW_DEBUG_ACS == 1 + mgmLis3Handler->enablePeriodicPrintouts(true, 10); +#endif #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); - mgmRm3100Handler->setStartUpImmediately(); -#if FSFW_HAL_RM3100_MGM_DEBUG == 1 - mgmRm3100Handler->setToGoToNormalMode(true); + 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); +#if OBSW_TEST_ACS == 1 + mgmRm3100Handler->setStartUpImmediately(); + mgmRm3100Handler->setToGoToNormalMode(true); +#if OBSW_DEBUG_ACS == 1 + mgmRm3100Handler->enablePeriodicPrintouts(true, 10); +#endif #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); - auto mgmLis3Handler2 = new MgmLIS3MDLHandler(objects::MGM_2_LIS3_HANDLER, objects::SPI_COM_IF, - spiCookie, spi::LIS3_TRANSITION_DELAY); - mgmLis3Handler2->setStartUpImmediately(); -#if FSFW_HAL_LIS3MDL_MGM_DEBUG == 1 - mgmLis3Handler2->setToGoToNormalMode(true); + 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); + auto mgmLis3Handler2 = new MgmLIS3MDLHandler(objects::MGM_2_LIS3_HANDLER, objects::SPI_COM_IF, + spiCookie, spi::LIS3_TRANSITION_DELAY); +#if OBSW_TEST_ACS == 1 + mgmLis3Handler2->setStartUpImmediately(); + mgmLis3Handler2->setToGoToNormalMode(true); +#if OBSW_DEBUG_ACS == 1 + mgmLis3Handler2->enablePeriodicPrintouts(true, 10); +#endif #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); - mgmRm3100Handler->setStartUpImmediately(); -#if FSFW_HAL_RM3100_MGM_DEBUG == 1 - mgmRm3100Handler->setToGoToNormalMode(true); + 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); +#if OBSW_TEST_ACS == 1 + mgmRm3100Handler->setStartUpImmediately(); + mgmRm3100Handler->setToGoToNormalMode(true); +#if OBSW_DEBUG_ACS == 1 + mgmRm3100Handler->enablePeriodicPrintouts(true, 10); +#endif #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, - ADIS16507::MAXIMUM_REPLY_SIZE, spi::DEFAULT_ADIS16507_MODE, - spi::DEFAULT_ADIS16507_SPEED); - auto adisHandler = new GyroADIS16507Handler(objects::GYRO_0_ADIS_HANDLER, objects::SPI_COM_IF, - spiCookie); - adisHandler->setStartUpImmediately(); - // 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); - gyroL3gHandler->setStartUpImmediately(); -#if FSFW_HAL_L3GD20_GYRO_DEBUG == 1 - gyroL3gHandler->setToGoToNormalMode(true); + // 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); +#if OBSW_TEST_ACS == 1 + adisHandler->setStartUpImmediately(); + adisHandler->setToGoToNormalModeImmediately(); +#if OBSW_DEBUG_ACS == 1 + adisHandler->enablePeriodicPrintouts(true, 10); #endif - // Gyro 2 Side B - spiCookie = new SpiCookie(addresses::GYRO_2_ADIS, gpioIds::GYRO_2_ADIS_CS, spiDev, - ADIS16507::MAXIMUM_REPLY_SIZE, spi::DEFAULT_ADIS16507_MODE, - spi::DEFAULT_ADIS16507_SPEED); - adisHandler = new GyroADIS16507Handler(objects::GYRO_2_ADIS_HANDLER, objects::SPI_COM_IF, - spiCookie); - adisHandler->setStartUpImmediately(); - // 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); - gyroL3gHandler->setStartUpImmediately(); -#if FSFW_HAL_L3GD20_GYRO_DEBUG == 1 - gyroL3gHandler->setToGoToNormalMode(true); #endif - bool debugGps = false; + // 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); +#if OBSW_TEST_ACS == 1 + gyroL3gHandler->setStartUpImmediately(); + gyroL3gHandler->setToGoToNormalMode(true); +#if OBSW_DEBUG_ACS == 1 + gyroL3gHandler->enablePeriodicPrintouts(true, 10); +#endif +#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); +#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); +#if OBSW_TEST_ACS == 1 + gyroL3gHandler->setStartUpImmediately(); + gyroL3gHandler->setToGoToNormalMode(true); +#if OBSW_DEBUG_ACS == 1 + gyroL3gHandler->enablePeriodicPrintouts(true, 10); +#endif +#endif + + bool debugGps = false; #if OBSW_DEBUG_GPS == 1 - debugGps = true; + debugGps = true; #endif - resetArgsGnss1.gnss1 = true; - resetArgsGnss1.gpioComIF = gpioComIF; - resetArgsGnss1.waitPeriodMs = 100; - resetArgsGnss0.gnss1 = false; - resetArgsGnss0.gpioComIF = gpioComIF; - resetArgsGnss0.waitPeriodMs = 100; - auto uartCookieGps0 = new UartCookie(objects::GPS0_HANDLER, q7s::UART_GNSS_0_DEV, - UartModes::CANONICAL, uart::GNSS_BAUD, uart::HYPERION_GPS_REPLY_MAX_BUFFER); - uartCookieGps0->setToFlushInput(true); - uartCookieGps0->setReadCycles(6); - auto uartCookieGps1 = new UartCookie(objects::GPS1_HANDLER, q7s::UART_GNSS_1_DEV, - UartModes::CANONICAL, uart::GNSS_BAUD, uart::HYPERION_GPS_REPLY_MAX_BUFFER); - uartCookieGps1->setToFlushInput(true); - uartCookieGps1->setReadCycles(6); - auto gpsHandler0 = new GPSHyperionHandler(objects::GPS0_HANDLER, objects::UART_COM_IF, - uartCookieGps0, debugGps); - gpsHandler0->setResetPinTriggerFunction(gps::triggerGpioResetPin, &resetArgsGnss0); - gpsHandler0->setStartUpImmediately(); - auto gpsHandler1 = new GPSHyperionHandler(objects::GPS1_HANDLER, objects::UART_COM_IF, - uartCookieGps1, debugGps); - gpsHandler1->setResetPinTriggerFunction(gps::triggerGpioResetPin, &resetArgsGnss1); - gpsHandler1->setStartUpImmediately(); + 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); +#endif /* OBSW_ADD_ACS_HANDLERS == 1 */ } void ObjectFactory::createHeaterComponents() { + using namespace gpio; + GpioCookie* heaterGpiosCookie = new GpioCookie; + GpiodRegularByLineName* gpio = nullptr; - GpioCookie* heaterGpiosCookie = new GpioCookie; + 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-11 on stack connector */ - auto gpioConfigHeater0 = new GpiodRegularByLabel(q7s::GPIO_HEATER_LABEL, q7s::GPIO_HEATER_0_PIN, - "Heater0", gpio::OUT, gpio::LOW); - heaterGpiosCookie->addGpio(gpioIds::HEATER_0, gpioConfigHeater0); - /* Pin H2-12 on stack connector */ - auto gpioConfigHeater1 = new GpiodRegularByLabel(q7s::GPIO_HEATER_LABEL, q7s::GPIO_HEATER_1_PIN, - "Heater1", gpio::OUT, gpio::LOW); - heaterGpiosCookie->addGpio(gpioIds::HEATER_1, gpioConfigHeater1); + /* 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); - /* Pin H2-13 on stack connector */ - auto gpioConfigHeater2 = new GpiodRegularByLabel(q7s::GPIO_HEATER_LABEL, q7s::GPIO_HEATER_2_PIN, - "Heater2", gpio::OUT, gpio::LOW); - heaterGpiosCookie->addGpio(gpioIds::HEATER_2, gpioConfigHeater2); + gpio = new GpiodRegularByLineName(q7s::gpioNames::HEATER_3, consumer.str(), Direction::OUT, + Levels::LOW); + heaterGpiosCookie->addGpio(gpioIds::HEATER_3, gpio); - auto gpioConfigHeater3 = new GpiodRegularByLabel(q7s::GPIO_HEATER_LABEL, q7s::GPIO_HEATER_3_PIN, - "Heater3", gpio::OUT, gpio::LOW); - heaterGpiosCookie->addGpio(gpioIds::HEATER_3, gpioConfigHeater3); + gpio = new GpiodRegularByLineName(q7s::gpioNames::HEATER_4, consumer.str(), Direction::OUT, + Levels::LOW); + heaterGpiosCookie->addGpio(gpioIds::HEATER_4, gpio); - auto gpioConfigHeater4 = new GpiodRegularByLabel(q7s::GPIO_HEATER_LABEL, q7s::GPIO_HEATER_4_PIN, - "Heater4", gpio::OUT, gpio::LOW); - heaterGpiosCookie->addGpio(gpioIds::HEATER_4, gpioConfigHeater4); + gpio = new GpiodRegularByLineName(q7s::gpioNames::HEATER_5, consumer.str(), Direction::OUT, + Levels::LOW); + heaterGpiosCookie->addGpio(gpioIds::HEATER_5, gpio); - auto gpioConfigHeater5 = new GpiodRegularByLabel(q7s::GPIO_HEATER_LABEL, q7s::GPIO_HEATER_5_PIN, - "Heater5", gpio::OUT, gpio::LOW); - heaterGpiosCookie->addGpio(gpioIds::HEATER_5, gpioConfigHeater5); + gpio = new GpiodRegularByLineName(q7s::gpioNames::HEATER_6, consumer.str(), Direction::OUT, + Levels::LOW); + heaterGpiosCookie->addGpio(gpioIds::HEATER_6, gpio); - auto gpioConfigHeater6 = new GpiodRegularByLabel(q7s::GPIO_HEATER_LABEL, q7s::GPIO_HEATER_6_PIN, - "Heater6", gpio::OUT, gpio::LOW); - heaterGpiosCookie->addGpio(gpioIds::HEATER_6, gpioConfigHeater6); + gpio = new GpiodRegularByLineName(q7s::gpioNames::HEATER_7, consumer.str(), Direction::OUT, + Levels::LOW); + heaterGpiosCookie->addGpio(gpioIds::HEATER_7, gpio); - auto gpioConfigHeater7 = new GpiodRegularByLabel(q7s::GPIO_HEATER_LABEL, q7s::GPIO_HEATER_7_PIN, - "Heater7", gpio::OUT, gpio::LOW); - heaterGpiosCookie->addGpio(gpioIds::HEATER_7, gpioConfigHeater7); - - new HeaterHandler(objects::HEATER_HANDLER, objects::GPIO_IF, heaterGpiosCookie, - objects::PCDU_HANDLER, pcduSwitches::TCS_BOARD_8V_HEATER_IN); + new HeaterHandler(objects::HEATER_HANDLER, objects::GPIO_IF, heaterGpiosCookie, + objects::PCDU_HANDLER, pcduSwitches::TCS_BOARD_8V_HEATER_IN); } void ObjectFactory::createSolarArrayDeploymentComponents() { - GpioCookie* solarArrayDeplCookie = new GpioCookie; + using namespace gpio; + GpioCookie* solarArrayDeplCookie = new GpioCookie; + GpiodRegularByLineName* gpio = nullptr; - auto gpioConfigDeplSA0 = new GpiodRegularByLabel(q7s::GPIO_SOLAR_ARR_DEPL_LABEL, - q7s::GPIO_SOL_DEPL_SA_0_PIN, "DeplSA0", gpio::OUT, gpio::LOW); - solarArrayDeplCookie->addGpio(gpioIds::DEPLSA1, gpioConfigDeplSA0); - auto gpioConfigDeplSA1 = new GpiodRegularByLabel(q7s::GPIO_SOLAR_ARR_DEPL_LABEL, - q7s::GPIO_SOL_DEPL_SA_1_PIN, "DeplSA1", gpio::OUT, gpio::LOW); - solarArrayDeplCookie->addGpio(gpioIds::DEPLSA2, gpioConfigDeplSA1); + 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, pcduSwitches::DEPLOYMENT_MECHANISM, - gpioIds::DEPLSA1, gpioIds::DEPLSA2, 1000); + // 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, + pcduSwitches::DEPLOYMENT_MECHANISM, gpioIds::DEPLSA1, + gpioIds::DEPLSA2, 1000); } void ObjectFactory::createSyrlinksComponents() { - UartCookie* syrlinksUartCookie = new UartCookie(objects::SYRLINKS_HK_HANDLER, - q7s::UART_SYRLINKS_DEV, UartModes::NON_CANONICAL, uart::SYRLINKS_BAUD, - SYRLINKS::MAX_REPLY_SIZE); - syrlinksUartCookie->setParityEven(); + UartCookie* syrlinksUartCookie = + new UartCookie(objects::SYRLINKS_HK_HANDLER, q7s::UART_SYRLINKS_DEV, UartModes::NON_CANONICAL, + uart::SYRLINKS_BAUD, SYRLINKS::MAX_REPLY_SIZE); + syrlinksUartCookie->setParityEven(); - new SyrlinksHkHandler(objects::SYRLINKS_HK_HANDLER, objects::UART_COM_IF, syrlinksUartCookie); + new SyrlinksHkHandler(objects::SYRLINKS_HK_HANDLER, objects::UART_COM_IF, syrlinksUartCookie); } -void ObjectFactory::createRtdComponents(LinuxLibgpioIF *gpioComIF) { - GpioCookie* rtdGpioCookie = new GpioCookie; +void ObjectFactory::createRtdComponents(LinuxLibgpioIF* gpioComIF) { + using namespace gpio; + GpioCookie* rtdGpioCookie = new GpioCookie; - GpioCallback* gpioRtdIc3 = new GpioCallback("Chip select RTD IC3", gpio::OUT, gpio::HIGH, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - rtdGpioCookie->addGpio(gpioIds::RTD_IC3, gpioRtdIc3); - GpioCallback* gpioRtdIc4 = new GpioCallback("Chip select RTD IC4", gpio::OUT, gpio::HIGH, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - rtdGpioCookie->addGpio(gpioIds::RTD_IC4, gpioRtdIc4); - GpioCallback* gpioRtdIc5 = new GpioCallback("Chip select RTD IC5", gpio::OUT, gpio::HIGH, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - rtdGpioCookie->addGpio(gpioIds::RTD_IC5, gpioRtdIc5); - GpioCallback* gpioRtdIc6 = new GpioCallback("Chip select RTD IC6", gpio::OUT, gpio::HIGH, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - rtdGpioCookie->addGpio(gpioIds::RTD_IC6, gpioRtdIc6); - GpioCallback* gpioRtdIc7 = new GpioCallback("Chip select RTD IC7", gpio::OUT, gpio::HIGH, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - rtdGpioCookie->addGpio(gpioIds::RTD_IC7, gpioRtdIc7); - GpioCallback* gpioRtdIc8 = new GpioCallback("Chip select RTD IC8", gpio::OUT, gpio::HIGH, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - rtdGpioCookie->addGpio(gpioIds::RTD_IC8, gpioRtdIc8); - GpioCallback* gpioRtdIc9 = new GpioCallback("Chip select RTD IC9", gpio::OUT, gpio::HIGH, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - rtdGpioCookie->addGpio(gpioIds::RTD_IC9, gpioRtdIc9); - GpioCallback* gpioRtdIc10 = new GpioCallback("Chip select RTD IC10", gpio::OUT, gpio::HIGH, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - rtdGpioCookie->addGpio(gpioIds::RTD_IC10, gpioRtdIc10); - GpioCallback* gpioRtdIc11 = new GpioCallback("Chip select RTD IC11", gpio::OUT, gpio::HIGH, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - rtdGpioCookie->addGpio(gpioIds::RTD_IC11, gpioRtdIc11); - GpioCallback* gpioRtdIc12 = new GpioCallback("Chip select RTD IC12", gpio::OUT, gpio::HIGH, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - rtdGpioCookie->addGpio(gpioIds::RTD_IC12, gpioRtdIc12); - GpioCallback* gpioRtdIc13 = new GpioCallback("Chip select RTD IC13", gpio::OUT, gpio::HIGH, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - rtdGpioCookie->addGpio(gpioIds::RTD_IC13, gpioRtdIc13); - GpioCallback* gpioRtdIc14 = new GpioCallback("Chip select RTD IC14", gpio::OUT, gpio::HIGH, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - rtdGpioCookie->addGpio(gpioIds::RTD_IC14, gpioRtdIc14); - GpioCallback* gpioRtdIc15 = new GpioCallback("Chip select RTD IC15", gpio::OUT, gpio::HIGH, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - rtdGpioCookie->addGpio(gpioIds::RTD_IC15, gpioRtdIc15); - GpioCallback* gpioRtdIc16 = new GpioCallback("Chip select RTD IC16", gpio::OUT, gpio::HIGH, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - rtdGpioCookie->addGpio(gpioIds::RTD_IC16, gpioRtdIc16); - GpioCallback* gpioRtdIc17 = new GpioCallback("Chip select RTD IC17", gpio::OUT, gpio::HIGH, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - rtdGpioCookie->addGpio(gpioIds::RTD_IC17, gpioRtdIc17); - GpioCallback* gpioRtdIc18 = new GpioCallback("Chip select RTD IC18", gpio::OUT, gpio::HIGH, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - rtdGpioCookie->addGpio(gpioIds::RTD_IC18, gpioRtdIc18); + GpioCallback* gpioRtdIc0 = new GpioCallback("Chip select RTD IC0", Direction::OUT, Levels::HIGH, + &gpioCallbacks::spiCsDecoderCallback, gpioComIF); + rtdGpioCookie->addGpio(gpioIds::RTD_IC_3, gpioRtdIc0); + GpioCallback* gpioRtdIc1 = new GpioCallback("Chip select RTD IC1", Direction::OUT, Levels::HIGH, + &gpioCallbacks::spiCsDecoderCallback, gpioComIF); + rtdGpioCookie->addGpio(gpioIds::RTD_IC_4, gpioRtdIc1); + GpioCallback* gpioRtdIc2 = new GpioCallback("Chip select RTD IC2", Direction::OUT, Levels::HIGH, + &gpioCallbacks::spiCsDecoderCallback, gpioComIF); + rtdGpioCookie->addGpio(gpioIds::RTD_IC_5, gpioRtdIc2); + GpioCallback* gpioRtdIc3 = new GpioCallback("Chip select RTD IC3", Direction::OUT, Levels::HIGH, + &gpioCallbacks::spiCsDecoderCallback, gpioComIF); + rtdGpioCookie->addGpio(gpioIds::RTD_IC_6, gpioRtdIc3); + GpioCallback* gpioRtdIc4 = new GpioCallback("Chip select RTD IC4", Direction::OUT, Levels::HIGH, + &gpioCallbacks::spiCsDecoderCallback, gpioComIF); + rtdGpioCookie->addGpio(gpioIds::RTD_IC_7, gpioRtdIc4); + GpioCallback* gpioRtdIc5 = new GpioCallback("Chip select RTD IC5", Direction::OUT, Levels::HIGH, + &gpioCallbacks::spiCsDecoderCallback, gpioComIF); + rtdGpioCookie->addGpio(gpioIds::RTD_IC_8, gpioRtdIc5); + GpioCallback* gpioRtdIc6 = new GpioCallback("Chip select RTD IC6", Direction::OUT, Levels::HIGH, + &gpioCallbacks::spiCsDecoderCallback, gpioComIF); + rtdGpioCookie->addGpio(gpioIds::RTD_IC_9, gpioRtdIc6); + GpioCallback* gpioRtdIc7 = new GpioCallback("Chip select RTD IC7", Direction::OUT, Levels::HIGH, + &gpioCallbacks::spiCsDecoderCallback, gpioComIF); + rtdGpioCookie->addGpio(gpioIds::RTD_IC_10, gpioRtdIc7); + GpioCallback* gpioRtdIc8 = new GpioCallback("Chip select RTD IC8", Direction::OUT, Levels::HIGH, + &gpioCallbacks::spiCsDecoderCallback, gpioComIF); + rtdGpioCookie->addGpio(gpioIds::RTD_IC_11, gpioRtdIc8); + GpioCallback* gpioRtdIc9 = new GpioCallback("Chip select RTD IC9", Direction::OUT, Levels::HIGH, + &gpioCallbacks::spiCsDecoderCallback, gpioComIF); + rtdGpioCookie->addGpio(gpioIds::RTD_IC_12, gpioRtdIc9); + GpioCallback* gpioRtdIc10 = new GpioCallback("Chip select RTD IC10", Direction::OUT, Levels::HIGH, + &gpioCallbacks::spiCsDecoderCallback, gpioComIF); + rtdGpioCookie->addGpio(gpioIds::RTD_IC_13, gpioRtdIc10); + GpioCallback* gpioRtdIc11 = new GpioCallback("Chip select RTD IC11", Direction::OUT, Levels::HIGH, + &gpioCallbacks::spiCsDecoderCallback, gpioComIF); + rtdGpioCookie->addGpio(gpioIds::RTD_IC_14, gpioRtdIc11); + GpioCallback* gpioRtdIc12 = new GpioCallback("Chip select RTD IC12", Direction::OUT, Levels::HIGH, + &gpioCallbacks::spiCsDecoderCallback, gpioComIF); + rtdGpioCookie->addGpio(gpioIds::RTD_IC_15, gpioRtdIc12); + GpioCallback* gpioRtdIc13 = new GpioCallback("Chip select RTD IC13", Direction::OUT, Levels::HIGH, + &gpioCallbacks::spiCsDecoderCallback, gpioComIF); + rtdGpioCookie->addGpio(gpioIds::RTD_IC_16, gpioRtdIc13); + GpioCallback* gpioRtdIc14 = new GpioCallback("Chip select RTD IC14", Direction::OUT, Levels::HIGH, + &gpioCallbacks::spiCsDecoderCallback, gpioComIF); + rtdGpioCookie->addGpio(gpioIds::RTD_IC_17, gpioRtdIc14); + GpioCallback* gpioRtdIc15 = new GpioCallback("Chip select RTD IC15", Direction::OUT, Levels::HIGH, + &gpioCallbacks::spiCsDecoderCallback, gpioComIF); + rtdGpioCookie->addGpio(gpioIds::RTD_IC_18, gpioRtdIc15); - gpioComIF->addGpios(rtdGpioCookie); + gpioComIF->addGpios(rtdGpioCookie); - SpiCookie* spiRtdIc3 = new SpiCookie(addresses::RTD_IC3, gpioIds::RTD_IC3, q7s::SPI_DEFAULT_DEV, - Max31865Definitions::MAX_REPLY_SIZE, spi::SpiModes::MODE_1, spi::RTD_SPEED); - SpiCookie* spiRtdIc4 = new SpiCookie(addresses::RTD_IC4, gpioIds::RTD_IC4, q7s::SPI_DEFAULT_DEV, - Max31865Definitions::MAX_REPLY_SIZE, spi::SpiModes::MODE_1, spi::RTD_SPEED); - SpiCookie* spiRtdIc5 = new SpiCookie(addresses::RTD_IC5, gpioIds::RTD_IC5, q7s::SPI_DEFAULT_DEV, - Max31865Definitions::MAX_REPLY_SIZE, spi::SpiModes::MODE_1, spi::RTD_SPEED); - SpiCookie* spiRtdIc6 = new SpiCookie(addresses::RTD_IC6, gpioIds::RTD_IC6, q7s::SPI_DEFAULT_DEV, - Max31865Definitions::MAX_REPLY_SIZE, spi::SpiModes::MODE_1, spi::RTD_SPEED); - SpiCookie* spiRtdIc7 = new SpiCookie(addresses::RTD_IC7, gpioIds::RTD_IC7, q7s::SPI_DEFAULT_DEV, - Max31865Definitions::MAX_REPLY_SIZE, spi::SpiModes::MODE_1, spi::RTD_SPEED); - SpiCookie* spiRtdIc8 = new SpiCookie(addresses::RTD_IC8, gpioIds::RTD_IC8, q7s::SPI_DEFAULT_DEV, - Max31865Definitions::MAX_REPLY_SIZE, spi::SpiModes::MODE_1, spi::RTD_SPEED); - SpiCookie* spiRtdIc9 = new SpiCookie(addresses::RTD_IC9, gpioIds::RTD_IC9, q7s::SPI_DEFAULT_DEV, - Max31865Definitions::MAX_REPLY_SIZE, spi::SpiModes::MODE_1, spi::RTD_SPEED); - SpiCookie* spiRtdIc10 = new SpiCookie(addresses::RTD_IC10, gpioIds::RTD_IC10, - q7s::SPI_DEFAULT_DEV, Max31865Definitions::MAX_REPLY_SIZE, spi::SpiModes::MODE_1, - spi::RTD_SPEED); - SpiCookie* spiRtdIc11 = new SpiCookie(addresses::RTD_IC11, gpioIds::RTD_IC11, - q7s::SPI_DEFAULT_DEV, Max31865Definitions::MAX_REPLY_SIZE, spi::SpiModes::MODE_1, - spi::RTD_SPEED); - SpiCookie* spiRtdIc12 = new SpiCookie(addresses::RTD_IC12, gpioIds::RTD_IC12, - q7s::SPI_DEFAULT_DEV, Max31865Definitions::MAX_REPLY_SIZE, spi::SpiModes::MODE_1, - spi::RTD_SPEED); - SpiCookie* spiRtdIc13 = new SpiCookie(addresses::RTD_IC13, gpioIds::RTD_IC13, - q7s::SPI_DEFAULT_DEV, Max31865Definitions::MAX_REPLY_SIZE, spi::SpiModes::MODE_1, - spi::RTD_SPEED); - SpiCookie* spiRtdIc14 = new SpiCookie(addresses::RTD_IC14, gpioIds::RTD_IC14, - q7s::SPI_DEFAULT_DEV, Max31865Definitions::MAX_REPLY_SIZE, spi::SpiModes::MODE_1, - spi::RTD_SPEED); - SpiCookie* spiRtdIc15 = new SpiCookie(addresses::RTD_IC15, gpioIds::RTD_IC15, - q7s::SPI_DEFAULT_DEV, Max31865Definitions::MAX_REPLY_SIZE, spi::SpiModes::MODE_1, - spi::RTD_SPEED); - SpiCookie* spiRtdIc16 = new SpiCookie(addresses::RTD_IC16, gpioIds::RTD_IC16, - std::string(q7s::SPI_DEFAULT_DEV), Max31865Definitions::MAX_REPLY_SIZE, - spi::SpiModes::MODE_1, spi::RTD_SPEED); - SpiCookie* spiRtdIc17 = new SpiCookie(addresses::RTD_IC17, gpioIds::RTD_IC17, - q7s::SPI_DEFAULT_DEV, Max31865Definitions::MAX_REPLY_SIZE, spi::SpiModes::MODE_1, - spi::RTD_SPEED); - SpiCookie* spiRtdIc18 = new SpiCookie(addresses::RTD_IC18, gpioIds::RTD_IC18, - q7s::SPI_DEFAULT_DEV, Max31865Definitions::MAX_REPLY_SIZE, spi::SpiModes::MODE_1, - spi::RTD_SPEED); +#if OBSW_ADD_RTD_DEVICES == 1 + SpiCookie* spiRtdIc0 = + new SpiCookie(addresses::RTD_IC_3, gpioIds::RTD_IC_3, q7s::SPI_DEFAULT_DEV, + Max31865Definitions::MAX_REPLY_SIZE, spi::RTD_MODE, spi::RTD_SPEED); + SpiCookie* spiRtdIc1 = + new SpiCookie(addresses::RTD_IC_4, gpioIds::RTD_IC_4, q7s::SPI_DEFAULT_DEV, + Max31865Definitions::MAX_REPLY_SIZE, spi::RTD_MODE, spi::RTD_SPEED); + SpiCookie* spiRtdIc2 = + new SpiCookie(addresses::RTD_IC_5, gpioIds::RTD_IC_5, q7s::SPI_DEFAULT_DEV, + Max31865Definitions::MAX_REPLY_SIZE, spi::RTD_MODE, spi::RTD_SPEED); + SpiCookie* spiRtdIc3 = + new SpiCookie(addresses::RTD_IC_6, gpioIds::RTD_IC_6, q7s::SPI_DEFAULT_DEV, + Max31865Definitions::MAX_REPLY_SIZE, spi::RTD_MODE, spi::RTD_SPEED); + SpiCookie* spiRtdIc4 = + new SpiCookie(addresses::RTD_IC_7, gpioIds::RTD_IC_7, q7s::SPI_DEFAULT_DEV, + Max31865Definitions::MAX_REPLY_SIZE, spi::RTD_MODE, spi::RTD_SPEED); + SpiCookie* spiRtdIc5 = + new SpiCookie(addresses::RTD_IC_8, gpioIds::RTD_IC_8, q7s::SPI_DEFAULT_DEV, + Max31865Definitions::MAX_REPLY_SIZE, spi::RTD_MODE, spi::RTD_SPEED); + SpiCookie* spiRtdIc6 = + new SpiCookie(addresses::RTD_IC_9, gpioIds::RTD_IC_9, q7s::SPI_DEFAULT_DEV, + Max31865Definitions::MAX_REPLY_SIZE, spi::RTD_MODE, spi::RTD_SPEED); + SpiCookie* spiRtdIc7 = + new SpiCookie(addresses::RTD_IC_10, gpioIds::RTD_IC_10, q7s::SPI_DEFAULT_DEV, + Max31865Definitions::MAX_REPLY_SIZE, spi::RTD_MODE, spi::RTD_SPEED); + SpiCookie* spiRtdIc8 = + new SpiCookie(addresses::RTD_IC_11, gpioIds::RTD_IC_11, q7s::SPI_DEFAULT_DEV, + Max31865Definitions::MAX_REPLY_SIZE, spi::RTD_MODE, spi::RTD_SPEED); + SpiCookie* spiRtdIc9 = + new SpiCookie(addresses::RTD_IC_12, gpioIds::RTD_IC_12, q7s::SPI_DEFAULT_DEV, + Max31865Definitions::MAX_REPLY_SIZE, spi::RTD_MODE, spi::RTD_SPEED); + SpiCookie* spiRtdIc10 = + new SpiCookie(addresses::RTD_IC_13, gpioIds::RTD_IC_13, q7s::SPI_DEFAULT_DEV, + Max31865Definitions::MAX_REPLY_SIZE, spi::RTD_MODE, spi::RTD_SPEED); + SpiCookie* spiRtdIc11 = + new SpiCookie(addresses::RTD_IC_14, gpioIds::RTD_IC_14, q7s::SPI_DEFAULT_DEV, + Max31865Definitions::MAX_REPLY_SIZE, spi::RTD_MODE, spi::RTD_SPEED); + SpiCookie* spiRtdIc12 = + new SpiCookie(addresses::RTD_IC_15, gpioIds::RTD_IC_15, q7s::SPI_DEFAULT_DEV, + Max31865Definitions::MAX_REPLY_SIZE, spi::RTD_MODE, spi::RTD_SPEED); + SpiCookie* spiRtdIc13 = + new SpiCookie(addresses::RTD_IC_16, gpioIds::RTD_IC_16, std::string(q7s::SPI_DEFAULT_DEV), + Max31865Definitions::MAX_REPLY_SIZE, spi::RTD_MODE, spi::RTD_SPEED); + SpiCookie* spiRtdIc14 = + new SpiCookie(addresses::RTD_IC_17, gpioIds::RTD_IC_17, q7s::SPI_DEFAULT_DEV, + Max31865Definitions::MAX_REPLY_SIZE, spi::RTD_MODE, spi::RTD_SPEED); + SpiCookie* spiRtdIc15 = + new SpiCookie(addresses::RTD_IC_18, gpioIds::RTD_IC_18, q7s::SPI_DEFAULT_DEV, + Max31865Definitions::MAX_REPLY_SIZE, spi::RTD_MODE, spi::RTD_SPEED); - Max31865PT1000Handler* rtdIc3 = new Max31865PT1000Handler(objects::RTD_IC3, objects::SPI_COM_IF, - spiRtdIc3, 0); // 0 is switchId - Max31865PT1000Handler* rtdIc4 = new Max31865PT1000Handler(objects::RTD_IC4, objects::SPI_COM_IF, - spiRtdIc4, 0); - Max31865PT1000Handler* rtdIc5 = new Max31865PT1000Handler(objects::RTD_IC5, objects::SPI_COM_IF, - spiRtdIc5, 0); - Max31865PT1000Handler* rtdIc6 = new Max31865PT1000Handler(objects::RTD_IC6, objects::SPI_COM_IF, - spiRtdIc6, 0); - Max31865PT1000Handler* rtdIc7 = new Max31865PT1000Handler(objects::RTD_IC7, objects::SPI_COM_IF, - spiRtdIc7, 0); - Max31865PT1000Handler* rtdIc8 = new Max31865PT1000Handler(objects::RTD_IC8, objects::SPI_COM_IF, - spiRtdIc8, 0); - Max31865PT1000Handler* rtdIc9 = new Max31865PT1000Handler(objects::RTD_IC9, objects::SPI_COM_IF, - spiRtdIc9, 0); - Max31865PT1000Handler* rtdIc10 = new Max31865PT1000Handler(objects::RTD_IC10, - objects::SPI_COM_IF, spiRtdIc10, 0); - Max31865PT1000Handler* rtdIc11 = new Max31865PT1000Handler(objects::RTD_IC11, - objects::SPI_COM_IF, spiRtdIc11, 0); - Max31865PT1000Handler* rtdIc12 = new Max31865PT1000Handler(objects::RTD_IC12, - objects::SPI_COM_IF, spiRtdIc12, 0); - Max31865PT1000Handler* rtdIc13 = new Max31865PT1000Handler(objects::RTD_IC13, - objects::SPI_COM_IF, spiRtdIc13, 0); - Max31865PT1000Handler* rtdIc14 = new Max31865PT1000Handler(objects::RTD_IC14, - objects::SPI_COM_IF, spiRtdIc14, 0); - Max31865PT1000Handler* rtdIc15 = new Max31865PT1000Handler(objects::RTD_IC15, - objects::SPI_COM_IF, spiRtdIc15, 0); - Max31865PT1000Handler* rtdIc16 = new Max31865PT1000Handler(objects::RTD_IC16, - objects::SPI_COM_IF, spiRtdIc16, 0); - Max31865PT1000Handler* rtdIc17 = new Max31865PT1000Handler(objects::RTD_IC17, - objects::SPI_COM_IF, spiRtdIc17, 0); - Max31865PT1000Handler* rtdIc18 = new Max31865PT1000Handler(objects::RTD_IC18, - objects::SPI_COM_IF, spiRtdIc18, 0); + Max31865PT1000Handler* rtdIc0 = + new Max31865PT1000Handler(objects::RTD_IC_3, objects::SPI_COM_IF, spiRtdIc0); + Max31865PT1000Handler* rtdIc1 = + new Max31865PT1000Handler(objects::RTD_IC_4, objects::SPI_COM_IF, spiRtdIc1); + Max31865PT1000Handler* rtdIc2 = + new Max31865PT1000Handler(objects::RTD_IC_5, objects::SPI_COM_IF, spiRtdIc2); + Max31865PT1000Handler* rtdIc3 = + new Max31865PT1000Handler(objects::RTD_IC_6, objects::SPI_COM_IF, spiRtdIc3); + Max31865PT1000Handler* rtdIc4 = + new Max31865PT1000Handler(objects::RTD_IC_7, objects::SPI_COM_IF, spiRtdIc4); + Max31865PT1000Handler* rtdIc5 = + new Max31865PT1000Handler(objects::RTD_IC_8, objects::SPI_COM_IF, spiRtdIc5); + Max31865PT1000Handler* rtdIc6 = + new Max31865PT1000Handler(objects::RTD_IC_9, objects::SPI_COM_IF, spiRtdIc6); + Max31865PT1000Handler* rtdIc7 = + new Max31865PT1000Handler(objects::RTD_IC_10, objects::SPI_COM_IF, spiRtdIc7); + Max31865PT1000Handler* rtdIc8 = + new Max31865PT1000Handler(objects::RTD_IC_11, objects::SPI_COM_IF, spiRtdIc8); + Max31865PT1000Handler* rtdIc9 = + new Max31865PT1000Handler(objects::RTD_IC_12, objects::SPI_COM_IF, spiRtdIc9); + Max31865PT1000Handler* rtdIc10 = + new Max31865PT1000Handler(objects::RTD_IC_13, objects::SPI_COM_IF, spiRtdIc10); + Max31865PT1000Handler* rtdIc11 = + new Max31865PT1000Handler(objects::RTD_IC_14, objects::SPI_COM_IF, spiRtdIc11); + Max31865PT1000Handler* rtdIc12 = + new Max31865PT1000Handler(objects::RTD_IC_15, objects::SPI_COM_IF, spiRtdIc12); + Max31865PT1000Handler* rtdIc13 = + new Max31865PT1000Handler(objects::RTD_IC_16, objects::SPI_COM_IF, spiRtdIc13); + Max31865PT1000Handler* rtdIc14 = + new Max31865PT1000Handler(objects::RTD_IC_17, objects::SPI_COM_IF, spiRtdIc14); + Max31865PT1000Handler* rtdIc15 = + new Max31865PT1000Handler(objects::RTD_IC_18, objects::SPI_COM_IF, spiRtdIc15); - (void) rtdIc3; - (void) rtdIc4; - (void) rtdIc5; - (void) rtdIc6; - (void) rtdIc7; - (void) rtdIc8; - (void) rtdIc9; - (void) rtdIc10; - (void) rtdIc11; - (void) rtdIc12; - (void) rtdIc13; - (void) rtdIc14; - (void) rtdIc15; - (void) rtdIc16; - (void) rtdIc17; - (void) rtdIc18; +#if OBSW_TEST_RTD == 1 + rtdIc0->setStartUpImmediately(); + rtdIc1->setStartUpImmediately(); + rtdIc2->setStartUpImmediately(); + rtdIc3->setStartUpImmediately(); + rtdIc4->setStartUpImmediately(); + rtdIc5->setStartUpImmediately(); + rtdIc6->setStartUpImmediately(); + rtdIc7->setStartUpImmediately(); + rtdIc8->setStartUpImmediately(); + rtdIc9->setStartUpImmediately(); + rtdIc10->setStartUpImmediately(); + rtdIc11->setStartUpImmediately(); + rtdIc12->setStartUpImmediately(); + rtdIc13->setStartUpImmediately(); + rtdIc14->setStartUpImmediately(); + rtdIc15->setStartUpImmediately(); + + rtdIc0->setInstantNormal(true); + rtdIc1->setInstantNormal(true); + rtdIc2->setInstantNormal(true); + rtdIc3->setInstantNormal(true); + rtdIc4->setInstantNormal(true); + rtdIc5->setInstantNormal(true); + rtdIc6->setInstantNormal(true); + rtdIc7->setInstantNormal(true); + rtdIc8->setInstantNormal(true); + rtdIc9->setInstantNormal(true); + rtdIc10->setInstantNormal(true); + rtdIc11->setInstantNormal(true); + rtdIc12->setInstantNormal(true); + rtdIc13->setInstantNormal(true); + rtdIc14->setInstantNormal(true); + rtdIc15->setInstantNormal(true); +#endif + + static_cast(rtdIc0); + static_cast(rtdIc1); + static_cast(rtdIc2); + static_cast(rtdIc3); + static_cast(rtdIc4); + static_cast(rtdIc5); + static_cast(rtdIc6); + static_cast(rtdIc7); + static_cast(rtdIc8); + static_cast(rtdIc9); + static_cast(rtdIc10); + static_cast(rtdIc11); + static_cast(rtdIc12); + static_cast(rtdIc13); + static_cast(rtdIc14); + static_cast(rtdIc15); +#endif } void ObjectFactory::createReactionWheelComponents(LinuxLibgpioIF* gpioComIF) { - GpioCookie* gpioCookieRw = new GpioCookie; - GpioCallback* csRw1 = new GpioCallback("Chip select reaction wheel 1", gpio::OUT, gpio::HIGH, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - gpioCookieRw->addGpio(gpioIds::CS_RW1, csRw1); - GpioCallback* csRw2 = new GpioCallback("Chip select reaction wheel 2", gpio::OUT, gpio::HIGH, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - gpioCookieRw->addGpio(gpioIds::CS_RW2, csRw2); - GpioCallback* csRw3 = new GpioCallback("Chip select reaction wheel 3", gpio::OUT, gpio::HIGH, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - gpioCookieRw->addGpio(gpioIds::CS_RW3, csRw3); - GpioCallback* csRw4 = new GpioCallback("Chip select reaction wheel 4", gpio::OUT, gpio::HIGH, - &gpioCallbacks::spiCsDecoderCallback, gpioComIF); - gpioCookieRw->addGpio(gpioIds::CS_RW4, csRw4); + 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); - auto enRw1 = new GpiodRegularByLabel(q7s::GPIO_RW_DEFAULT_LABEL, q7s::GPIO_RW_0_CS, - "Enable reaction wheel 1", gpio::OUT, gpio::LOW); - gpioCookieRw->addGpio(gpioIds::EN_RW1, enRw1); - auto enRw2 = new GpiodRegularByLabel(q7s::GPIO_RW_DEFAULT_LABEL, q7s::GPIO_RW_1_CS, - "Enable reaction wheel 2", gpio::OUT, gpio::LOW); - gpioCookieRw->addGpio(gpioIds::EN_RW2, enRw2); - auto enRw3 = new GpiodRegularByLabel(q7s::GPIO_RW_DEFAULT_LABEL, q7s::GPIO_RW_2_CS, - "Enable reaction wheel 3", gpio::OUT, gpio::LOW); - gpioCookieRw->addGpio(gpioIds::EN_RW3, enRw3); - auto enRw4 = new GpiodRegularByLabel(q7s::GPIO_RW_DEFAULT_LABEL, q7s::GPIO_RW_3_CS, - "Enable reaction wheel 4", gpio::OUT, gpio::LOW); - gpioCookieRw->addGpio(gpioIds::EN_RW4, enRw4); + 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); - /** - * This GPIO is only internally connected to the SPI MUX module and responsible to disconnect - * the PS SPI peripheral from the SPI interface and route out the SPI lines of the AXI SPI core. - * Per default the PS SPI is selected (EMIO = 0). - */ - auto spiMux = new GpiodRegularByLabel(q7s::GPIO_RW_SPI_MUX_LABEL, - q7s::GPIO_RW_SPI_MUX_CS, "EMIO 0 SPI Mux", gpio::OUT, gpio::LOW); - gpioCookieRw->addGpio(gpioIds::SPI_MUX, spiMux); + gpioComIF->addGpios(gpioCookieRw); - 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 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); + auto rwHandler1 = + new RwHandler(objects::RW1, objects::SPI_COM_IF, rw1SpiCookie, gpioComIF, gpioIds::EN_RW1); #if OBSW_DEBUG_RW == 1 - rwHandler1->setStartUpImmediately(); + rwHandler1->setStartUpImmediately(); #endif - rw1SpiCookie->setCallbackArgs(rwHandler1); + rw1SpiCookie->setCallbackArgs(rwHandler1); + rwHandler1->setStartUpImmediately(); - auto rwHandler2 = new RwHandler(objects::RW2, objects::SPI_COM_IF, rw2SpiCookie, gpioComIF, - gpioIds::EN_RW2); + auto rwHandler2 = + new RwHandler(objects::RW2, objects::SPI_COM_IF, rw2SpiCookie, gpioComIF, gpioIds::EN_RW2); #if OBSW_DEBUG_RW == 1 - rwHandler2->setStartUpImmediately(); + rwHandler2->setStartUpImmediately(); #endif - rw2SpiCookie->setCallbackArgs(rwHandler2); + rw2SpiCookie->setCallbackArgs(rwHandler2); - auto rwHandler3 = new RwHandler(objects::RW3, objects::SPI_COM_IF, rw3SpiCookie, gpioComIF, - gpioIds::EN_RW3); + auto rwHandler3 = + new RwHandler(objects::RW3, objects::SPI_COM_IF, rw3SpiCookie, gpioComIF, gpioIds::EN_RW3); #if OBSW_DEBUG_RW == 1 - rwHandler3->setStartUpImmediately(); + rwHandler3->setStartUpImmediately(); #endif - rw3SpiCookie->setCallbackArgs(rwHandler3); + rw3SpiCookie->setCallbackArgs(rwHandler3); - auto rwHandler4 = new RwHandler(objects::RW4, objects::SPI_COM_IF, rw4SpiCookie, gpioComIF, - gpioIds::EN_RW4); + auto rwHandler4 = + new RwHandler(objects::RW4, objects::SPI_COM_IF, rw4SpiCookie, gpioComIF, gpioIds::EN_RW4); #if OBSW_DEBUG_RW == 1 - rwHandler4->setStartUpImmediately(); + rwHandler4->setStartUpImmediately(); +#endif + rw4SpiCookie->setCallbackArgs(rwHandler4); + +#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); + 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); + + 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); + +#if BOARD_TE0720 == 0 + 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); +#endif /* BOARD_TE0720 == 0 */ +} + +void ObjectFactory::createPlPcduComponents(LinuxLibgpioIF* gpioComIF, SpiComIF* spiComIF) { + 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(), false); + spiCookie->setCallbackMode(PayloadPcduHandler::extConvAsTwoCallback, plPcduHandler); + static_cast(plPcduHandler); +#if OBSW_TEST_PL_PCDU == 1 + plPcduHandler->setStartUpImmediately(); +#if OBSW_DEBUG_PL_PCDU == 1 + plPcduHandler->setToGoToNormalModeImmediately(true); + plPcduHandler->enablePeriodicPrintout(true, 5); +#endif #endif - rw4SpiCookie->setCallbackArgs(rwHandler4); } void ObjectFactory::createTestComponents(LinuxLibgpioIF* gpioComIF) { - #if BOARD_TE0720 == 0 - new Q7STestTask(objects::TEST_TASK); + new Q7STestTask(objects::TEST_TASK); #endif #if BOARD_TE0720 == 1 && OBSW_TEST_LIBGPIOD == 1 -#if OBSW_TEST_GPIO_LABEL == 1 - /* Configure MIO0 as input */ - GpiodRegular* testGpio = new GpiodRegular("MIO0", gpio::OUT, 0, "/amba_pl/gpio@41200000", 0); +#if OBSW_TEST_GPIO_OPEN_BYLABEL == 1 + /* Configure MIO0 as input */ + GpiodRegular* testGpio = new GpiodRegular("MIO0", Direction::OUT, 0, "/amba_pl/gpio@41200000", 0); +#elif OBSW_TEST_GPIO_OPEN_BY_LINE_NAME + GpiodRegularByLineName* testGpio = + new GpiodRegularByLineName("test-name", "gpio-test", Direction::OUT, 0); #else - /* Configure MIO0 as input */ - GpiodRegular* testGpio = new GpiodRegular("gpiochip0", 0, "MIO0", gpio::IN, 0); + /* Configure MIO0 as input */ + GpiodRegular* testGpio = new GpiodRegular("gpiochip0", 0, "MIO0", gpio::IN, 0); #endif /* OBSW_TEST_GPIO_LABEL == 1 */ - GpioCookie* gpioCookie = new GpioCookie; - gpioCookie->addGpio(gpioIds::TEST_ID_0, testGpio); - new LibgpiodTest(objects::LIBGPIOD_TEST, objects::GPIO_IF, gpioCookie); + GpioCookie* gpioCookie = new GpioCookie; + gpioCookie->addGpio(gpioIds::TEST_ID_0, testGpio); + new LibgpiodTest(objects::LIBGPIOD_TEST, objects::GPIO_IF, gpioCookie); #endif -#if BOARD_TE0720 == 1 && OBSW_TEST_SUS_HANDLER == 1 - GpioCookie* gpioCookieSus = new GpioCookie; - GpiodRegular* chipSelectSus = new GpiodRegular(std::string("gpiochip1"), 9, - std::string("Chip Select Sus Sensor"), gpio::OUT, 1); - gpioCookieSus->addGpio(gpioIds::CS_SUS_1, chipSelectSus); - gpioComIF->addGpios(gpioCookieSus); +#if BOARD_TE0720 == 1 && OBSW_TEST_SUS == 1 + GpioCookie* gpioCookieSus = new GpioCookie; + GpiodRegular* chipSelectSus = new GpiodRegular( + std::string("gpiochip1"), 9, std::string("Chip Select Sus Sensor"), Direction::OUT, 1); + gpioCookieSus->addGpio(gpioIds::CS_SUS_0, chipSelectSus); + gpioComIF->addGpios(gpioCookieSus); - SpiCookie* spiCookieSus = new SpiCookie(addresses::SUS_1, std::string("/dev/spidev1.0"), - SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE, spi::DEFAULT_MAX_1227_SPEED); + SpiCookie* spiCookieSus = + new SpiCookie(addresses::SUS_0, std::string("/dev/spidev1.0"), SUS::MAX_CMD_SIZE, + spi::DEFAULT_MAX_1227_MODE, spi::DEFAULT_MAX_1227_SPEED); - new SusHandler(objects::SUS_1, objects::SPI_COM_IF, spiCookieSus, gpioComIF, - gpioIds::CS_SUS_1); + new SusHandler(objects::SUS_0, objects::SPI_COM_IF, spiCookieSus, gpioComIF, gpioIds::CS_SUS_0); #endif #if BOARD_TE0720 == 1 && OBSW_TEST_CCSDS_BRIDGE == 1 - GpioCookie* gpioCookieCcsdsIp = new GpioCookie; - GpiodRegular* papbBusyN = new GpiodRegular(std::string("gpiochip0"), 0, std::string("PAPBBusy_N")); - gpioCookieCcsdsIp->addGpio(gpioIds::PAPB_BUSY_N, papbBusyN); - GpiodRegular* papbEmpty = new GpiodRegular(std::string("gpiochip0"), 1, - std::string("Chip Select Sus Sensor")); - gpioCookieCcsdsIp->addGpio(gpioIds::PAPB_EMPTY, papbEmpty); - gpioComIF->addGpios(gpioCookieCcsdsIp); + 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); + 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 BOARD_TE0720 == 1 && OBSW_TEST_RADIATION_SENSOR_HANDLER == 1 - GpioCookie* gpioCookieRadSensor = new GpioCookie; - GpiodRegular* chipSelectRadSensor = new GpiodRegular(std::string("gpiochip1"), 0, - std::string("Chip select radiation sensor"), gpio::OUT, 1); - gpioCookieRadSensor->addGpio(gpioIds::CS_RAD_SENSOR, chipSelectRadSensor); - gpioComIF->addGpios(gpioCookieRadSensor); +#if BOARD_TE0720 == 1 && OBSW_TEST_RAD_SENSOR == 1 + GpioCookie* gpioCookieRadSensor = new GpioCookie; + GpiodRegular* chipSelectRadSensor = new GpiodRegular( + std::string("gpiochip1"), 0, std::string("Chip select radiation sensor"), Direction::OUT, 1); + gpioCookieRadSensor->addGpio(gpioIds::CS_RAD_SENSOR, chipSelectRadSensor); + gpioComIF->addGpios(gpioCookieRadSensor); - SpiCookie* spiCookieRadSensor = new SpiCookie(addresses::RAD_SENSOR, gpioIds::CS_RAD_SENSOR, - std::string("/dev/spidev1.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE, - spi::DEFAULT_MAX_1227_SPEED); + SpiCookie* spiCookieRadSensor = + new SpiCookie(addresses::RAD_SENSOR, gpioIds::CS_RAD_SENSOR, std::string("/dev/spidev1.0"), + SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE, spi::DEFAULT_MAX_1227_SPEED); - RadiationSensorHandler* radSensor = new RadiationSensorHandler(objects::RAD_SENSOR, - objects::SPI_COM_IF, spiCookieRadSensor); - radSensor->setStartUpImmediately(); + RadiationSensorHandler* radSensor = + new RadiationSensorHandler(objects::RAD_SENSOR, objects::SPI_COM_IF, spiCookieRadSensor); + radSensor->setStartUpImmediately(); #endif #if BOARD_TE0720 == 1 && OBSW_ADD_PLOC_MPSOC == 1 - UartCookie* plocUartCookie = new UartCookie(std::string("/dev/ttyPS1"), 115200, - PLOC_MPSOC::MAX_REPLY_SIZE); - /* Testing PlocMPSoCHandler on TE0720-03-1CFA */ - PlocMPSoCHandler* mpsocPlocHandler = new PlocMPSoCHandler(objects::PLOC_MPSOC_HANDLER, objects::UART_COM_IF, - plocUartCookie); - mpsocPlocHandler->setStartUpImmediately(); + UartCookie* plocUartCookie = + new UartCookie(std::string("/dev/ttyPS1"), 115200, PLOC_MPSOC::MAX_REPLY_SIZE); + /* Testing PlocMPSoCHandler on TE0720-03-1CFA */ + PlocMPSoCHandler* mpsocPlocHandler = + new PlocMPSoCHandler(objects::PLOC_MPSOC_HANDLER, objects::UART_COM_IF, plocUartCookie); + mpsocPlocHandler->setStartUpImmediately(); #endif #if BOARD_TE0720 == 1 && OBSW_TEST_TE7020_HEATER == 1 - /* Configuration for MIO0 on TE0720-03-1CFA */ - GpiodRegular* heaterGpio = new GpiodRegular(std::string("gpiochip0"), 0, std::string("MIO0"), gpio::IN, 0); - 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); + /* Configuration for MIO0 on TE0720-03-1CFA */ + GpiodRegular* heaterGpio = + new GpiodRegular(std::string("gpiochip0"), 0, std::string("MIO0"), gpio::IN, 0); + 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); #endif #if BOARD_TE0720 == 1 && 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(); + /* 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 #if OBSW_ADD_SPI_TEST_CODE == 1 - new SpiTestClass(objects::SPI_TEST, gpioComIF); + 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 - } diff --git a/bsp_q7s/core/ObjectFactory.h b/bsp_q7s/core/ObjectFactory.h index ad9533a5..ecc92f01 100644 --- a/bsp_q7s/core/ObjectFactory.h +++ b/bsp_q7s/core/ObjectFactory.h @@ -4,6 +4,7 @@ class LinuxLibgpioIF; class UartComIF; class SpiComIF; +class I2cComIF; namespace ObjectFactory { @@ -11,9 +12,11 @@ void setStatics(); void produce(void* args); void createCommunicationInterfaces(LinuxLibgpioIF** gpioComIF, UartComIF** uartComIF, - SpiComIF** spiComIF); + SpiComIF** spiComIF, I2cComIF** i2cComIF); + +void createPlPcduComponents(LinuxLibgpioIF* gpioComIF, SpiComIF* spiComIF); void createTmpComponents(); -void createPcduComponents(); +void createPcduComponents(LinuxLibgpioIF* gpioComIF); void createRadSensorComponent(LinuxLibgpioIF* gpioComIF); void createSunSensorComponents(LinuxLibgpioIF* gpioComIF, SpiComIF* spiComIF); void createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, UartComIF* uartComIF); @@ -22,8 +25,9 @@ void createSolarArrayDeploymentComponents(); void createSyrlinksComponents(); void createRtdComponents(LinuxLibgpioIF* gpioComIF); void createReactionWheelComponents(LinuxLibgpioIF* gpioComIF); +void createCcsdsComponents(LinuxLibgpioIF* gpioComIF); void createTestComponents(LinuxLibgpioIF* gpioComIF); -}; +}; // namespace ObjectFactory #endif /* BSP_Q7S_OBJECTFACTORY_H_ */ diff --git a/bsp_q7s/core/ParameterHandler.cpp b/bsp_q7s/core/ParameterHandler.cpp index d6c8f34f..8cee046e 100644 --- a/bsp_q7s/core/ParameterHandler.cpp +++ b/bsp_q7s/core/ParameterHandler.cpp @@ -1,8 +1,5 @@ #include "ParameterHandler.h" -ParameterHandler::ParameterHandler(std::string mountPrefix): mountPrefix(mountPrefix) { -} +ParameterHandler::ParameterHandler(std::string mountPrefix) : mountPrefix(mountPrefix) {} -void ParameterHandler::setMountPrefix(std::string prefix) { - mountPrefix = prefix; -} +void ParameterHandler::setMountPrefix(std::string prefix) { mountPrefix = prefix; } diff --git a/bsp_q7s/core/ParameterHandler.h b/bsp_q7s/core/ParameterHandler.h index 81cbc099..4a108586 100644 --- a/bsp_q7s/core/ParameterHandler.h +++ b/bsp_q7s/core/ParameterHandler.h @@ -4,19 +4,17 @@ #include #include - - class ParameterHandler { -public: - ParameterHandler(std::string mountPrefix); + public: + ParameterHandler(std::string mountPrefix); - void setMountPrefix(std::string prefix); + void setMountPrefix(std::string prefix); - void setUpDummyParameter(); -private: - std::string mountPrefix; - DummyParameter dummyParam; + void setUpDummyParameter(); + + private: + std::string mountPrefix; + DummyParameter dummyParam; }; - #endif /* BSP_Q7S_CORE_PARAMETERHANDLER_H_ */ diff --git a/bsp_q7s/core/obsw.cpp b/bsp_q7s/core/obsw.cpp index e55d5652..04163a82 100644 --- a/bsp_q7s/core/obsw.cpp +++ b/bsp_q7s/core/obsw.cpp @@ -1,43 +1,44 @@ #include "obsw.h" -#include "OBSWVersion.h" -#include "OBSWConfig.h" -#include "InitMission.h" -#include "watchdogConf.h" -#include "fsfw/tasks/TaskFactory.h" -#include "fsfw/FSFWVersion.h" - -#include #include +#include + +#include "InitMission.h" +#include "OBSWConfig.h" +#include "OBSWVersion.h" +#include "fsfw/FSFWVersion.h" +#include "fsfw/tasks/TaskFactory.h" +#include "watchdogConf.h" static int OBSW_ALREADY_RUNNING = -2; int obsw::obsw() { - std::cout << "-- EIVE OBSW --" << std::endl; + std::cout << "-- EIVE OBSW --" << std::endl; #if BOARD_TE0720 == 0 - std::cout << "-- Compiled for Linux (Xiphos Q7S) --" << std::endl; + std::cout << "-- Compiled for Linux (Xiphos Q7S) --" << std::endl; #else - std::cout << "-- Compiled for Linux (TE0720) --" << std::endl; + std::cout << "-- Compiled for Linux (TE0720) --" << std::endl; #endif - std::cout << "-- OBSW v" << SW_VERSION << "." << SW_SUBVERSION << - "." << SW_REVISION << ", FSFW v" << FSFW_VERSION << "." << FSFW_SUBVERSION << "." << - FSFW_REVISION << "--" << std::endl; - std::cout << "-- " << __DATE__ << " " << __TIME__ << " --" << std::endl; + std::cout << "-- OBSW v" << SW_VERSION << "." << SW_SUBVERSION << "." << SW_REVISION << ", FSFW v" + << FSFW_VERSION << "." << FSFW_SUBVERSION << "." << FSFW_REVISION << "--" << std::endl; + std::cout << "-- " << __DATE__ << " " << __TIME__ << " --" << std::endl; #if Q7S_CHECK_FOR_ALREADY_RUNNING_IMG == 1 - // Check special file here. This file is created or deleted by the eive-watchdog application - // or systemd service! - if(std::filesystem::exists(watchdog::RUNNING_FILE_NAME)) { - sif::warning << "File " << watchdog::RUNNING_FILE_NAME << " exists so the software might " - "already be running. Aborting.." << std::endl; - return OBSW_ALREADY_RUNNING; - } + // Check special file here. This file is created or deleted by the eive-watchdog application + // or systemd service! + if (std::filesystem::exists(watchdog::RUNNING_FILE_NAME)) { + sif::warning << "File " << watchdog::RUNNING_FILE_NAME + << " exists so the software might " + "already be running. Check if obsw systemd service has been stopped." + << std::endl; + return OBSW_ALREADY_RUNNING; + } #endif - initmission::initMission(); + initmission::initMission(); - for(;;) { - /* Suspend main thread by sleeping it. */ - TaskFactory::delayTask(5000); - } - return 0; + for (;;) { + /* Suspend main thread by sleeping it. */ + TaskFactory::delayTask(5000); + } + return 0; } diff --git a/bsp_q7s/devices/CMakeLists.txt b/bsp_q7s/devices/CMakeLists.txt index 6347b5f8..e0f6ee2f 100644 --- a/bsp_q7s/devices/CMakeLists.txt +++ b/bsp_q7s/devices/CMakeLists.txt @@ -1,4 +1,4 @@ -target_sources(${TARGET_NAME} PRIVATE +target_sources(${OBSW_NAME} PRIVATE PlocSupervisorHandler.cpp PlocUpdater.cpp PlocMemoryDumper.cpp diff --git a/bsp_q7s/devices/PlocMemoryDumper.cpp b/bsp_q7s/devices/PlocMemoryDumper.cpp index cc4361bb..1d5dce85 100644 --- a/bsp_q7s/devices/PlocMemoryDumper.cpp +++ b/bsp_q7s/devices/PlocMemoryDumper.cpp @@ -1,206 +1,194 @@ -#include -#include "fsfw/ipc/QueueFactory.h" #include "PlocMemoryDumper.h" -#include +#include + #include +#include #include -PlocMemoryDumper::PlocMemoryDumper(object_id_t objectId) : - SystemObject(objectId), commandActionHelper(this), actionHelper(this, nullptr) { - commandQueue = QueueFactory::instance()->createMessageQueue(QUEUE_SIZE); +#include "fsfw/ipc/QueueFactory.h" + +PlocMemoryDumper::PlocMemoryDumper(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); } -PlocMemoryDumper::~PlocMemoryDumper() { -} +PlocMemoryDumper::~PlocMemoryDumper() {} ReturnValue_t PlocMemoryDumper::initialize() { + 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; + } - 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; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t PlocMemoryDumper::performOperation(uint8_t operationCode) { - readCommandQueue(); - doStateMachine(); - return HasReturnvaluesIF::RETURN_OK; + readCommandQueue(); + doStateMachine(); + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t PlocMemoryDumper::executeAction(ActionId_t actionId, - MessageQueueId_t commandedBy, const uint8_t* data, size_t size) { +ReturnValue_t PlocMemoryDumper::executeAction(ActionId_t actionId, MessageQueueId_t commandedBy, + const uint8_t* data, size_t size) { + if (state != State::IDLE) { + return IS_BUSY; + } - if (state != State::IDLE) { - return IS_BUSY; - } - - switch (actionId) { + switch (actionId) { case DUMP_MRAM: { - size_t deserializeSize = sizeof(mram.startAddress) + sizeof(mram.endAddress); - SerializeAdapter::deSerialize(&mram.startAddress, &data, &deserializeSize, - SerializeIF::Endianness::BIG); - SerializeAdapter::deSerialize(&mram.endAddress, &data, &deserializeSize, - SerializeIF::Endianness::BIG); - if (mram.endAddress > MAX_MRAM_ADDRESS) { - return MRAM_ADDRESS_TOO_HIGH; - } - if (mram.endAddress <= mram.startAddress) { - return MRAM_INVALID_ADDRESS_COMBINATION; - } - state = State::COMMAND_FIRST_MRAM_DUMP; - break; + size_t deserializeSize = sizeof(mram.startAddress) + sizeof(mram.endAddress); + SerializeAdapter::deSerialize(&mram.startAddress, &data, &deserializeSize, + SerializeIF::Endianness::BIG); + SerializeAdapter::deSerialize(&mram.endAddress, &data, &deserializeSize, + SerializeIF::Endianness::BIG); + if (mram.endAddress > MAX_MRAM_ADDRESS) { + return MRAM_ADDRESS_TOO_HIGH; + } + if (mram.endAddress <= mram.startAddress) { + return MRAM_INVALID_ADDRESS_COMBINATION; + } + state = State::COMMAND_FIRST_MRAM_DUMP; + break; } default: { - sif::warning << "PlocMemoryDumper::executeAction: Received command with invalid action id" - << std::endl; - return INVALID_ACTION_ID; - } + sif::warning << "PlocMemoryDumper::executeAction: Received command with invalid action id" + << std::endl; + return INVALID_ACTION_ID; } + } - return EXECUTION_FINISHED; + return EXECUTION_FINISHED; } -MessageQueueId_t PlocMemoryDumper::getCommandQueue() const { - return commandQueue->getId(); -} +MessageQueueId_t PlocMemoryDumper::getCommandQueue() const { return commandQueue->getId(); } -MessageQueueIF* PlocMemoryDumper::getCommandQueuePtr() { - return commandQueue; -} +MessageQueueIF* PlocMemoryDumper::getCommandQueuePtr() { return commandQueue; } void PlocMemoryDumper::readCommandQueue() { - CommandMessage message; - ReturnValue_t result; + 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; - } - - sif::debug << "PlocMemoryDumper::readCommandQueue: Received message with invalid format" - << std::endl; + 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; + } + + sif::debug << "PlocMemoryDumper::readCommandQueue: Received message with invalid format" + << std::endl; + } } void PlocMemoryDumper::doStateMachine() { - switch (state) { + switch (state) { case State::IDLE: - break; + break; case State::COMMAND_FIRST_MRAM_DUMP: - commandNextMramDump(PLOC_SPV::FIRST_MRAM_DUMP); - break; + commandNextMramDump(PLOC_SPV::FIRST_MRAM_DUMP); + break; case State::COMMAND_CONSECUTIVE_MRAM_DUMP: - commandNextMramDump(PLOC_SPV::CONSECUTIVE_MRAM_DUMP); - break; + commandNextMramDump(PLOC_SPV::CONSECUTIVE_MRAM_DUMP); + break; case State::EXECUTING_MRAM_DUMP: - break; + break; default: - sif::debug << "PlocMemoryDumper::doStateMachine: Invalid state" << std::endl; - break; - } + sif::debug << "PlocMemoryDumper::doStateMachine: Invalid state" << std::endl; + break; + } } -void PlocMemoryDumper::stepSuccessfulReceived(ActionId_t actionId, - uint8_t step) { -} +void PlocMemoryDumper::stepSuccessfulReceived(ActionId_t actionId, uint8_t step) {} void PlocMemoryDumper::stepFailedReceived(ActionId_t actionId, uint8_t step, - ReturnValue_t returnCode) { -} + ReturnValue_t returnCode) {} -void PlocMemoryDumper::dataReceived(ActionId_t actionId, const uint8_t* data, uint32_t size) { - -} +void PlocMemoryDumper::dataReceived(ActionId_t actionId, const uint8_t* data, uint32_t size) {} void PlocMemoryDumper::completionSuccessfulReceived(ActionId_t actionId) { - switch (pendingCommand) { + switch (pendingCommand) { case (PLOC_SPV::FIRST_MRAM_DUMP): case (PLOC_SPV::CONSECUTIVE_MRAM_DUMP): - if (mram.endAddress == mram.startAddress) { - triggerEvent(MRAM_DUMP_FINISHED); - state = State::IDLE; - } - else { - state = State::COMMAND_CONSECUTIVE_MRAM_DUMP; - } - break; - default: - sif::debug << "PlocMemoryDumper::completionSuccessfulReceived: Invalid pending command" - << std::endl; + if (mram.endAddress == mram.startAddress) { + triggerEvent(MRAM_DUMP_FINISHED); state = State::IDLE; - break; - } + } else { + state = State::COMMAND_CONSECUTIVE_MRAM_DUMP; + } + break; + default: + sif::debug << "PlocMemoryDumper::completionSuccessfulReceived: Invalid pending command" + << std::endl; + state = State::IDLE; + break; + } } -void PlocMemoryDumper::completionFailedReceived(ActionId_t actionId, - ReturnValue_t returnCode) { - switch(pendingCommand) { - case(PLOC_SPV::FIRST_MRAM_DUMP): - case(PLOC_SPV::CONSECUTIVE_MRAM_DUMP): - triggerEvent(MRAM_DUMP_FAILED, mram.lastStartAddress); - break; +void PlocMemoryDumper::completionFailedReceived(ActionId_t actionId, ReturnValue_t returnCode) { + switch (pendingCommand) { + case (PLOC_SPV::FIRST_MRAM_DUMP): + case (PLOC_SPV::CONSECUTIVE_MRAM_DUMP): + triggerEvent(MRAM_DUMP_FAILED, mram.lastStartAddress); + break; default: - sif::debug << "PlocMemoryDumper::completionFailedReceived: Invalid pending command " - << std::endl; - break; - } - state = State::IDLE; + sif::debug << "PlocMemoryDumper::completionFailedReceived: Invalid pending command " + << std::endl; + break; + } + state = State::IDLE; } void PlocMemoryDumper::commandNextMramDump(ActionId_t dumpCommand) { - ReturnValue_t result = RETURN_OK; + ReturnValue_t result = RETURN_OK; - uint32_t tempStartAddress = 0; - uint32_t tempEndAddress = 0; + uint32_t tempStartAddress = 0; + uint32_t tempEndAddress = 0; - if (mram.endAddress - mram.startAddress > MAX_MRAM_DUMP_SIZE) { - 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; - } + if (mram.endAddress - mram.startAddress > MAX_MRAM_DUMP_SIZE) { + 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; + } - MemoryParams params(tempStartAddress, tempEndAddress); + MemoryParams params(tempStartAddress, tempEndAddress); - result = commandActionHelper.commandAction(objects::PLOC_SUPERVISOR_HANDLER, - dumpCommand, ¶ms); - if (result != RETURN_OK) { - sif::warning << "PlocMemoryDumper::commandNextMramDump: Failed to send mram dump command " - << "with start address " << tempStartAddress << " and end address " - << tempEndAddress << std::endl; - triggerEvent(SEND_MRAM_DUMP_FAILED, result, tempStartAddress); - state = State::IDLE; - pendingCommand = NONE; - return; - } - state = State::EXECUTING_MRAM_DUMP; - pendingCommand = dumpCommand; + result = + commandActionHelper.commandAction(objects::PLOC_SUPERVISOR_HANDLER, dumpCommand, ¶ms); + if (result != RETURN_OK) { + sif::warning << "PlocMemoryDumper::commandNextMramDump: Failed to send mram dump command " + << "with start address " << tempStartAddress << " and end address " + << tempEndAddress << std::endl; + triggerEvent(SEND_MRAM_DUMP_FAILED, result, tempStartAddress); + state = State::IDLE; + pendingCommand = NONE; return; + } + state = State::EXECUTING_MRAM_DUMP; + pendingCommand = dumpCommand; + return; } - diff --git a/bsp_q7s/devices/PlocMemoryDumper.h b/bsp_q7s/devices/PlocMemoryDumper.h index 72b031ae..2ee26824 100644 --- a/bsp_q7s/devices/PlocMemoryDumper.h +++ b/bsp_q7s/devices/PlocMemoryDumper.h @@ -3,18 +3,18 @@ #include #include + #include "OBSWConfig.h" -#include "fsfw/action/CommandActionHelper.h" +#include "bsp_q7s/memory/SdCardManager.h" #include "fsfw/action/ActionHelper.h" -#include "fsfw/action/HasActionsIF.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/objectmanager/SystemObject.h" -#include "bsp_q7s/memory/SdCardManager.h" -#include "linux/fsfwconfig/objects/systemObjectList.h" #include "fsfw/tmtcpacket/SpacePacket.h" - +#include "linux/fsfwconfig/objects/systemObjectList.h" /** * @brief Because the buffer of the linux tty driver is limited to 2 x 65535 bytes, this class is @@ -25,91 +25,90 @@ * @author J. Meier */ class PlocMemoryDumper : public SystemObject, - public HasActionsIF, - public ExecutableObjectIF, - public HasReturnvaluesIF, - public CommandsActionsIF { -public: + public HasActionsIF, + public ExecutableObjectIF, + public HasReturnvaluesIF, + public CommandsActionsIF { + public: + static const ActionId_t NONE = 0; + static const ActionId_t DUMP_MRAM = 1; - static const ActionId_t NONE = 0; - static const ActionId_t DUMP_MRAM = 1; + PlocMemoryDumper(object_id_t objectId); + virtual ~PlocMemoryDumper(); - PlocMemoryDumper(object_id_t objectId); - virtual ~PlocMemoryDumper(); + 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; - 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 uint32_t QUEUE_SIZE = 10; -private: + static const uint8_t INTERFACE_ID = CLASS_ID::PLOC_MEMORY_DUMPER; - static const uint32_t QUEUE_SIZE = 10; + //! [EXPORT] : [COMMENT] The capacity of the MRAM amounts to 512 kB. Thus the maximum address must + //! not be higher than 0x7d000. + static const ReturnValue_t MRAM_ADDRESS_TOO_HIGH = MAKE_RETURN_CODE(0xA0); + //! [EXPORT] : [COMMENT] The specified end address is lower than the start address + static const ReturnValue_t MRAM_INVALID_ADDRESS_COMBINATION = MAKE_RETURN_CODE(0xA1); - static const uint8_t INTERFACE_ID = CLASS_ID::PLOC_MEMORY_DUMPER; + static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PLOC_MEMORY_DUMPER; - //! [EXPORT] : [COMMENT] The capacity of the MRAM amounts to 512 kB. Thus the maximum address must not be higher than 0x7d000. - static const ReturnValue_t MRAM_ADDRESS_TOO_HIGH = MAKE_RETURN_CODE(0xA0); - //! [EXPORT] : [COMMENT] The specified end address is lower than the start address - static const ReturnValue_t MRAM_INVALID_ADDRESS_COMBINATION = MAKE_RETURN_CODE(0xA1); + //! [EXPORT] : [COMMENT] 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 + static const Event SEND_MRAM_DUMP_FAILED = MAKE_EVENT(0, severity::LOW); + //! [EXPORT] : [COMMENT] Received completion failure report form PLOC supervisor handler + //! P1: MRAM start address of failing dump command + static const Event MRAM_DUMP_FAILED = MAKE_EVENT(1, severity::LOW); + //! [EXPORT] : [COMMENT] MRAM dump finished successfully + static const Event MRAM_DUMP_FINISHED = MAKE_EVENT(2, severity::LOW); - static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PLOC_MEMORY_DUMPER; + // Maximum size of mram dump which can be retrieved with one command + static const uint32_t MAX_MRAM_DUMP_SIZE = 100000; + static const uint32_t MAX_MRAM_ADDRESS = 0x7d000; - //! [EXPORT] : [COMMENT] 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 - static const Event SEND_MRAM_DUMP_FAILED = MAKE_EVENT(0, severity::LOW); - //! [EXPORT] : [COMMENT] Received completion failure report form PLOC supervisor handler - //! P1: MRAM start address of failing dump command - static const Event MRAM_DUMP_FAILED = MAKE_EVENT(1, severity::LOW); - //! [EXPORT] : [COMMENT] MRAM dump finished successfully - static const Event MRAM_DUMP_FINISHED = MAKE_EVENT(2, severity::LOW); + MessageQueueIF* commandQueue = nullptr; - // Maximum size of mram dump which can be retrieved with one command - static const uint32_t MAX_MRAM_DUMP_SIZE = 100000; - static const uint32_t MAX_MRAM_ADDRESS = 0x7d000; + CommandActionHelper commandActionHelper; - MessageQueueIF* commandQueue = nullptr; + ActionHelper actionHelper; - CommandActionHelper commandActionHelper; + enum class State : uint8_t { + IDLE, + COMMAND_FIRST_MRAM_DUMP, + COMMAND_CONSECUTIVE_MRAM_DUMP, + EXECUTING_MRAM_DUMP + }; - ActionHelper actionHelper; + State state = State::IDLE; - enum class State: uint8_t { - IDLE, - COMMAND_FIRST_MRAM_DUMP, - COMMAND_CONSECUTIVE_MRAM_DUMP, - EXECUTING_MRAM_DUMP - }; + ActionId_t pendingCommand = NONE; - State state = State::IDLE; + typedef struct MemoryInfo { + // Stores the start address of the next memory range to dump + uint32_t startAddress; + uint32_t endAddress; + // Stores the start address of the last sent dump command + uint32_t lastStartAddress; + } MemoryInfo_t; - ActionId_t pendingCommand = NONE; + MemoryInfo_t mram = {0, 0, 0}; - typedef struct MemoryInfo { - // Stores the start address of the next memory range to dump - uint32_t startAddress; - uint32_t endAddress; - // Stores the start address of the last sent dump command - uint32_t lastStartAddress; - } MemoryInfo_t; + void readCommandQueue(); + void doStateMachine(); - MemoryInfo_t mram = {0, 0, 0}; - - void readCommandQueue(); - void doStateMachine(); - - /** - * @brief Sends the next mram dump command to the PLOC supervisor handler. - */ - void commandNextMramDump(ActionId_t dumpCommand); + /** + * @brief Sends the next mram dump command to the PLOC supervisor handler. + */ + void commandNextMramDump(ActionId_t dumpCommand); }; #endif /* MISSION_DEVICES_PLOCMEMORYDUMPER_H_ */ diff --git a/bsp_q7s/devices/PlocSupervisorHandler.cpp b/bsp_q7s/devices/PlocSupervisorHandler.cpp index 30ea9572..a56c9e1c 100644 --- a/bsp_q7s/devices/PlocSupervisorHandler.cpp +++ b/bsp_q7s/devices/PlocSupervisorHandler.cpp @@ -1,540 +1,530 @@ -#include -#include -#include -#include - #include "PlocSupervisorHandler.h" -#include "OBSWConfig.h" -#include #include +#include #include +#include +#include +#include +#include + +#include "OBSWConfig.h" + PlocSupervisorHandler::PlocSupervisorHandler(object_id_t objectId, object_id_t uartComIFid, - CookieIF * comCookie) : - DeviceHandlerBase(objectId, uartComIFid, comCookie), hkset(this), bootStatusReport(this), latchupStatusReport( - this) { - if (comCookie == NULL) { - sif::error << "PlocSupervisorHandler: Invalid com cookie" << std::endl; - } + CookieIF* comCookie) + : DeviceHandlerBase(objectId, uartComIFid, comCookie), + hkset(this), + bootStatusReport(this), + latchupStatusReport(this) { + if (comCookie == NULL) { + sif::error << "PlocSupervisorHandler: Invalid com cookie" << std::endl; + } } -PlocSupervisorHandler::~PlocSupervisorHandler() { -} +PlocSupervisorHandler::~PlocSupervisorHandler() {} ReturnValue_t PlocSupervisorHandler::initialize() { - ReturnValue_t result = RETURN_OK; - result = DeviceHandlerBase::initialize(); - if (result != RETURN_OK) { - return result; - } - uartComIf = dynamic_cast(communicationInterface); - if (uartComIf == nullptr) { - sif::warning << "PlocSupervisorHandler::initialize: Invalid uart com if" << std::endl; - return INVALID_UART_COM_IF; - } + ReturnValue_t result = RETURN_OK; + result = DeviceHandlerBase::initialize(); + if (result != RETURN_OK) { + return result; + } + uartComIf = dynamic_cast(communicationInterface); + if (uartComIf == nullptr) { + sif::warning << "PlocSupervisorHandler::initialize: Invalid uart com if" << std::endl; + return INVALID_UART_COM_IF; + } #if BOARD_TE0720 == 0 - sdcMan = SdCardManager::instance(); + sdcMan = SdCardManager::instance(); #endif /* BOARD_TE0720 == 0 */ - return result; + return result; } - -void PlocSupervisorHandler::doStartUp(){ +void PlocSupervisorHandler::doStartUp() { #if OBSW_SWITCH_TO_NORMAL_MODE_AFTER_STARTUP == 1 - setMode(MODE_NORMAL); + setMode(MODE_NORMAL); #else - setMode(_MODE_TO_ON); + setMode(_MODE_TO_ON); #endif } -void PlocSupervisorHandler::doShutDown(){ - setMode(_MODE_POWER_DOWN); +void PlocSupervisorHandler::doShutDown() { setMode(_MODE_POWER_DOWN); } + +ReturnValue_t PlocSupervisorHandler::buildNormalDeviceCommand(DeviceCommandId_t* id) { + return NOTHING_TO_SEND; } -ReturnValue_t PlocSupervisorHandler::buildNormalDeviceCommand( - DeviceCommandId_t * id) { - return NOTHING_TO_SEND; +ReturnValue_t PlocSupervisorHandler::buildTransitionDeviceCommand(DeviceCommandId_t* id) { + return NOTHING_TO_SEND; } -ReturnValue_t PlocSupervisorHandler::buildTransitionDeviceCommand( - DeviceCommandId_t * id){ - return NOTHING_TO_SEND; -} - -ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand( - DeviceCommandId_t deviceCommand, const uint8_t * commandData, - size_t commandDataLen) { - ReturnValue_t result = RETURN_FAILED; - switch(deviceCommand) { - case(PLOC_SPV::GET_HK_REPORT): { - prepareEmptyCmd(PLOC_SPV::APID_GET_HK_REPORT); - result = RETURN_OK; - break; - } - case(PLOC_SPV::RESTART_MPSOC): { - prepareEmptyCmd(PLOC_SPV::APID_RESTART_MPSOC); - result = RETURN_OK; - break; - } - case(PLOC_SPV::START_MPSOC): { - prepareEmptyCmd(PLOC_SPV::APID_START_MPSOC); - result = RETURN_OK; - break; - } - case(PLOC_SPV::SHUTDOWN_MPSOC): { - prepareEmptyCmd(PLOC_SPV::APID_SHUTWOWN_MPSOC); - result = RETURN_OK; - break; - } - case(PLOC_SPV::SEL_MPSOC_BOOT_IMAGE): { - prepareSelBootImageCmd(commandData); - result = RETURN_OK; - break; - } - case(PLOC_SPV::RESET_MPSOC): { - prepareEmptyCmd(PLOC_SPV::APID_RESET_MPSOC); - result = RETURN_OK; - break; +ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t deviceCommand, + const uint8_t* commandData, + size_t commandDataLen) { + ReturnValue_t result = RETURN_FAILED; + switch (deviceCommand) { + case (PLOC_SPV::GET_HK_REPORT): { + prepareEmptyCmd(PLOC_SPV::APID_GET_HK_REPORT); + result = RETURN_OK; + break; } - case(PLOC_SPV::SET_TIME_REF): { - result = prepareSetTimeRefCmd(); - break; - } - case(PLOC_SPV::SET_BOOT_TIMEOUT): { - prepareSetBootTimeoutCmd(commandData); - result = RETURN_OK; - break; + case (PLOC_SPV::RESTART_MPSOC): { + prepareEmptyCmd(PLOC_SPV::APID_RESTART_MPSOC); + result = RETURN_OK; + break; } - case(PLOC_SPV::SET_MAX_RESTART_TRIES): { - prepareRestartTriesCmd(commandData); - result = RETURN_OK; - break; + case (PLOC_SPV::START_MPSOC): { + prepareEmptyCmd(PLOC_SPV::APID_START_MPSOC); + result = RETURN_OK; + break; } - case(PLOC_SPV::DISABLE_PERIOIC_HK_TRANSMISSION): { - prepareDisableHk(); - result = RETURN_OK; - break; + case (PLOC_SPV::SHUTDOWN_MPSOC): { + prepareEmptyCmd(PLOC_SPV::APID_SHUTWOWN_MPSOC); + result = RETURN_OK; + break; } - case(PLOC_SPV::GET_BOOT_STATUS_REPORT): { - prepareEmptyCmd(PLOC_SPV::APID_GET_BOOT_STATUS_RPT); - result = RETURN_OK; - break; + case (PLOC_SPV::SEL_MPSOC_BOOT_IMAGE): { + prepareSelBootImageCmd(commandData); + result = RETURN_OK; + break; } - case(PLOC_SPV::WATCHDOGS_ENABLE): { - prepareWatchdogsEnableCmd(commandData); - result = RETURN_OK; - break; + case (PLOC_SPV::RESET_MPSOC): { + prepareEmptyCmd(PLOC_SPV::APID_RESET_MPSOC); + result = RETURN_OK; + break; } - case(PLOC_SPV::WATCHDOGS_CONFIG_TIMEOUT): { - result = prepareWatchdogsConfigTimeoutCmd(commandData); - break; + case (PLOC_SPV::SET_TIME_REF): { + result = prepareSetTimeRefCmd(); + break; } - case(PLOC_SPV::ENABLE_LATCHUP_ALERT): { - result = prepareLatchupConfigCmd(commandData, deviceCommand); - break; + case (PLOC_SPV::SET_BOOT_TIMEOUT): { + prepareSetBootTimeoutCmd(commandData); + result = RETURN_OK; + break; } - case(PLOC_SPV::DISABLE_LATCHUP_ALERT): { - result = prepareLatchupConfigCmd(commandData, deviceCommand); - break; + case (PLOC_SPV::SET_MAX_RESTART_TRIES): { + prepareRestartTriesCmd(commandData); + result = RETURN_OK; + break; } - case(PLOC_SPV::AUTO_CALIBRATE_ALERT): { - result = prepareAutoCalibrateAlertCmd(commandData); - break; + case (PLOC_SPV::DISABLE_PERIOIC_HK_TRANSMISSION): { + prepareDisableHk(); + result = RETURN_OK; + break; } - case(PLOC_SPV::SET_ALERT_LIMIT): { - result = prepareSetAlertLimitCmd(commandData); - break; + case (PLOC_SPV::GET_BOOT_STATUS_REPORT): { + prepareEmptyCmd(PLOC_SPV::APID_GET_BOOT_STATUS_RPT); + result = RETURN_OK; + break; } - case(PLOC_SPV::SET_ALERT_IRQ_FILTER): { - result = prepareSetAlertIrqFilterCmd(commandData); - break; + case (PLOC_SPV::WATCHDOGS_ENABLE): { + prepareWatchdogsEnableCmd(commandData); + result = RETURN_OK; + break; } - case(PLOC_SPV::SET_ADC_SWEEP_PERIOD): { - result = prepareSetAdcSweetPeriodCmd(commandData); - break; + case (PLOC_SPV::WATCHDOGS_CONFIG_TIMEOUT): { + result = prepareWatchdogsConfigTimeoutCmd(commandData); + break; } - case(PLOC_SPV::SET_ADC_ENABLED_CHANNELS): { - prepareSetAdcEnabledChannelsCmd(commandData); - result = RETURN_OK; - break; + case (PLOC_SPV::ENABLE_LATCHUP_ALERT): { + result = prepareLatchupConfigCmd(commandData, deviceCommand); + break; } - case(PLOC_SPV::SET_ADC_WINDOW_AND_STRIDE): { - prepareSetAdcWindowAndStrideCmd(commandData); - result = RETURN_OK; - break; + case (PLOC_SPV::DISABLE_LATCHUP_ALERT): { + result = prepareLatchupConfigCmd(commandData, deviceCommand); + break; } - case(PLOC_SPV::SET_ADC_THRESHOLD): { - prepareSetAdcThresholdCmd(commandData); - result = RETURN_OK; - break; + case (PLOC_SPV::AUTO_CALIBRATE_ALERT): { + result = prepareAutoCalibrateAlertCmd(commandData); + break; } - case(PLOC_SPV::GET_LATCHUP_STATUS_REPORT): { - prepareEmptyCmd(PLOC_SPV::APID_GET_LATCHUP_STATUS_REPORT); - result = RETURN_OK; - break; + case (PLOC_SPV::SET_ALERT_LIMIT): { + result = prepareSetAlertLimitCmd(commandData); + break; } - case(PLOC_SPV::COPY_ADC_DATA_TO_MRAM): { - prepareEmptyCmd(PLOC_SPV::APID_COPY_ADC_DATA_TO_MRAM); - result = RETURN_OK; - break; + case (PLOC_SPV::SET_ALERT_IRQ_FILTER): { + result = prepareSetAlertIrqFilterCmd(commandData); + break; } - case(PLOC_SPV::ENABLE_NVMS): { - prepareEnableNvmsCmd(commandData); - result = RETURN_OK; - break; + case (PLOC_SPV::SET_ADC_SWEEP_PERIOD): { + result = prepareSetAdcSweetPeriodCmd(commandData); + break; } - case(PLOC_SPV::SELECT_NVM): { - prepareSelectNvmCmd(commandData); - result = RETURN_OK; - break; + case (PLOC_SPV::SET_ADC_ENABLED_CHANNELS): { + prepareSetAdcEnabledChannelsCmd(commandData); + result = RETURN_OK; + break; } - case(PLOC_SPV::RUN_AUTO_EM_TESTS): { - result = prepareRunAutoEmTest(commandData); - break; + case (PLOC_SPV::SET_ADC_WINDOW_AND_STRIDE): { + prepareSetAdcWindowAndStrideCmd(commandData); + result = RETURN_OK; + break; } - case(PLOC_SPV::WIPE_MRAM): { - result = prepareWipeMramCmd(commandData); - break; + case (PLOC_SPV::SET_ADC_THRESHOLD): { + prepareSetAdcThresholdCmd(commandData); + result = RETURN_OK; + break; } - case(PLOC_SPV::FIRST_MRAM_DUMP): - case(PLOC_SPV::CONSECUTIVE_MRAM_DUMP): - result = prepareDumpMramCmd(commandData); - break; - case(PLOC_SPV::PRINT_CPU_STATS): { - preparePrintCpuStatsCmd(commandData); - result = RETURN_OK; - break; + case (PLOC_SPV::GET_LATCHUP_STATUS_REPORT): { + prepareEmptyCmd(PLOC_SPV::APID_GET_LATCHUP_STATUS_REPORT); + result = RETURN_OK; + break; } - case(PLOC_SPV::SET_DBG_VERBOSITY): { - prepareSetDbgVerbosityCmd(commandData); - result = RETURN_OK; - break; + case (PLOC_SPV::COPY_ADC_DATA_TO_MRAM): { + prepareEmptyCmd(PLOC_SPV::APID_COPY_ADC_DATA_TO_MRAM); + result = RETURN_OK; + break; } - case(PLOC_SPV::CAN_LOOPBACK_TEST): { - prepareEmptyCmd(PLOC_SPV::APID_CAN_LOOPBACK_TEST); - result = RETURN_OK; - break; + case (PLOC_SPV::ENABLE_NVMS): { + prepareEnableNvmsCmd(commandData); + result = RETURN_OK; + break; } - case(PLOC_SPV::SET_GPIO): { - prepareSetGpioCmd(commandData); - result = RETURN_OK; - break; + case (PLOC_SPV::SELECT_NVM): { + prepareSelectNvmCmd(commandData); + result = RETURN_OK; + break; } - case(PLOC_SPV::READ_GPIO): { - prepareReadGpioCmd(commandData); - result = RETURN_OK; - break; + case (PLOC_SPV::RUN_AUTO_EM_TESTS): { + result = prepareRunAutoEmTest(commandData); + break; } - case(PLOC_SPV::RESTART_SUPERVISOR): { - prepareEmptyCmd(PLOC_SPV::APID_RESTART_SUPERVISOR); - result = RETURN_OK; - break; - } - case(PLOC_SPV::FACTORY_RESET_CLEAR_ALL): { - PLOC_SPV::FactoryReset packet(PLOC_SPV::FactoryReset::Op::CLEAR_ALL); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); - result = RETURN_OK; - break; - } - case(PLOC_SPV::FACTORY_RESET_CLEAR_MIRROR): { - PLOC_SPV::FactoryReset packet(PLOC_SPV::FactoryReset::Op::MIRROR_ENTRIES); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); - result = RETURN_OK; - break; - } - case(PLOC_SPV::FACTORY_RESET_CLEAR_CIRCULAR): { - PLOC_SPV::FactoryReset packet(PLOC_SPV::FactoryReset::Op::CIRCULAR_ENTRIES); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); - result = RETURN_OK; - break; - } - case(PLOC_SPV::UPDATE_AVAILABLE): - case(PLOC_SPV::UPDATE_IMAGE_DATA): - case(PLOC_SPV::UPDATE_VERIFY): - // Simply forward data from PLOC Updater to supervisor - std::memcpy(commandBuffer, commandData, commandDataLen); - rawPacket = commandBuffer; - rawPacketLen = commandDataLen; - nextReplyId = PLOC_SPV::ACK_REPORT; - result = RETURN_OK; - break; - default: - sif::debug << "PlocSupervisorHandler::buildCommandFromCommand: Command not implemented" - << std::endl; - result = DeviceHandlerIF::COMMAND_NOT_IMPLEMENTED; - break; - } - - if (result == RETURN_OK) { - /** - * Flushing the receive buffer to make sure there are no data left from a faulty reply. - */ - uartComIf->flushUartRxBuffer(comCookie); - } - - return result; -} - -void PlocSupervisorHandler::fillCommandAndReplyMap() { - this->insertInCommandMap(PLOC_SPV::GET_HK_REPORT); - this->insertInCommandMap(PLOC_SPV::RESTART_MPSOC); - this->insertInCommandMap(PLOC_SPV::START_MPSOC); - this->insertInCommandMap(PLOC_SPV::SHUTDOWN_MPSOC); - this->insertInCommandMap(PLOC_SPV::SEL_MPSOC_BOOT_IMAGE); - this->insertInCommandMap(PLOC_SPV::SET_BOOT_TIMEOUT); - this->insertInCommandMap(PLOC_SPV::SET_MAX_RESTART_TRIES); - this->insertInCommandMap(PLOC_SPV::RESET_MPSOC); - this->insertInCommandMap(PLOC_SPV::SET_TIME_REF); - this->insertInCommandMap(PLOC_SPV::DISABLE_PERIOIC_HK_TRANSMISSION); - this->insertInCommandMap(PLOC_SPV::GET_BOOT_STATUS_REPORT); - this->insertInCommandMap(PLOC_SPV::UPDATE_AVAILABLE); - this->insertInCommandMap(PLOC_SPV::UPDATE_VERIFY); - this->insertInCommandMap(PLOC_SPV::UPDATE_IMAGE_DATA); - this->insertInCommandMap(PLOC_SPV::WATCHDOGS_ENABLE); - this->insertInCommandMap(PLOC_SPV::WATCHDOGS_CONFIG_TIMEOUT); - this->insertInCommandMap(PLOC_SPV::ENABLE_LATCHUP_ALERT); - this->insertInCommandMap(PLOC_SPV::DISABLE_LATCHUP_ALERT); - this->insertInCommandMap(PLOC_SPV::AUTO_CALIBRATE_ALERT); - this->insertInCommandMap(PLOC_SPV::SET_ALERT_LIMIT); - this->insertInCommandMap(PLOC_SPV::SET_ALERT_IRQ_FILTER); - this->insertInCommandMap(PLOC_SPV::SET_ADC_SWEEP_PERIOD); - this->insertInCommandMap(PLOC_SPV::SET_ADC_ENABLED_CHANNELS); - this->insertInCommandMap(PLOC_SPV::SET_ADC_WINDOW_AND_STRIDE); - this->insertInCommandMap(PLOC_SPV::SET_ADC_THRESHOLD); - this->insertInCommandMap(PLOC_SPV::GET_LATCHUP_STATUS_REPORT); - this->insertInCommandMap(PLOC_SPV::COPY_ADC_DATA_TO_MRAM); - this->insertInCommandMap(PLOC_SPV::ENABLE_NVMS); - this->insertInCommandMap(PLOC_SPV::SELECT_NVM); - this->insertInCommandMap(PLOC_SPV::RUN_AUTO_EM_TESTS); - this->insertInCommandMap(PLOC_SPV::WIPE_MRAM); - this->insertInCommandMap(PLOC_SPV::PRINT_CPU_STATS); - this->insertInCommandMap(PLOC_SPV::SET_DBG_VERBOSITY); - this->insertInCommandMap(PLOC_SPV::SET_GPIO); - this->insertInCommandMap(PLOC_SPV::READ_GPIO); - this->insertInCommandMap(PLOC_SPV::RESTART_SUPERVISOR); - this->insertInCommandMap(PLOC_SPV::FACTORY_RESET_CLEAR_ALL); - this->insertInCommandMap(PLOC_SPV::FACTORY_RESET_CLEAR_MIRROR); - this->insertInCommandMap(PLOC_SPV::FACTORY_RESET_CLEAR_CIRCULAR); - this->insertInCommandMap(PLOC_SPV::CAN_LOOPBACK_TEST); - this->insertInCommandAndReplyMap(PLOC_SPV::FIRST_MRAM_DUMP, 3); - this->insertInCommandAndReplyMap(PLOC_SPV::CONSECUTIVE_MRAM_DUMP, 3); - this->insertInReplyMap(PLOC_SPV::ACK_REPORT, 3, nullptr, PLOC_SPV::SIZE_ACK_REPORT); - this->insertInReplyMap(PLOC_SPV::EXE_REPORT, 3, nullptr, PLOC_SPV::SIZE_EXE_REPORT); - this->insertInReplyMap(PLOC_SPV::HK_REPORT, 3, &hkset, PLOC_SPV::SIZE_HK_REPORT); - this->insertInReplyMap(PLOC_SPV::BOOT_STATUS_REPORT, 3, &bootStatusReport, - PLOC_SPV::SIZE_BOOT_STATUS_REPORT); - this->insertInReplyMap(PLOC_SPV::LATCHUP_REPORT, 3, &latchupStatusReport, - PLOC_SPV::SIZE_LATCHUP_STATUS_REPORT); -} - -ReturnValue_t PlocSupervisorHandler::scanForReply(const uint8_t *start, - size_t remainingSize, DeviceCommandId_t *foundId, size_t *foundLen) { - - if (nextReplyId == PLOC_SPV::FIRST_MRAM_DUMP) { - *foundId = PLOC_SPV::FIRST_MRAM_DUMP; - return parseMramPackets(start, remainingSize, foundLen); - } - else if (nextReplyId == PLOC_SPV::CONSECUTIVE_MRAM_DUMP) { - *foundId = PLOC_SPV::CONSECUTIVE_MRAM_DUMP; - return parseMramPackets(start, remainingSize, foundLen); - } - - ReturnValue_t result = RETURN_OK; - - uint16_t apid = (*(start) << 8 | *(start + 1)) & APID_MASK; - - switch(apid) { - case(PLOC_SPV::APID_ACK_SUCCESS): - *foundLen = PLOC_SPV::SIZE_ACK_REPORT; - *foundId = PLOC_SPV::ACK_REPORT; - break; - case(PLOC_SPV::APID_ACK_FAILURE): - *foundLen = PLOC_SPV::SIZE_ACK_REPORT; - *foundId = PLOC_SPV::ACK_REPORT; - break; - case(PLOC_SPV::APID_HK_REPORT): - *foundLen = PLOC_SPV::SIZE_HK_REPORT; - *foundId = PLOC_SPV::HK_REPORT; - break; - case(PLOC_SPV::APID_BOOT_STATUS_REPORT): - *foundLen = PLOC_SPV::SIZE_BOOT_STATUS_REPORT; - *foundId = PLOC_SPV::BOOT_STATUS_REPORT; - break; - case(PLOC_SPV::APID_LATCHUP_STATUS_REPORT): - *foundLen = PLOC_SPV::SIZE_LATCHUP_STATUS_REPORT; - *foundId = PLOC_SPV::LATCHUP_REPORT; - break; - case(PLOC_SPV::APID_EXE_SUCCESS): - *foundLen = PLOC_SPV::SIZE_EXE_REPORT; - *foundId = PLOC_SPV::EXE_REPORT; - break; - case(PLOC_SPV::APID_EXE_FAILURE): - *foundLen = PLOC_SPV::SIZE_EXE_REPORT; - *foundId = PLOC_SPV::EXE_REPORT; - break; - default: { - sif::debug << "PlocSupervisorHandler::scanForReply: Reply has invalid apid" << std::endl; - *foundLen = remainingSize; - return INVALID_APID; - } - } - - return result; -} - -ReturnValue_t PlocSupervisorHandler::interpretDeviceReply(DeviceCommandId_t id, - const uint8_t *packet) { - - ReturnValue_t result = RETURN_OK; - - switch (id) { - case PLOC_SPV::ACK_REPORT: { - result = handleAckReport(packet); - break; - } - case (PLOC_SPV::HK_REPORT): { - result = handleHkReport(packet); - break; - } - case (PLOC_SPV::BOOT_STATUS_REPORT): { - result = handleBootStatusReport(packet); - break; - } - case (PLOC_SPV::LATCHUP_REPORT): { - result = handleLatchupStatusReport(packet); - break; + case (PLOC_SPV::WIPE_MRAM): { + result = prepareWipeMramCmd(commandData); + break; } case (PLOC_SPV::FIRST_MRAM_DUMP): case (PLOC_SPV::CONSECUTIVE_MRAM_DUMP): - result = handleMramDumpPacket(id); - break; + result = prepareDumpMramCmd(commandData); + break; + case (PLOC_SPV::PRINT_CPU_STATS): { + preparePrintCpuStatsCmd(commandData); + result = RETURN_OK; + break; + } + case (PLOC_SPV::SET_DBG_VERBOSITY): { + prepareSetDbgVerbosityCmd(commandData); + result = RETURN_OK; + break; + } + case (PLOC_SPV::CAN_LOOPBACK_TEST): { + prepareEmptyCmd(PLOC_SPV::APID_CAN_LOOPBACK_TEST); + result = RETURN_OK; + break; + } + case (PLOC_SPV::SET_GPIO): { + prepareSetGpioCmd(commandData); + result = RETURN_OK; + break; + } + case (PLOC_SPV::READ_GPIO): { + prepareReadGpioCmd(commandData); + result = RETURN_OK; + break; + } + case (PLOC_SPV::RESTART_SUPERVISOR): { + prepareEmptyCmd(PLOC_SPV::APID_RESTART_SUPERVISOR); + result = RETURN_OK; + break; + } + case (PLOC_SPV::FACTORY_RESET_CLEAR_ALL): { + PLOC_SPV::FactoryReset packet(PLOC_SPV::FactoryReset::Op::CLEAR_ALL); + packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + result = RETURN_OK; + break; + } + case (PLOC_SPV::FACTORY_RESET_CLEAR_MIRROR): { + PLOC_SPV::FactoryReset packet(PLOC_SPV::FactoryReset::Op::MIRROR_ENTRIES); + packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + result = RETURN_OK; + break; + } + case (PLOC_SPV::FACTORY_RESET_CLEAR_CIRCULAR): { + PLOC_SPV::FactoryReset packet(PLOC_SPV::FactoryReset::Op::CIRCULAR_ENTRIES); + packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + result = RETURN_OK; + break; + } + case (PLOC_SPV::UPDATE_AVAILABLE): + case (PLOC_SPV::UPDATE_IMAGE_DATA): + case (PLOC_SPV::UPDATE_VERIFY): + // Simply forward data from PLOC Updater to supervisor + std::memcpy(commandBuffer, commandData, commandDataLen); + rawPacket = commandBuffer; + rawPacketLen = commandDataLen; + nextReplyId = PLOC_SPV::ACK_REPORT; + result = RETURN_OK; + break; + default: + sif::debug << "PlocSupervisorHandler::buildCommandFromCommand: Command not implemented" + << std::endl; + result = DeviceHandlerIF::COMMAND_NOT_IMPLEMENTED; + break; + } + + if (result == RETURN_OK) { + /** + * Flushing the receive buffer to make sure there are no data left from a faulty reply. + */ + uartComIf->flushUartRxBuffer(comCookie); + } + + return result; +} + +void PlocSupervisorHandler::fillCommandAndReplyMap() { + this->insertInCommandMap(PLOC_SPV::GET_HK_REPORT); + this->insertInCommandMap(PLOC_SPV::RESTART_MPSOC); + this->insertInCommandMap(PLOC_SPV::START_MPSOC); + this->insertInCommandMap(PLOC_SPV::SHUTDOWN_MPSOC); + this->insertInCommandMap(PLOC_SPV::SEL_MPSOC_BOOT_IMAGE); + this->insertInCommandMap(PLOC_SPV::SET_BOOT_TIMEOUT); + this->insertInCommandMap(PLOC_SPV::SET_MAX_RESTART_TRIES); + this->insertInCommandMap(PLOC_SPV::RESET_MPSOC); + this->insertInCommandMap(PLOC_SPV::SET_TIME_REF); + this->insertInCommandMap(PLOC_SPV::DISABLE_PERIOIC_HK_TRANSMISSION); + this->insertInCommandMap(PLOC_SPV::GET_BOOT_STATUS_REPORT); + this->insertInCommandMap(PLOC_SPV::UPDATE_AVAILABLE); + this->insertInCommandMap(PLOC_SPV::UPDATE_VERIFY); + this->insertInCommandMap(PLOC_SPV::UPDATE_IMAGE_DATA); + this->insertInCommandMap(PLOC_SPV::WATCHDOGS_ENABLE); + this->insertInCommandMap(PLOC_SPV::WATCHDOGS_CONFIG_TIMEOUT); + this->insertInCommandMap(PLOC_SPV::ENABLE_LATCHUP_ALERT); + this->insertInCommandMap(PLOC_SPV::DISABLE_LATCHUP_ALERT); + this->insertInCommandMap(PLOC_SPV::AUTO_CALIBRATE_ALERT); + this->insertInCommandMap(PLOC_SPV::SET_ALERT_LIMIT); + this->insertInCommandMap(PLOC_SPV::SET_ALERT_IRQ_FILTER); + this->insertInCommandMap(PLOC_SPV::SET_ADC_SWEEP_PERIOD); + this->insertInCommandMap(PLOC_SPV::SET_ADC_ENABLED_CHANNELS); + this->insertInCommandMap(PLOC_SPV::SET_ADC_WINDOW_AND_STRIDE); + this->insertInCommandMap(PLOC_SPV::SET_ADC_THRESHOLD); + this->insertInCommandMap(PLOC_SPV::GET_LATCHUP_STATUS_REPORT); + this->insertInCommandMap(PLOC_SPV::COPY_ADC_DATA_TO_MRAM); + this->insertInCommandMap(PLOC_SPV::ENABLE_NVMS); + this->insertInCommandMap(PLOC_SPV::SELECT_NVM); + this->insertInCommandMap(PLOC_SPV::RUN_AUTO_EM_TESTS); + this->insertInCommandMap(PLOC_SPV::WIPE_MRAM); + this->insertInCommandMap(PLOC_SPV::PRINT_CPU_STATS); + this->insertInCommandMap(PLOC_SPV::SET_DBG_VERBOSITY); + this->insertInCommandMap(PLOC_SPV::SET_GPIO); + this->insertInCommandMap(PLOC_SPV::READ_GPIO); + this->insertInCommandMap(PLOC_SPV::RESTART_SUPERVISOR); + this->insertInCommandMap(PLOC_SPV::FACTORY_RESET_CLEAR_ALL); + this->insertInCommandMap(PLOC_SPV::FACTORY_RESET_CLEAR_MIRROR); + this->insertInCommandMap(PLOC_SPV::FACTORY_RESET_CLEAR_CIRCULAR); + this->insertInCommandMap(PLOC_SPV::CAN_LOOPBACK_TEST); + this->insertInCommandAndReplyMap(PLOC_SPV::FIRST_MRAM_DUMP, 3); + this->insertInCommandAndReplyMap(PLOC_SPV::CONSECUTIVE_MRAM_DUMP, 3); + this->insertInReplyMap(PLOC_SPV::ACK_REPORT, 3, nullptr, PLOC_SPV::SIZE_ACK_REPORT); + this->insertInReplyMap(PLOC_SPV::EXE_REPORT, 3, nullptr, PLOC_SPV::SIZE_EXE_REPORT); + this->insertInReplyMap(PLOC_SPV::HK_REPORT, 3, &hkset, PLOC_SPV::SIZE_HK_REPORT); + this->insertInReplyMap(PLOC_SPV::BOOT_STATUS_REPORT, 3, &bootStatusReport, + PLOC_SPV::SIZE_BOOT_STATUS_REPORT); + this->insertInReplyMap(PLOC_SPV::LATCHUP_REPORT, 3, &latchupStatusReport, + PLOC_SPV::SIZE_LATCHUP_STATUS_REPORT); +} + +ReturnValue_t PlocSupervisorHandler::scanForReply(const uint8_t* start, size_t remainingSize, + DeviceCommandId_t* foundId, size_t* foundLen) { + if (nextReplyId == PLOC_SPV::FIRST_MRAM_DUMP) { + *foundId = PLOC_SPV::FIRST_MRAM_DUMP; + return parseMramPackets(start, remainingSize, foundLen); + } else if (nextReplyId == PLOC_SPV::CONSECUTIVE_MRAM_DUMP) { + *foundId = PLOC_SPV::CONSECUTIVE_MRAM_DUMP; + return parseMramPackets(start, remainingSize, foundLen); + } + + ReturnValue_t result = RETURN_OK; + + uint16_t apid = (*(start) << 8 | *(start + 1)) & APID_MASK; + + switch (apid) { + case (PLOC_SPV::APID_ACK_SUCCESS): + *foundLen = PLOC_SPV::SIZE_ACK_REPORT; + *foundId = PLOC_SPV::ACK_REPORT; + break; + case (PLOC_SPV::APID_ACK_FAILURE): + *foundLen = PLOC_SPV::SIZE_ACK_REPORT; + *foundId = PLOC_SPV::ACK_REPORT; + break; + case (PLOC_SPV::APID_HK_REPORT): + *foundLen = PLOC_SPV::SIZE_HK_REPORT; + *foundId = PLOC_SPV::HK_REPORT; + break; + case (PLOC_SPV::APID_BOOT_STATUS_REPORT): + *foundLen = PLOC_SPV::SIZE_BOOT_STATUS_REPORT; + *foundId = PLOC_SPV::BOOT_STATUS_REPORT; + break; + case (PLOC_SPV::APID_LATCHUP_STATUS_REPORT): + *foundLen = PLOC_SPV::SIZE_LATCHUP_STATUS_REPORT; + *foundId = PLOC_SPV::LATCHUP_REPORT; + break; + case (PLOC_SPV::APID_EXE_SUCCESS): + *foundLen = PLOC_SPV::SIZE_EXE_REPORT; + *foundId = PLOC_SPV::EXE_REPORT; + break; + case (PLOC_SPV::APID_EXE_FAILURE): + *foundLen = PLOC_SPV::SIZE_EXE_REPORT; + *foundId = PLOC_SPV::EXE_REPORT; + break; + default: { + sif::debug << "PlocSupervisorHandler::scanForReply: Reply has invalid apid" << std::endl; + *foundLen = remainingSize; + return INVALID_APID; + } + } + + return result; +} + +ReturnValue_t PlocSupervisorHandler::interpretDeviceReply(DeviceCommandId_t id, + const uint8_t* packet) { + ReturnValue_t result = RETURN_OK; + + switch (id) { + case PLOC_SPV::ACK_REPORT: { + result = handleAckReport(packet); + break; + } + case (PLOC_SPV::HK_REPORT): { + result = handleHkReport(packet); + break; + } + case (PLOC_SPV::BOOT_STATUS_REPORT): { + result = handleBootStatusReport(packet); + break; + } + case (PLOC_SPV::LATCHUP_REPORT): { + result = handleLatchupStatusReport(packet); + break; + } + case (PLOC_SPV::FIRST_MRAM_DUMP): + case (PLOC_SPV::CONSECUTIVE_MRAM_DUMP): + result = handleMramDumpPacket(id); + break; case (PLOC_SPV::EXE_REPORT): { - result = handleExecutionReport(packet); - break; + result = handleExecutionReport(packet); + break; } default: { - sif::debug << "PlocSupervisorHandler::interpretDeviceReply: Unknown device reply id" << std::endl; - return DeviceHandlerIF::UNKNOWN_DEVICE_REPLY; - } + sif::debug << "PlocSupervisorHandler::interpretDeviceReply: Unknown device reply id" + << std::endl; + return DeviceHandlerIF::UNKNOWN_DEVICE_REPLY; } + } - return result; + return result; } -void PlocSupervisorHandler::setNormalDatapoolEntriesInvalid(){ +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 500; } ReturnValue_t PlocSupervisorHandler::initializeLocalDataPool(localpool::DataPool& localDataPoolMap, - LocalDataPoolManager& poolManager) { + LocalDataPoolManager& poolManager) { + localDataPoolMap.emplace(PLOC_SPV::NUM_TMS, new PoolEntry({0})); + localDataPoolMap.emplace(PLOC_SPV::TEMP_PS, new PoolEntry({0})); + localDataPoolMap.emplace(PLOC_SPV::TEMP_PL, new PoolEntry({0})); + localDataPoolMap.emplace(PLOC_SPV::SOC_STATE, new PoolEntry({0})); + localDataPoolMap.emplace(PLOC_SPV::NVM0_1_STATE, new PoolEntry({0})); + localDataPoolMap.emplace(PLOC_SPV::NVM3_STATE, new PoolEntry({0})); + localDataPoolMap.emplace(PLOC_SPV::MISSION_IO_STATE, new PoolEntry({0})); + localDataPoolMap.emplace(PLOC_SPV::FMC_STATE, new PoolEntry({0})); + localDataPoolMap.emplace(PLOC_SPV::NUM_TCS, new PoolEntry({0})); + localDataPoolMap.emplace(PLOC_SPV::UPTIME, new PoolEntry({0})); + localDataPoolMap.emplace(PLOC_SPV::CPULOAD, new PoolEntry({0})); + localDataPoolMap.emplace(PLOC_SPV::AVAILABLEHEAP, new PoolEntry({0})); - localDataPoolMap.emplace(PLOC_SPV::NUM_TMS, new PoolEntry( { 0 })); - localDataPoolMap.emplace(PLOC_SPV::TEMP_PS, new PoolEntry( { 0 })); - localDataPoolMap.emplace(PLOC_SPV::TEMP_PL, new PoolEntry( { 0 })); - localDataPoolMap.emplace(PLOC_SPV::SOC_STATE, new PoolEntry( { 0 })); - localDataPoolMap.emplace(PLOC_SPV::NVM0_1_STATE, new PoolEntry( { 0 })); - localDataPoolMap.emplace(PLOC_SPV::NVM3_STATE, new PoolEntry( { 0 })); - localDataPoolMap.emplace(PLOC_SPV::MISSION_IO_STATE, new PoolEntry( { 0 })); - localDataPoolMap.emplace(PLOC_SPV::FMC_STATE, new PoolEntry( { 0 })); - localDataPoolMap.emplace(PLOC_SPV::NUM_TCS, new PoolEntry( { 0 })); - localDataPoolMap.emplace(PLOC_SPV::UPTIME, new PoolEntry( { 0 })); - localDataPoolMap.emplace(PLOC_SPV::CPULOAD, new PoolEntry( { 0 })); - localDataPoolMap.emplace(PLOC_SPV::AVAILABLEHEAP, new PoolEntry( { 0 })); + localDataPoolMap.emplace(PLOC_SPV::BOOT_SIGNAL, new PoolEntry({0})); + localDataPoolMap.emplace(PLOC_SPV::RESET_COUNTER, new PoolEntry({0})); + localDataPoolMap.emplace(PLOC_SPV::BOOT_AFTER_MS, new PoolEntry({0})); + localDataPoolMap.emplace(PLOC_SPV::BOOT_TIMEOUT_MS, new PoolEntry({0})); + localDataPoolMap.emplace(PLOC_SPV::ACTIVE_NVM, new PoolEntry({0})); + localDataPoolMap.emplace(PLOC_SPV::BP0_STATE, new PoolEntry({0})); + localDataPoolMap.emplace(PLOC_SPV::BP1_STATE, new PoolEntry({0})); + localDataPoolMap.emplace(PLOC_SPV::BP2_STATE, new PoolEntry({0})); - localDataPoolMap.emplace(PLOC_SPV::BOOT_SIGNAL, new PoolEntry( { 0 })); - localDataPoolMap.emplace(PLOC_SPV::RESET_COUNTER, new PoolEntry( { 0 })); - localDataPoolMap.emplace(PLOC_SPV::BOOT_AFTER_MS, new PoolEntry( { 0 })); - localDataPoolMap.emplace(PLOC_SPV::BOOT_TIMEOUT_MS, new PoolEntry( { 0 })); - localDataPoolMap.emplace(PLOC_SPV::ACTIVE_NVM, new PoolEntry( { 0 })); - localDataPoolMap.emplace(PLOC_SPV::BP0_STATE, new PoolEntry( { 0 })); - localDataPoolMap.emplace(PLOC_SPV::BP1_STATE, new PoolEntry( { 0 })); - localDataPoolMap.emplace(PLOC_SPV::BP2_STATE, new PoolEntry( { 0 })); + localDataPoolMap.emplace(PLOC_SPV::LATCHUP_ID, new PoolEntry({0})); + localDataPoolMap.emplace(PLOC_SPV::CNT0, new PoolEntry({0})); + localDataPoolMap.emplace(PLOC_SPV::CNT1, new PoolEntry({0})); + localDataPoolMap.emplace(PLOC_SPV::CNT2, new PoolEntry({0})); + localDataPoolMap.emplace(PLOC_SPV::CNT3, new PoolEntry({0})); + localDataPoolMap.emplace(PLOC_SPV::CNT4, new PoolEntry({0})); + localDataPoolMap.emplace(PLOC_SPV::CNT5, new PoolEntry({0})); + localDataPoolMap.emplace(PLOC_SPV::CNT6, new PoolEntry({0})); + localDataPoolMap.emplace(PLOC_SPV::LATCHUP_RPT_TIME_SEC, new PoolEntry({0})); + localDataPoolMap.emplace(PLOC_SPV::LATCHUP_RPT_TIME_MIN, new PoolEntry({0})); + localDataPoolMap.emplace(PLOC_SPV::LATCHUP_RPT_TIME_HOUR, new PoolEntry({0})); + localDataPoolMap.emplace(PLOC_SPV::LATCHUP_RPT_TIME_DAY, new PoolEntry({0})); + localDataPoolMap.emplace(PLOC_SPV::LATCHUP_RPT_TIME_MON, new PoolEntry({0})); + localDataPoolMap.emplace(PLOC_SPV::LATCHUP_RPT_TIME_YEAR, new PoolEntry({0})); + localDataPoolMap.emplace(PLOC_SPV::LATCHUP_RPT_TIME_MSEC, new PoolEntry({0})); + localDataPoolMap.emplace(PLOC_SPV::LATCHUP_RPT_TIME_IS_SET, new PoolEntry({0})); - localDataPoolMap.emplace(PLOC_SPV::LATCHUP_ID, new PoolEntry( { 0 })); - localDataPoolMap.emplace(PLOC_SPV::CNT0, new PoolEntry( { 0 })); - localDataPoolMap.emplace(PLOC_SPV::CNT1, new PoolEntry( { 0 })); - localDataPoolMap.emplace(PLOC_SPV::CNT2, new PoolEntry( { 0 })); - localDataPoolMap.emplace(PLOC_SPV::CNT3, new PoolEntry( { 0 })); - localDataPoolMap.emplace(PLOC_SPV::CNT4, new PoolEntry( { 0 })); - localDataPoolMap.emplace(PLOC_SPV::CNT5, new PoolEntry( { 0 })); - localDataPoolMap.emplace(PLOC_SPV::CNT6, new PoolEntry( { 0 })); - localDataPoolMap.emplace(PLOC_SPV::LATCHUP_RPT_TIME_SEC, new PoolEntry( { 0 })); - localDataPoolMap.emplace(PLOC_SPV::LATCHUP_RPT_TIME_MIN, new PoolEntry( { 0 })); - localDataPoolMap.emplace(PLOC_SPV::LATCHUP_RPT_TIME_HOUR, new PoolEntry( { 0 })); - localDataPoolMap.emplace(PLOC_SPV::LATCHUP_RPT_TIME_DAY, new PoolEntry( { 0 })); - localDataPoolMap.emplace(PLOC_SPV::LATCHUP_RPT_TIME_MON, new PoolEntry( { 0 })); - localDataPoolMap.emplace(PLOC_SPV::LATCHUP_RPT_TIME_YEAR, new PoolEntry( { 0 })); - localDataPoolMap.emplace(PLOC_SPV::LATCHUP_RPT_TIME_MSEC, new PoolEntry( { 0 })); - localDataPoolMap.emplace(PLOC_SPV::LATCHUP_RPT_TIME_IS_SET, new PoolEntry( { 0 })); - - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t PlocSupervisorHandler::enableReplyInReplyMap(DeviceCommandMap::iterator command, - uint8_t expectedReplies, bool useAlternateId, - DeviceCommandId_t alternateReplyID) { + uint8_t expectedReplies, + bool useAlternateId, + DeviceCommandId_t alternateReplyID) { + ReturnValue_t result = RETURN_OK; - ReturnValue_t result = RETURN_OK; + uint8_t enabledReplies = 0; - uint8_t enabledReplies = 0; - - switch (command->first) { + switch (command->first) { case PLOC_SPV::GET_HK_REPORT: { - enabledReplies = 3; - result = DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true, - PLOC_SPV::HK_REPORT); - if (result != RETURN_OK) { - sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id " - << PLOC_SPV::HK_REPORT << " not in replyMap" << std::endl; - } - break; + enabledReplies = 3; + result = DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true, + PLOC_SPV::HK_REPORT); + if (result != RETURN_OK) { + sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id " + << PLOC_SPV::HK_REPORT << " not in replyMap" << std::endl; + } + break; } case PLOC_SPV::GET_BOOT_STATUS_REPORT: { - enabledReplies = 3; - result = DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true, - PLOC_SPV::BOOT_STATUS_REPORT); - if (result != RETURN_OK) { - sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id " - << PLOC_SPV::BOOT_STATUS_REPORT << " not in replyMap" << std::endl; - } - break; + enabledReplies = 3; + result = DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true, + PLOC_SPV::BOOT_STATUS_REPORT); + if (result != RETURN_OK) { + sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id " + << PLOC_SPV::BOOT_STATUS_REPORT << " not in replyMap" << std::endl; + } + break; } case PLOC_SPV::GET_LATCHUP_STATUS_REPORT: { - enabledReplies = 3; - result = DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true, - PLOC_SPV::LATCHUP_REPORT); - if (result != RETURN_OK) { - sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id " - << PLOC_SPV::LATCHUP_REPORT << " not in replyMap" << std::endl; - } - break; + enabledReplies = 3; + result = DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true, + PLOC_SPV::LATCHUP_REPORT); + if (result != RETURN_OK) { + sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id " + << PLOC_SPV::LATCHUP_REPORT << " not in replyMap" << std::endl; + } + break; } case PLOC_SPV::FIRST_MRAM_DUMP: { - enabledReplies = 2; // expected replies will be increased in handleMramDumpPacket - result = DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true, - PLOC_SPV::FIRST_MRAM_DUMP); - if (result != RETURN_OK) { - sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id " - << PLOC_SPV::FIRST_MRAM_DUMP << " not in replyMap" << std::endl; - } - break; + enabledReplies = 2; // expected replies will be increased in handleMramDumpPacket + result = DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true, + PLOC_SPV::FIRST_MRAM_DUMP); + if (result != RETURN_OK) { + sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id " + << PLOC_SPV::FIRST_MRAM_DUMP << " not in replyMap" << std::endl; + } + break; } case PLOC_SPV::CONSECUTIVE_MRAM_DUMP: { - enabledReplies = 2; // expected replies will be increased in handleMramDumpPacket - result = DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true, - PLOC_SPV::CONSECUTIVE_MRAM_DUMP); - if (result != RETURN_OK) { - sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id " - << PLOC_SPV::CONSECUTIVE_MRAM_DUMP << " not in replyMap" << std::endl; - } - break; + enabledReplies = 2; // expected replies will be increased in handleMramDumpPacket + result = DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true, + PLOC_SPV::CONSECUTIVE_MRAM_DUMP); + if (result != RETURN_OK) { + sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id " + << PLOC_SPV::CONSECUTIVE_MRAM_DUMP << " not in replyMap" << std::endl; + } + break; } case PLOC_SPV::RESTART_MPSOC: case PLOC_SPV::START_MPSOC: @@ -574,957 +564,948 @@ ReturnValue_t PlocSupervisorHandler::enableReplyInReplyMap(DeviceCommandMap::ite case PLOC_SPV::FACTORY_RESET_CLEAR_CIRCULAR: case PLOC_SPV::REQUEST_LOGGING_DATA: case PLOC_SPV::DISABLE_PERIOIC_HK_TRANSMISSION: - enabledReplies = 2; - break; + enabledReplies = 2; + break; default: - sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Unknown command id" << std::endl; - break; - } + 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, - PLOC_SPV::ACK_REPORT); - if (result != RETURN_OK) { - sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id " - << PLOC_SPV::ACK_REPORT << " not in replyMap" << std::endl; - } + /** + * Every command causes at least one acknowledgment and one execution report. Therefore both + * replies will be enabled here. + */ + result = + DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true, PLOC_SPV::ACK_REPORT); + if (result != RETURN_OK) { + sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id " + << PLOC_SPV::ACK_REPORT << " not in replyMap" << std::endl; + } - result = DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true, - PLOC_SPV::EXE_REPORT); - if (result != RETURN_OK) { - sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id " - << PLOC_SPV::EXE_REPORT << " not in replyMap" << std::endl; - } + result = + DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true, PLOC_SPV::EXE_REPORT); + if (result != RETURN_OK) { + sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id " + << PLOC_SPV::EXE_REPORT << " not in replyMap" << std::endl; + } - return RETURN_OK; + 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 receivedCrc = *(start + foundLen - 2) << 8 | *(start + foundLen - 1); + uint16_t recalculatedCrc = CRC::crc16ccitt(start, foundLen - 2); - uint16_t recalculatedCrc = CRC::crc16ccitt(start, foundLen - 2); + if (receivedCrc != recalculatedCrc) { + return CRC_FAILURE; + } - if (receivedCrc != recalculatedCrc) { - return CRC_FAILURE; - } - - return RETURN_OK; + return RETURN_OK; } ReturnValue_t PlocSupervisorHandler::handleAckReport(const uint8_t* data) { + ReturnValue_t result = RETURN_OK; - ReturnValue_t result = RETURN_OK; + result = verifyPacket(data, PLOC_SPV::SIZE_ACK_REPORT); + if (result == CRC_FAILURE) { + sif::error << "PlocSupervisorHandler::handleAckReport: CRC failure" << std::endl; + nextReplyId = PLOC_SPV::NONE; + replyRawReplyIfnotWiretapped(data, PLOC_SPV::SIZE_ACK_REPORT); + triggerEvent(SUPV_CRC_FAILURE_EVENT); + sendFailureReport(PLOC_SPV::ACK_REPORT, CRC_FAILURE); + disableAllReplies(); + return RETURN_OK; + } - result = verifyPacket(data, PLOC_SPV::SIZE_ACK_REPORT); - if(result == CRC_FAILURE) { - sif::error << "PlocSupervisorHandler::handleAckReport: CRC failure" << std::endl; - nextReplyId = PLOC_SPV::NONE; - replyRawReplyIfnotWiretapped(data, PLOC_SPV::SIZE_ACK_REPORT); - triggerEvent(SUPV_CRC_FAILURE_EVENT); - sendFailureReport(PLOC_SPV::ACK_REPORT, CRC_FAILURE); - disableAllReplies(); - return RETURN_OK; + uint16_t apid = (*(data) << 8 | *(data + 1)) & APID_MASK; + + switch (apid) { + case PLOC_SPV::APID_ACK_FAILURE: { + // TODO: Interpretation of status field in acknowledgment report + sif::debug << "PlocSupervisorHandler::handleAckReport: Received Ack failure report" + << std::endl; + DeviceCommandId_t commandId = getPendingCommand(); + if (commandId != DeviceHandlerIF::NO_COMMAND_ID) { + triggerEvent(SUPV_ACK_FAILURE, commandId); + } + sendFailureReport(PLOC_SPV::ACK_REPORT, RECEIVED_ACK_FAILURE); + disableAllReplies(); + nextReplyId = PLOC_SPV::NONE; + result = IGNORE_REPLY_DATA; + break; } + case PLOC_SPV::APID_ACK_SUCCESS: { + setNextReplyId(); + break; + } + default: { + sif::debug << "PlocSupervisorHandler::handleAckReport: Invalid APID in Ack report" + << std::endl; + result = RETURN_FAILED; + break; + } + } - uint16_t apid = (*(data) << 8 | *(data + 1)) & APID_MASK; - - switch(apid) { - case PLOC_SPV::APID_ACK_FAILURE: { - //TODO: Interpretation of status field in acknowledgment report - sif::debug << "PlocSupervisorHandler::handleAckReport: Received Ack failure report" << std::endl; - DeviceCommandId_t commandId = getPendingCommand(); - if (commandId != DeviceHandlerIF::NO_COMMAND_ID) { - triggerEvent(SUPV_ACK_FAILURE, commandId); - } - sendFailureReport(PLOC_SPV::ACK_REPORT, RECEIVED_ACK_FAILURE); - disableAllReplies(); - nextReplyId = PLOC_SPV::NONE; - result = IGNORE_REPLY_DATA; - break; - } - case PLOC_SPV::APID_ACK_SUCCESS: { - setNextReplyId(); - break; - } - default: { - sif::debug << "PlocSupervisorHandler::handleAckReport: Invalid APID in Ack report" << std::endl; - result = RETURN_FAILED; - break; - } - } - - return result; + return result; } ReturnValue_t PlocSupervisorHandler::handleExecutionReport(const uint8_t* data) { + ReturnValue_t result = RETURN_OK; - ReturnValue_t result = RETURN_OK; + result = verifyPacket(data, PLOC_SPV::SIZE_EXE_REPORT); + if (result == CRC_FAILURE) { + sif::error << "PlocSupervisorHandler::handleExecutionReport: CRC failure" << std::endl; + nextReplyId = PLOC_SPV::NONE; + return result; + } - result = verifyPacket(data, PLOC_SPV::SIZE_EXE_REPORT); - if(result == CRC_FAILURE) { - sif::error << "PlocSupervisorHandler::handleExecutionReport: CRC failure" << std::endl; - nextReplyId = PLOC_SPV::NONE; - return result; - } + uint16_t apid = (*(data) << 8 | *(data + 1)) & APID_MASK; - uint16_t apid = (*(data) << 8 | *(data + 1)) & APID_MASK; - - switch (apid) { + switch (apid) { case (PLOC_SPV::APID_EXE_SUCCESS): { - break; + break; } case (PLOC_SPV::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(PLOC_SPV::EXE_REPORT, RECEIVED_EXE_FAILURE); - disableExeReportReply(); - result = IGNORE_REPLY_DATA; - break; + // 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(PLOC_SPV::EXE_REPORT, RECEIVED_EXE_FAILURE); + disableExeReportReply(); + result = IGNORE_REPLY_DATA; + break; } default: { - sif::error << "PlocSupervisorHandler::handleExecutionReport: Unknown APID" << std::endl; - result = RETURN_FAILED; - break; - } + sif::error << "PlocSupervisorHandler::handleExecutionReport: Unknown APID" << std::endl; + result = RETURN_FAILED; + break; } + } - nextReplyId = PLOC_SPV::NONE; + nextReplyId = PLOC_SPV::NONE; - return result; + return result; } ReturnValue_t PlocSupervisorHandler::handleHkReport(const uint8_t* data) { + ReturnValue_t result = RETURN_OK; - ReturnValue_t result = RETURN_OK; + result = verifyPacket(data, PLOC_SPV::SIZE_HK_REPORT); - result = verifyPacket(data, PLOC_SPV::SIZE_HK_REPORT); + if (result == CRC_FAILURE) { + sif::error << "PlocSupervisorHandler::handleHkReport: Hk report has invalid crc" << std::endl; + } - if(result == CRC_FAILURE) { - sif::error << "PlocSupervisorHandler::handleHkReport: Hk report has invalid crc" - << std::endl; - } + uint16_t offset = PLOC_SPV::DATA_FIELD_OFFSET; + hkset.tempPs = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8 | + *(data + offset + 3); + offset += 4; + hkset.tempPl = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8 | + *(data + offset + 3); + offset += 4; + 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; + hkset.cpuLoad = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8 | + *(data + offset + 3); + offset += 4; + hkset.availableHeap = *(data + offset) << 24 | *(data + offset + 1) << 16 | + *(data + offset + 2) << 8 | *(data + offset + 3); + offset += 4; + hkset.numTcs = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8 | + *(data + offset + 3); + offset += 4; + hkset.numTms = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8 | + *(data + offset + 3); + offset += 4; + hkset.socState = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8 | + *(data + offset + 3); + offset += 4; + hkset.nvm0_1_state = *(data + offset); + offset += 1; + hkset.nvm3_state = *(data + offset); + offset += 1; + hkset.missionIoState = *(data + offset); + offset += 1; + hkset.fmcState = *(data + offset); + offset += 1; - uint16_t offset = PLOC_SPV::DATA_FIELD_OFFSET; - hkset.tempPs = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8 - | *(data + offset + 3); - offset += 4; - hkset.tempPl = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8 - | *(data + offset + 3); - offset += 4; - 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; - hkset.cpuLoad = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8 - | *(data + offset + 3); - offset += 4; - hkset.availableHeap = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8 - | *(data + offset + 3); - offset += 4; - hkset.numTcs = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8 - | *(data + offset + 3); - offset += 4; - hkset.numTms = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8 - | *(data + offset + 3); - offset += 4; - hkset.socState = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8 - | *(data + offset + 3); - offset += 4; - hkset.nvm0_1_state = *(data + offset); - offset += 1; - hkset.nvm3_state = *(data + offset); - offset += 1; - hkset.missionIoState = *(data + offset); - offset += 1; - hkset.fmcState = *(data + offset); - offset += 1; - - nextReplyId = PLOC_SPV::EXE_REPORT; + nextReplyId = PLOC_SPV::EXE_REPORT; #if OBSW_VERBOSE_LEVEL >= 1 && OBSW_DEBUG_PLOC_SUPERVISOR == 1 - sif::info << "PlocSupervisorHandler::handleHkReport: temp_ps: " << hkset.tempPs << std::endl; - sif::info << "PlocSupervisorHandler::handleHkReport: temp_pl: " << hkset.tempPl << std::endl; - sif::info << "PlocSupervisorHandler::handleHkReport: temp_sup: " << hkset.tempSup << std::endl; - sif::info << "PlocSupervisorHandler::handleHkReport: uptime: " << hkset.uptime << std::endl; - sif::info << "PlocSupervisorHandler::handleHkReport: cpu_load: " << hkset.cpuLoad << std::endl; - sif::info << "PlocSupervisorHandler::handleHkReport: available_heap: " << hkset.availableHeap << std::endl; - sif::info << "PlocSupervisorHandler::handleHkReport: num_tcs: " << hkset.numTcs << std::endl; - sif::info << "PlocSupervisorHandler::handleHkReport: num_tms: " << hkset.numTms << std::endl; - sif::info << "PlocSupervisorHandler::handleHkReport: soc_state: " << hkset.socState << std::endl; - sif::info << "PlocSupervisorHandler::handleHkReport: nvm0_1_state: " + sif::info << "PlocSupervisorHandler::handleHkReport: temp_ps: " << hkset.tempPs << std::endl; + sif::info << "PlocSupervisorHandler::handleHkReport: temp_pl: " << hkset.tempPl << std::endl; + sif::info << "PlocSupervisorHandler::handleHkReport: temp_sup: " << hkset.tempSup << std::endl; + sif::info << "PlocSupervisorHandler::handleHkReport: uptime: " << hkset.uptime << std::endl; + sif::info << "PlocSupervisorHandler::handleHkReport: cpu_load: " << hkset.cpuLoad << std::endl; + sif::info << "PlocSupervisorHandler::handleHkReport: available_heap: " << hkset.availableHeap + << std::endl; + sif::info << "PlocSupervisorHandler::handleHkReport: num_tcs: " << hkset.numTcs << std::endl; + sif::info << "PlocSupervisorHandler::handleHkReport: num_tms: " << hkset.numTms << std::endl; + sif::info << "PlocSupervisorHandler::handleHkReport: soc_state: " << hkset.socState << std::endl; + sif::info << "PlocSupervisorHandler::handleHkReport: nvm0_1_state: " << static_cast(hkset.nvm0_1_state.value) << std::endl; - sif::info << "PlocSupervisorHandler::handleHkReport: nvm3_state: " + 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: missoin_io_state: " << static_cast(hkset.missionIoState.value) << std::endl; - sif::info << "PlocSupervisorHandler::handleHkReport: fmc_state: " + sif::info << "PlocSupervisorHandler::handleHkReport: fmc_state: " << static_cast(hkset.fmcState.value) << std::endl; #endif - return result; + return result; } ReturnValue_t PlocSupervisorHandler::handleBootStatusReport(const uint8_t* data) { + ReturnValue_t result = RETURN_OK; - ReturnValue_t result = RETURN_OK; + result = verifyPacket(data, PLOC_SPV::SIZE_BOOT_STATUS_REPORT); - result = verifyPacket(data, PLOC_SPV::SIZE_BOOT_STATUS_REPORT); + if (result == CRC_FAILURE) { + sif::error << "PlocSupervisorHandler::handleBootStatusReport: Boot status report has invalid" + " crc" + << std::endl; + return result; + } - if(result == CRC_FAILURE) { - sif::error << "PlocSupervisorHandler::handleBootStatusReport: Boot status report has invalid" - " crc" << std::endl; - return result; - } + uint16_t offset = PLOC_SPV::DATA_FIELD_OFFSET; + bootStatusReport.bootSignal = *(data + offset); + offset += 1; + bootStatusReport.resetCounter = *(data + offset); + offset += 1; + bootStatusReport.bootAfterMs = *(data + offset) << 24 | *(data + offset + 1) << 16 | + *(data + offset + 2) << 8 | *(data + offset + 3); + offset += 4; + bootStatusReport.bootTimeoutMs = *(data + offset) << 24 | *(data + offset + 1) << 16 | + *(data + offset + 2) << 8 | *(data + offset + 3); + offset += 4; + bootStatusReport.activeNvm = *(data + offset); + offset += 1; + bootStatusReport.bp0State = *(data + offset); + offset += 1; + bootStatusReport.bp1State = *(data + offset); + offset += 1; + bootStatusReport.bp2State = *(data + offset); - uint16_t offset = PLOC_SPV::DATA_FIELD_OFFSET; - bootStatusReport.bootSignal = *(data + offset); - offset += 1; - bootStatusReport.resetCounter = *(data + offset); - offset += 1; - bootStatusReport.bootAfterMs = *(data + offset) << 24 | *(data + offset + 1) << 16 | - *(data + offset + 2) << 8 | *(data + offset + 3); - offset += 4; - bootStatusReport.bootTimeoutMs = *(data + offset) << 24 | *(data + offset + 1) << 16 | - *(data + offset + 2) << 8 | *(data + offset + 3); - offset += 4; - bootStatusReport.activeNvm = *(data + offset); - offset += 1; - bootStatusReport.bp0State = *(data + offset); - offset += 1; - bootStatusReport.bp1State = *(data + offset); - offset += 1; - bootStatusReport.bp2State = *(data + offset); - - nextReplyId = PLOC_SPV::EXE_REPORT; + nextReplyId = PLOC_SPV::EXE_REPORT; #if OBSW_VERBOSE_LEVEL >= 1 && OBSW_DEBUG_PLOC_SUPERVISOR == 1 - sif::info << "PlocSupervisorHandler::handleBootStatusReport: Boot signal: " + sif::info << "PlocSupervisorHandler::handleBootStatusReport: Boot signal: " << static_cast(bootStatusReport.bootSignal.value) << std::endl; - sif::info << "PlocSupervisorHandler::handleBootStatusReport: Reset counter: " + sif::info << "PlocSupervisorHandler::handleBootStatusReport: Reset counter: " << static_cast(bootStatusReport.resetCounter.value) << std::endl; - sif::info << "PlocSupervisorHandler::handleBootStatusReport: BootAfterMs: " + sif::info << "PlocSupervisorHandler::handleBootStatusReport: BootAfterMs: " << bootStatusReport.bootAfterMs << " ms" << std::endl; - sif::info << "PlocSupervisorHandler::handleBootStatusReport: BootTimeoutMs: " + sif::info << "PlocSupervisorHandler::handleBootStatusReport: BootTimeoutMs: " << bootStatusReport.bootTimeoutMs << " ms" << std::endl; - sif::info << "PlocSupervisorHandler::handleBootStatusReport: Active NVM: " + sif::info << "PlocSupervisorHandler::handleBootStatusReport: Active NVM: " << static_cast(bootStatusReport.activeNvm.value) << std::endl; - sif::info << "PlocSupervisorHandler::handleBootStatusReport: BP0: " + sif::info << "PlocSupervisorHandler::handleBootStatusReport: BP0: " << static_cast(bootStatusReport.bp0State.value) << std::endl; - sif::info << "PlocSupervisorHandler::handleBootStatusReport: BP1: " + sif::info << "PlocSupervisorHandler::handleBootStatusReport: BP1: " << static_cast(bootStatusReport.bp1State.value) << std::endl; - sif::info << "PlocSupervisorHandler::handleBootStatusReport: BP2: " + sif::info << "PlocSupervisorHandler::handleBootStatusReport: BP2: " << static_cast(bootStatusReport.bp2State.value) << std::endl; #endif - return result; + return result; } ReturnValue_t PlocSupervisorHandler::handleLatchupStatusReport(const uint8_t* data) { + ReturnValue_t result = RETURN_OK; - ReturnValue_t result = RETURN_OK; + result = verifyPacket(data, PLOC_SPV::SIZE_LATCHUP_STATUS_REPORT); - result = verifyPacket(data, PLOC_SPV::SIZE_LATCHUP_STATUS_REPORT); + if (result == CRC_FAILURE) { + sif::error << "PlocSupervisorHandler::handleLatchupStatusReport: Latchup status report has " + << "invalid crc" << std::endl; + return result; + } - if(result == CRC_FAILURE) { - sif::error << "PlocSupervisorHandler::handleLatchupStatusReport: Latchup status report has " - << "invalid crc" << std::endl; - return result; - } + uint16_t offset = PLOC_SPV::DATA_FIELD_OFFSET; + latchupStatusReport.id = *(data + offset); + offset += 1; + latchupStatusReport.cnt0 = *(data + offset) << 8 | *(data + offset + 1); + offset += 2; + latchupStatusReport.cnt1 = *(data + offset) << 8 | *(data + offset + 1); + offset += 2; + latchupStatusReport.cnt2 = *(data + offset) << 8 | *(data + offset + 1); + offset += 2; + latchupStatusReport.cnt3 = *(data + offset) << 8 | *(data + offset + 1); + offset += 2; + latchupStatusReport.cnt4 = *(data + offset) << 8 | *(data + offset + 1); + offset += 2; + latchupStatusReport.cnt5 = *(data + offset) << 8 | *(data + offset + 1); + 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 offset = PLOC_SPV::DATA_FIELD_OFFSET; - latchupStatusReport.id = *(data + offset); - offset += 1; - latchupStatusReport.cnt0 = *(data + offset) << 8 | *(data + offset + 1); - offset += 2; - latchupStatusReport.cnt1 = *(data + offset) << 8 | *(data + offset + 1); - offset += 2; - latchupStatusReport.cnt2 = *(data + offset) << 8 | *(data + offset + 1); - offset += 2; - latchupStatusReport.cnt3 = *(data + offset) << 8 | *(data + offset + 1); - offset += 2; - latchupStatusReport.cnt4 = *(data + offset) << 8 | *(data + offset + 1); - offset += 2; - latchupStatusReport.cnt5 = *(data + offset) << 8 | *(data + offset + 1); - 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; - - nextReplyId = PLOC_SPV::EXE_REPORT; + nextReplyId = PLOC_SPV::EXE_REPORT; #if OBSW_VERBOSE_LEVEL >= 1 && OBSW_DEBUG_PLOC_SUPERVISOR == 1 - sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: Latchup ID: " + sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: Latchup ID: " << static_cast(latchupStatusReport.id.value) << std::endl; - sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: CNT0: " + sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: CNT0: " << latchupStatusReport.cnt0 << std::endl; - sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: CNT1: " + sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: CNT1: " << latchupStatusReport.cnt1 << std::endl; - sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: CNT2: " + sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: CNT2: " << latchupStatusReport.cnt2 << std::endl; - sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: CNT3: " + sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: CNT3: " << latchupStatusReport.cnt3 << std::endl; - sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: CNT4: " + sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: CNT4: " << latchupStatusReport.cnt4 << std::endl; - sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: CNT5: " + sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: CNT5: " << latchupStatusReport.cnt5 << std::endl; - sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: CNT6: " + sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: CNT6: " << latchupStatusReport.cnt6 << std::endl; - sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: Sec: " + sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: Sec: " << latchupStatusReport.timeSec << std::endl; - sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: Min: " + sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: Min: " << latchupStatusReport.timeMin << std::endl; - sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: Hour: " + sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: Hour: " << latchupStatusReport.timeHour << std::endl; - sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: Day: " + sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: Day: " << latchupStatusReport.timeDay << std::endl; - sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: Mon: " + sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: Mon: " << latchupStatusReport.timeMon << std::endl; - sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: Year: " + sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: Year: " << latchupStatusReport.timeYear << std::endl; - sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: Msec: " + sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: Msec: " << latchupStatusReport.timeMsec << std::endl; - sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: isSet: 0x" - << std::hex << latchupStatusReport.timeMsec << std::dec << std::endl; + sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: isSet: 0x" << std::hex + << latchupStatusReport.timeMsec << std::dec << std::endl; #endif - return result; + return result; } void PlocSupervisorHandler::setNextReplyId() { - switch(getPendingCommand()) { + switch (getPendingCommand()) { case PLOC_SPV::GET_HK_REPORT: - nextReplyId = PLOC_SPV::HK_REPORT; - break; + nextReplyId = PLOC_SPV::HK_REPORT; + break; case PLOC_SPV::GET_BOOT_STATUS_REPORT: - nextReplyId = PLOC_SPV::BOOT_STATUS_REPORT; - break; + nextReplyId = PLOC_SPV::BOOT_STATUS_REPORT; + break; case PLOC_SPV::GET_LATCHUP_STATUS_REPORT: - nextReplyId = PLOC_SPV::LATCHUP_REPORT; - break; + nextReplyId = PLOC_SPV::LATCHUP_REPORT; + break; case PLOC_SPV::FIRST_MRAM_DUMP: - nextReplyId = PLOC_SPV::FIRST_MRAM_DUMP; - break; + nextReplyId = PLOC_SPV::FIRST_MRAM_DUMP; + break; case PLOC_SPV::CONSECUTIVE_MRAM_DUMP: - nextReplyId = PLOC_SPV::CONSECUTIVE_MRAM_DUMP; - break; + nextReplyId = PLOC_SPV::CONSECUTIVE_MRAM_DUMP; + break; default: - /* If no telemetry is expected the next reply is always the execution report */ - nextReplyId = PLOC_SPV::EXE_REPORT; - break; - } + /* If no telemetry is expected the next reply is always the execution report */ + nextReplyId = PLOC_SPV::EXE_REPORT; + break; + } } -size_t PlocSupervisorHandler::getNextReplyLength(DeviceCommandId_t commandId){ - - size_t replyLen = 0; - - if (nextReplyId == PLOC_SPV::NONE) { - return replyLen; - } - - if (nextReplyId == PLOC_SPV::FIRST_MRAM_DUMP - || nextReplyId == PLOC_SPV::CONSECUTIVE_MRAM_DUMP) { - /** - * Try to read 20 MRAM packets. If reply is larger, the packets will be read with the - * next doSendRead call. The command will be as long active as the packet with the sequence - * count indicating the last packet has not been received. - */ - replyLen = PLOC_SPV::MAX_PACKET_SIZE * 20; - return replyLen; - } - - DeviceReplyIter iter = deviceReplyMap.find(nextReplyId); - if (iter != deviceReplyMap.end()) { - if (iter->second.delayCycles == 0) { - /* Reply inactive */ - return replyLen; - } - replyLen = iter->second.replyLen; - } - else { - sif::debug << "PlocSupervisorHandler::getNextReplyLength: No entry for reply with reply id " - << std::hex << nextReplyId << " in deviceReplyMap" << std::endl; - } +size_t PlocSupervisorHandler::getNextReplyLength(DeviceCommandId_t commandId) { + size_t replyLen = 0; + if (nextReplyId == PLOC_SPV::NONE) { return replyLen; + } + + if (nextReplyId == PLOC_SPV::FIRST_MRAM_DUMP || nextReplyId == PLOC_SPV::CONSECUTIVE_MRAM_DUMP) { + /** + * Try to read 20 MRAM packets. If reply is larger, the packets will be read with the + * next doSendRead call. The command will be as long active as the packet with the sequence + * count indicating the last packet has not been received. + */ + replyLen = PLOC_SPV::MAX_PACKET_SIZE * 20; + return replyLen; + } + + DeviceReplyIter iter = deviceReplyMap.find(nextReplyId); + if (iter != deviceReplyMap.end()) { + if (iter->second.delayCycles == 0) { + /* Reply inactive */ + return replyLen; + } + replyLen = iter->second.replyLen; + } else { + sif::debug << "PlocSupervisorHandler::getNextReplyLength: No entry for reply with reply id " + << std::hex << nextReplyId << " in deviceReplyMap" << std::endl; + } + + return replyLen; } -void PlocSupervisorHandler::handleDeviceTM(const uint8_t* data, size_t dataSize, DeviceCommandId_t replyId) { +void PlocSupervisorHandler::handleDeviceTM(const uint8_t* data, size_t dataSize, + DeviceCommandId_t replyId) { + ReturnValue_t result = RETURN_OK; - ReturnValue_t result = RETURN_OK; + if (wiretappingMode == RAW) { + /* Data already sent in doGetRead() */ + return; + } - if (wiretappingMode == RAW) { - /* Data already sent in doGetRead() */ - return; - } + DeviceReplyMap::iterator iter = deviceReplyMap.find(replyId); + if (iter == deviceReplyMap.end()) { + sif::debug << "PlocSupervisorHandler::handleDeviceTM: Unknown reply id" << std::endl; + return; + } + MessageQueueId_t queueId = iter->second.command->second.sendReplyTo; - DeviceReplyMap::iterator iter = deviceReplyMap.find(replyId); - if (iter == deviceReplyMap.end()) { - sif::debug << "PlocSupervisorHandler::handleDeviceTM: Unknown reply id" << std::endl; - return; - } - MessageQueueId_t queueId = iter->second.command->second.sendReplyTo; + if (queueId == NO_COMMANDER) { + return; + } - if (queueId == NO_COMMANDER) { - return; - } - - result = actionHelper.reportData(queueId, replyId, data, dataSize); - if (result != RETURN_OK) { - sif::debug << "PlocSupervisorHandler::handleDeviceTM: Failed to report data" << std::endl; - } + result = actionHelper.reportData(queueId, replyId, data, dataSize); + if (result != RETURN_OK) { + sif::debug << "PlocSupervisorHandler::handleDeviceTM: Failed to report data" << std::endl; + } } void PlocSupervisorHandler::prepareEmptyCmd(uint16_t apid) { - PLOC_SPV::EmptyPacket packet(apid); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + PLOC_SPV::EmptyPacket packet(apid); + packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); } -void PlocSupervisorHandler::prepareSelBootImageCmd(const uint8_t * commandData) { - PLOC_SPV::MPSoCBootSelect packet(*commandData, *(commandData + 1), *(commandData + 2), - *(commandData + 3)); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); +void PlocSupervisorHandler::prepareSelBootImageCmd(const uint8_t* commandData) { + PLOC_SPV::MPSoCBootSelect packet(*commandData, *(commandData + 1), *(commandData + 2), + *(commandData + 3)); + packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); } ReturnValue_t PlocSupervisorHandler::prepareSetTimeRefCmd() { - Clock::TimeOfDay_t time; - ReturnValue_t result = Clock::getDateAndTime(&time); - if (result != RETURN_OK) { - sif::warning << "PlocSupervisorHandler::prepareSetTimeRefCmd: Failed to get current time" - << std::endl; - return GET_TIME_FAILURE; - } - PLOC_SPV::SetTimeRef packet(&time); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); - return RETURN_OK; + Clock::TimeOfDay_t time; + ReturnValue_t result = Clock::getDateAndTime(&time); + if (result != RETURN_OK) { + sif::warning << "PlocSupervisorHandler::prepareSetTimeRefCmd: Failed to get current time" + << std::endl; + return GET_TIME_FAILURE; + } + PLOC_SPV::SetTimeRef packet(&time); + packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + return RETURN_OK; } void PlocSupervisorHandler::prepareDisableHk() { - PLOC_SPV::DisablePeriodicHkTransmission packet; - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + PLOC_SPV::DisablePeriodicHkTransmission packet; + packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); } -void PlocSupervisorHandler::prepareSetBootTimeoutCmd(const uint8_t * commandData) { - uint32_t timeout = *(commandData) << 24 | *(commandData + 1) << 16 | *(commandData + 2) << 8 - | *(commandData + 3); - PLOC_SPV::SetBootTimeout packet(timeout); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); +void PlocSupervisorHandler::prepareSetBootTimeoutCmd(const uint8_t* commandData) { + uint32_t timeout = *(commandData) << 24 | *(commandData + 1) << 16 | *(commandData + 2) << 8 | + *(commandData + 3); + PLOC_SPV::SetBootTimeout packet(timeout); + packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); } -void PlocSupervisorHandler::prepareRestartTriesCmd(const uint8_t * commandData) { - uint8_t restartTries = *(commandData); - PLOC_SPV::SetRestartTries packet(restartTries); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); +void PlocSupervisorHandler::prepareRestartTriesCmd(const uint8_t* commandData) { + uint8_t restartTries = *(commandData); + PLOC_SPV::SetRestartTries packet(restartTries); + 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); - PLOC_SPV::WatchdogsEnable packet(watchdogPs, watchdogPl, watchdogInt); - 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); + PLOC_SPV::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; - } - PLOC_SPV::WatchdogsConfigTimeout packet(watchdog, timeout); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); - return RETURN_OK; +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; + } + PLOC_SPV::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; - } - switch (deviceCommand) { + DeviceCommandId_t deviceCommand) { + ReturnValue_t result = RETURN_OK; + uint8_t latchupId = *commandData; + if (latchupId > 6) { + return INVALID_LATCHUP_ID; + } + switch (deviceCommand) { case (PLOC_SPV::ENABLE_LATCHUP_ALERT): { - PLOC_SPV::LatchupAlert packet(true, latchupId); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); - break; + PLOC_SPV::LatchupAlert packet(true, latchupId); + packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + break; } case (PLOC_SPV::DISABLE_LATCHUP_ALERT): { - PLOC_SPV::LatchupAlert packet(false, latchupId); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); - break; + PLOC_SPV::LatchupAlert packet(false, latchupId); + packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + break; } default: { - sif::debug << "PlocSupervisorHandler::prepareLatchupConfigCmd: Invalid command id" - << std::endl; - result = RETURN_FAILED; - break; + sif::debug << "PlocSupervisorHandler::prepareLatchupConfigCmd: Invalid command id" + << std::endl; + result = RETURN_FAILED; + break; } - } - return result; + } + 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; - } - PLOC_SPV::AutoCalibrateAlert packet(latchupId, mg); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); - return RETURN_OK; + 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; + } + PLOC_SPV::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; - } - PLOC_SPV::SetAlertIrqFilter packet(latchupId, tp, div); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); - return RETURN_OK; + uint8_t latchupId = *commandData; + uint8_t tp = *(commandData + 1); + uint8_t div = *(commandData + 2); + if (latchupId > 6) { + return INVALID_LATCHUP_ID; + } + PLOC_SPV::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; - offset += 1; - uint32_t dutycycle = *(commandData + offset) << 24 | *(commandData + offset + 1) << 16 - | *(commandData + offset + 2) << 8 | *(commandData + offset + 3); - if (latchupId > 6) { - return INVALID_LATCHUP_ID; - } - PLOC_SPV::SetAlertlimit packet(latchupId, dutycycle); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); - return RETURN_OK; + uint8_t offset = 0; + uint8_t latchupId = *commandData; + offset += 1; + uint32_t dutycycle = *(commandData + offset) << 24 | *(commandData + offset + 1) << 16 | + *(commandData + offset + 2) << 8 | *(commandData + offset + 3); + if (latchupId > 6) { + return INVALID_LATCHUP_ID; + } + PLOC_SPV::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; - } - PLOC_SPV::SetAdcSweepPeriod packet(sweepPeriod); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); - return RETURN_OK; + uint32_t sweepPeriod = *(commandData) << 24 | *(commandData + 1) << 16 | *(commandData + 2) << 8 | + *(commandData + 3); + if (sweepPeriod < 21) { + return SWEEP_PERIOD_TOO_SMALL; + } + PLOC_SPV::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); - PLOC_SPV::SetAdcEnabledChannels packet(ch); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + uint16_t ch = *(commandData) << 8 | *(commandData + 1); + PLOC_SPV::SetAdcEnabledChannels packet(ch); + packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); } void PlocSupervisorHandler::prepareSetAdcWindowAndStrideCmd(const uint8_t* commandData) { - uint8_t offset = 0; - uint16_t windowSize = *(commandData + offset) << 8 | *(commandData + offset + 1); - offset += 2; - uint16_t stridingStepSize = *(commandData + offset) << 8 | *(commandData + offset + 1); - PLOC_SPV::SetAdcWindowAndStride packet(windowSize, stridingStepSize); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + uint8_t offset = 0; + uint16_t windowSize = *(commandData + offset) << 8 | *(commandData + offset + 1); + offset += 2; + uint16_t stridingStepSize = *(commandData + offset) << 8 | *(commandData + offset + 1); + PLOC_SPV::SetAdcWindowAndStride packet(windowSize, stridingStepSize); + packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); } void PlocSupervisorHandler::prepareSetAdcThresholdCmd(const uint8_t* commandData) { - uint32_t threshold = *(commandData) << 24 | *(commandData + 1) << 16 | *(commandData + 2) << 8 - | *(commandData + 3); - PLOC_SPV::SetAdcThreshold packet(threshold); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + uint32_t threshold = *(commandData) << 24 | *(commandData + 1) << 16 | *(commandData + 2) << 8 | + *(commandData + 3); + PLOC_SPV::SetAdcThreshold packet(threshold); + packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); } void PlocSupervisorHandler::prepareEnableNvmsCmd(const uint8_t* commandData) { - uint8_t n01 = *commandData; - uint8_t n3 = *(commandData + 1); - PLOC_SPV::EnableNvms packet(n01, n3); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + uint8_t n01 = *commandData; + uint8_t n3 = *(commandData + 1); + PLOC_SPV::EnableNvms packet(n01, n3); + packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); } void PlocSupervisorHandler::prepareSelectNvmCmd(const uint8_t* commandData) { - uint8_t mem = *commandData; - PLOC_SPV::SelectNvm packet(mem); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + uint8_t mem = *commandData; + PLOC_SPV::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; - } - PLOC_SPV::RunAutoEmTests packet(test); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); - return RETURN_OK; + uint8_t test = *commandData; + if (test != 1 && test != 2) { + return INVALID_TEST_PARAM; + } + PLOC_SPV::RunAutoEmTests packet(test); + packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + return RETURN_OK; } ReturnValue_t PlocSupervisorHandler::prepareWipeMramCmd(const uint8_t* commandData) { - uint32_t start = 0; - uint32_t stop = 0; - size_t size = sizeof(start) + sizeof(stop); - SerializeAdapter::deSerialize(&start, &commandData, &size, SerializeIF::Endianness::BIG); - SerializeAdapter::deSerialize(&stop, &commandData, &size, SerializeIF::Endianness::BIG); - if ((stop - start) <= 0) { - return INVALID_MRAM_ADDRESSES; - } - PLOC_SPV::MramCmd packet(start, stop, PLOC_SPV::MramCmd::MramAction::WIPE); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); - return RETURN_OK; + uint32_t start = 0; + uint32_t stop = 0; + size_t size = sizeof(start) + sizeof(stop); + SerializeAdapter::deSerialize(&start, &commandData, &size, SerializeIF::Endianness::BIG); + SerializeAdapter::deSerialize(&stop, &commandData, &size, SerializeIF::Endianness::BIG); + if ((stop - start) <= 0) { + return INVALID_MRAM_ADDRESSES; + } + PLOC_SPV::MramCmd packet(start, stop, PLOC_SPV::MramCmd::MramAction::WIPE); + packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + return RETURN_OK; } ReturnValue_t PlocSupervisorHandler::prepareDumpMramCmd(const uint8_t* commandData) { - uint32_t start = 0; - uint32_t stop = 0; - size_t size = sizeof(start) + sizeof(stop); - SerializeAdapter::deSerialize(&start, &commandData, &size, SerializeIF::Endianness::BIG); - SerializeAdapter::deSerialize(&stop, &commandData, &size, SerializeIF::Endianness::BIG); - PLOC_SPV::MramCmd packet(start, stop, PLOC_SPV::MramCmd::MramAction::DUMP); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); - if ((stop - start) <= 0) { - return INVALID_MRAM_ADDRESSES; - } - expectedMramDumpPackets = (stop - start) / PLOC_SPV::MAX_DATA_CAPACITY; - if ((stop - start) % PLOC_SPV::MAX_DATA_CAPACITY) { - expectedMramDumpPackets++; - } - receivedMramDumpPackets = 0; - return RETURN_OK; + uint32_t start = 0; + uint32_t stop = 0; + size_t size = sizeof(start) + sizeof(stop); + SerializeAdapter::deSerialize(&start, &commandData, &size, SerializeIF::Endianness::BIG); + SerializeAdapter::deSerialize(&stop, &commandData, &size, SerializeIF::Endianness::BIG); + PLOC_SPV::MramCmd packet(start, stop, PLOC_SPV::MramCmd::MramAction::DUMP); + packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + if ((stop - start) <= 0) { + return INVALID_MRAM_ADDRESSES; + } + expectedMramDumpPackets = (stop - start) / PLOC_SPV::MAX_DATA_CAPACITY; + if ((stop - start) % PLOC_SPV::MAX_DATA_CAPACITY) { + expectedMramDumpPackets++; + } + receivedMramDumpPackets = 0; + return RETURN_OK; } void PlocSupervisorHandler::preparePrintCpuStatsCmd(const uint8_t* commandData) { - uint8_t en = *commandData; - PLOC_SPV::PrintCpuStats packet(en); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + uint8_t en = *commandData; + PLOC_SPV::PrintCpuStats packet(en); + packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); } void PlocSupervisorHandler::prepareSetDbgVerbosityCmd(const uint8_t* commandData) { - uint8_t vb = *commandData; - PLOC_SPV::SetDbgVerbosity packet(vb); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + uint8_t vb = *commandData; + PLOC_SPV::SetDbgVerbosity packet(vb); + packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); } void PlocSupervisorHandler::prepareSetGpioCmd(const uint8_t* commandData) { - uint8_t port = *commandData; - uint8_t pin = *(commandData + 1); - uint8_t val = *(commandData + 2); - PLOC_SPV::SetGpio packet(port, pin, val); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + uint8_t port = *commandData; + uint8_t pin = *(commandData + 1); + uint8_t val = *(commandData + 2); + PLOC_SPV::SetGpio packet(port, pin, val); + packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); } void PlocSupervisorHandler::prepareReadGpioCmd(const uint8_t* commandData) { - uint8_t port = *commandData; - uint8_t pin = *(commandData + 1); - PLOC_SPV::ReadGpio packet(port, pin); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + uint8_t port = *commandData; + uint8_t pin = *(commandData + 1); + PLOC_SPV::ReadGpio packet(port, pin); + packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); } void PlocSupervisorHandler::packetToOutBuffer(uint8_t* packetData, size_t fullSize) { - memcpy(commandBuffer, packetData, fullSize); - rawPacket = commandBuffer; - rawPacketLen = fullSize; - nextReplyId = PLOC_SPV::ACK_REPORT; + memcpy(commandBuffer, packetData, fullSize); + rawPacket = commandBuffer; + rawPacketLen = fullSize; + nextReplyId = PLOC_SPV::ACK_REPORT; } void PlocSupervisorHandler::disableAllReplies() { + DeviceReplyMap::iterator iter; - DeviceReplyMap::iterator iter; + /* Disable ack reply */ + iter = deviceReplyMap.find(PLOC_SPV::ACK_REPORT); + DeviceReplyInfo* info = &(iter->second); + info->delayCycles = 0; + info->command = deviceCommandMap.end(); - /* Disable ack reply */ - iter = deviceReplyMap.find(PLOC_SPV::ACK_REPORT); - DeviceReplyInfo *info = &(iter->second); - info->delayCycles = 0; - info->command = deviceCommandMap.end(); + DeviceCommandId_t commandId = getPendingCommand(); - DeviceCommandId_t commandId = getPendingCommand(); - - /* If the command expects a telemetry packet the appropriate tm reply will be disabled here */ - switch (commandId) { + /* If the command expects a telemetry packet the appropriate tm reply will be disabled here */ + switch (commandId) { case PLOC_SPV::GET_HK_REPORT: { - iter = deviceReplyMap.find(PLOC_SPV::GET_HK_REPORT); - info = &(iter->second); - info->delayCycles = 0; - info->command = deviceCommandMap.end(); - break; + iter = deviceReplyMap.find(PLOC_SPV::GET_HK_REPORT); + info = &(iter->second); + info->delayCycles = 0; + info->command = deviceCommandMap.end(); + break; } default: { - break; - } + break; } + } - /* We must always disable the execution report reply here */ - disableExeReportReply(); + /* We must always disable the execution report reply here */ + disableExeReportReply(); } void PlocSupervisorHandler::sendFailureReport(DeviceCommandId_t replyId, ReturnValue_t status) { + DeviceReplyIter iter = deviceReplyMap.find(replyId); - DeviceReplyIter iter = deviceReplyMap.find(replyId); + if (iter == deviceReplyMap.end()) { + sif::debug << "PlocSupervisorHandler::sendFailureReport: Reply not in reply map" << std::endl; + return; + } - if (iter == deviceReplyMap.end()) { - sif::debug << "PlocSupervisorHandler::sendFailureReport: Reply not in reply map" << std::endl; - return; - } + DeviceCommandInfo* info = &(iter->second.command->second); - DeviceCommandInfo* info = &(iter->second.command->second); + if (info == nullptr) { + sif::debug << "PlocSupervisorHandler::sendFailureReport: Reply has no active command" + << std::endl; + return; + } - if (info == nullptr) { - sif::debug << "PlocSupervisorHandler::sendFailureReport: Reply has no active command" << std::endl; - return; - } - - if (info->sendReplyTo != NO_COMMANDER) { - actionHelper.finish(false, info->sendReplyTo, iter->first, status); - } - info->isExecuting = false; + if (info->sendReplyTo != NO_COMMANDER) { + actionHelper.finish(false, info->sendReplyTo, iter->first, status); + } + info->isExecuting = false; } void PlocSupervisorHandler::disableExeReportReply() { - DeviceReplyIter iter = deviceReplyMap.find(PLOC_SPV::EXE_REPORT); - DeviceReplyInfo *info = &(iter->second); - info->delayCycles = 0; - info->command = deviceCommandMap.end(); - /* Expected replies is set to one here. The value will set to 0 in replyToReply() */ - info->command->second.expectedReplies = 1; + DeviceReplyIter iter = deviceReplyMap.find(PLOC_SPV::EXE_REPORT); + DeviceReplyInfo* info = &(iter->second); + info->delayCycles = 0; + info->command = deviceCommandMap.end(); + /* Expected replies is set to one here. The value will set to 0 in replyToReply() */ + info->command->second.expectedReplies = 1; } -ReturnValue_t PlocSupervisorHandler::parseMramPackets(const uint8_t *packet, size_t remainingSize, - size_t* foundLen) { - ReturnValue_t result = IGNORE_FULL_PACKET; - uint16_t packetLen = 0; - *foundLen = 0; +ReturnValue_t PlocSupervisorHandler::parseMramPackets(const uint8_t* packet, size_t remainingSize, + size_t* foundLen) { + ReturnValue_t result = IGNORE_FULL_PACKET; + uint16_t packetLen = 0; + *foundLen = 0; - for (size_t idx = 0; idx < remainingSize; idx++) { - std::memcpy(spacePacketBuffer + bufferTop, packet + idx, 1); - bufferTop += 1; - *foundLen += 1; - if (bufferTop >= PLOC_SPV::SPACE_PACKET_HEADER_LENGTH) { - packetLen = readSpacePacketLength(spacePacketBuffer); - } - - if (bufferTop == PLOC_SPV::SPACE_PACKET_HEADER_LENGTH + packetLen + 1) { - packetInBuffer = true; - bufferTop = 0; - return checkMramPacketApid(); - } - - if (bufferTop == PLOC_SPV::MAX_PACKET_SIZE) { - *foundLen = remainingSize; - disableAllReplies(); - bufferTop = 0; - return MRAM_PACKET_PARSING_FAILURE; - } + for (size_t idx = 0; idx < remainingSize; idx++) { + std::memcpy(spacePacketBuffer + bufferTop, packet + idx, 1); + bufferTop += 1; + *foundLen += 1; + if (bufferTop >= PLOC_SPV::SPACE_PACKET_HEADER_LENGTH) { + packetLen = readSpacePacketLength(spacePacketBuffer); } - return result; + if (bufferTop == PLOC_SPV::SPACE_PACKET_HEADER_LENGTH + packetLen + 1) { + packetInBuffer = true; + bufferTop = 0; + return checkMramPacketApid(); + } + + if (bufferTop == PLOC_SPV::MAX_PACKET_SIZE) { + *foundLen = remainingSize; + disableAllReplies(); + bufferTop = 0; + return MRAM_PACKET_PARSING_FAILURE; + } + } + + return result; } ReturnValue_t PlocSupervisorHandler::handleMramDumpPacket(DeviceCommandId_t id) { + ReturnValue_t result = RETURN_FAILED; - ReturnValue_t result = RETURN_FAILED; - - // Prepare packet for downlink - if (packetInBuffer) { - uint16_t packetLen = readSpacePacketLength(spacePacketBuffer); - result = verifyPacket(spacePacketBuffer, PLOC_SPV::SPACE_PACKET_HEADER_LENGTH + packetLen + 1); - if (result != RETURN_OK) { - sif::warning << "PlocSupervisorHandler::handleMramDumpPacket: CRC failure" << std::endl; - return result; - } - handleMramDumpFile(id); - if (downlinkMramDump == true) { - handleDeviceTM(spacePacketBuffer + PLOC_SPV::SPACE_PACKET_HEADER_LENGTH, packetLen - 1, - id); - } - packetInBuffer = false; - receivedMramDumpPackets++; - if (expectedMramDumpPackets == receivedMramDumpPackets) { - nextReplyId = PLOC_SPV::EXE_REPORT; - } - increaseExpectedMramReplies(id); - return RETURN_OK; + // Prepare packet for downlink + if (packetInBuffer) { + uint16_t packetLen = readSpacePacketLength(spacePacketBuffer); + result = verifyPacket(spacePacketBuffer, PLOC_SPV::SPACE_PACKET_HEADER_LENGTH + packetLen + 1); + if (result != RETURN_OK) { + sif::warning << "PlocSupervisorHandler::handleMramDumpPacket: CRC failure" << std::endl; + return result; } - return result; + handleMramDumpFile(id); + if (downlinkMramDump == true) { + handleDeviceTM(spacePacketBuffer + PLOC_SPV::SPACE_PACKET_HEADER_LENGTH, packetLen - 1, id); + } + packetInBuffer = false; + receivedMramDumpPackets++; + if (expectedMramDumpPackets == receivedMramDumpPackets) { + nextReplyId = PLOC_SPV::EXE_REPORT; + } + increaseExpectedMramReplies(id); + return RETURN_OK; + } + return result; } void PlocSupervisorHandler::increaseExpectedMramReplies(DeviceCommandId_t id) { - DeviceReplyMap::iterator mramDumpIter = deviceReplyMap.find(id); - DeviceReplyMap::iterator exeReportIter = deviceReplyMap.find(PLOC_SPV::EXE_REPORT); - if (mramDumpIter == deviceReplyMap.end()) { - sif::debug << "PlocSupervisorHandler::increaseExpectedMramReplies: Dump MRAM reply not " - << "in reply map" << std::endl; - return; - } - if (exeReportIter == deviceReplyMap.end()) { - sif::debug << "PlocSupervisorHandler::increaseExpectedMramReplies: Execution report not " - << "in reply map" << std::endl; - return; - } - DeviceReplyInfo *mramReplyInfo = &(mramDumpIter->second); - if (mramReplyInfo == nullptr) { - sif::debug << "PlocSupervisorHandler::increaseExpectedReplies: MRAM reply info nullptr" - << std::endl; - return; - } - DeviceReplyInfo *exeReplyInfo = &(exeReportIter->second); - if (exeReplyInfo == nullptr) { - sif::debug << "PlocSupervisorHandler::increaseExpectedReplies: Execution reply info" - << " nullptr" << std::endl; - return; - } - DeviceCommandInfo* info = &(mramReplyInfo->command->second); - if (info == nullptr){ - sif::debug << "PlocSupervisorHandler::increaseExpectedReplies: Command info nullptr" - << std::endl; - return; - } - uint8_t sequenceFlags = spacePacketBuffer[2] >> 6; - if (sequenceFlags != static_cast(PLOC_SPV::SequenceFlags::LAST_PKT) - && (sequenceFlags != static_cast(PLOC_SPV::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; - } - else { - // Command expects the execution report - info->expectedReplies = 1; - mramReplyInfo->delayCycles = 0; - } + DeviceReplyMap::iterator mramDumpIter = deviceReplyMap.find(id); + DeviceReplyMap::iterator exeReportIter = deviceReplyMap.find(PLOC_SPV::EXE_REPORT); + if (mramDumpIter == deviceReplyMap.end()) { + sif::debug << "PlocSupervisorHandler::increaseExpectedMramReplies: Dump MRAM reply not " + << "in reply map" << std::endl; return; + } + if (exeReportIter == deviceReplyMap.end()) { + sif::debug << "PlocSupervisorHandler::increaseExpectedMramReplies: Execution report not " + << "in reply map" << std::endl; + return; + } + DeviceReplyInfo* mramReplyInfo = &(mramDumpIter->second); + if (mramReplyInfo == nullptr) { + sif::debug << "PlocSupervisorHandler::increaseExpectedReplies: MRAM reply info nullptr" + << std::endl; + return; + } + DeviceReplyInfo* exeReplyInfo = &(exeReportIter->second); + if (exeReplyInfo == nullptr) { + sif::debug << "PlocSupervisorHandler::increaseExpectedReplies: Execution reply info" + << " nullptr" << std::endl; + return; + } + DeviceCommandInfo* info = &(mramReplyInfo->command->second); + if (info == nullptr) { + sif::debug << "PlocSupervisorHandler::increaseExpectedReplies: Command info nullptr" + << std::endl; + return; + } + uint8_t sequenceFlags = spacePacketBuffer[2] >> 6; + if (sequenceFlags != static_cast(PLOC_SPV::SequenceFlags::LAST_PKT) && + (sequenceFlags != static_cast(PLOC_SPV::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; + } else { + // Command expects the execution report + info->expectedReplies = 1; + mramReplyInfo->delayCycles = 0; + } + return; } ReturnValue_t PlocSupervisorHandler::checkMramPacketApid() { - uint16_t apid = (spacePacketBuffer[0] << 8 | spacePacketBuffer[1]) & PLOC_SPV::APID_MASK; - if (apid != PLOC_SPV::APID_MRAM_DUMP_TM) { - return NO_MRAM_PACKET; - } - return APERIODIC_REPLY; + uint16_t apid = (spacePacketBuffer[0] << 8 | spacePacketBuffer[1]) & PLOC_SPV::APID_MASK; + if (apid != PLOC_SPV::APID_MRAM_DUMP_TM) { + return NO_MRAM_PACKET; + } + return APERIODIC_REPLY; } ReturnValue_t PlocSupervisorHandler::handleMramDumpFile(DeviceCommandId_t id) { - ReturnValue_t result = RETURN_OK; - uint16_t packetLen = readSpacePacketLength(spacePacketBuffer); - uint8_t sequenceFlags = readSequenceFlags(spacePacketBuffer); - if (id == PLOC_SPV::FIRST_MRAM_DUMP) { - if (sequenceFlags == static_cast(PLOC_SPV::SequenceFlags::FIRST_PKT) - || (sequenceFlags == static_cast(PLOC_SPV::SequenceFlags::STANDALONE_PKT))) { - result = createMramDumpFile(); - if (result != RETURN_OK) { - return result; - } - } + ReturnValue_t result = RETURN_OK; + uint16_t packetLen = readSpacePacketLength(spacePacketBuffer); + uint8_t sequenceFlags = readSequenceFlags(spacePacketBuffer); + if (id == PLOC_SPV::FIRST_MRAM_DUMP) { + if (sequenceFlags == static_cast(PLOC_SPV::SequenceFlags::FIRST_PKT) || + (sequenceFlags == static_cast(PLOC_SPV::SequenceFlags::STANDALONE_PKT))) { + result = createMramDumpFile(); + if (result != RETURN_OK) { + return result; + } } - if (not std::filesystem::exists(activeMramFile)) { - sif::warning << "PlocSupervisorHandler::handleMramDumpFile: MRAM file does not exist" - << std::endl; - return MRAM_FILE_NOT_EXISTS; - } - std::ofstream file(activeMramFile, std::ios_base::app | std::ios_base::out); - file.write( - reinterpret_cast(spacePacketBuffer + PLOC_SPV::SPACE_PACKET_HEADER_LENGTH), - packetLen - 1); - file.close(); - return RETURN_OK; + } + if (not std::filesystem::exists(activeMramFile)) { + sif::warning << "PlocSupervisorHandler::handleMramDumpFile: MRAM file does not exist" + << std::endl; + return MRAM_FILE_NOT_EXISTS; + } + std::ofstream file(activeMramFile, std::ios_base::app | std::ios_base::out); + file.write( + reinterpret_cast(spacePacketBuffer + PLOC_SPV::SPACE_PACKET_HEADER_LENGTH), + packetLen - 1); + file.close(); + return RETURN_OK; } uint16_t PlocSupervisorHandler::readSpacePacketLength(uint8_t* spacePacket) { - return spacePacket[4] << 8 | spacePacket[5]; + return spacePacket[4] << 8 | spacePacket[5]; } uint8_t PlocSupervisorHandler::readSequenceFlags(uint8_t* spacePacket) { - return spacePacketBuffer[2] >> 6; + return spacePacketBuffer[2] >> 6; } ReturnValue_t PlocSupervisorHandler::createMramDumpFile() { - ReturnValue_t result = RETURN_OK; - std::string timeStamp; - result = getTimeStampString(timeStamp); - if (result != RETURN_OK) { - return result; - } + ReturnValue_t result = RETURN_OK; + std::string timeStamp; + result = getTimeStampString(timeStamp); + if (result != RETURN_OK) { + return result; + } - std::string filename = "mram-dump--" + timeStamp + ".bin"; + std::string filename = "mram-dump--" + timeStamp + ".bin"; #if BOARD_TE0720 == 0 - std::string currentMountPrefix = sdcMan->getCurrentMountPrefix(); + std::string currentMountPrefix = sdcMan->getCurrentMountPrefix(); #else - std::string currentMountPrefix("/mnt/sd0"); + 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" - << std::endl; - return PATH_DOES_NOT_EXIST; - } - activeMramFile = currentMountPrefix + "/" + plocFilePath + "/" + filename; - // Create new file - std::ofstream file(activeMramFile, std::ios_base::out); - file.close(); + // 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" + << std::endl; + return PATH_DOES_NOT_EXIST; + } + activeMramFile = currentMountPrefix + "/" + plocFilePath + "/" + filename; + // Create new file + std::ofstream file(activeMramFile, std::ios_base::out); + file.close(); - return RETURN_OK; + return RETURN_OK; } 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" - << std::endl; - return 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; + Clock::TimeOfDay_t time; + ReturnValue_t result = Clock::getDateAndTime(&time); + if (result != RETURN_OK) { + sif::warning << "PlocSupervisorHandler::createMramDumpFile: Failed to get current time" + << std::endl; + return 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; } diff --git a/bsp_q7s/devices/PlocSupervisorHandler.h b/bsp_q7s/devices/PlocSupervisorHandler.h index f22c86b1..1a77af6a 100644 --- a/bsp_q7s/devices/PlocSupervisorHandler.h +++ b/bsp_q7s/devices/PlocSupervisorHandler.h @@ -1,12 +1,13 @@ #ifndef MISSION_DEVICES_PLOCSUPERVISORHANDLER_H_ #define MISSION_DEVICES_PLOCSUPERVISORHANDLER_H_ -#include "devicedefinitions/PlocSupervisorDefinitions.h" +#include "OBSWConfig.h" #include - #include #include +#include "devicedefinitions/PlocSupervisorDefinitions.h" + /** * @brief This is the device handler for the supervisor of the PLOC which is programmed by * Thales. @@ -19,324 +20,327 @@ * Arbeitsdaten/08_Used%20Components/PLOC&fileid=940960 * @author J. Meier */ -class PlocSupervisorHandler: public DeviceHandlerBase { -public: +class PlocSupervisorHandler : public DeviceHandlerBase { + public: + PlocSupervisorHandler(object_id_t objectId, object_id_t uartComIFid, CookieIF* comCookie); + virtual ~PlocSupervisorHandler(); - PlocSupervisorHandler(object_id_t objectId, object_id_t uartComIFid, CookieIF * comCookie); - virtual ~PlocSupervisorHandler(); + virtual ReturnValue_t initialize() override; - virtual ReturnValue_t initialize() override; + protected: + void doStartUp() override; + void doShutDown() override; + ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t* id) override; + ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t* id) override; + void fillCommandAndReplyMap() override; + ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t* commandData, + size_t commandDataLen) override; + ReturnValue_t scanForReply(const uint8_t* start, size_t remainingSize, DeviceCommandId_t* foundId, + size_t* foundLen) override; + ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t* packet) override; + void setNormalDatapoolEntriesInvalid() override; + uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override; + ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, + LocalDataPoolManager& poolManager) override; + ReturnValue_t enableReplyInReplyMap(DeviceCommandMap::iterator command, + uint8_t expectedReplies = 1, bool useAlternateId = false, + DeviceCommandId_t alternateReplyID = 0) override; + size_t getNextReplyLength(DeviceCommandId_t deviceCommand) override; -protected: - void doStartUp() override; - void doShutDown() override; - ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t * id) override; - ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t * id) override; - void fillCommandAndReplyMap() override; - ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, - const uint8_t * commandData,size_t commandDataLen) override; - ReturnValue_t scanForReply(const uint8_t *start, size_t remainingSize, - DeviceCommandId_t *foundId, size_t *foundLen) override; - ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, - const uint8_t *packet) override; - void setNormalDatapoolEntriesInvalid() override; - uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override; - ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, - LocalDataPoolManager& poolManager) override; - ReturnValue_t enableReplyInReplyMap(DeviceCommandMap::iterator command, - uint8_t expectedReplies = 1, bool useAlternateId = false, - DeviceCommandId_t alternateReplyID = 0) override; - size_t getNextReplyLength(DeviceCommandId_t deviceCommand) override; + private: + static const uint8_t INTERFACE_ID = CLASS_ID::PLOC_SUPERVISOR_HANDLER; -private: + //! [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] Invalid communication interface specified + static const ReturnValue_t INVALID_UART_COM_IF = MAKE_RETURN_CODE(0xA5); + //! [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(0xA6); + //! [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(0xA7); + //! [EXPORT] : [COMMENT] Received latchup config command with invalid latchup ID + static const ReturnValue_t INVALID_LATCHUP_ID = MAKE_RETURN_CODE(0xA8); + //! [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(0xA9); + //! [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(0xAA); + //! [EXPORT] : [COMMENT] Returned when scanning for MRAM dump packets failed. + static const ReturnValue_t MRAM_PACKET_PARSING_FAILURE = MAKE_RETURN_CODE(0xAB); + //! [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(0xAC); + //! [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(0xAD); + //! [EXPORT] : [COMMENT] Path to PLOC directory on SD card does not exist + static const ReturnValue_t PATH_DOES_NOT_EXIST = MAKE_RETURN_CODE(0xAE); + //! [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(0xAF); - static const uint8_t INTERFACE_ID = CLASS_ID::PLOC_SUPERVISOR_HANDLER; + static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_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] Invalid communication interface specified - static const ReturnValue_t INVALID_UART_COM_IF = MAKE_RETURN_CODE(0xA5); - //! [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(0xA6); - //! [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(0xA7); - //! [EXPORT] : [COMMENT] Received latchup config command with invalid latchup ID - static const ReturnValue_t INVALID_LATCHUP_ID = MAKE_RETURN_CODE(0xA8); - //! [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(0xA9); - //! [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(0xAA); - //! [EXPORT] : [COMMENT] Returned when scanning for MRAM dump packets failed. - static const ReturnValue_t MRAM_PACKET_PARSING_FAILURE = MAKE_RETURN_CODE(0xAB); - //! [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(0xAC); - //! [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(0xAD); - //! [EXPORT] : [COMMENT] Path to PLOC directory on SD card does not exist - static const ReturnValue_t PATH_DOES_NOT_EXIST = MAKE_RETURN_CODE(0xAE); - //! [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(0xAF); + //! [EXPORT] : [COMMENT] PLOC supervisor crc failure in telemetry packet + static const Event SUPV_MEMORY_READ_RPT_CRC_FAILURE = MAKE_EVENT(1, severity::LOW); + //! [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 + 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); - static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PLOC_SUPERVISOR_HANDLER; + static const uint16_t APID_MASK = 0x7FF; + static const uint16_t PACKET_SEQUENCE_COUNT_MASK = 0x3FFF; - //! [EXPORT] : [COMMENT] PLOC supervisor crc failure in telemetry packet - static const Event SUPV_MEMORY_READ_RPT_CRC_FAILURE = MAKE_EVENT(1, severity::LOW); - //! [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 - 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); + uint8_t commandBuffer[PLOC_SPV::MAX_COMMAND_SIZE]; - static const uint16_t APID_MASK = 0x7FF; - static const uint16_t PACKET_SEQUENCE_COUNT_MASK = 0x3FFF; + /** + * This variable is used to store the id of the next reply to receive. This is necessary + * because the PLOC sends as reply to each command at least one acknowledgment and execution + * report. + */ + DeviceCommandId_t nextReplyId = PLOC_SPV::NONE; - uint8_t commandBuffer[PLOC_SPV::MAX_COMMAND_SIZE]; + UartComIF* uartComIf = nullptr; - /** - * This variable is used to store the id of the next reply to receive. This is necessary - * because the PLOC sends as reply to each command at least one acknowledgment and execution - * report. - */ - DeviceCommandId_t nextReplyId = PLOC_SPV::NONE; + PLOC_SPV::HkSet hkset; + PLOC_SPV::BootStatusReport bootStatusReport; + PLOC_SPV::LatchupStatusReport latchupStatusReport; - UartComIF* uartComIf = nullptr; + /** Number of expected replies following the MRAM dump command */ + uint32_t expectedMramDumpPackets = 0; + uint32_t receivedMramDumpPackets = 0; + /** Set to true as soon as a complete space packet is present in the spacePacketBuffer */ + bool packetInBuffer = false; + /** Points to the next free position in the space packet buffer */ + uint16_t bufferTop = 0; - PLOC_SPV::HkSet hkset; - PLOC_SPV::BootStatusReport bootStatusReport; - PLOC_SPV::LatchupStatusReport latchupStatusReport; - - /** Number of expected replies following the MRAM dump command */ - uint32_t expectedMramDumpPackets = 0; - uint32_t receivedMramDumpPackets = 0; - /** Set to true as soon as a complete space packet is present in the spacePacketBuffer */ - bool packetInBuffer = false; - /** Points to the next free position in the space packet buffer */ - uint16_t bufferTop = 0; - - /** This buffer is used to concatenate space packets received in two different read steps */ - uint8_t spacePacketBuffer[PLOC_SPV::MAX_PACKET_SIZE]; + /** This buffer is used to concatenate space packets received in two different read steps */ + uint8_t spacePacketBuffer[PLOC_SPV::MAX_PACKET_SIZE]; #if BOARD_TE0720 == 0 - SdCardManager* sdcMan = nullptr; + SdCardManager* sdcMan = nullptr; #endif /* BOARD_TE0720 == 0 */ - /** Path to PLOC specific files on SD card */ - std::string plocFilePath = "ploc"; - std::string activeMramFile; + /** Path to PLOC specific files on SD card */ + std::string plocFilePath = "ploc"; + std::string activeMramFile; - /** Setting this variable to true will enable direct downlink of MRAM packets */ - bool downlinkMramDump = false; + /** Setting this variable to true will enable direct downlink of MRAM packets */ + bool downlinkMramDump = false; - /** - * @brief This function checks the crc of the received PLOC reply. - * - * @param start Pointer to the first byte of the reply. - * @param foundLen Pointer to the length of the whole packet. - * - * @return RETURN_OK if CRC is ok, otherwise CRC_FAILURE. - */ - ReturnValue_t verifyPacket(const uint8_t* start, size_t foundLen); + /** + * @brief This function checks the crc of the received PLOC reply. + * + * @param start Pointer to the first byte of the reply. + * @param foundLen Pointer to the length of the whole packet. + * + * @return RETURN_OK if CRC is ok, otherwise CRC_FAILURE. + */ + ReturnValue_t verifyPacket(const uint8_t* start, size_t foundLen); - /** - * @brief This function handles the acknowledgment report. - * - * @param data Pointer to the data holding the acknowledgment report. - * - * @return RETURN_OK if successful, otherwise an error code. - */ - ReturnValue_t handleAckReport(const uint8_t* data); + /** + * @brief This function handles the acknowledgment report. + * + * @param data Pointer to the data holding the acknowledgment report. + * + * @return RETURN_OK if successful, otherwise an error code. + */ + ReturnValue_t handleAckReport(const uint8_t* data); - /** - * @brief This function handles the data of a execution report. - * - * @param data Pointer to the received data packet. - * - * @return RETURN_OK if successful, otherwise an error code. - */ - ReturnValue_t handleExecutionReport(const uint8_t* data); + /** + * @brief This function handles the data of a execution report. + * + * @param data Pointer to the received data packet. + * + * @return RETURN_OK if successful, otherwise an error code. + */ + ReturnValue_t handleExecutionReport(const uint8_t* data); - /** - * @brief This function handles the housekeeping report. This means verifying the CRC of the - * reply and filling the appropriate dataset. - * - * @param data Pointer to the data buffer holding the housekeeping read report. - * - * @return RETURN_OK if successful, otherwise an error code. - */ - ReturnValue_t handleHkReport(const uint8_t* data); + /** + * @brief This function handles the housekeeping report. This means verifying the CRC of the + * reply and filling the appropriate dataset. + * + * @param data Pointer to the data buffer holding the housekeeping read report. + * + * @return RETURN_OK if successful, otherwise an error code. + */ + ReturnValue_t handleHkReport(const uint8_t* data); - /** - * @brief This function calls the function to check the CRC of the received boot status report - * and fills the associated dataset with the boot status information. - */ - ReturnValue_t handleBootStatusReport(const uint8_t* data); + /** + * @brief This function calls the function to check the CRC of the received boot status report + * and fills the associated dataset with the boot status information. + */ + ReturnValue_t handleBootStatusReport(const uint8_t* data); - ReturnValue_t handleLatchupStatusReport(const uint8_t* data); + ReturnValue_t handleLatchupStatusReport(const uint8_t* data); - /** - * @brief Depending on the current active command, this function sets the reply id of the - * next reply after a successful acknowledgment report has been received. This is - * required by the function getNextReplyLength() to identify the length of the next - * reply to read. - */ - void setNextReplyId(); + /** + * @brief Depending on the current active command, this function sets the reply id of the + * next reply after a successful acknowledgment report has been received. This is + * required by the function getNextReplyLength() to identify the length of the next + * reply to read. + */ + void setNextReplyId(); - /** - * @brief This function handles action message replies in case the telemetry has been - * requested by another object. - * - * @param data Pointer to the telemetry data. - * @param dataSize Size of telemetry in bytes. - * @param replyId Id of the reply. This will be added to the ActionMessage. - */ - void handleDeviceTM(const uint8_t* data, size_t dataSize, DeviceCommandId_t replyId); + /** + * @brief This function handles action message replies in case the telemetry has been + * requested by another object. + * + * @param data Pointer to the telemetry data. + * @param dataSize Size of telemetry in bytes. + * @param replyId Id of the reply. This will be added to the ActionMessage. + */ + void handleDeviceTM(const uint8_t* data, size_t dataSize, DeviceCommandId_t replyId); - /** - * @brief This function prepares a space packet which does not transport any data in the - * packet data field apart from the crc. - */ - void prepareEmptyCmd(uint16_t apid); + /** + * @brief This function prepares a space packet which does not transport any data in the + * packet data field apart from the crc. + */ + void prepareEmptyCmd(uint16_t apid); - /** - * @brief This function initializes the space packet to select the boot image of the MPSoC. - */ - void prepareSelBootImageCmd(const uint8_t * commandData); + /** + * @brief This function initializes the space packet to select the boot image of the MPSoC. + */ + void prepareSelBootImageCmd(const uint8_t* commandData); - void prepareDisableHk(); + void prepareDisableHk(); - /** - * @brief This function fills the commandBuffer with the data to update the time of the - * PLOC supervisor. - */ - ReturnValue_t prepareSetTimeRefCmd(); + /** + * @brief This function fills the commandBuffer with the data to update the time of the + * PLOC supervisor. + */ + ReturnValue_t prepareSetTimeRefCmd(); - /** - * @brief This function fills the commandBuffer with the data to change the boot timeout - * value in the PLOC supervisor. - */ - void prepareSetBootTimeoutCmd(const uint8_t * commandData); + /** + * @brief This function fills the commandBuffer with the data to change the boot timeout + * value in the PLOC supervisor. + */ + void prepareSetBootTimeoutCmd(const uint8_t* commandData); - void prepareRestartTriesCmd(const uint8_t * commandData); + void prepareRestartTriesCmd(const uint8_t* commandData); - /** - * @brief This function fills the command buffer with the packet to enable or disable the - * watchdogs on the PLOC. - */ - void prepareWatchdogsEnableCmd(const uint8_t * commandData); + /** + * @brief This function fills the command buffer with the packet to enable or disable the + * watchdogs on the PLOC. + */ + void prepareWatchdogsEnableCmd(const uint8_t* commandData); - /** - * @brief This function fills the command buffer with the packet to set the watchdog timer - * of one of the three watchdogs (PS, PL, INT). - */ - ReturnValue_t prepareWatchdogsConfigTimeoutCmd(const uint8_t * commandData); + /** + * @brief This function fills the command buffer with the packet to set the watchdog timer + * of one of the three watchdogs (PS, PL, INT). + */ + ReturnValue_t prepareWatchdogsConfigTimeoutCmd(const uint8_t* commandData); - 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 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); + /** + * @brief Copies the content of a space packet to the command buffer. + */ + void packetToOutBuffer(uint8_t* packetData, size_t fullSize); - /** - * @brief Copies the content of a space packet to the command buffer. - */ - void packetToOutBuffer(uint8_t* packetData, size_t fullSize); + /** + * @brief In case an acknowledgment failure reply has been received this function disables + * all previously enabled commands and resets the exepected replies variable of an + * active command. + */ + void disableAllReplies(); - /** - * @brief In case an acknowledgment failure reply has been received this function disables - * all previously enabled commands and resets the exepected replies variable of an - * active command. - */ - void disableAllReplies(); + /** + * @brief This function sends a failure report if the active action was commanded by an other + * object. + * + * @param replyId The id of the reply which signals a failure. + * @param status A status byte which gives information about the failure type. + */ + void sendFailureReport(DeviceCommandId_t replyId, ReturnValue_t status); - /** - * @brief This function sends a failure report if the active action was commanded by an other - * object. - * - * @param replyId The id of the reply which signals a failure. - * @param status A status byte which gives information about the failure type. - */ - void sendFailureReport(DeviceCommandId_t replyId, ReturnValue_t status); + /** + * @brief This function disables the execution report reply. Within this function also the + * the variable expectedReplies of an active command will be set to 0. + */ + void disableExeReportReply(); - /** - * @brief This function disables the execution report reply. Within this function also the - * the variable expectedReplies of an active command will be set to 0. - */ - void disableExeReportReply(); + /** + * @brief Function is called in scanForReply and fills the spacePacketBuffer with the read + * data until a full packet has been received. + */ + ReturnValue_t parseMramPackets(const uint8_t* packet, size_t remainingSize, size_t* foundlen); - /** - * @brief Function is called in scanForReply and fills the spacePacketBuffer with the read - * data until a full packet has been received. - */ - ReturnValue_t parseMramPackets(const uint8_t *packet, size_t remainingSize, size_t* foundlen); + /** + * @brief This function generates the Service 8 packets for the MRAM dump data. + */ + ReturnValue_t handleMramDumpPacket(DeviceCommandId_t id); - /** - * @brief This function generates the Service 8 packets for the MRAM dump data. - */ - ReturnValue_t handleMramDumpPacket(DeviceCommandId_t id); + /** + * @brief With this function the number of expected replies following an MRAM dump command + * will be increased. This is necessary to release the command in case not all replies + * have been received. + */ + void increaseExpectedMramReplies(DeviceCommandId_t id); - /** - * @brief With this function the number of expected replies following an MRAM dump command - * will be increased. This is necessary to release the command in case not all replies - * have been received. - */ - void increaseExpectedMramReplies(DeviceCommandId_t id); + /** + * @brief Function checks if the packet written to the space packet buffer is really a + * MRAM dump packet. + */ + ReturnValue_t checkMramPacketApid(); - /** - * @brief Function checks if the packet written to the space packet buffer is really a - * MRAM dump packet. - */ - ReturnValue_t checkMramPacketApid(); + /** + * @brief Writes the data of the MRAM dump to a file. The file will be created when receiving + * the first packet. + */ + ReturnValue_t handleMramDumpFile(DeviceCommandId_t id); - /** - * @brief Writes the data of the MRAM dump to a file. The file will be created when receiving - * the first packet. - */ - ReturnValue_t handleMramDumpFile(DeviceCommandId_t id); + /** + * @brief Extracts the length field of a spacePacket referenced by the spacePacket pointer. + * + * @param spacePacket Pointer to the buffer holding the space packet. + * + * @return The value stored in the length field of the data field. + */ + uint16_t readSpacePacketLength(uint8_t* spacePacket); - /** - * @brief Extracts the length field of a spacePacket referenced by the spacePacket pointer. - * - * @param spacePacket Pointer to the buffer holding the space packet. - * - * @return The value stored in the length field of the data field. - */ - uint16_t readSpacePacketLength(uint8_t* spacePacket); + /** + * @brief Extracts the sequence flags from a space packet referenced by the spacePacket + * pointer. + * + * @param spacePacket Pointer to the buffer holding the space packet. + * + * @return uint8_t where the two least significant bits hold the sequence flags. + */ + uint8_t readSequenceFlags(uint8_t* spacePacket); - /** - * @brief Extracts the sequence flags from a space packet referenced by the spacePacket - * pointer. - * - * @param spacePacket Pointer to the buffer holding the space packet. - * - * @return uint8_t where the two least significant bits hold the sequence flags. - */ - uint8_t readSequenceFlags(uint8_t* spacePacket); - - ReturnValue_t createMramDumpFile(); - ReturnValue_t getTimeStampString(std::string& timeStamp); + ReturnValue_t createMramDumpFile(); + ReturnValue_t getTimeStampString(std::string& timeStamp); }; #endif /* MISSION_DEVICES_PLOCSUPERVISORHANDLER_H_ */ diff --git a/bsp_q7s/devices/PlocUpdater.cpp b/bsp_q7s/devices/PlocUpdater.cpp index 5a94495b..b1d7f0c9 100644 --- a/bsp_q7s/devices/PlocUpdater.cpp +++ b/bsp_q7s/devices/PlocUpdater.cpp @@ -1,436 +1,395 @@ -#include "fsfw/ipc/QueueFactory.h" #include "PlocUpdater.h" -#include #include +#include #include -PlocUpdater::PlocUpdater(object_id_t objectId) : - SystemObject(objectId), commandActionHelper(this), actionHelper(this, nullptr) { - commandQueue = QueueFactory::instance()->createMessageQueue(QUEUE_SIZE); +#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() { -} +PlocUpdater::~PlocUpdater() {} ReturnValue_t PlocUpdater::initialize() { #if BOARD_TE0720 == 0 - sdcMan = SdCardManager::instance(); + 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; - } + 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; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t PlocUpdater::performOperation(uint8_t operationCode) { - readCommandQueue(); - doStateMachine(); - return HasReturnvaluesIF::RETURN_OK; + 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; +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 (state != State::IDLE) { + return IS_BUSY; + } - if (size > MAX_PLOC_UPDATE_PATH) { - return NAME_TOO_LONG; - } + if (size > MAX_PLOC_UPDATE_PATH) { + return NAME_TOO_LONG; + } - switch (actionId) { + switch (actionId) { case UPDATE_A_UBOOT: - image = Image::A; - partition = Partition::UBOOT; - break; + image = Image::A; + partition = Partition::UBOOT; + break; case UPDATE_A_BITSTREAM: - image = Image::A; - partition = Partition::BITSTREAM; - break; + image = Image::A; + partition = Partition::BITSTREAM; + break; case UPDATE_A_LINUX: - image = Image::A; - partition = Partition::LINUX_OS; - break; + image = Image::A; + partition = Partition::LINUX_OS; + break; case UPDATE_A_APP_SW: - image = Image::A; - partition = Partition::APP_SW; - break; + image = Image::A; + partition = Partition::APP_SW; + break; case UPDATE_B_UBOOT: - image = Image::B; - partition = Partition::UBOOT; - break; + image = Image::B; + partition = Partition::UBOOT; + break; case UPDATE_B_BITSTREAM: - image = Image::B; - partition = Partition::BITSTREAM; - break; + image = Image::B; + partition = Partition::BITSTREAM; + break; case UPDATE_B_LINUX: - image = Image::B; - partition = Partition::LINUX_OS; - break; + image = Image::B; + partition = Partition::LINUX_OS; + break; case UPDATE_B_APP_SW: - image = Image::B; - partition = Partition::APP_SW; - break; + image = Image::B; + partition = Partition::APP_SW; + break; default: - return INVALID_ACTION_ID; - } + return INVALID_ACTION_ID; + } - result = getImageLocation(data, size); + result = getImageLocation(data, size); - if (result != RETURN_OK) { - return result; - } + if (result != RETURN_OK) { + return result; + } - state = State::UPDATE_AVAILABLE; + state = State::UPDATE_AVAILABLE; - return EXECUTION_FINISHED; + return EXECUTION_FINISHED; } -MessageQueueId_t PlocUpdater::getCommandQueue() const { - return commandQueue->getId(); -} +MessageQueueId_t PlocUpdater::getCommandQueue() const { return commandQueue->getId(); } -MessageQueueIF* PlocUpdater::getCommandQueuePtr() { - return commandQueue; -} +MessageQueueIF* PlocUpdater::getCommandQueuePtr() { return commandQueue; } void PlocUpdater::readCommandQueue() { - CommandMessage message; - ReturnValue_t result; + 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; - } - - sif::debug << "PlocUpdater::readCommandQueue: Received message with invalid format" - << std::endl; + 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; + } + + sif::debug << "PlocUpdater::readCommandQueue: Received message with invalid format" + << std::endl; + } } void PlocUpdater::doStateMachine() { - switch (state) { + switch (state) { case State::IDLE: - break; + break; case State::UPDATE_AVAILABLE: - commandUpdateAvailable(); - break; + commandUpdateAvailable(); + break; case State::UPDATE_TRANSFER: - commandUpdatePacket(); - break; + commandUpdatePacket(); + break; case State::UPDATE_VERIFY: - commandUpdateVerify(); - break; + commandUpdateVerify(); + break; case State::COMMAND_EXECUTING: - break; + break; default: - sif::debug << "PlocUpdater::doStateMachine: Invalid state" << std::endl; - break; - } + sif::debug << "PlocUpdater::doStateMachine: Invalid state" << std::endl; + break; + } } ReturnValue_t PlocUpdater::checkNameLength(size_t size) { - if (size > MAX_PLOC_UPDATE_PATH) { - return NAME_TOO_LONG; - } - return RETURN_OK; + 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; - } + ReturnValue_t result = checkNameLength(size); + if (result != RETURN_OK) { + return result; + } #if BOARD_TE0720 == 0 - // 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 (!isSdCardMounted(sd::SLOT_0)) { - sif::warning << "PlocUpdater::prepareNvm0AUpdate: SD card 0 not mounted" << std::endl; - return SD_NOT_MOUNTED; - } + // 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 (!isSdCardMounted(sd::SLOT_0)) { - sif::warning << "PlocUpdater::prepareNvm0AUpdate: SD card 1 not mounted" << std::endl; - return SD_NOT_MOUNTED; - } - } - else { - //update image not stored on SD card + } 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); + updateFile = std::string(reinterpret_cast(data), size); - // Check if file exists - if(not std::filesystem::exists(updateFile)) { - return FILE_NOT_EXISTS; - } - return RETURN_OK; + // Check if file exists + if (not std::filesystem::exists(updateFile)) { + return FILE_NOT_EXISTS; + } + return RETURN_OK; } -#if BOARD_TE0720 == 0 -bool PlocUpdater::isSdCardMounted(sd::SdCard sdCard) { - SdCardManager::SdStatePair active; - ReturnValue_t result = sdcMan->getSdCardActiveStatus(active); - if (result != RETURN_OK) { - sif::debug << "PlocUpdater::isSdCardMounted: Failed to get SD card active state"; - return false; - } - if (sdCard == sd::SLOT_0) { - if (active.first == sd::MOUNTED) { - return true; - } - else { - return false; - } - } - else if (sdCard == sd::SLOT_1) { - if (active.second == sd::MOUNTED) { - return true; - } - else { - return false; - } - } - else { - sif::debug << "PlocUpdater::isSdCardMounted: Unknown SD card specified" << std::endl; - } - return false; -} -#endif /* #if BOARD_TE0720 == 0 */ +void PlocUpdater::stepSuccessfulReceived(ActionId_t actionId, uint8_t step) {} -void PlocUpdater::stepSuccessfulReceived(ActionId_t actionId, - uint8_t step) { -} +void PlocUpdater::stepFailedReceived(ActionId_t actionId, uint8_t step, ReturnValue_t returnCode) {} -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::dataReceived(ActionId_t actionId, const uint8_t* data, uint32_t size) {} void PlocUpdater::completionSuccessfulReceived(ActionId_t actionId) { - switch (pendingCommand) { + switch (pendingCommand) { case (PLOC_SPV::UPDATE_AVAILABLE): - state = State::UPDATE_TRANSFER; - break; + state = State::UPDATE_TRANSFER; + break; case (PLOC_SPV::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; + if (remainingPackets == 0) { + packetsSent = 0; // Reset packets sent variable for next update sequence + state = State::UPDATE_VERIFY; + } else { + state = State::UPDATE_TRANSFER; + } + break; case (PLOC_SPV::UPDATE_VERIFY): - triggerEvent(UPDATE_FINISHED); - state = State::IDLE; - pendingCommand = PLOC_SPV::NONE; - break; + triggerEvent(UPDATE_FINISHED); + state = State::IDLE; + pendingCommand = PLOC_SPV::NONE; + break; default: - sif::debug << "PlocUpdater::completionSuccessfulReceived: Invalid pending command" - << std::endl; - state = State::IDLE; - break; - } + sif::debug << "PlocUpdater::completionSuccessfulReceived: Invalid pending command" + << std::endl; + state = State::IDLE; + break; + } } -void PlocUpdater::completionFailedReceived(ActionId_t actionId, - ReturnValue_t returnCode) { - switch(pendingCommand) { - case(PLOC_SPV::UPDATE_AVAILABLE): { - triggerEvent(UPDATE_AVAILABLE_FAILED); - break; +void PlocUpdater::completionFailedReceived(ActionId_t actionId, ReturnValue_t returnCode) { + switch (pendingCommand) { + case (PLOC_SPV::UPDATE_AVAILABLE): { + triggerEvent(UPDATE_AVAILABLE_FAILED); + break; } - case(PLOC_SPV::UPDATE_IMAGE_DATA): { - triggerEvent(UPDATE_TRANSFER_FAILED, packetsSent); - break; + case (PLOC_SPV::UPDATE_IMAGE_DATA): { + triggerEvent(UPDATE_TRANSFER_FAILED, packetsSent); + break; } - case(PLOC_SPV::UPDATE_VERIFY): { - triggerEvent(UPDATE_VERIFY_FAILED); - break; + case (PLOC_SPV::UPDATE_VERIFY): { + triggerEvent(UPDATE_VERIFY_FAILED); + break; } default: - sif::debug << "PlocUpdater::completionFailedReceived: Invalid pending command " - << std::endl; - break; - } - state = State::IDLE; + sif::debug << "PlocUpdater::completionFailedReceived: Invalid pending command " << std::endl; + break; + } + state = State::IDLE; } void PlocUpdater::commandUpdateAvailable() { - ReturnValue_t result = RETURN_OK; + 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(); - - PLOC_SPV::UpdateInfo packet(PLOC_SPV::APID_UPDATE_AVAILABLE, static_cast(image), - static_cast(partition), imageSize, imageCrc, numOfUpdatePackets); - - result = commandActionHelper.commandAction(objects::PLOC_SUPERVISOR_HANDLER, - PLOC_SPV::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, PLOC_SPV::UPDATE_AVAILABLE); - state = State::IDLE; - pendingCommand = PLOC_SPV::NONE; - return; - } - - pendingCommand = PLOC_SPV::UPDATE_AVAILABLE; - state = State::COMMAND_EXECUTING; + 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(); + + PLOC_SPV::UpdateInfo packet(PLOC_SPV::APID_UPDATE_AVAILABLE, static_cast(image), + static_cast(partition), imageSize, imageCrc, + numOfUpdatePackets); + + result = commandActionHelper.commandAction(objects::PLOC_SUPERVISOR_HANDLER, + PLOC_SPV::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, PLOC_SPV::UPDATE_AVAILABLE); + state = State::IDLE; + pendingCommand = PLOC_SPV::NONE; + return; + } + + pendingCommand = PLOC_SPV::UPDATE_AVAILABLE; + state = State::COMMAND_EXECUTING; + return; } void PlocUpdater::commandUpdatePacket() { - ReturnValue_t result = RETURN_OK; - uint16_t payloadLength = 0; + 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; - } + 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); + 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; - } + if (remainingPackets == 1) { + payloadLength = imageSize - static_cast(file.tellg()); + } else { + payloadLength = MAX_SP_DATA; + } - PLOC_SPV::UpdatePacket packet(payloadLength); - file.read(reinterpret_cast(packet.getDataFieldPointer()), payloadLength); - file.close(); - // sequence count of first packet is 1 - packet.setPacketSequenceCount((packetsSent + 1) & PLOC_SPV::SEQUENCE_COUNT_MASK); - if (numOfUpdatePackets > 1) { - adjustSequenceFlags(packet); - } - packet.makeCrc(); + PLOC_SPV::UpdatePacket packet(payloadLength); + file.read(reinterpret_cast(packet.getDataFieldPointer()), payloadLength); + file.close(); + // sequence count of first packet is 1 + packet.setPacketSequenceCount((packetsSent + 1) & PLOC_SPV::SEQUENCE_COUNT_MASK); + if (numOfUpdatePackets > 1) { + adjustSequenceFlags(packet); + } + packet.makeCrc(); - result = commandActionHelper.commandAction(objects::PLOC_SUPERVISOR_HANDLER, - PLOC_SPV::UPDATE_IMAGE_DATA, packet.getWholeData(), packet.getFullSize()); + result = commandActionHelper.commandAction(objects::PLOC_SUPERVISOR_HANDLER, + PLOC_SPV::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, PLOC_SPV::UPDATE_IMAGE_DATA); - state = State::IDLE; - pendingCommand = PLOC_SPV::NONE; - return; - } + if (result != RETURN_OK) { + sif::warning << "PlocUpdater::commandUpdateAvailable: Failed to send update" + << " packet to supervisor handler" << std::endl; + triggerEvent(ACTION_COMMANDING_FAILED, result, PLOC_SPV::UPDATE_IMAGE_DATA); + state = State::IDLE; + pendingCommand = PLOC_SPV::NONE; + return; + } - remainingPackets--; - packetsSent++; + remainingPackets--; + packetsSent++; - pendingCommand = PLOC_SPV::UPDATE_IMAGE_DATA; - state = State::COMMAND_EXECUTING; + pendingCommand = PLOC_SPV::UPDATE_IMAGE_DATA; + state = State::COMMAND_EXECUTING; } void PlocUpdater::commandUpdateVerify() { - ReturnValue_t result = RETURN_OK; + ReturnValue_t result = RETURN_OK; - PLOC_SPV::UpdateInfo packet(PLOC_SPV::APID_UPDATE_VERIFY, static_cast(image), - static_cast(partition), imageSize, imageCrc, numOfUpdatePackets); + PLOC_SPV::UpdateInfo packet(PLOC_SPV::APID_UPDATE_VERIFY, static_cast(image), + static_cast(partition), imageSize, imageCrc, + numOfUpdatePackets); - result = commandActionHelper.commandAction(objects::PLOC_SUPERVISOR_HANDLER, - PLOC_SPV::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, PLOC_SPV::UPDATE_VERIFY); - state = State::IDLE; - pendingCommand = PLOC_SPV::NONE; - return; - } - state = State::COMMAND_EXECUTING; - pendingCommand = PLOC_SPV::UPDATE_VERIFY; + result = + commandActionHelper.commandAction(objects::PLOC_SUPERVISOR_HANDLER, PLOC_SPV::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, PLOC_SPV::UPDATE_VERIFY); + state = State::IDLE; + pendingCommand = PLOC_SPV::NONE; return; + } + state = State::COMMAND_EXECUTING; + pendingCommand = PLOC_SPV::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); - } - } + 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); + } + file.close(); + imageCrc = (remainder ^ FINAL_XOR_VALUE_32); } void PlocUpdater::adjustSequenceFlags(PLOC_SPV::UpdatePacket& packet) { - if (packetsSent == 0) { - packet.setSequenceFlags(static_cast(PLOC_SPV::SequenceFlags::FIRST_PKT)); - } - else if (remainingPackets == 1) { - packet.setSequenceFlags(static_cast(PLOC_SPV::SequenceFlags::LAST_PKT)); - } - else { - packet.setSequenceFlags(static_cast(PLOC_SPV::SequenceFlags::CONTINUED_PKT)); - } + if (packetsSent == 0) { + packet.setSequenceFlags(static_cast(PLOC_SPV::SequenceFlags::FIRST_PKT)); + } else if (remainingPackets == 1) { + packet.setSequenceFlags(static_cast(PLOC_SPV::SequenceFlags::LAST_PKT)); + } else { + packet.setSequenceFlags(static_cast(PLOC_SPV::SequenceFlags::CONTINUED_PKT)); + } } - diff --git a/bsp_q7s/devices/PlocUpdater.h b/bsp_q7s/devices/PlocUpdater.h index 50404d14..bfd86995 100644 --- a/bsp_q7s/devices/PlocUpdater.h +++ b/bsp_q7s/devices/PlocUpdater.h @@ -2,188 +2,170 @@ #define MISSION_DEVICES_PLOCUPDATER_H_ #include "OBSWConfig.h" +#include "bsp_q7s/memory/SdCardManager.h" #include "devicedefinitions/PlocSupervisorDefinitions.h" - -#include "fsfw/action/CommandActionHelper.h" #include "fsfw/action/ActionHelper.h" -#include "fsfw/action/HasActionsIF.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/objectmanager/SystemObject.h" -#include "bsp_q7s/memory/SdCardManager.h" -#include "linux/fsfwconfig/objects/systemObjectList.h" #include "fsfw/tmtcpacket/SpacePacket.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) + * @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: + 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; - 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(); - 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; - 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; -private: + //! [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 INTERFACE_ID = CLASS_ID::PLOC_UPDATER; + static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_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); + //! [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 uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PLOC_UPDATER; + 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; - //! [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 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; - 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; + MessageQueueIF* commandQueue = nullptr; #if BOARD_TE0720 == 0 - SdCardManager* sdcMan = nullptr; + SdCardManager* sdcMan = nullptr; #endif - CommandActionHelper commandActionHelper; + CommandActionHelper commandActionHelper; - ActionHelper actionHelper; + ActionHelper actionHelper; - enum class State: uint8_t { - IDLE, - UPDATE_AVAILABLE, - UPDATE_TRANSFER, - UPDATE_VERIFY, - COMMAND_EXECUTING - }; + enum class State : uint8_t { + IDLE, + UPDATE_AVAILABLE, + UPDATE_TRANSFER, + UPDATE_VERIFY, + COMMAND_EXECUTING + }; - State state = State::IDLE; + State state = State::IDLE; - ActionId_t pendingCommand = PLOC_SPV::NONE; + ActionId_t pendingCommand = PLOC_SPV::NONE; - enum class Image: uint8_t { - NONE, - A, - B - }; + enum class Image : uint8_t { NONE, A, B }; - Image image = Image::NONE; + Image image = Image::NONE; - enum class Partition: uint8_t { - NONE, - UBOOT, - BITSTREAM, - LINUX_OS, - APP_SW - }; + enum class Partition : uint8_t { NONE, UBOOT, BITSTREAM, LINUX_OS, APP_SW }; - Partition partition = Partition::NONE; + 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; + 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; + std::string updateFile; + uint32_t imageSize = 0; + uint32_t imageCrc = 0; - void readCommandQueue(); - void doStateMachine(); + 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); + /** + * @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); + ReturnValue_t checkNameLength(size_t size); - /** - * @brief Prepares and sends update available command to PLOC supervisor handler. - */ - void commandUpdateAvailable(); + /** + * @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 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(); + /** + * @brief Prepares and sends the update verification packet to the PLOC supervisor handler. + */ + void commandUpdateVerify(); -#if BOARD_TE0720 == 0 - /** - * @brief Checks whether the SD card to read from is mounted or not. - */ - bool isSdCardMounted(sd::SdCard sdCard); -#endif + void calcImageCrc(); - void calcImageCrc(); - - void adjustSequenceFlags(PLOC_SPV::UpdatePacket& packet); + void adjustSequenceFlags(PLOC_SPV::UpdatePacket& packet); }; #endif /* MISSION_DEVICES_PLOCUPDATER_H_ */ diff --git a/bsp_q7s/devices/devicedefinitions/PlocMemDumpDefinitions.h b/bsp_q7s/devices/devicedefinitions/PlocMemDumpDefinitions.h index 6e44cf35..00dc9003 100644 --- a/bsp_q7s/devices/devicedefinitions/PlocMemDumpDefinitions.h +++ b/bsp_q7s/devices/devicedefinitions/PlocMemDumpDefinitions.h @@ -3,31 +3,26 @@ #include -class MemoryParams: public SerialLinkedListAdapter { -public: +class MemoryParams : public SerialLinkedListAdapter { + public: + /** + * @brief Constructor + * @param startAddress Start of address range to dump + * @param endAddress End of address range to dump + */ + MemoryParams(uint32_t startAddress, uint32_t endAddress) + : startAddress(startAddress), endAddress(endAddress) { + setLinks(); + } - /** - * @brief Constructor - * @param startAddress Start of address range to dump - * @param endAddress End of address range to dump - */ - MemoryParams(uint32_t startAddress, uint32_t endAddress) : - startAddress(startAddress), endAddress(endAddress) { - setLinks(); - } -private: - - void setLinks() { - setStart(&startAddress); - startAddress.setNext(&endAddress); - } - - SerializeElement startAddress; - SerializeElement endAddress; + private: + void setLinks() { + setStart(&startAddress); + startAddress.setNext(&endAddress); + } + SerializeElement startAddress; + SerializeElement endAddress; }; - - - #endif /* BSP_Q7S_DEVICES_DEVICEDEFINITIONS_PLOCMEMDUMPDEFINITIONS_H_ */ diff --git a/bsp_q7s/devices/devicedefinitions/PlocSupervisorDefinitions.h b/bsp_q7s/devices/devicedefinitions/PlocSupervisorDefinitions.h index 0235d281..3fc21441 100644 --- a/bsp_q7s/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/bsp_q7s/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -1,12 +1,12 @@ #ifndef MISSION_DEVICES_DEVICEDEFINITIONS_PLOCSVPDEFINITIONS_H_ #define MISSION_DEVICES_DEVICEDEFINITIONS_PLOCSVPDEFINITIONS_H_ -#include +#include +#include #include #include #include -#include -#include +#include namespace PLOC_SPV { @@ -143,7 +143,7 @@ static const uint8_t DATA_FIELD_OFFSET = 6; * Space packet length for fixed size packets. This is the size of the whole packet data * field. For the length field in the space packet this size will be substracted by one. */ -static const uint16_t LENGTH_EMPTY_TC = 2; // Only CRC will be transported with the data field +static const uint16_t LENGTH_EMPTY_TC = 2; // Only CRC will be transported with the data field /** This is the maximum length of a space packet as defined by the TAS ICD */ static const size_t MAX_COMMAND_SIZE = 1024; @@ -153,51 +153,53 @@ static const size_t MAX_PACKET_SIZE = 1024; static const uint8_t SPACE_PACKET_HEADER_LENGTH = 6; -enum class SequenceFlags: uint8_t { - CONTINUED_PKT = 0b00, FIRST_PKT = 0b01, LAST_PKT = 0b10, STANDALONE_PKT = 0b11 +enum class SequenceFlags : uint8_t { + CONTINUED_PKT = 0b00, + FIRST_PKT = 0b01, + LAST_PKT = 0b10, + STANDALONE_PKT = 0b11 }; -enum PoolIds - : lp_id_t { - NUM_TMS, - TEMP_PS, - TEMP_PL, - SOC_STATE, - NVM0_1_STATE, - NVM3_STATE, - MISSION_IO_STATE, - FMC_STATE, - NUM_TCS, - TEMP_SUP, - UPTIME, - CPULOAD, - AVAILABLEHEAP, - BOOT_SIGNAL, - RESET_COUNTER, - BOOT_AFTER_MS, - BOOT_TIMEOUT_MS, - ACTIVE_NVM, - BP0_STATE, - BP1_STATE, - BP2_STATE, +enum PoolIds : lp_id_t { + NUM_TMS, + TEMP_PS, + TEMP_PL, + SOC_STATE, + NVM0_1_STATE, + NVM3_STATE, + MISSION_IO_STATE, + FMC_STATE, + NUM_TCS, + TEMP_SUP, + UPTIME, + CPULOAD, + AVAILABLEHEAP, + BOOT_SIGNAL, + RESET_COUNTER, + BOOT_AFTER_MS, + BOOT_TIMEOUT_MS, + ACTIVE_NVM, + BP0_STATE, + BP1_STATE, + BP2_STATE, - LATCHUP_ID, - CNT0, - CNT1, - CNT2, - CNT3, - CNT4, - CNT5, - CNT6, - LATCHUP_RPT_TIME_SEC, - LATCHUP_RPT_TIME_MIN, - LATCHUP_RPT_TIME_HOUR, - LATCHUP_RPT_TIME_DAY, - LATCHUP_RPT_TIME_MON, - LATCHUP_RPT_TIME_YEAR, - LATCHUP_RPT_TIME_MSEC, - LATCHUP_RPT_TIME_USEC, - LATCHUP_RPT_TIME_IS_SET, + LATCHUP_ID, + CNT0, + CNT1, + CNT2, + CNT3, + CNT4, + CNT5, + CNT6, + LATCHUP_RPT_TIME_SEC, + LATCHUP_RPT_TIME_MIN, + LATCHUP_RPT_TIME_HOUR, + LATCHUP_RPT_TIME_DAY, + LATCHUP_RPT_TIME_MON, + LATCHUP_RPT_TIME_YEAR, + LATCHUP_RPT_TIME_MSEC, + LATCHUP_RPT_TIME_USEC, + LATCHUP_RPT_TIME_IS_SET, }; static const uint8_t HK_SET_ENTRIES = 13; @@ -211,285 +213,273 @@ static const uint32_t LATCHUP_RPT_ID = LATCHUP_REPORT; /** * @brief With this class a space packet can be created which does not contain any data. */ -class EmptyPacket: public SpacePacket { -public: +class EmptyPacket : public SpacePacket { + public: + /** + * @brief Constructor + * + * @param apid The APID to set in the space packet. + * + * @note Sequence count of empty packet is always 1. + */ + EmptyPacket(uint16_t apid) : SpacePacket(LENGTH_EMPTY_TC - 1, true, apid, 1) { calcCrc(); } - /** - * @brief Constructor - * - * @param apid The APID to set in the space packet. - * - * @note Sequence count of empty packet is always 1. - */ - EmptyPacket(uint16_t apid) : - SpacePacket(LENGTH_EMPTY_TC - 1, true, apid, 1) { - calcCrc(); - } + private: + /** + * @brief CRC calculation which involves only the header in an empty packet + */ + void calcCrc() { + /* Calculate crc */ + uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, sizeof(CCSDSPrimaryHeader)); -private: - - /** - * @brief CRC calculation which involves only the header in an empty packet - */ - void calcCrc() { - - /* Calculate crc */ - uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, sizeof(CCSDSPrimaryHeader)); - - /* Add crc to packet data field of space packet */ - size_t serializedSize = 0; - uint8_t* crcPos = this->localData.fields.buffer; - SerializeAdapter::serialize(&crc, &crcPos, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); - } + /* Add crc to packet data field of space packet */ + size_t serializedSize = 0; + uint8_t* crcPos = this->localData.fields.buffer; + SerializeAdapter::serialize(&crc, &crcPos, &serializedSize, sizeof(crc), + SerializeIF::Endianness::BIG); + } }; /** * @brief This class can be used to generate the space packet selecting the boot image of * of the MPSoC. */ -class MPSoCBootSelect: public SpacePacket { -public: +class MPSoCBootSelect : 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 + */ + MPSoCBootSelect(uint8_t mem, uint8_t bp0, uint8_t bp1, uint8_t bp2) + : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_SEL_MPSOC_BOOT_IMAGE, DEFAULT_SEQUENCE_COUNT), + mem(mem), + bp0(bp0), + bp1(bp1), + bp2(bp2) { + initPacket(); + } - /** - * @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 - */ - MPSoCBootSelect(uint8_t mem, uint8_t bp0, uint8_t bp1, uint8_t bp2) : - SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_SEL_MPSOC_BOOT_IMAGE, - DEFAULT_SEQUENCE_COUNT), mem(mem), bp0(bp0), bp1(bp1), bp2(bp2) { - initPacket(); - } + private: + static const uint16_t DATA_FIELD_LENGTH = 6; + static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; -private: + static const uint8_t MEM_OFFSET = 0; + static const uint8_t BP0_OFFSET = 1; + static const uint8_t BP1_OFFSET = 2; + static const uint8_t BP2_OFFSET = 3; + static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - static const uint16_t DATA_FIELD_LENGTH = 6; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; + uint8_t mem = 0; + uint8_t bp0 = 0; + uint8_t bp1 = 0; + uint8_t bp2 = 0; - static const uint8_t MEM_OFFSET = 0; - static const uint8_t BP0_OFFSET = 1; - static const uint8_t BP1_OFFSET = 2; - static const uint8_t BP2_OFFSET = 3; - static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; + void initPacket() { + uint8_t* data_field_start = this->localData.fields.buffer; + std::memcpy(data_field_start + MEM_OFFSET, &mem, sizeof(mem)); + std::memcpy(data_field_start + BP0_OFFSET, &bp0, sizeof(bp0)); + std::memcpy(data_field_start + BP1_OFFSET, &bp1, sizeof(bp1)); + std::memcpy(data_field_start + BP2_OFFSET, &bp2, sizeof(bp2)); + /* Calculate crc */ + uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, + sizeof(CCSDSPrimaryHeader) + DATA_FIELD_LENGTH - 2); - uint8_t mem = 0; - uint8_t bp0 = 0; - uint8_t bp1 = 0; - uint8_t bp2 = 0; - - void initPacket() { - uint8_t* data_field_start = this->localData.fields.buffer; - std::memcpy(data_field_start + MEM_OFFSET, &mem, sizeof(mem)); - std::memcpy(data_field_start + BP0_OFFSET, &bp0, sizeof(bp0)); - std::memcpy(data_field_start + BP1_OFFSET, &bp1, sizeof(bp1)); - std::memcpy(data_field_start + BP2_OFFSET, &bp2, sizeof(bp2)); - /* 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); - } + /* 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. */ -class SetTimeRef: public SpacePacket { -public: +class SetTimeRef : public SpacePacket { + public: + SetTimeRef(Clock::TimeOfDay_t* time) + : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_SET_TIME_REF, DEFAULT_SEQUENCE_COUNT) { + initPacket(time); + } - SetTimeRef(Clock::TimeOfDay_t* time) : - SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_SET_TIME_REF, DEFAULT_SEQUENCE_COUNT) { - initPacket(time); - } + private: + static const uint16_t DATA_FIELD_LENGTH = 34; + static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; + static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; -private: - - static const uint16_t DATA_FIELD_LENGTH = 34; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; - static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - - 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, - sizeof(milliseconds), SerializeIF::Endianness::BIG); - serializedSize = 0; - uint32_t isSet = 0xFFFFFFFF; - SerializeAdapter::serialize(&isSet, &data_field_ptr, &serializedSize, - sizeof(isSet), 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), - SerializeIF::Endianness::BIG); - } + 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, + sizeof(milliseconds), SerializeIF::Endianness::BIG); + serializedSize = 0; + uint32_t isSet = 0xFFFFFFFF; + SerializeAdapter::serialize(&isSet, &data_field_ptr, &serializedSize, sizeof(isSet), + 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), + SerializeIF::Endianness::BIG); + } }; /** * @brief This class can be used to generate the set boot timout command. */ -class SetBootTimeout: public SpacePacket { -public: +class SetBootTimeout : public SpacePacket { + public: + /** + * @brief Constructor + * + * @param timeout The boot timeout in milliseconds. + */ + SetBootTimeout(uint32_t timeout) + : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_SET_BOOT_TIMEOUT, 1), timeout(timeout) { + initPacket(); + } - /** - * @brief Constructor - * - * @param timeout The boot timeout in milliseconds. - */ - SetBootTimeout(uint32_t timeout) : - SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_SET_BOOT_TIMEOUT, 1), timeout(timeout) { - initPacket(); - } + private: + uint32_t timeout = 0; -private: + /** boot timeout value (uint32_t) and crc (uint16_t) */ + static const uint16_t DATA_FIELD_LENGTH = 6; - uint32_t timeout = 0; - - /** boot timeout value (uint32_t) and crc (uint16_t) */ - static const uint16_t DATA_FIELD_LENGTH = 6; - - 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); - /* 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), - SerializeIF::Endianness::BIG); - } + 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); + /* 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), + SerializeIF::Endianness::BIG); + } }; /** * @brief This class can be used to generate the space packet to set the maximum boot tries. */ -class SetRestartTries: public SpacePacket { -public: +class SetRestartTries : public SpacePacket { + public: + /** + * @brief Constructor + * + * @param restartTries Maximum restart tries to set. + */ + SetRestartTries(uint8_t restartTries) + : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_SET_MAX_RESTART_TRIES, 1), + restartTries(restartTries) { + initPacket(); + } - /** - * @brief Constructor - * - * @param restartTries Maximum restart tries to set. - */ - SetRestartTries(uint8_t restartTries) : - SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_SET_MAX_RESTART_TRIES, 1), restartTries( - restartTries) { - initPacket(); - } + private: + uint8_t restartTries = 0; -private: + /** Restart tries value (uint8_t) and crc (uint16_t) */ + static const uint16_t DATA_FIELD_LENGTH = 3; - uint8_t restartTries = 0; - - /** Restart tries value (uint8_t) and crc (uint16_t) */ - static const uint16_t DATA_FIELD_LENGTH = 3; - - void initPacket() { - uint8_t* data_field_ptr = this->localData.fields.buffer; - *data_field_ptr = 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; - SerializeAdapter::serialize(&crc, &crcPtr, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); - } + void initPacket() { + uint8_t* data_field_ptr = this->localData.fields.buffer; + *data_field_ptr = 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; + 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: +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(); + } - /** - * @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; -private: + static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - static const uint16_t DATA_FIELD_LENGTH = 16; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; + uint8_t imageSelect = 0; + uint8_t imagePartition = 0; + uint32_t imageSize = 0; + uint32_t imageCrc = 0; + uint32_t numberOfPackets = 0; - 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); - } + 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); + } }; /** @@ -497,130 +487,126 @@ private: * of housekeeping data. Normally, this will be disabled by default. However, adding this * command can be useful for debugging. */ -class DisablePeriodicHkTransmission: public SpacePacket { -public: +class DisablePeriodicHkTransmission : public SpacePacket { + public: + /** + * @brief Constructor + */ + DisablePeriodicHkTransmission() : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_DISABLE_HK, 1) { + initPacket(); + } - /** - * @brief Constructor - */ - DisablePeriodicHkTransmission() : - SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_DISABLE_HK, 1) { - initPacket(); - } + private: + uint8_t disableHk = 0; -private: + /** Restart tries value (uint8_t) and crc (uint16_t) */ + static const uint16_t DATA_FIELD_LENGTH = 3; - uint8_t disableHk = 0; - - /** Restart tries value (uint8_t) and crc (uint16_t) */ - static const uint16_t DATA_FIELD_LENGTH = 3; - - void initPacket() { - uint8_t* data_field_ptr = this->localData.fields.buffer; - *data_field_ptr = 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; - SerializeAdapter::serialize(&crc, &crcPtr, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); - } + void initPacket() { + uint8_t* data_field_ptr = this->localData.fields.buffer; + *data_field_ptr = 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; + 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: +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(); + } - /** - * @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; -private: + static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - static const uint16_t DATA_FIELD_LENGTH = 5; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; + uint8_t watchdogPs = 0; + uint8_t watchdogPl = 0; + uint8_t watchdogInt = 0; - 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); - } + 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: +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(); + } - /** - * @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; -private: + static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - static const uint16_t DATA_FIELD_LENGTH = 7; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; + uint8_t watchdog = 0; + uint32_t timeout = 0; - 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); - } + 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); + } }; /** @@ -628,723 +614,693 @@ private: * * @details There are 7 different latchup alerts. */ -class LatchupAlert: public SpacePacket { -public: - - /** - * @brief Constructor - * - * @param state true - enable, false - disable - * @param latchupId Identifies the latchup to enable/disable (0 - 0.85V, 1 - 1.8V, 2 - MISC, - * 3 - 3.3V, 4 - NVM_4XO, 5 - MISSION, 6 - SAFECOTS) - */ - LatchupAlert(bool state, uint8_t latchupId) : - SpacePacket(DATA_FIELD_LENGTH - 1, true), latchupId(latchupId) { - if (state) { - this->setAPID(APID_ENABLE_LATCHUP_ALERT); - } else { - this->setAPID(APID_DISABLE_LATCHUP_ALERT); - } - this->setPacketSequenceCount(DEFAULT_SEQUENCE_COUNT); - initPacket(); +class LatchupAlert : public SpacePacket { + public: + /** + * @brief Constructor + * + * @param state true - enable, false - disable + * @param latchupId Identifies the latchup to enable/disable (0 - 0.85V, 1 - 1.8V, 2 - MISC, + * 3 - 3.3V, 4 - NVM_4XO, 5 - MISSION, 6 - SAFECOTS) + */ + LatchupAlert(bool state, uint8_t latchupId) + : SpacePacket(DATA_FIELD_LENGTH - 1, true), latchupId(latchupId) { + if (state) { + this->setAPID(APID_ENABLE_LATCHUP_ALERT); + } else { + this->setAPID(APID_DISABLE_LATCHUP_ALERT); } + this->setPacketSequenceCount(DEFAULT_SEQUENCE_COUNT); + initPacket(); + } -private: + private: + static const uint16_t DATA_FIELD_LENGTH = 3; + static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; - 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; - static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; + uint8_t latchupId = 0; - uint8_t latchupId = 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; - 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); - } + 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; + 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 calibrate a certain latchup alert. */ -class AutoCalibrateAlert: public SpacePacket { -public: +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(); + } - /** - * @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; -private: + static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - static const uint16_t DATA_FIELD_LENGTH = 7; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; + uint8_t latchupId = 0; + uint32_t mg = 0; - 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); - } + 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: + /** + * @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 dutycycle + */ + SetAlertlimit(uint8_t latchupId, uint32_t dutycycle) + : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_SET_ALERT_LIMIT, DEFAULT_SEQUENCE_COUNT), + latchupId(latchupId), + dutycycle(dutycycle) { + initPacket(); + } -class SetAlertlimit: public SpacePacket { -public: + private: + static const uint16_t DATA_FIELD_LENGTH = 7; + static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; - /** - * @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 dutycycle - */ - SetAlertlimit(uint8_t latchupId, uint32_t dutycycle) : - SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_SET_ALERT_LIMIT, - DEFAULT_SEQUENCE_COUNT), latchupId(latchupId), dutycycle(dutycycle) { - initPacket(); - } + static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; -private: + uint8_t latchupId = 0; + uint32_t dutycycle = 0; - 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 dutycycle = 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(&dutycycle, &data_field_ptr, &serializedSize, - sizeof(dutycycle), 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); - } + 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(&dutycycle, &data_field_ptr, &serializedSize, + sizeof(dutycycle), 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 SetAlertIrqFilter: public SpacePacket { -public: +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(); + } - /** - * @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; -private: + static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - static const uint16_t DATA_FIELD_LENGTH = 5; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; + uint8_t latchupId = 0; + uint8_t tp = 0; + uint8_t div = 0; - 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); - } + 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: +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(); + } - /** - * @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; -private: + static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - static const uint16_t DATA_FIELD_LENGTH = 6; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; + uint32_t sweepPeriod = 0; - 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); - } + 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. */ -class SetAdcEnabledChannels: public SpacePacket { -public: +class SetAdcEnabledChannels : public SpacePacket { + public: + /** + * @brief Constructor + * + * @param ch Defines channels to be enabled or disabled. + */ + SetAdcEnabledChannels(uint16_t ch) + : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_SET_ADC_ENABLED_CHANNELS, + DEFAULT_SEQUENCE_COUNT), + ch(ch) { + initPacket(); + } - /** - * @brief Constructor - * - * @param ch Defines channels to be enabled or disabled. - */ - SetAdcEnabledChannels(uint16_t ch) : - SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_SET_ADC_ENABLED_CHANNELS, - DEFAULT_SEQUENCE_COUNT), ch(ch) { - initPacket(); - } + private: + static const uint16_t DATA_FIELD_LENGTH = 4; + static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; -private: + static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - static const uint16_t DATA_FIELD_LENGTH = 4; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; + uint16_t ch = 0; - static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - - uint16_t ch = 0; - - void initPacket() { - size_t serializedSize = 0; - uint8_t* data_field_ptr = this->localData.fields.buffer; - SerializeAdapter::serialize(&ch, &data_field_ptr, &serializedSize, - sizeof(ch), 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); - } + void initPacket() { + size_t serializedSize = 0; + uint8_t* data_field_ptr = this->localData.fields.buffer; + SerializeAdapter::serialize(&ch, &data_field_ptr, &serializedSize, sizeof(ch), + 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 configures the window size and striding step of * the moving average filter applied to the ADC readings. */ -class SetAdcWindowAndStride: public SpacePacket { -public: +class SetAdcWindowAndStride : public SpacePacket { + public: + /** + * @brief Constructor + * + * @param windowSize + * @param stridingStepSize + */ + SetAdcWindowAndStride(uint16_t windowSize, uint16_t stridingStepSize) + : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_SET_ADC_WINDOW_AND_STRIDE, + DEFAULT_SEQUENCE_COUNT), + windowSize(windowSize), + stridingStepSize(stridingStepSize) { + initPacket(); + } - /** - * @brief Constructor - * - * @param windowSize - * @param stridingStepSize - */ - SetAdcWindowAndStride(uint16_t windowSize, uint16_t stridingStepSize) : - SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_SET_ADC_WINDOW_AND_STRIDE, - DEFAULT_SEQUENCE_COUNT), windowSize(windowSize), stridingStepSize( - stridingStepSize) { - initPacket(); - } + private: + static const uint16_t DATA_FIELD_LENGTH = 6; + static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; -private: + static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - static const uint16_t DATA_FIELD_LENGTH = 6; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; + uint16_t windowSize = 0; + uint16_t stridingStepSize = 0; - static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - - uint16_t windowSize = 0; - uint16_t stridingStepSize = 0; - - void initPacket() { - size_t serializedSize = 0; - uint8_t* data_field_ptr = this->localData.fields.buffer; - SerializeAdapter::serialize(&windowSize, &data_field_ptr, &serializedSize, - sizeof(windowSize), SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&stridingStepSize, &data_field_ptr, &serializedSize, - sizeof(stridingStepSize), 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); - } + void initPacket() { + size_t serializedSize = 0; + uint8_t* data_field_ptr = this->localData.fields.buffer; + SerializeAdapter::serialize(&windowSize, &data_field_ptr, &serializedSize, + sizeof(windowSize), SerializeIF::Endianness::BIG); + serializedSize = 0; + SerializeAdapter::serialize(&stridingStepSize, &data_field_ptr, &serializedSize, + sizeof(stridingStepSize), 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 ADC trigger threshold. */ -class SetAdcThreshold: public SpacePacket { -public: +class SetAdcThreshold : public SpacePacket { + public: + /** + * @brief Constructor + * + * @param threshold + */ + SetAdcThreshold(uint32_t threshold) + : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_SET_ADC_THRESHOLD, DEFAULT_SEQUENCE_COUNT), + threshold(threshold) { + initPacket(); + } - /** - * @brief Constructor - * - * @param threshold - */ - SetAdcThreshold(uint32_t threshold) : - SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_SET_ADC_THRESHOLD, - DEFAULT_SEQUENCE_COUNT), threshold(threshold) { - initPacket(); - } + private: + static const uint16_t DATA_FIELD_LENGTH = 6; + static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; -private: + static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - static const uint16_t DATA_FIELD_LENGTH = 6; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; + uint32_t threshold = 0; - static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - - uint32_t threshold = 0; - - void initPacket() { - size_t serializedSize = 0; - uint8_t* data_field_ptr = this->localData.fields.buffer; - SerializeAdapter::serialize(&threshold, &data_field_ptr, &serializedSize, - sizeof(threshold), 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); - } + void initPacket() { + size_t serializedSize = 0; + uint8_t* data_field_ptr = this->localData.fields.buffer; + SerializeAdapter::serialize(&threshold, &data_field_ptr, &serializedSize, + sizeof(threshold), 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 select between NVM 0 and NVM 1. */ -class SelectNvm: public SpacePacket { -public: +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(); + } - /** - * @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; -private: + static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - static const uint16_t DATA_FIELD_LENGTH = 3; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; + uint8_t mem = 0; - 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); - } + 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: +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(); + } - /** - * @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; -private: + static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - static const uint16_t DATA_FIELD_LENGTH = 4; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; + uint8_t n01 = 0; + uint8_t n3 = 0; - 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); - } + 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. */ -class RunAutoEmTests: public SpacePacket { -public: +class RunAutoEmTests : public SpacePacket { + public: + /** + * @brief Constructor + * + * @param test 1 - complete EM test, 2 - Short test (only memory readback NVM0,1,3) + */ + RunAutoEmTests(uint8_t test) + : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_RUN_AUTO_EM_TESTS, DEFAULT_SEQUENCE_COUNT), + test(test) { + initPacket(); + } - /** - * @brief Constructor - * - * @param test 1 - complete EM test, 2 - Short test (only memory readback NVM0,1,3) - */ - RunAutoEmTests(uint8_t test) : - SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_RUN_AUTO_EM_TESTS, - DEFAULT_SEQUENCE_COUNT), test(test) { - initPacket(); - } + private: + static const uint16_t DATA_FIELD_LENGTH = 3; + static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; -private: + static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - static const uint16_t DATA_FIELD_LENGTH = 3; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; + uint8_t test = 0; - static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - - uint8_t test = 0; - - 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); - } + 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: +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(); + } - /** - * @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; -private: + static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - static const uint16_t DATA_FIELD_LENGTH = 3; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; + uint8_t en = 0; - 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); - } + 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: +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(); + } - /** - * @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; -private: + static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - static const uint16_t DATA_FIELD_LENGTH = 3; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; + uint8_t vb = 0; - 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), 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); - } + void initPacket() { + size_t serializedSize = 0; + uint8_t* data_field_ptr = this->localData.fields.buffer; + SerializeAdapter::serialize(&vb, &data_field_ptr, &serializedSize, sizeof(vb), + 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 wipe or dump parts of the MRAM. */ -class MramCmd: public SpacePacket { -public: +class MramCmd : public SpacePacket { + public: + enum class MramAction { WIPE, DUMP }; - enum class MramAction { - WIPE, - DUMP - }; - - /** - * @brief Constructor - * - * @param start Start address of the MRAM section to wipe or dump - * @param stop End address of the MRAM section to wipe or dump - * @param action Dump or wipe MRAM - * - * @note The content at the stop address is excluded from the dump or wipe operation. - */ - MramCmd(uint32_t start, uint32_t stop, MramAction action) : - SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_IDLE_PACKET, - DEFAULT_SEQUENCE_COUNT), start(start), stop(stop) { - if(action == MramAction::WIPE) { - this->setAPID(APID_WIPE_MRAM); - } - else if (action == MramAction::DUMP) { - this->setAPID(APID_DUMP_MRAM); - } - else { - sif::debug << "WipeMram: Invalid action specified"; - } - initPacket(); + /** + * @brief Constructor + * + * @param start Start address of the MRAM section to wipe or dump + * @param stop End address of the MRAM section to wipe or dump + * @param action Dump or wipe MRAM + * + * @note The content at the stop address is excluded from the dump or wipe operation. + */ + MramCmd(uint32_t start, uint32_t stop, MramAction action) + : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_IDLE_PACKET, DEFAULT_SEQUENCE_COUNT), + start(start), + stop(stop) { + if (action == MramAction::WIPE) { + this->setAPID(APID_WIPE_MRAM); + } else if (action == MramAction::DUMP) { + this->setAPID(APID_DUMP_MRAM); + } else { + sif::debug << "WipeMram: Invalid action specified"; } + initPacket(); + } -private: + private: + static const uint16_t DATA_FIELD_LENGTH = 8; + static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; - static const uint16_t DATA_FIELD_LENGTH = 8; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; + static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; + uint32_t start = 0; + uint32_t stop = 0; - uint32_t start = 0; - uint32_t stop = 0; - - void initPacket() { - uint8_t concatBuffer[6]; - concatBuffer[0] = static_cast(start >> 16); - concatBuffer[1] = static_cast(start >> 8); - concatBuffer[2] = static_cast(start); - 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)); - size_t 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); - } + void initPacket() { + uint8_t concatBuffer[6]; + concatBuffer[0] = static_cast(start >> 16); + concatBuffer[1] = static_cast(start >> 8); + concatBuffer[2] = static_cast(start); + 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)); + size_t 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 change the state of a GPIO. This command is only * required for ground testing. */ -class SetGpio: public SpacePacket { -public: +class SetGpio : public SpacePacket { + public: + /** + * @brief Constructor + * + * @param port + * @param pin + * @param val + */ + SetGpio(uint8_t port, uint8_t pin, uint8_t val) + : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_SET_GPIO, DEFAULT_SEQUENCE_COUNT), + port(port), + pin(pin), + val(val) { + initPacket(); + } - /** - * @brief Constructor - * - * @param port - * @param pin - * @param val - */ - SetGpio(uint8_t port, uint8_t pin, uint8_t val) : - SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_SET_GPIO, - DEFAULT_SEQUENCE_COUNT), port(port), pin(pin), val(val) { - initPacket(); - } + private: + static const uint16_t DATA_FIELD_LENGTH = 5; + static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; -private: + static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - static const uint16_t DATA_FIELD_LENGTH = 5; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; + uint8_t port = 0; + uint8_t pin = 0; + uint8_t val = 0; - static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - - uint8_t port = 0; - uint8_t pin = 0; - uint8_t val = 0; - - void initPacket() { - size_t serializedSize = 0; - uint8_t* data_field_ptr = this->localData.fields.buffer; - SerializeAdapter::serialize(&port, &data_field_ptr, &serializedSize, - sizeof(port), SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&pin, &data_field_ptr, &serializedSize, - sizeof(pin), SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&val, &data_field_ptr, &serializedSize, - sizeof(val), 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); - } + void initPacket() { + size_t serializedSize = 0; + uint8_t* data_field_ptr = this->localData.fields.buffer; + SerializeAdapter::serialize(&port, &data_field_ptr, &serializedSize, sizeof(port), + SerializeIF::Endianness::BIG); + serializedSize = 0; + SerializeAdapter::serialize(&pin, &data_field_ptr, &serializedSize, sizeof(pin), + SerializeIF::Endianness::BIG); + serializedSize = 0; + SerializeAdapter::serialize(&val, &data_field_ptr, &serializedSize, sizeof(val), + 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 print the state of a GPIO * to the debug output. */ -class ReadGpio: public SpacePacket { -public: +class ReadGpio : public SpacePacket { + public: + /** + * @brief Constructor + * + * @param port + * @param pin + */ + ReadGpio(uint8_t port, uint8_t pin) + : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_READ_GPIO, DEFAULT_SEQUENCE_COUNT), + port(port), + pin(pin) { + initPacket(); + } - /** - * @brief Constructor - * - * @param port - * @param pin - */ - ReadGpio(uint8_t port, uint8_t pin) : - SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_READ_GPIO, - DEFAULT_SEQUENCE_COUNT), port(port), pin(pin) { - initPacket(); - } + private: + static const uint16_t DATA_FIELD_LENGTH = 4; + static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; -private: + static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - static const uint16_t DATA_FIELD_LENGTH = 4; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; + uint8_t port = 0; + uint8_t pin = 0; - static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - - uint8_t port = 0; - uint8_t pin = 0; - - void initPacket() { - size_t serializedSize = 0; - uint8_t* data_field_ptr = this->localData.fields.buffer; - SerializeAdapter::serialize(&port, &data_field_ptr, &serializedSize, - sizeof(port), SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&pin, &data_field_ptr, &serializedSize, - sizeof(pin), 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); - } + void initPacket() { + size_t serializedSize = 0; + uint8_t* data_field_ptr = this->localData.fields.buffer; + SerializeAdapter::serialize(&port, &data_field_ptr, &serializedSize, sizeof(port), + SerializeIF::Endianness::BIG); + serializedSize = 0; + SerializeAdapter::serialize(&pin, &data_field_ptr, &serializedSize, sizeof(pin), + 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); + } }; /** @@ -1355,255 +1311,236 @@ private: * OP = 0x01: Only the mirror entries will be wiped. * OP = 0x02: Only the circular entries will be wiped. */ -class FactoryReset: public SpacePacket { -public: +class FactoryReset : public SpacePacket { + public: + enum class Op { CLEAR_ALL, MIRROR_ENTRIES, CIRCULAR_ENTRIES }; - enum class Op { - CLEAR_ALL, - MIRROR_ENTRIES, - CIRCULAR_ENTRIES - }; + /** + * @brief Constructor + * + * @param op + */ + FactoryReset(Op op) : SpacePacket(0, true, APID_FACTORY_RESET, DEFAULT_SEQUENCE_COUNT), op(op) { + initPacket(); + } - /** - * @brief Constructor - * - * @param op - */ - FactoryReset(Op op) : - SpacePacket(0, true, APID_FACTORY_RESET, - DEFAULT_SEQUENCE_COUNT), op(op) { - initPacket(); - } - -private: - - uint16_t packetLen = 1; // only CRC in data field - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; - - uint8_t crcOffset = 0; - - Op op = Op::CLEAR_ALL; - - void initPacket() { - - uint8_t* data_field_ptr = this->localData.fields.buffer; - - switch(op) { - case Op::MIRROR_ENTRIES: - *data_field_ptr = 1; - packetLen = 2; - crcOffset = 1; - break; - case Op::CIRCULAR_ENTRIES: - *data_field_ptr = 2; - packetLen = 2; - crcOffset = 1; - break; - default: - break; - } - this->setPacketDataLength(packetLen); - size_t serializedSize = 0; - uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, - sizeof(CCSDSPrimaryHeader) + packetLen - 1); - uint8_t* crcPos = this->localData.fields.buffer + crcOffset; - SerializeAdapter::serialize(&crc, &crcPos, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); + private: + uint16_t packetLen = 1; // only CRC in data field + static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; + + uint8_t crcOffset = 0; + + Op op = Op::CLEAR_ALL; + + void initPacket() { + uint8_t* data_field_ptr = this->localData.fields.buffer; + + switch (op) { + case Op::MIRROR_ENTRIES: + *data_field_ptr = 1; + packetLen = 2; + crcOffset = 1; + break; + case Op::CIRCULAR_ENTRIES: + *data_field_ptr = 2; + packetLen = 2; + crcOffset = 1; + break; + default: + break; } + this->setPacketDataLength(packetLen); + size_t serializedSize = 0; + uint16_t crc = + CRC::crc16ccitt(this->localData.byteStream, sizeof(CCSDSPrimaryHeader) + packetLen - 1); + uint8_t* crcPos = this->localData.fields.buffer + crcOffset; + SerializeAdapter::serialize(&crc, &crcPos, &serializedSize, sizeof(crc), + SerializeIF::Endianness::BIG); + } }; class SupvTcSpacePacket : public SpacePacket { -public: - SupvTcSpacePacket(size_t payloadDataLen, uint16_t apid) : - SpacePacket(payloadDataLen + 1, true, apid, - DEFAULT_SEQUENCE_COUNT), payloadDataLen(payloadDataLen) { - } + public: + SupvTcSpacePacket(size_t payloadDataLen, uint16_t apid) + : SpacePacket(payloadDataLen + 1, true, apid, DEFAULT_SEQUENCE_COUNT), + payloadDataLen(payloadDataLen) {} - void makeCrc() { - size_t serializedSize = 0; - uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, - sizeof(CCSDSPrimaryHeader) + payloadDataLen); - uint8_t* crcPos = this->localData.fields.buffer + payloadDataLen; - SerializeAdapter::serialize(&crc, &crcPos, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); - } + void makeCrc() { + size_t serializedSize = 0; + uint16_t crc = + CRC::crc16ccitt(this->localData.byteStream, sizeof(CCSDSPrimaryHeader) + payloadDataLen); + uint8_t* crcPos = this->localData.fields.buffer + payloadDataLen; + SerializeAdapter::serialize(&crc, &crcPos, &serializedSize, sizeof(crc), + SerializeIF::Endianness::BIG); + } -private: - // The sequence count of most of the TC packets for the supervisor is 1. - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; + private: + // The sequence count of most of the TC packets for the supervisor is 1. + static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; - // The size of the payload data (data field without crc size) - size_t payloadDataLen = 0; + // The size of the payload data (data field without crc size) + size_t payloadDataLen = 0; }; /** * @brief This class can be used to package the update available or update verify command. */ -class UpdateInfo: public SupvTcSpacePacket { -public: +class UpdateInfo : 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) { + initPacket(); + makeCrc(); + } - /** - * @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) { - initPacket(); - makeCrc(); - } + private: + static const uint16_t PAYLOAD_LENGTH = 14; // length without CRC field -private: + uint8_t image = 0; + uint8_t partition = 0; + uint32_t imageSize = 0; + uint32_t imageCrc = 0; + uint32_t numPackets = 0; - static const uint16_t PAYLOAD_LENGTH = 14; // length without CRC field - - uint8_t image = 0; - uint8_t partition = 0; - uint32_t imageSize = 0; - uint32_t imageCrc = 0; - uint32_t numPackets = 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), SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&partition, &data_field_ptr, &serializedSize, - sizeof(partition), 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); - } + void initPacket() { + size_t serializedSize = 0; + uint8_t* data_field_ptr = this->localData.fields.buffer; + SerializeAdapter::serialize(&image, &data_field_ptr, &serializedSize, sizeof(image), + SerializeIF::Endianness::BIG); + serializedSize = 0; + SerializeAdapter::serialize(&partition, &data_field_ptr, &serializedSize, + sizeof(partition), 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); + } }; /** * @brief This class packages the space packet transporting a part of an MPSoC update. */ -class UpdatePacket: public SupvTcSpacePacket { -public: +class UpdatePacket : public SupvTcSpacePacket { + public: + /** + * @brief Constructor + * + * @param payloadLength Update data length (data field length without CRC) + */ + UpdatePacket(uint16_t payloadLength) : SupvTcSpacePacket(payloadLength, APID_UPDATE_IMAGE_DATA) {} - /** - * @brief Constructor - * - * @param payloadLength Update data length (data field length without CRC) - */ - UpdatePacket(uint16_t payloadLength) : - SupvTcSpacePacket(payloadLength, APID_UPDATE_IMAGE_DATA) { - } - - /** - * @brief Returns the pointer to the beginning of the data field. - */ - uint8_t* getDataFieldPointer() { - return this->localData.fields.buffer; - } + /** + * @brief Returns the pointer to the beginning of the data field. + */ + uint8_t* getDataFieldPointer() { return this->localData.fields.buffer; } }; /** * @brief This dataset stores the boot status report of the supervisor. */ -class BootStatusReport: public StaticLocalDataSet { -public: +class BootStatusReport : public StaticLocalDataSet { + public: + BootStatusReport(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, BOOT_REPORT_SET_ID) {} - BootStatusReport(HasLocalDataPoolIF* owner) : - StaticLocalDataSet(owner, BOOT_REPORT_SET_ID) { - } + BootStatusReport(object_id_t objectId) + : StaticLocalDataSet(sid_t(objectId, BOOT_REPORT_SET_ID)) {} - BootStatusReport(object_id_t objectId) : - 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); - /** 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 */ - lp_var_t bootTimeoutMs = lp_var_t(sid.objectId, PoolIds::BOOT_TIMEOUT_MS, this); - lp_var_t activeNvm = lp_var_t(sid.objectId, PoolIds::ACTIVE_NVM, this); - /** States of the boot partition pins */ - 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); + /** 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); + /** 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 */ + lp_var_t bootTimeoutMs = + lp_var_t(sid.objectId, PoolIds::BOOT_TIMEOUT_MS, this); + lp_var_t activeNvm = lp_var_t(sid.objectId, PoolIds::ACTIVE_NVM, this); + /** States of the boot partition pins */ + 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); }; /** * @brief This dataset stores the housekeeping data of the supervisor. */ -class HkSet: public StaticLocalDataSet { -public: +class HkSet : public StaticLocalDataSet { + public: + HkSet(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, HK_SET_ID) {} - HkSet(HasLocalDataPoolIF* owner) : - StaticLocalDataSet(owner, HK_SET_ID) { - } + HkSet(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, HK_SET_ID)) {} - HkSet(object_id_t objectId) : - StaticLocalDataSet(sid_t(objectId, HK_SET_ID)) { - } - - 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 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 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 = lp_var_t(sid.objectId, PoolIds::MISSION_IO_STATE, - this); - lp_var_t fmcState = lp_var_t(sid.objectId, PoolIds::FMC_STATE, this); + 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 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 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 = + lp_var_t(sid.objectId, PoolIds::MISSION_IO_STATE, this); + lp_var_t fmcState = lp_var_t(sid.objectId, PoolIds::FMC_STATE, this); }; /** * @brief This dataset stores the last requested latchup status report. */ -class LatchupStatusReport: public StaticLocalDataSet { -public: +class LatchupStatusReport : public StaticLocalDataSet { + public: + LatchupStatusReport(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, LATCHUP_RPT_ID) {} - LatchupStatusReport(HasLocalDataPoolIF* owner) : - StaticLocalDataSet(owner, LATCHUP_RPT_ID) { - } + LatchupStatusReport(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, LATCHUP_RPT_ID)) {} - LatchupStatusReport(object_id_t objectId) : - StaticLocalDataSet(sid_t(objectId, LATCHUP_RPT_ID)) { - } - - lp_var_t id = lp_var_t(sid.objectId, PoolIds::LATCHUP_ID, this); - lp_var_t cnt0 = lp_var_t(sid.objectId, PoolIds::CNT0, this); - lp_var_t cnt1 = lp_var_t(sid.objectId, PoolIds::CNT1, this); - lp_var_t cnt2 = lp_var_t(sid.objectId, PoolIds::CNT2, this); - lp_var_t cnt3 = lp_var_t(sid.objectId, PoolIds::CNT3, this); - 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 id = lp_var_t(sid.objectId, PoolIds::LATCHUP_ID, this); + lp_var_t cnt0 = lp_var_t(sid.objectId, PoolIds::CNT0, this); + lp_var_t cnt1 = lp_var_t(sid.objectId, PoolIds::CNT1, this); + lp_var_t cnt2 = lp_var_t(sid.objectId, PoolIds::CNT2, this); + lp_var_t cnt3 = lp_var_t(sid.objectId, PoolIds::CNT3, this); + 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); }; -} +} // namespace PLOC_SPV #endif /* MISSION_DEVICES_DEVICEDEFINITIONS_PLOCSVPDEFINITIONS_H_ */ diff --git a/bsp_q7s/gpio/CMakeLists.txt b/bsp_q7s/gpio/CMakeLists.txt deleted file mode 100644 index dd657546..00000000 --- a/bsp_q7s/gpio/CMakeLists.txt +++ /dev/null @@ -1,3 +0,0 @@ -target_sources(${TARGET_NAME} PRIVATE - gpioCallbacks.cpp -) diff --git a/bsp_q7s/gpio/gpioCallbacks.cpp b/bsp_q7s/gpio/gpioCallbacks.cpp deleted file mode 100644 index da7c58e4..00000000 --- a/bsp_q7s/gpio/gpioCallbacks.cpp +++ /dev/null @@ -1,340 +0,0 @@ -#include "gpioCallbacks.h" -#include "busConf.h" -#include - -#include -#include -#include - - -namespace gpioCallbacks { - -GpioIF* gpioComInterface; - -void initSpiCsDecoder(GpioIF* gpioComIF) { - - ReturnValue_t result; - - if (gpioComIF == nullptr) { - sif::debug << "initSpiCsDecoder: Invalid gpioComIF" << std::endl; - return; - } - - gpioComInterface = gpioComIF; - - GpioCookie* spiMuxGpios = new GpioCookie; - - GpiodRegularByLabel* spiMuxBit = nullptr; - /** Setting mux bit 1 to low will disable IC21 on the interface board */ - spiMuxBit = new GpiodRegularByLabel(q7s::GPIO_3V3_OBC1C, q7s::SPI_MUX_BIT_1, - "SPI Mux Bit 1", gpio::OUT, gpio::LOW); - spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_1, spiMuxBit); - /** Setting mux bit 2 to low disables IC1 on the TCS board */ - spiMuxBit = new GpiodRegularByLabel(q7s::GPIO_3V3_OBC1C, q7s::SPI_MUX_BIT_2, - "SPI Mux Bit 2", gpio::OUT, gpio::LOW); - spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_2, spiMuxBit); - /** Setting mux bit 3 to low disables IC2 on the TCS board and IC22 on the interface board */ - spiMuxBit = new GpiodRegularByLabel(q7s::GPIO_3V3_OBC1C, q7s::SPI_MUX_BIT_3, - "SPI Mux Bit 3", gpio::OUT, gpio::LOW); - spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_3, spiMuxBit); - /** The following gpios can take arbitrary initial values */ - spiMuxBit = new GpiodRegularByLabel(q7s::GPIO_3V3_OBC1C, q7s::SPI_MUX_BIT_4, - "SPI Mux Bit 4", gpio::OUT, gpio::LOW); - spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_4, spiMuxBit); - spiMuxBit = new GpiodRegularByLabel(q7s::GPIO_3V3_OBC1C, q7s::SPI_MUX_BIT_5, - "SPI Mux Bit 5", gpio::OUT, gpio::LOW); - spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_5, spiMuxBit); - spiMuxBit = new GpiodRegularByLabel(q7s::GPIO_3V3_OBC1C, q7s::SPI_MUX_BIT_6, - "SPI Mux Bit 6", gpio::OUT, gpio::LOW); - spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_6, spiMuxBit); - GpiodRegularByLabel* enRwDecoder = new GpiodRegularByLabel(q7s::GPIO_FLEX_OBC1F_B1, - q7s::EN_RW_CS, "EN_RW_CS", gpio::OUT, gpio::HIGH); - spiMuxGpios->addGpio(gpioIds::EN_RW_CS, enRwDecoder); - - result = gpioComInterface->addGpios(spiMuxGpios); - if (result != HasReturnvaluesIF::RETURN_OK) { - sif::error << "initSpiCsDecoder: Failed to add mux bit gpios to gpioComIF" << std::endl; - return; - } -} - -void spiCsDecoderCallback(gpioId_t gpioId, gpio::GpioOperation gpioOp, int value, - void* args) { - - if (gpioComInterface == nullptr) { - sif::debug << "spiCsDecoderCallback: No gpioComIF specified. Call initSpiCsDecoder " - << "to specify gpioComIF" << std::endl; - return; - } - - /* Reading is not supported by the callback function */ - if (gpioOp == gpio::GpioOperation::READ) { - return; - } - - if (value == 1) { - disableAllDecoder(); - } - else if (value == 0) { - switch (gpioId) { - case(gpioIds::RTD_IC3): { - enableDecoderTcsIc1(); - selectY7(); - break; - } - case(gpioIds::RTD_IC4): { - enableDecoderTcsIc1(); - selectY6(); - break; - } - case(gpioIds::RTD_IC5): { - enableDecoderTcsIc1(); - selectY5(); - break; - } - case(gpioIds::RTD_IC6): { - enableDecoderTcsIc1(); - selectY4(); - break; - } - case(gpioIds::RTD_IC7): { - enableDecoderTcsIc1(); - selectY3(); - break; - } - case(gpioIds::RTD_IC8): { - enableDecoderTcsIc1(); - selectY2(); - break; - } - case(gpioIds::RTD_IC9): { - enableDecoderTcsIc1(); - selectY1(); - break; - } - case(gpioIds::RTD_IC10): { - enableDecoderTcsIc1(); - selectY0(); - break; - } - case(gpioIds::RTD_IC11): { - enableDecoderTcsIc2(); - selectY7(); - break; - } - case(gpioIds::RTD_IC12): { - enableDecoderTcsIc2(); - selectY6(); - break; - } - case(gpioIds::RTD_IC13): { - enableDecoderTcsIc2(); - selectY5(); - break; - } - case(gpioIds::RTD_IC14): { - enableDecoderTcsIc2(); - selectY4(); - break; - } - case(gpioIds::RTD_IC15): { - enableDecoderTcsIc2(); - selectY3(); - break; - } - case(gpioIds::RTD_IC16): { - enableDecoderTcsIc2(); - selectY2(); - break; - } - case(gpioIds::RTD_IC17): { - enableDecoderTcsIc2(); - selectY1(); - break; - } - case(gpioIds::RTD_IC18): { - enableDecoderTcsIc2(); - selectY0(); - break; - } - case(gpioIds::CS_SUS_1): { - enableDecoderInterfaceBoardIc1(); - selectY0(); - break; - } - case(gpioIds::CS_SUS_2): { - enableDecoderInterfaceBoardIc1(); - selectY1(); - break; - } - case(gpioIds::CS_SUS_3): { - enableDecoderInterfaceBoardIc2(); - selectY0(); - break; - } - case(gpioIds::CS_SUS_4): { - enableDecoderInterfaceBoardIc2(); - selectY1(); - break; - } - case(gpioIds::CS_SUS_5): { - enableDecoderInterfaceBoardIc2(); - selectY2(); - break; - } - case(gpioIds::CS_SUS_6): { - enableDecoderInterfaceBoardIc1(); - selectY2(); - break; - } - case(gpioIds::CS_SUS_7): { - enableDecoderInterfaceBoardIc1(); - selectY3(); - break; - } - case(gpioIds::CS_SUS_8): { - enableDecoderInterfaceBoardIc2(); - selectY3(); - break; - } - case(gpioIds::CS_SUS_9): { - enableDecoderInterfaceBoardIc1(); - selectY4(); - break; - } - case(gpioIds::CS_SUS_10): { - enableDecoderInterfaceBoardIc1(); - selectY5(); - break; - } - case(gpioIds::CS_SUS_11): { - enableDecoderInterfaceBoardIc2(); - selectY4(); - break; - } - case(gpioIds::CS_SUS_12): { - enableDecoderInterfaceBoardIc2(); - selectY5(); - break; - } - case(gpioIds::CS_SUS_13): { - enableDecoderInterfaceBoardIc1(); - selectY6(); - break; - } - case(gpioIds::CS_RW1): { - enableRwDecoder(); - selectY0(); - break; - } - case(gpioIds::CS_RW2): { - enableRwDecoder(); - selectY1(); - break; - } - case(gpioIds::CS_RW3): { - enableRwDecoder(); - selectY2(); - break; - } - case(gpioIds::CS_RW4): { - enableRwDecoder(); - selectY3(); - break; - } - default: - sif::debug << "spiCsDecoderCallback: Invalid gpio id " << gpioId << std::endl; - } - } - else { - sif::debug << "spiCsDecoderCallback: Invalid value. Must be 0 or 1" << std::endl; - } -} - -void enableDecoderTcsIc1() { - gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_1); - gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_2); - gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_3); -} - -void enableDecoderTcsIc2() { - gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_1); - gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_2); - gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_3); -} - -void enableDecoderInterfaceBoardIc1() { - gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_1); - gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_2); - gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_3); -} - -void enableDecoderInterfaceBoardIc2() { - gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_1); - gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_2); - gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_3); -} - -void enableRwDecoder() { - gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_1); - gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_2); - gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_3); - gpioComInterface->pullHigh(gpioIds::EN_RW_CS); -} - -void selectY0() { - gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_4); - gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_5); - gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_6); -} - -void selectY1() { - gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_4); - gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_5); - gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_6); -} - -void selectY2() { - gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_4); - gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_5); - gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_6); -} - -void selectY3() { - gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_4); - gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_5); - gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_6); -} - -void selectY4() { - gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_4); - gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_5); - gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_6); -} - -void selectY5() { - gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_4); - gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_5); - gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_6); -} - -void selectY6() { - gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_4); - gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_5); - gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_6); -} - -void selectY7() { - gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_4); - gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_5); - gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_6); -} - -void disableAllDecoder() { - gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_1); - gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_2); - gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_3); - gpioComInterface->pullLow(gpioIds::EN_RW_CS); -} - -} diff --git a/bsp_q7s/gpio/gpioCallbacks.h b/bsp_q7s/gpio/gpioCallbacks.h deleted file mode 100644 index eaf9a701..00000000 --- a/bsp_q7s/gpio/gpioCallbacks.h +++ /dev/null @@ -1,67 +0,0 @@ -#ifndef LINUX_GPIO_GPIOCALLBACKS_H_ -#define LINUX_GPIO_GPIOCALLBACKS_H_ - -#include -#include - - -namespace gpioCallbacks { - - /** - * @brief This function initializes the GPIOs used to control the SN74LVC138APWR decoders on - * the TCS Board and the interface board. - */ - void initSpiCsDecoder(GpioIF* gpioComIF); - - /** - * @brief This function implements the decoding to multiply gpios by using the decoder - * chips SN74LVC138APWR on the TCS board and the interface board. - */ - void spiCsDecoderCallback(gpioId_t gpioId, gpio::GpioOperation gpioOp, int value, void* args); - - /** - * @brief This function sets mux bits 1-3 to a state which will only enable the decoder - * on the TCS board which is named to IC1 in the schematic. - */ - void enableDecoderTcsIc1(); - - /** - * @brief This function sets mux bits 1-3 to a state which will only enable the decoder - * on the TCS board which is named to IC2 in the schematic. - */ - void enableDecoderTcsIc2(); - - /** - * @brief This function sets mux bits 1-3 to a state which will only enable the decoder - * on the inteface board board which is named to IC21 in the schematic. - */ - void enableDecoderInterfaceBoardIc1(); - - /** - * @brief This function sets mux bits 1-3 to a state which will only enable the decoder - * on the inteface board board which is named to IC22 in the schematic. - */ - void enableDecoderInterfaceBoardIc2(); - - /** - * @brief Enables the reaction wheel chip select decoder (IC3). - */ - void enableRwDecoder(); - - /** - * @brief This function disables all decoder. - */ - void disableAllDecoder(); - - /** The following functions enable the appropriate channel of the currently enabled decoder */ - void selectY0(); - void selectY1(); - void selectY2(); - void selectY3(); - void selectY4(); - void selectY5(); - void selectY6(); - void selectY7(); -} - -#endif /* LINUX_GPIO_GPIOCALLBACKS_H_ */ diff --git a/bsp_q7s/main.cpp b/bsp_q7s/main.cpp index 9ce0dca2..dfcaebf0 100644 --- a/bsp_q7s/main.cpp +++ b/bsp_q7s/main.cpp @@ -12,12 +12,11 @@ * @brief This is the main program for the target hardware. * @return */ -int main(void) -{ - using namespace std; +int main(void) { + using namespace std; #if Q7S_SIMPLE_MODE == 0 - return obsw::obsw(); + return obsw::obsw(); #else - return simple::simple(); + return simple::simple(); #endif } diff --git a/bsp_q7s/memory/CMakeLists.txt b/bsp_q7s/memory/CMakeLists.txt index 6c7d0a94..0658242a 100644 --- a/bsp_q7s/memory/CMakeLists.txt +++ b/bsp_q7s/memory/CMakeLists.txt @@ -1,4 +1,4 @@ -target_sources(${TARGET_NAME} PRIVATE +target_sources(${OBSW_NAME} PRIVATE FileSystemHandler.cpp SdCardManager.cpp scratchApi.cpp diff --git a/bsp_q7s/memory/FileSystemHandler.cpp b/bsp_q7s/memory/FileSystemHandler.cpp index ad8ec137..7a4a791c 100644 --- a/bsp_q7s/memory/FileSystemHandler.cpp +++ b/bsp_q7s/memory/FileSystemHandler.cpp @@ -1,270 +1,243 @@ #include "FileSystemHandler.h" -#include "bsp_q7s/core/CoreController.h" - -#include "fsfw/tasks/TaskFactory.h" -#include "fsfw/memory/GenericFileSystemMessage.h" -#include "fsfw/ipc/QueueFactory.h" - #include -#include #include +#include -FileSystemHandler::FileSystemHandler(object_id_t fileSystemHandler): - SystemObject(fileSystemHandler) { - mq = QueueFactory::instance()->createMessageQueue(FS_MAX_QUEUE_SIZE); +#include "bsp_q7s/core/CoreController.h" +#include "fsfw/ipc/QueueFactory.h" +#include "fsfw/memory/GenericFileSystemMessage.h" +#include "fsfw/tasks/TaskFactory.h" + +FileSystemHandler::FileSystemHandler(object_id_t fileSystemHandler) + : SystemObject(fileSystemHandler) { + auto mqArgs = MqArgs(this->getObjectId()); + mq = QueueFactory::instance()->createMessageQueue(FS_MAX_QUEUE_SIZE, + MessageQueueMessage::MAX_MESSAGE_SIZE, &mqArgs); } -FileSystemHandler::~FileSystemHandler() { - QueueFactory::instance()->deleteMessageQueue(mq); -} +FileSystemHandler::~FileSystemHandler() { QueueFactory::instance()->deleteMessageQueue(mq); } ReturnValue_t FileSystemHandler::performOperation(uint8_t unsignedChar) { - while(true) { - try { - fileSystemHandlerLoop(); - } - catch(std::bad_alloc& e) { - // Restart OBSW, hints at a memory leak - sif::error << "Allocation error in FileSystemHandler::performOperation" - << e.what() << std::endl; - // Set up an error file or a special flag in the scratch buffer for these cases - triggerEvent(CoreController::ALLOC_FAILURE, 0 , 0); - CoreController::incrementAllocationFailureCount(); - } + while (true) { + try { + fileSystemHandlerLoop(); + } catch (std::bad_alloc& e) { + // Restart OBSW, hints at a memory leak + sif::error << "Allocation error in FileSystemHandler::performOperation" << e.what() + << std::endl; + // Set up an error file or a special flag in the scratch buffer for these cases + triggerEvent(CoreController::ALLOC_FAILURE, 0, 0); + CoreController::incrementAllocationFailureCount(); } + } } - void FileSystemHandler::fileSystemHandlerLoop() { - CommandMessage filemsg; - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - while(true) { - if(opCounter % 5 == 0) { - if(coreCtrl->sdInitFinished()) { - fileSystemCheckup(); - } - } - result = mq->receiveMessage(&filemsg); - if(result == MessageQueueIF::EMPTY) { - break; - } - else if(result != HasReturnvaluesIF::RETURN_FAILED) { - sif::warning << "FileSystemHandler::performOperation: Message reception failed!" - << std::endl; - break; - } - Command_t command = filemsg.getCommand(); - switch(command) { - case(GenericFileSystemMessage::CMD_CREATE_DIRECTORY): { - break; - } - case(GenericFileSystemMessage::CMD_CREATE_FILE): { - break; - } - } - opCounter++; + CommandMessage filemsg; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + while (true) { + if (opCounter % 5 == 0) { + if (coreCtrl->sdInitFinished()) { + fileSystemCheckup(); + } + } + result = mq->receiveMessage(&filemsg); + if (result == MessageQueueIF::EMPTY) { + break; + } else if (result != HasReturnvaluesIF::RETURN_FAILED) { + sif::warning << "FileSystemHandler::performOperation: Message reception failed!" << std::endl; + break; + } + Command_t command = filemsg.getCommand(); + switch (command) { + case (GenericFileSystemMessage::CMD_CREATE_DIRECTORY): { + break; + } + case (GenericFileSystemMessage::CMD_CREATE_FILE): { + break; + } } - - // This task will have a low priority and will run permanently in the background - // so we will just run in a permanent loop here and check file system - // messages permanently opCounter++; - TaskFactory::instance()->delayTask(1000); + } + + // This task will have a low priority and will run permanently in the background + // so we will just run in a permanent loop here and check file system + // messages permanently + opCounter++; + TaskFactory::instance()->delayTask(1000); } void FileSystemHandler::fileSystemCheckup() { - SdCardManager::SdStatePair statusPair; - sdcMan->getSdCardActiveStatus(statusPair); - sd::SdCard preferredSdCard; - sdcMan->getPreferredSdCard(preferredSdCard); - if((preferredSdCard == sd::SdCard::SLOT_0) and - (statusPair.first == sd::SdState::MOUNTED)) { - currentMountPrefix = SdCardManager::SD_0_MOUNT_POINT; + SdCardManager::SdStatePair statusPair; + sdcMan->getSdCardActiveStatus(statusPair); + sd::SdCard preferredSdCard; + sdcMan->getPreferredSdCard(preferredSdCard); + 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 + (statusPair.second == sd::SdState::MOUNTED)) { + currentMountPrefix = SdCardManager::SD_1_MOUNT_POINT; + } else { + std::string sdString; + if (preferredSdCard == sd::SdCard::SLOT_0) { + sdString = "0"; + } else { + sdString = "1"; } - else if((preferredSdCard == sd::SdCard::SLOT_1) and - (statusPair.second == sd::SdState::MOUNTED)) { - currentMountPrefix = SdCardManager::SD_1_MOUNT_POINT; - } - else { - std::string sdString; - if(preferredSdCard == sd::SdCard::SLOT_0) { - sdString = "0"; - } - else { - sdString = "1"; - } - sif::warning << "FileSystemHandler::performOperation: " - "Inconsistent state detected" << std::endl; - sif::warning << "Preferred SD card is " << sdString << - " but does not appear to be mounted. Attempting fix.." << std::endl; - // This function will appear to fix the inconsistent state - ReturnValue_t result = sdcMan->sanitizeState(&statusPair, preferredSdCard); - if(result != HasReturnvaluesIF::RETURN_OK) { - // Oh no. - triggerEvent(SdCardManager::SANITIZATION_FAILED, 0, 0); - sif::error << "FileSystemHandler::fileSystemCheckup: Sanitization failed" << std::endl; - } + sif::warning << "FileSystemHandler::performOperation: " + "Inconsistent state detected" + << std::endl; + sif::warning << "Preferred SD card is " << sdString + << " but does not appear to be mounted. Attempting fix.." << std::endl; + // This function will appear to fix the inconsistent state + ReturnValue_t result = sdcMan->sanitizeState(&statusPair, preferredSdCard); + if (result != HasReturnvaluesIF::RETURN_OK) { + // Oh no. + triggerEvent(SdCardManager::SANITIZATION_FAILED, 0, 0); + sif::error << "FileSystemHandler::fileSystemCheckup: Sanitization failed" << std::endl; } + } } -MessageQueueId_t FileSystemHandler::getCommandQueue() const { - return mq->getId(); -} +MessageQueueId_t FileSystemHandler::getCommandQueue() const { return mq->getId(); } ReturnValue_t FileSystemHandler::initialize() { - coreCtrl = ObjectManager::instance()->get(objects::CORE_CONTROLLER); - if(coreCtrl == nullptr) { - sif::error << "FileSystemHandler::initialize: Could not retrieve core controller handle" << - std::endl; - } - sdcMan = SdCardManager::instance(); - sd::SdCard preferredSdCard; - ReturnValue_t result = sdcMan->getPreferredSdCard(preferredSdCard); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - if(preferredSdCard == sd::SdCard::SLOT_0) { - currentMountPrefix = SdCardManager::SD_0_MOUNT_POINT; - } - else if(preferredSdCard == sd::SdCard::SLOT_1) { - currentMountPrefix = SdCardManager::SD_1_MOUNT_POINT; - } - return HasReturnvaluesIF::RETURN_OK; + coreCtrl = ObjectManager::instance()->get(objects::CORE_CONTROLLER); + if (coreCtrl == nullptr) { + sif::error << "FileSystemHandler::initialize: Could not retrieve core controller handle" + << std::endl; + } + sdcMan = SdCardManager::instance(); + sd::SdCard preferredSdCard; + ReturnValue_t result = sdcMan->getPreferredSdCard(preferredSdCard); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if (preferredSdCard == sd::SdCard::SLOT_0) { + currentMountPrefix = SdCardManager::SD_0_MOUNT_POINT; + } else if (preferredSdCard == sd::SdCard::SLOT_1) { + currentMountPrefix = SdCardManager::SD_1_MOUNT_POINT; + } + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t FileSystemHandler::appendToFile(const char *repositoryPath, const char *filename, - const uint8_t *data, size_t size, uint16_t packetNumber, void *args) { - // A double slash between repo and filename should not be an issue, so add it in any case - std::string fullPath = currentMountPrefix + std::string(repositoryPath) + "/" + - std::string(filename); - if(not std::filesystem::exists(fullPath)) { - return FILE_DOES_NOT_EXIST; - } - std::ofstream file(fullPath, std::ios_base::app|std::ios_base::out); - file.write(reinterpret_cast(data), size); - if(not file.good()) { - return GENERIC_FILE_ERROR; - } - return HasReturnvaluesIF::RETURN_OK; -} - -ReturnValue_t FileSystemHandler::createFile(const char *repositoryPath, const char *filename, - const uint8_t *data, size_t size, void *args) { - std::string fullPath; - bool useMountPrefix = true; - parseCfg(reinterpret_cast(args), useMountPrefix); - if(useMountPrefix) { - fullPath += currentMountPrefix; - } - - // A double slash between repo and filename should not be an issue, so add it in any case - fullPath += std::string(repositoryPath) + "/" + std::string(filename); - if(std::filesystem::exists(fullPath)) { - return FILE_ALREADY_EXISTS; - } - std::ofstream file(fullPath); - file.write(reinterpret_cast(data), size); - if(not file.good()) { - return GENERIC_FILE_ERROR; - } - return HasReturnvaluesIF::RETURN_OK; -} - -ReturnValue_t FileSystemHandler::removeFile(const char *repositoryPath, const char *filename, - void *args) { - std::string fullPath; - bool useMountPrefix = true; - parseCfg(reinterpret_cast(args), useMountPrefix); - if(useMountPrefix) { - fullPath += currentMountPrefix; - } - - // A double slash between repo and filename should not be an issue, so add it in any case - fullPath += std::string(repositoryPath) + "/" + std::string(filename); - if(not std::filesystem::exists(fullPath)) { - return FILE_DOES_NOT_EXIST; - } - int result = std::remove(fullPath.c_str()); - if(result != 0) { - sif::warning << "FileSystemHandler::deleteFile: Failed with code " << result << std::endl; - return GENERIC_FILE_ERROR; - } - return HasReturnvaluesIF::RETURN_OK; -} - -ReturnValue_t FileSystemHandler::createDirectory(const char *repositoryPath, void *args) { - std::string fullPath; - bool useMountPrefix = true; - parseCfg(reinterpret_cast(args), useMountPrefix); - if(useMountPrefix) { - fullPath += currentMountPrefix; - } - - fullPath += std::string(repositoryPath); - if(std::filesystem::exists(fullPath)) { - return DIRECTORY_ALREADY_EXISTS; - } - if(std::filesystem::create_directory(fullPath)) { - return HasReturnvaluesIF::RETURN_OK; - } - sif::warning << "Creating directory " << fullPath << " failed" << std::endl; +ReturnValue_t FileSystemHandler::appendToFile(const char* repositoryPath, const char* filename, + const uint8_t* data, size_t size, + uint16_t packetNumber, FileSystemArgsIF* args) { + auto path = getInitPath(args) / repositoryPath / filename; + if (not std::filesystem::exists(path)) { + return FILE_DOES_NOT_EXIST; + } + std::ofstream file(path, std::ios_base::app | std::ios_base::out); + file.write(reinterpret_cast(data), size); + if (not file.good()) { return GENERIC_FILE_ERROR; + } + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t FileSystemHandler::removeDirectory(const char *repositoryPath, - bool deleteRecurively, void *args) { - std::string fullPath; - bool useMountPrefix = true; - parseCfg(reinterpret_cast(args), useMountPrefix); - if(useMountPrefix) { - fullPath += currentMountPrefix; - } +ReturnValue_t FileSystemHandler::createFile(const char* repositoryPath, const char* filename, + const uint8_t* data, size_t size, + FileSystemArgsIF* args) { + auto path = getInitPath(args) / filename; + if (std::filesystem::exists(path)) { + return FILE_ALREADY_EXISTS; + } + std::ofstream file(path); + file.write(reinterpret_cast(data), size); + if (not file.good()) { + return GENERIC_FILE_ERROR; + } + return HasReturnvaluesIF::RETURN_OK; +} - fullPath += std::string(repositoryPath); - if(not std::filesystem::exists(fullPath)) { - return DIRECTORY_DOES_NOT_EXIST; - } - std::error_code err; - if(not deleteRecurively) { - if(std::filesystem::remove(fullPath, err)) { - return HasReturnvaluesIF::RETURN_OK; - } - else { - // Check error code. Most probably denied permissions because folder is not empty - sif::warning << "FileSystemHandler::removeDirectory: Deleting directory failed with " - "code " << err.value() << ": " << strerror(err.value()) << std::endl; - if(err.value() == ENOTEMPTY) { - return DIRECTORY_NOT_EMPTY; - } - else { - return GENERIC_FILE_ERROR; - } - - } - } - else { - if(std::filesystem::remove_all(fullPath, err)) { - return HasReturnvaluesIF::RETURN_OK; - } - else { - sif::warning << "FileSystemHandler::removeDirectory: Deleting directory failed with " - "code " << err.value() << ": " << strerror(err.value()) << std::endl; - // Check error code - if(err.value() == ENOTEMPTY) { - return DIRECTORY_NOT_EMPTY; - } - else { - return GENERIC_FILE_ERROR; - } - } - } +ReturnValue_t FileSystemHandler::removeFile(const char* repositoryPath, const char* filename, + FileSystemArgsIF* args) { + auto path = getInitPath(args) / repositoryPath / filename; + if (not std::filesystem::exists(path)) { + return FILE_DOES_NOT_EXIST; + } + int result = std::remove(path.c_str()); + if (result != 0) { + sif::warning << "FileSystemHandler::deleteFile: Failed with code " << result << std::endl; + return GENERIC_FILE_ERROR; + } + return HasReturnvaluesIF::RETURN_OK; +} +ReturnValue_t FileSystemHandler::createDirectory(const char* repositoryPath, const char* dirname, + bool createParentDirs, FileSystemArgsIF* args) { + auto path = getInitPath(args) / repositoryPath / dirname; + if (std::filesystem::exists(path)) { + return DIRECTORY_ALREADY_EXISTS; + } + if (std::filesystem::create_directory(path)) { return HasReturnvaluesIF::RETURN_OK; + } + sif::warning << "Creating directory " << path << " failed" << std::endl; + return GENERIC_FILE_ERROR; } -void FileSystemHandler::parseCfg(FsCommandCfg *cfg, bool& useMountPrefix) { - if(cfg != nullptr) { - useMountPrefix = cfg->useMountPrefix; +ReturnValue_t FileSystemHandler::removeDirectory(const char* repositoryPath, const char* dirname, + bool deleteRecurively, FileSystemArgsIF* args) { + auto path = getInitPath(args) / repositoryPath / dirname; + if (not std::filesystem::exists(path)) { + return DIRECTORY_DOES_NOT_EXIST; + } + std::error_code err; + if (not deleteRecurively) { + if (std::filesystem::remove(path, err)) { + return HasReturnvaluesIF::RETURN_OK; + } else { + // Check error code. Most probably denied permissions because folder is not empty + sif::warning << "FileSystemHandler::removeDirectory: Deleting directory failed with " + "code " + << err.value() << ": " << strerror(err.value()) << std::endl; + if (err.value() == ENOTEMPTY) { + return DIRECTORY_NOT_EMPTY; + } else { + return GENERIC_FILE_ERROR; + } } + } else { + if (std::filesystem::remove_all(path, err)) { + return HasReturnvaluesIF::RETURN_OK; + } else { + sif::warning << "FileSystemHandler::removeDirectory: Deleting directory failed with " + "code " + << err.value() << ": " << strerror(err.value()) << std::endl; + // Check error code + if (err.value() == ENOTEMPTY) { + return DIRECTORY_NOT_EMPTY; + } else { + return GENERIC_FILE_ERROR; + } + } + } + + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t FileSystemHandler::renameFile(const char* repositoryPath, const char* oldFilename, + const char* newFilename, FileSystemArgsIF* args) { + auto basepath = getInitPath(args) / repositoryPath; + std::filesystem::rename(basepath / oldFilename, basepath / newFilename); + return HasReturnvaluesIF::RETURN_OK; +} + +void FileSystemHandler::parseCfg(FsCommandCfg* cfg, bool& useMountPrefix) { + if (cfg != nullptr) { + useMountPrefix = cfg->useMountPrefix; + } +} + +std::filesystem::path FileSystemHandler::getInitPath(FileSystemArgsIF* args) { + bool useMountPrefix = true; + parseCfg(reinterpret_cast(args), useMountPrefix); + std::string path; + if (useMountPrefix) { + path = currentMountPrefix; + } + return std::filesystem::path(path); } diff --git a/bsp_q7s/memory/FileSystemHandler.h b/bsp_q7s/memory/FileSystemHandler.h index 1ff5d7c9..6973c3c8 100644 --- a/bsp_q7s/memory/FileSystemHandler.h +++ b/bsp_q7s/memory/FileSystemHandler.h @@ -1,67 +1,67 @@ #ifndef BSP_Q7S_MEMORY_FILESYSTEMHANDLER_H_ #define BSP_Q7S_MEMORY_FILESYSTEMHANDLER_H_ -#include "SdCardManager.h" -#include "OBSWConfig.h" - -#include "fsfw/ipc/MessageQueueIF.h" -#include "fsfw/tasks/ExecutableObjectIF.h" -#include "fsfw/objectmanager/SystemObject.h" -#include "fsfw/memory/HasFileSystemIF.h" - +#include #include +#include "OBSWConfig.h" +#include "SdCardManager.h" +#include "fsfw/ipc/MessageQueueIF.h" +#include "fsfw/memory/HasFileSystemIF.h" +#include "fsfw/objectmanager/SystemObject.h" +#include "fsfw/tasks/ExecutableObjectIF.h" + class CoreController; -class FileSystemHandler: public SystemObject, - public ExecutableObjectIF, - public HasFileSystemIF { -public: - struct FsCommandCfg { - // Can be used to automatically use mount prefix of active SD card. - // Otherwise, the operator has to specify the full path to the mounted SD card as well. - bool useMountPrefix = false; - }; +class FileSystemHandler : public SystemObject, public ExecutableObjectIF, public HasFileSystemIF { + public: + struct FsCommandCfg : public FileSystemArgsIF { + // Can be used to automatically use mount prefix of active SD card. + // Otherwise, the operator has to specify the full path to the mounted SD card as well. + bool useMountPrefix = false; + }; - FileSystemHandler(object_id_t fileSystemHandler); - virtual~ FileSystemHandler(); + FileSystemHandler(object_id_t fileSystemHandler); + virtual ~FileSystemHandler(); - ReturnValue_t performOperation(uint8_t) override; + ReturnValue_t performOperation(uint8_t) override; - ReturnValue_t initialize() override; + ReturnValue_t initialize() override; - /** - * Function to get the MessageQueueId_t of the implementing object - * @return MessageQueueId_t of the object - */ - MessageQueueId_t getCommandQueue() const override; + /** + * Function to get the MessageQueueId_t of the implementing object + * @return MessageQueueId_t of the object + */ + MessageQueueId_t getCommandQueue() const override; + ReturnValue_t appendToFile(const char* repositoryPath, const char* filename, const uint8_t* data, + size_t size, uint16_t packetNumber, + FileSystemArgsIF* args = nullptr) override; + ReturnValue_t createFile(const char* repositoryPath, const char* filename, + const uint8_t* data = nullptr, size_t size = 0, + FileSystemArgsIF* args = nullptr) override; + ReturnValue_t removeFile(const char* repositoryPath, const char* filename, + FileSystemArgsIF* args = nullptr) override; + ReturnValue_t createDirectory(const char* repositoryPath, const char* dirname, + bool createParentDirs, FileSystemArgsIF* args = nullptr) override; + ReturnValue_t removeDirectory(const char* repositoryPath, const char* dirname, + bool deleteRecurively = false, + FileSystemArgsIF* args = nullptr) override; + ReturnValue_t renameFile(const char* repositoryPath, const char* oldFilename, + const char* newFilename, FileSystemArgsIF* args = nullptr) override; - ReturnValue_t appendToFile(const char* repositoryPath, - const char* filename, const uint8_t* data, size_t size, - uint16_t packetNumber, void* args = nullptr) override; - ReturnValue_t createFile(const char* repositoryPath, - const char* filename, const uint8_t* data = nullptr, - size_t size = 0, void* args = nullptr) override; - ReturnValue_t removeFile(const char* repositoryPath, - const char* filename, void* args = nullptr) override; - ReturnValue_t createDirectory(const char* repositoryPath, void* args = nullptr) override; - ReturnValue_t removeDirectory(const char* repositoryPath, bool deleteRecurively = false, - void* args = nullptr) override; + private: + CoreController* coreCtrl = nullptr; + MessageQueueIF* mq = nullptr; + std::string currentMountPrefix = SdCardManager::SD_0_MOUNT_POINT; + static constexpr uint32_t FS_MAX_QUEUE_SIZE = config::OBSW_FILESYSTEM_HANDLER_QUEUE_SIZE; -private: - CoreController* coreCtrl = nullptr; - MessageQueueIF* mq = nullptr; - std::string currentMountPrefix = SdCardManager::SD_0_MOUNT_POINT; - static constexpr uint32_t FS_MAX_QUEUE_SIZE = config::OBSW_FILESYSTEM_HANDLER_QUEUE_SIZE; + SdCardManager* sdcMan = nullptr; + uint8_t opCounter = 0; - SdCardManager* sdcMan = nullptr; - uint8_t opCounter = 0; - - void fileSystemHandlerLoop(); - void fileSystemCheckup(); - void parseCfg(FsCommandCfg* cfg, bool& useMountPrefix); + void fileSystemHandlerLoop(); + void fileSystemCheckup(); + std::filesystem::path getInitPath(FileSystemArgsIF* args); + void parseCfg(FsCommandCfg* cfg, bool& useMountPrefix); }; - - #endif /* BSP_Q7S_MEMORY_FILESYSTEMMANAGER_H_ */ diff --git a/bsp_q7s/memory/SdCardManager.cpp b/bsp_q7s/memory/SdCardManager.cpp index 873bb6a4..b76cee12 100644 --- a/bsp_q7s/memory/SdCardManager.cpp +++ b/bsp_q7s/memory/SdCardManager.cpp @@ -1,458 +1,468 @@ -#include #include "SdCardManager.h" -#include "scratchApi.h" - -#include "linux/utility/utility.h" - -#include "fsfw/ipc/MutexFactory.h" -#include "fsfw/serviceinterface/ServiceInterface.h" +#include "OBSWConfig.h" +#include +#include #include +#include +#include #include #include -#include -#include + +#include "common/config/commonObjects.h" +#include "fsfw/ipc/MutexFactory.h" +#include "fsfw/serviceinterface/ServiceInterface.h" +#include "linux/utility/utility.h" +#include "scratchApi.h" SdCardManager* SdCardManager::factoryInstance = nullptr; -SdCardManager::SdCardManager(): cmdExecutor(256) { +SdCardManager::SdCardManager() : SystemObject(objects::SDC_MANAGER), cmdExecutor(256) { + mutex = MutexFactory::instance()->createMutex(); } -SdCardManager::~SdCardManager() { -} +SdCardManager::~SdCardManager() {} void SdCardManager::create() { - if(factoryInstance == nullptr) { - factoryInstance = new SdCardManager(); - } + if (factoryInstance == nullptr) { + factoryInstance = new SdCardManager(); + } } SdCardManager* SdCardManager::instance() { - SdCardManager::create(); - return SdCardManager::factoryInstance; + SdCardManager::create(); + return SdCardManager::factoryInstance; } ReturnValue_t SdCardManager::switchOnSdCard(sd::SdCard sdCard, bool doMountSdCard, - SdStatePair* statusPair) { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - if(doMountSdCard) { - if(not blocking) { - sif::warning << "SdCardManager::switchOnSdCard: Two-step command but manager is" - " not configured for blocking operation. " - "Forcing blocking mode.." << std::endl; - blocking = true; - } + SdStatePair* statusPair) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + if (doMountSdCard) { + if (not blocking) { + sif::warning << "SdCardManager::switchOnSdCard: Two-step command but manager is" + " not configured for blocking operation. " + "Forcing blocking mode.." + << std::endl; + blocking = true; } - std::unique_ptr sdStatusPtr; - if(statusPair == nullptr) { - sdStatusPtr = std::make_unique(); - statusPair = sdStatusPtr.get(); - result = getSdCardActiveStatus(*statusPair); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + } + std::unique_ptr sdStatusPtr; + if (statusPair == nullptr) { + sdStatusPtr = std::make_unique(); + statusPair = sdStatusPtr.get(); + result = getSdCardActiveStatus(*statusPair); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; } + } - // Not allowed, this function turns on one SD card - if(sdCard == sd::SdCard::BOTH) { - sif::warning << "SdCardManager::switchOffSdCard: API does not allow sd::SdStatus::BOTH" - << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; - } + // Not allowed, this function turns on one SD card + if (sdCard == sd::SdCard::BOTH) { + sif::warning << "SdCardManager::switchOffSdCard: API does not allow sd::SdStatus::BOTH" + << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } - sd::SdState currentState; - if(sdCard == sd::SdCard::SLOT_0) { - currentState = statusPair->first; - } - else if(sdCard == sd::SdCard::SLOT_1) { - currentState = statusPair->second; - } - else { - // Should not happen - currentState = sd::SdState::OFF; - } + sd::SdState currentState; + if (sdCard == sd::SdCard::SLOT_0) { + currentState = statusPair->first; + } else if (sdCard == sd::SdCard::SLOT_1) { + currentState = statusPair->second; + } else { + // Should not happen + currentState = sd::SdState::OFF; + } - if(currentState == sd::SdState::ON) { - if(not doMountSdCard) { - return ALREADY_ON; - } - else { - return mountSdCard(sdCard); - } - } - else if(currentState == sd::SdState::MOUNTED) { - result = ALREADY_MOUNTED; - } - else if(currentState == sd::SdState::OFF) { - result = setSdCardState(sdCard, true); - } - else { - result = HasReturnvaluesIF::RETURN_FAILED; + if (currentState == sd::SdState::ON) { + if (not doMountSdCard) { + return ALREADY_ON; + } else { + return mountSdCard(sdCard); } + } else if (currentState == sd::SdState::MOUNTED) { + result = ALREADY_MOUNTED; + } else if (currentState == sd::SdState::OFF) { + result = setSdCardState(sdCard, true); + } else { + result = HasReturnvaluesIF::RETURN_FAILED; + } - if(result != HasReturnvaluesIF::RETURN_OK or not doMountSdCard) { - return result; - } + if (result != HasReturnvaluesIF::RETURN_OK or not doMountSdCard) { + return result; + } - return mountSdCard(sdCard); + return mountSdCard(sdCard); } ReturnValue_t SdCardManager::switchOffSdCard(sd::SdCard sdCard, bool doUnmountSdCard, - SdStatePair* statusPair) { - std::pair active; - ReturnValue_t result = getSdCardActiveStatus(active); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; + SdStatePair* statusPair) { + std::pair active; + ReturnValue_t result = getSdCardActiveStatus(active); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + if (doUnmountSdCard) { + if (not blocking) { + sif::warning << "SdCardManager::switchOffSdCard: Two-step command but manager is" + " not configured for blocking operation. Forcing blocking mode.." + << std::endl; + blocking = true; } - if(doUnmountSdCard) { - if(not blocking) { - sif::warning << "SdCardManager::switchOffSdCard: Two-step command but manager is" - " not configured for blocking operation. Forcing blocking mode.." << std::endl; - blocking = true; - } + } + // Not allowed, this function turns off one SD card + if (sdCard == sd::SdCard::BOTH) { + sif::warning << "SdCardManager::switchOffSdCard: API does not allow sd::SdStatus::BOTH" + << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } + if (sdCard == sd::SdCard::SLOT_0) { + if (active.first == sd::SdState::OFF) { + return ALREADY_OFF; } - // Not allowed, this function turns off one SD card - if(sdCard == sd::SdCard::BOTH) { - sif::warning << "SdCardManager::switchOffSdCard: API does not allow sd::SdStatus::BOTH" - << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; - } - if(sdCard == sd::SdCard::SLOT_0) { - if(active.first == sd::SdState::OFF) { - return ALREADY_OFF; - } - } - else if(sdCard == sd::SdCard::SLOT_1) { - if(active.second == sd::SdState::OFF) { - return ALREADY_OFF; - } + } else if (sdCard == sd::SdCard::SLOT_1) { + if (active.second == sd::SdState::OFF) { + return ALREADY_OFF; } + } - if(doUnmountSdCard) { - result = unmountSdCard(sdCard); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + if (doUnmountSdCard) { + result = unmountSdCard(sdCard); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; } + } - return setSdCardState(sdCard, false); + return setSdCardState(sdCard, false); } ReturnValue_t SdCardManager::setSdCardState(sd::SdCard sdCard, bool on) { - using namespace std; - if(cmdExecutor.getCurrentState() == CommandExecutor::States::PENDING) { - return CommandExecutor::COMMAND_PENDING; - } - string sdstring = ""; - string statestring = ""; - if(sdCard == sd::SdCard::SLOT_0) { - sdstring = "0"; - } - else if(sdCard == sd::SdCard::SLOT_1) { - sdstring = "1"; - } - if(on) { - currentOp = Operations::SWITCHING_ON; - statestring = "on"; - } - else { - currentOp = Operations::SWITCHING_OFF; - statestring = "off"; - } - ostringstream command; - command << "q7hw sd set " << sdstring << " " << statestring; - cmdExecutor.load(command.str(), blocking, printCmdOutput); - ReturnValue_t result = cmdExecutor.execute(); - if(blocking and result != HasReturnvaluesIF::RETURN_OK) { - utility::handleSystemError(cmdExecutor.getLastError(), "SdCardManager::setSdCardState"); - } - return result; + using namespace std; + if (cmdExecutor.getCurrentState() == CommandExecutor::States::PENDING) { + return CommandExecutor::COMMAND_PENDING; + } + string sdstring = ""; + string statestring = ""; + if (sdCard == sd::SdCard::SLOT_0) { + sdstring = "0"; + } else if (sdCard == sd::SdCard::SLOT_1) { + sdstring = "1"; + } + if (on) { + currentOp = Operations::SWITCHING_ON; + statestring = "on"; + } else { + currentOp = Operations::SWITCHING_OFF; + statestring = "off"; + } + ostringstream command; + command << "q7hw sd set " << sdstring << " " << statestring; + cmdExecutor.load(command.str(), blocking, printCmdOutput); + ReturnValue_t result = cmdExecutor.execute(); + if (blocking and result != HasReturnvaluesIF::RETURN_OK) { + utility::handleSystemError(cmdExecutor.getLastError(), "SdCardManager::setSdCardState"); + } + return result; } ReturnValue_t SdCardManager::getSdCardActiveStatus(SdStatePair& active) { - using namespace std; - if(not filesystem::exists(SD_STATE_FILE)) { - return STATUS_FILE_NEXISTS; - } + using namespace std; + MutexGuard mg(mutex); + if (not filesystem::exists(SD_STATE_FILE)) { + return STATUS_FILE_NEXISTS; + } - // Now the file should exist in any case. Still check whether it exists. - fstream sdStatus(SD_STATE_FILE); - if (not sdStatus.good()) { - return STATUS_FILE_NEXISTS; - } - string line; - uint8_t idx = 0; - sd::SdCard currentSd = sd::SdCard::SLOT_0; - // Process status file line by line - while (std::getline(sdStatus, line)) { - processSdStatusLine(active, line, idx, currentSd); - } - return HasReturnvaluesIF::RETURN_OK; + // Now the file should exist in any case. Still check whether it exists. + fstream sdStatus(SD_STATE_FILE); + if (not sdStatus.good()) { + return STATUS_FILE_NEXISTS; + } + string line; + uint8_t idx = 0; + sd::SdCard currentSd = sd::SdCard::SLOT_0; + // Process status file line by line + while (std::getline(sdStatus, line)) { + processSdStatusLine(active, line, idx, currentSd); + } + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t SdCardManager::mountSdCard(sd::SdCard sdCard) { - using namespace std; - if(cmdExecutor.getCurrentState() == CommandExecutor::States::PENDING) { - return CommandExecutor::COMMAND_PENDING; - } - if(sdCard == sd::SdCard::BOTH) { - sif::warning << "SdCardManager::mountSdCard: API does not allow sd::SdStatus::BOTH" - << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; - } - string mountDev; - string mountPoint; - if(sdCard == sd::SdCard::SLOT_0) { - mountDev = SD_0_DEV_NAME; - mountPoint = SD_0_MOUNT_POINT; - } - else if(sdCard == sd::SdCard::SLOT_1) { - mountDev = SD_1_DEV_NAME; - mountPoint = SD_1_MOUNT_POINT; - } - if(not filesystem::exists(mountDev)) { - sif::warning << "SdCardManager::mountSdCard: Device file does not exists. Make sure to" - " turn on the SD card" << std::endl; - return MOUNT_ERROR; - } + using namespace std; + if (cmdExecutor.getCurrentState() == CommandExecutor::States::PENDING) { + return CommandExecutor::COMMAND_PENDING; + } + if (sdCard == sd::SdCard::BOTH) { + sif::warning << "SdCardManager::mountSdCard: API does not allow sd::SdStatus::BOTH" + << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } + string mountDev; + string mountPoint; + if (sdCard == sd::SdCard::SLOT_0) { + mountDev = SD_0_DEV_NAME; + mountPoint = SD_0_MOUNT_POINT; + } else if (sdCard == sd::SdCard::SLOT_1) { + mountDev = SD_1_DEV_NAME; + mountPoint = SD_1_MOUNT_POINT; + } + if (not filesystem::exists(mountDev)) { + sif::warning << "SdCardManager::mountSdCard: Device file does not exists. Make sure to" + " turn on the SD card" + << std::endl; + return MOUNT_ERROR; + } - if(not blocking) { - currentOp = Operations::MOUNTING; - } - string sdMountCommand = "mount " + mountDev + " " + mountPoint; - cmdExecutor.load(sdMountCommand, blocking, printCmdOutput); - ReturnValue_t result = cmdExecutor.execute(); - if(blocking and result != HasReturnvaluesIF::RETURN_OK) { - utility::handleSystemError(cmdExecutor.getLastError(), "SdCardManager::mountSdCard"); - } - return result; + if (not blocking) { + currentOp = Operations::MOUNTING; + } + string sdMountCommand = "mount " + mountDev + " " + mountPoint; + cmdExecutor.load(sdMountCommand, blocking, printCmdOutput); + ReturnValue_t result = cmdExecutor.execute(); + if (blocking and result != HasReturnvaluesIF::RETURN_OK) { + utility::handleSystemError(cmdExecutor.getLastError(), "SdCardManager::mountSdCard"); + } + return result; } ReturnValue_t SdCardManager::unmountSdCard(sd::SdCard sdCard) { - if(cmdExecutor.getCurrentState() == CommandExecutor::States::PENDING) { - return CommandExecutor::COMMAND_PENDING; - } - using namespace std; - if(sdCard == sd::SdCard::BOTH) { - sif::warning << "SdCardManager::unmountSdCard: API does not allow sd::SdStatus::BOTH" - << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; - } - string mountPoint; - if(sdCard == sd::SdCard::SLOT_0) { - mountPoint = SD_0_MOUNT_POINT; - } - else if(sdCard == sd::SdCard::SLOT_1) { - mountPoint = SD_1_MOUNT_POINT; - } - if(not filesystem::exists(mountPoint)) { - sif::error << "SdCardManager::unmountSdCard: Default mount point " << mountPoint << - "does not exist" << std::endl; - return UNMOUNT_ERROR; - } - if(filesystem::is_empty(mountPoint)) { - // The mount point will always exist, but if it is empty, that is strong hint that - // the SD card was not mounted properly. Still proceed with operation. - sif::warning << "SdCardManager::unmountSdCard: Mount point is empty!" << std::endl; - } - string sdUnmountCommand = "umount " + mountPoint; - if(not blocking) { - currentOp = Operations::UNMOUNTING; - } - cmdExecutor.load(sdUnmountCommand, blocking, printCmdOutput); - ReturnValue_t result = cmdExecutor.execute(); - if(blocking and result != HasReturnvaluesIF::RETURN_OK) { - utility::handleSystemError(cmdExecutor.getLastError(), "SdCardManager::unmountSdCard"); - } - return result; + if (cmdExecutor.getCurrentState() == CommandExecutor::States::PENDING) { + return CommandExecutor::COMMAND_PENDING; + } + using namespace std; + if (sdCard == sd::SdCard::BOTH) { + sif::warning << "SdCardManager::unmountSdCard: API does not allow sd::SdStatus::BOTH" + << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } + string mountPoint; + if (sdCard == sd::SdCard::SLOT_0) { + mountPoint = SD_0_MOUNT_POINT; + } else if (sdCard == sd::SdCard::SLOT_1) { + mountPoint = SD_1_MOUNT_POINT; + } + if (not filesystem::exists(mountPoint)) { + sif::error << "SdCardManager::unmountSdCard: Default mount point " << mountPoint + << "does not exist" << std::endl; + return UNMOUNT_ERROR; + } + if (filesystem::is_empty(mountPoint)) { + // The mount point will always exist, but if it is empty, that is strong hint that + // the SD card was not mounted properly. Still proceed with operation. + sif::warning << "SdCardManager::unmountSdCard: Mount point is empty!" << std::endl; + } + string sdUnmountCommand = "umount " + mountPoint; + if (not blocking) { + currentOp = Operations::UNMOUNTING; + } + cmdExecutor.load(sdUnmountCommand, blocking, printCmdOutput); + ReturnValue_t result = cmdExecutor.execute(); + if (blocking and result != HasReturnvaluesIF::RETURN_OK) { + utility::handleSystemError(cmdExecutor.getLastError(), "SdCardManager::unmountSdCard"); + } + return result; } ReturnValue_t SdCardManager::sanitizeState(SdStatePair* statusPair, sd::SdCard prefSdCard) { - std::unique_ptr sdStatusPtr; - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - // Enforce blocking operation for now. Be careful to reset it when returning prematurely! - bool resetNonBlockingState = false; - if(not this->blocking) { - blocking = true; - resetNonBlockingState = true; - } - if(prefSdCard == sd::SdCard::NONE) { - result = getPreferredSdCard(prefSdCard); - if(result != HasReturnvaluesIF::RETURN_OK) {} - } - if(statusPair == nullptr) { - sdStatusPtr = std::make_unique(); - statusPair = sdStatusPtr.get(); - getSdCardActiveStatus(*statusPair); + std::unique_ptr sdStatusPtr; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + // Enforce blocking operation for now. Be careful to reset it when returning prematurely! + bool resetNonBlockingState = false; + if (not this->blocking) { + blocking = true; + resetNonBlockingState = true; + } + if (prefSdCard == sd::SdCard::NONE) { + result = getPreferredSdCard(prefSdCard); + if (result != HasReturnvaluesIF::RETURN_OK) { } + } + if (statusPair == nullptr) { + sdStatusPtr = std::make_unique(); + statusPair = sdStatusPtr.get(); + getSdCardActiveStatus(*statusPair); + } - if(statusPair->first == sd::SdState::ON) { - result = mountSdCard(prefSdCard); - } + if (statusPair->first == sd::SdState::ON) { + result = mountSdCard(prefSdCard); + } - result = switchOnSdCard(prefSdCard, true, statusPair); - if(resetNonBlockingState) { - blocking = false; - } - return result; + result = switchOnSdCard(prefSdCard, true, statusPair); + if (resetNonBlockingState) { + blocking = false; + } + return result; } void SdCardManager::resetState() { - cmdExecutor.reset(); - currentOp = Operations::IDLE; + cmdExecutor.reset(); + currentOp = Operations::IDLE; } -void SdCardManager::processSdStatusLine(std::pair &active, - std::string& line, uint8_t& idx, sd::SdCard& currentSd) { - using namespace std; - istringstream iss(line); - string word; - bool slotLine = false; - bool mountLine = false; - while(iss >> word) { - if (word == "Slot") { - slotLine = true; - } - if(word == "Mounted") { - mountLine = true; - } - - if(slotLine) { - if (word == "1:") { - currentSd = sd::SdCard::SLOT_1; - } - - if(word == "on") { - if(currentSd == sd::SdCard::SLOT_0) { - active.first = sd::SdState::ON; - } - else { - active.second = sd::SdState::ON; - } - } - else if (word == "off") { - if(currentSd == sd::SdCard::SLOT_0) { - active.first = sd::SdState::OFF; - } - else { - active.second = sd::SdState::OFF; - } - } - } - - if(mountLine) { - if(currentSd == sd::SdCard::SLOT_0) { - active.first = sd::SdState::MOUNTED; - } - else { - active.second = sd::SdState::MOUNTED; - } - } - - if(idx > 5) { - sif::warning << "SdCardManager::sdCardActive: /tmp/sd_status.txt has more than 6 " - "lines and might be invalid!" << std::endl; - } +void SdCardManager::processSdStatusLine(std::pair& active, + std::string& line, uint8_t& idx, sd::SdCard& currentSd) { + using namespace std; + istringstream iss(line); + string word; + bool slotLine = false; + bool mountLine = false; + while (iss >> word) { + if (word == "Slot") { + slotLine = true; } - idx++; + if (word == "Mounted") { + mountLine = true; + } + + if (slotLine) { + if (word == "1:") { + currentSd = sd::SdCard::SLOT_1; + } + + if (word == "on") { + if (currentSd == sd::SdCard::SLOT_0) { + active.first = sd::SdState::ON; + } else { + active.second = sd::SdState::ON; + } + } else if (word == "off") { + if (currentSd == sd::SdCard::SLOT_0) { + active.first = sd::SdState::OFF; + } else { + active.second = sd::SdState::OFF; + } + } + } + + if (mountLine) { + if (currentSd == sd::SdCard::SLOT_0) { + active.first = sd::SdState::MOUNTED; + } else { + active.second = sd::SdState::MOUNTED; + } + } + + if (idx > 5) { + sif::warning << "SdCardManager::sdCardActive: /tmp/sd_status.txt has more than 6 " + "lines and might be invalid!" + << std::endl; + } + } + 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; - } - sdCard = static_cast(prefSdCard); - return HasReturnvaluesIF::RETURN_OK; + uint8_t prefSdCard = 0; + ReturnValue_t result = scratch::readNumber(scratch::PREFERED_SDC_KEY, prefSdCard); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + sdCard = static_cast(prefSdCard); + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t SdCardManager::setPreferredSdCard(sd::SdCard sdCard) { - if(sdCard == sd::SdCard::BOTH) { - return HasReturnvaluesIF::RETURN_FAILED; - } - return scratch::writeNumber(scratch::PREFERED_SDC_KEY, static_cast(sdCard)); + if (sdCard == sd::SdCard::BOTH) { + return HasReturnvaluesIF::RETURN_FAILED; + } + return scratch::writeNumber(scratch::PREFERED_SDC_KEY, static_cast(sdCard)); } ReturnValue_t SdCardManager::updateSdCardStateFile() { - if(cmdExecutor.getCurrentState() == CommandExecutor::States::PENDING) { - return CommandExecutor::COMMAND_PENDING; - } - // Use q7hw utility and pipe the command output into the state file - std::string updateCmd = "q7hw sd info all > " + std::string(SD_STATE_FILE); - cmdExecutor.load(updateCmd, blocking, printCmdOutput); - ReturnValue_t result = cmdExecutor.execute(); - if(blocking and result != HasReturnvaluesIF::RETURN_OK) { - utility::handleSystemError(cmdExecutor.getLastError(), "SdCardManager::mountSdCard"); - } - return result; + if (cmdExecutor.getCurrentState() == CommandExecutor::States::PENDING) { + return CommandExecutor::COMMAND_PENDING; + } + MutexGuard mg(mutex); + // Use q7hw utility and pipe the command output into the state file + std::string updateCmd = "q7hw sd info all > " + std::string(SD_STATE_FILE); + cmdExecutor.load(updateCmd, blocking, printCmdOutput); + ReturnValue_t result = cmdExecutor.execute(); + if (blocking and result != HasReturnvaluesIF::RETURN_OK) { + utility::handleSystemError(cmdExecutor.getLastError(), "SdCardManager::mountSdCard"); + } + 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) { - return SD_0_MOUNT_POINT; - } - else { - return SD_1_MOUNT_POINT; + 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) { + return SD_0_MOUNT_POINT; + } else { + return SD_1_MOUNT_POINT; + } } -SdCardManager::OpStatus SdCardManager::checkCurrentOp(Operations ¤tOp) { - CommandExecutor::States state = cmdExecutor.getCurrentState(); - if(state == CommandExecutor::States::IDLE or state == CommandExecutor::States::COMMAND_LOADED) { - return OpStatus::IDLE; - } - currentOp = this->currentOp; - bool bytesRead = false; +SdCardManager::OpStatus SdCardManager::checkCurrentOp(Operations& currentOp) { + CommandExecutor::States state = cmdExecutor.getCurrentState(); + if (state == CommandExecutor::States::IDLE or state == CommandExecutor::States::COMMAND_LOADED) { + return OpStatus::IDLE; + } + currentOp = this->currentOp; + bool bytesRead = false; #if OBSW_ENABLE_TIMERS == 1 - Timer timer; - timer.setTimer(100); - uint32_t remainingTimeMs = 0; + Countdown timer(100); #endif - while(true) { - ReturnValue_t result = cmdExecutor.check(bytesRead); - // This timer can prevent deadlocks due to missconfigurations + while (true) { + ReturnValue_t result = cmdExecutor.check(bytesRead); + // This timer can prevent deadlocks due to missconfigurations #if OBSW_ENABLE_TIMERS == 1 - timer.getTimer(&remainingTimeMs); - if(remainingTimeMs == 0) { - sif::error << "SdCardManager::checkCurrentOp: Timeout!" << std::endl; - return OpStatus::FAIL; - } -#endif - switch(result) { - case(CommandExecutor::BYTES_READ): { - continue; - } - case(CommandExecutor::EXECUTION_FINISHED): { - return OpStatus::SUCCESS; - } - case(HasReturnvaluesIF::RETURN_OK): { - return OpStatus::ONGOING; - } - case(HasReturnvaluesIF::RETURN_FAILED): { - return OpStatus::FAIL; - } - default: { - sif::warning << "SdCardManager::checkCurrentOp: Unhandled case" << std::endl; - } - } + if (timer.hasTimedOut()) { + sif::error << "SdCardManager::checkCurrentOp: Timeout!" << std::endl; + return OpStatus::FAIL; } +#endif + switch (result) { + case (CommandExecutor::BYTES_READ): { + continue; + } + case (CommandExecutor::EXECUTION_FINISHED): { + return OpStatus::SUCCESS; + } + case (HasReturnvaluesIF::RETURN_OK): { + return OpStatus::ONGOING; + } + case (HasReturnvaluesIF::RETURN_FAILED): { + return OpStatus::FAIL; + } + default: { + sif::warning << "SdCardManager::checkCurrentOp: Unhandled case" << std::endl; + } + } + } } -void SdCardManager::setBlocking(bool blocking) { - this->blocking = blocking; +void SdCardManager::setBlocking(bool blocking) { this->blocking = blocking; } + +void SdCardManager::setPrintCommandOutput(bool print) { this->printCmdOutput = print; } + +bool SdCardManager::isSdCardMounted(sd::SdCard sdCard) { + SdCardManager::SdStatePair active; + ReturnValue_t result = this->getSdCardActiveStatus(active); + + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::debug << "SdCardManager::isSdCardMounted: Failed to get SD card active state"; + return false; + } + if (sdCard == sd::SLOT_0) { + if (active.first == sd::MOUNTED) { + return true; + } else { + return false; + } + } else if (sdCard == sd::SLOT_1) { + if (active.second == sd::MOUNTED) { + return true; + } else { + return false; + } + } else { + sif::debug << "SdCardManager::isSdCardMounted: Unknown SD card specified" << std::endl; + } + return false; } - -void SdCardManager::setPrintCommandOutput(bool print) { - this->printCmdOutput = print; - -} - diff --git a/bsp_q7s/memory/SdCardManager.h b/bsp_q7s/memory/SdCardManager.h index 1a86f711..37660f75 100644 --- a/bsp_q7s/memory/SdCardManager.h +++ b/bsp_q7s/memory/SdCardManager.h @@ -1,21 +1,22 @@ #ifndef BSP_Q7S_MEMORY_SDCARDACCESSMANAGER_H_ #define BSP_Q7S_MEMORY_SDCARDACCESSMANAGER_H_ -#include -#include "definitions.h" -#include "returnvalues/classIds.h" -#include "events/subsystemIdRanges.h" - -#include "fsfw/events/Event.h" -#include "fsfw/returnvalues/HasReturnvaluesIF.h" - +#include #include -#include -#include -#include -#include #include +#include +#include +#include +#include + +#include "events/subsystemIdRanges.h" +#include "fsfw/events/Event.h" +#include "fsfw/returnvalues/HasReturnvaluesIF.h" +#include "fsfw_hal/linux/CommandExecutor.h" +#include "mission/memory/SdCardMountedIF.h" +#include "mission/memory/definitions.h" +#include "returnvalues/classIds.h" class MutexIF; @@ -23,194 +24,193 @@ class MutexIF; * @brief Manages handling of SD cards like switching them on or off or getting the current * state */ -class SdCardManager { - friend class SdCardAccess; -public: - enum class Operations { - SWITCHING_ON, - SWITCHING_OFF, - MOUNTING, - UNMOUNTING, - IDLE - }; +class SdCardManager : public SystemObject, public SdCardMountedIF { + friend class SdCardAccess; - enum class OpStatus { - IDLE, - TIMEOUT, - ONGOING, - SUCCESS, - FAIL - }; + public: + using mountInitCb = ReturnValue_t (*)(void* args); - using SdStatePair = std::pair; + enum class Operations { SWITCHING_ON, SWITCHING_OFF, MOUNTING, UNMOUNTING, IDLE }; - static constexpr uint8_t INTERFACE_ID = CLASS_ID::SD_CARD_MANAGER; + enum class OpStatus { IDLE, TIMEOUT, ONGOING, SUCCESS, FAIL }; - static constexpr ReturnValue_t OP_ONGOING = - HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 0); - static constexpr ReturnValue_t ALREADY_ON = - HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 1); - static constexpr ReturnValue_t ALREADY_MOUNTED = - HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 2); - static constexpr ReturnValue_t ALREADY_OFF = - HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 3); - static constexpr ReturnValue_t STATUS_FILE_NEXISTS = - HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 10); - static constexpr ReturnValue_t STATUS_FILE_FORMAT_INVALID = - HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 11); - static constexpr ReturnValue_t MOUNT_ERROR = - HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 12); - static constexpr ReturnValue_t UNMOUNT_ERROR = - HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 13); - static constexpr ReturnValue_t SYSTEM_CALL_ERROR = - HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 14); - static constexpr ReturnValue_t POPEN_CALL_ERROR = - HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 15); + using SdStatePair = std::pair; - static constexpr uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::FILE_SYSTEM; + static constexpr uint8_t INTERFACE_ID = CLASS_ID::SD_CARD_MANAGER; - static constexpr Event SANITIZATION_FAILED = event::makeEvent(SUBSYSTEM_ID, 0, severity::LOW); + static constexpr ReturnValue_t OP_ONGOING = HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 0); + static constexpr ReturnValue_t ALREADY_ON = HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 1); + static constexpr ReturnValue_t ALREADY_MOUNTED = + HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 2); + static constexpr ReturnValue_t ALREADY_OFF = HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 3); + static constexpr ReturnValue_t STATUS_FILE_NEXISTS = + HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 10); + static constexpr ReturnValue_t STATUS_FILE_FORMAT_INVALID = + HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 11); + static constexpr ReturnValue_t MOUNT_ERROR = HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 12); + static constexpr ReturnValue_t UNMOUNT_ERROR = + HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 13); + static constexpr ReturnValue_t SYSTEM_CALL_ERROR = + HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 14); + static constexpr ReturnValue_t POPEN_CALL_ERROR = + HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 15); - // C++17 does not support constexpr std::string yet - static constexpr char SD_0_DEV_NAME[] = "/dev/mmcblk0p1"; - static constexpr char SD_1_DEV_NAME[] = "/dev/mmcblk1p1"; - static constexpr char SD_0_MOUNT_POINT[] = "/mnt/sd0"; - static constexpr char SD_1_MOUNT_POINT[] = "/mnt/sd1"; - static constexpr char SD_STATE_FILE[] = "/tmp/sd_status.txt"; + static constexpr uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::FILE_SYSTEM; - virtual ~SdCardManager(); + static constexpr Event SANITIZATION_FAILED = event::makeEvent(SUBSYSTEM_ID, 0, severity::LOW); + static constexpr Event MOUNTED_SD_CARD = event::makeEvent(SUBSYSTEM_ID, 1, severity::INFO); - static void create(); + // C++17 does not support constexpr std::string yet + static constexpr char SD_0_DEV_NAME[] = "/dev/mmcblk0p1"; + static constexpr char SD_1_DEV_NAME[] = "/dev/mmcblk1p1"; + static constexpr char SD_0_MOUNT_POINT[] = "/mnt/sd0"; + static constexpr char SD_1_MOUNT_POINT[] = "/mnt/sd1"; + static constexpr char SD_STATE_FILE[] = "/tmp/sd_status.txt"; - /** - * Returns the single instance of the SD card manager. - */ - static SdCardManager* instance(); + virtual ~SdCardManager(); - /** - * Set the preferred SD card which will determine which SD card will be used as the primary - * SD card in hot redundant and cold redundant mode. This function will not switch the - * SD cards which are currently on and mounted, this needs to be implemented by - * an upper layer by using #switchOffSdCard , #switchOnSdCard and #updateSdCardStateFile - * @param sdCard - * @return - */ - ReturnValue_t setPreferredSdCard(sd::SdCard sdCard); + static void create(); - /** - * Get the currently configured preferred SD card - * @param sdCard - * @return - */ - ReturnValue_t getPreferredSdCard(sd::SdCard& sdCard) const; + /** + * Returns the single instance of the SD card manager. + */ + static SdCardManager* instance(); - /** - * Switch on the specified SD card. - * @param sdCard - * @param doMountSdCard Mount the SD card after switching it on, which is necessary - * to use it - * @param statusPair If the status pair is already available, it can be passed here - * @return - RETURN_OK on success, ALREADY_ON if it is already on, - * SYSTEM_CALL_ERROR on system error - */ - ReturnValue_t switchOnSdCard(sd::SdCard sdCard, bool doMountSdCard = true, - SdStatePair* statusPair = nullptr); + /** + * Set the preferred SD card which will determine which SD card will be used as the primary + * SD card in hot redundant and cold redundant mode. This function will not switch the + * SD cards which are currently on and mounted, this needs to be implemented by + * an upper layer by using #switchOffSdCard , #switchOnSdCard and #updateSdCardStateFile + * @param sdCard + * @return + */ + ReturnValue_t setPreferredSdCard(sd::SdCard sdCard); - /** - * Switch off the specified SD card. - * @param sdCard - * @param doUnmountSdCard Unmount the SD card before switching the card off, which makes - * the operation safer - * @param statusPair If the status pair is already available, it can be passed here - * @return - RETURN_OK on success, ALREADY_ON if it is already on, - * SYSTEM_CALL_ERROR on system error - */ - ReturnValue_t switchOffSdCard(sd::SdCard sdCard, bool doUnmountSdCard = true, - SdStatePair* statusPair = nullptr); + /** + * Get the currently configured preferred SD card + * @param sdCard + * @return + */ + ReturnValue_t getPreferredSdCard(sd::SdCard& sdCard) const override; - /** - * Update the state file or creates one if it does not exist. You need to call this - * function before calling #sdCardActive - * @return - * - RETURN_OK if the state file was updated successfully - * - CommandExecutor::COMMAND_PENDING: Non-blocking command is pending - * - RETURN_FAILED: blocking command failed - */ - ReturnValue_t updateSdCardStateFile(); + /** + * Switch on the specified SD card. + * @param sdCard + * @param doMountSdCard Mount the SD card after switching it on, which is necessary + * to use it + * @param statusPair If the status pair is already available, it can be passed here + * @return - RETURN_OK on success, ALREADY_ON if it is already on, + * SYSTEM_CALL_ERROR on system error + */ + ReturnValue_t switchOnSdCard(sd::SdCard sdCard, bool doMountSdCard = true, + SdStatePair* statusPair = nullptr); - /** - * Get the state of the SD cards. If the state file does not exist, this function will - * take care of updating it. If it does not, the function will use the state file to get - * the status of the SD cards and set the field of the provided boolean pair. - * @param active Pair of booleans, where the first entry is the state of the first SD card - * and the second one the state of the second SD card - * @return - RETURN_OK if the state was read successfully - * - STATUS_FILE_FORMAT_INVALID if there was an issue with the state file. The user - * should call #updateSdCardStateFile again in that case - * - STATUS_FILE_NEXISTS if the status file does not exist - */ - ReturnValue_t getSdCardActiveStatus(SdStatePair& active); + /** + * Switch off the specified SD card. + * @param sdCard + * @param doUnmountSdCard Unmount the SD card before switching the card off, which makes + * the operation safer + * @param statusPair If the status pair is already available, it can be passed here + * @return - RETURN_OK on success, ALREADY_ON if it is already on, + * SYSTEM_CALL_ERROR on system error + */ + ReturnValue_t switchOffSdCard(sd::SdCard sdCard, bool doUnmountSdCard = true, + SdStatePair* statusPair = nullptr); - /** - * Mount the specified SD card. This is necessary to use it. - * @param sdCard - * @return - */ - ReturnValue_t mountSdCard(sd::SdCard sdCard); - /** - * Unmount the specified SD card. This is recommended before switching it off. The SD card - * can't be used after it has been unmounted. - * @param sdCard - * @return - */ - ReturnValue_t unmountSdCard(sd::SdCard sdCard); + /** + * Update the state file or creates one if it does not exist. You need to call this + * function before calling #sdCardActive + * @return + * - RETURN_OK if the state file was updated successfully + * - CommandExecutor::COMMAND_PENDING: Non-blocking command is pending + * - RETURN_FAILED: blocking command failed + */ + ReturnValue_t updateSdCardStateFile(); - /** - * In case that there is a discrepancy between the preferred SD card and the currently - * mounted one, this function will sanitize the state by attempting to mount the - * currently preferred SD card. If the caller already has state information, it can be - * passed into the function. For now, this operation will be enforced in blocking mode. - * @param statusPair Current SD card status capture with #getSdCardActiveStatus - * @param prefSdCard Preferred SD card captured with #getPreferredSdCard - * @throws std::bad_alloc if one of the two arguments was a nullptr and an allocation failed - * @return - */ - ReturnValue_t sanitizeState(SdStatePair* statusPair = nullptr, - sd::SdCard prefSdCard = sd::SdCard::NONE); + /** + * Get the state of the SD cards. If the state file does not exist, this function will + * take care of updating it. If it does not, the function will use the state file to get + * the status of the SD cards and set the field of the provided boolean pair. + * @param active Pair of booleans, where the first entry is the state of the first SD card + * and the second one the state of the second SD card + * @return - RETURN_OK if the state was read successfully + * - STATUS_FILE_FORMAT_INVALID if there was an issue with the state file. The user + * should call #updateSdCardStateFile again in that case + * - STATUS_FILE_NEXISTS if the status file does not exist + */ + ReturnValue_t getSdCardActiveStatus(SdStatePair& active); - /** - * If sd::SdCard::NONE is passed as an argument, this function will get the currently - * preferred SD card from the scratch buffer. - * @param prefSdCardPtr - * @return - */ - std::string getCurrentMountPrefix(sd::SdCard prefSdCardPtr = sd::SdCard::NONE); + /** + * Mount the specified SD card. This is necessary to use it. + * @param sdCard + * @return + */ + ReturnValue_t mountSdCard(sd::SdCard sdCard); + /** + * Unmount the specified SD card. This is recommended before switching it off. The SD card + * can't be used after it has been unmounted. + * @param sdCard + * @return + */ + ReturnValue_t unmountSdCard(sd::SdCard sdCard); - OpStatus checkCurrentOp(Operations& currentOp); + /** + * In case that there is a discrepancy between the preferred SD card and the currently + * mounted one, this function will sanitize the state by attempting to mount the + * currently preferred SD card. If the caller already has state information, it can be + * passed into the function. For now, this operation will be enforced in blocking mode. + * @param statusPair Current SD card status capture with #getSdCardActiveStatus + * @param prefSdCard Preferred SD card captured with #getPreferredSdCard + * @throws std::bad_alloc if one of the two arguments was a nullptr and an allocation failed + * @return + */ + ReturnValue_t sanitizeState(SdStatePair* statusPair = nullptr, + sd::SdCard prefSdCard = sd::SdCard::NONE); - /** - * If there are issues with the state machine, it can be reset with this function - */ - void resetState(); + /** + * If sd::SdCard::NONE is passed as an argument, this function will get the currently + * preferred SD card from the scratch buffer. + * @param prefSdCardPtr + * @return + */ + std::string getCurrentMountPrefix(sd::SdCard prefSdCardPtr = sd::SdCard::NONE) override; - void setBlocking(bool blocking); - void setPrintCommandOutput(bool print); -private: - CommandExecutor cmdExecutor; - Operations currentOp = Operations::IDLE; - bool blocking = false; - bool printCmdOutput = true; + OpStatus checkCurrentOp(Operations& currentOp); - SdCardManager(); + /** + * If there are issues with the state machine, it can be reset with this function + */ + void resetState(); - ReturnValue_t setSdCardState(sd::SdCard sdCard, bool on); + void setBlocking(bool blocking); + void setPrintCommandOutput(bool print); - void processSdStatusLine(SdStatePair& active, std::string& line, uint8_t& idx, - sd::SdCard& currentSd); + /** + * @brief Checks if an SD card is mounted. + * + * @param sdCard The SD card to check + * + * @return true if mounted, otherwise false + */ + bool isSdCardMounted(sd::SdCard sdCard) override; - std::string currentPrefix; + private: + CommandExecutor cmdExecutor; + Operations currentOp = Operations::IDLE; + bool blocking = false; + bool printCmdOutput = true; + MutexIF* mutex = nullptr; - static SdCardManager* factoryInstance; + SdCardManager(); + + ReturnValue_t setSdCardState(sd::SdCard sdCard, bool on); + + void processSdStatusLine(SdStatePair& active, std::string& line, uint8_t& idx, + sd::SdCard& currentSd); + + std::string currentPrefix; + + static SdCardManager* factoryInstance; }; #endif /* BSP_Q7S_MEMORY_SDCARDACCESSMANAGER_H_ */ diff --git a/bsp_q7s/memory/definitions.h b/bsp_q7s/memory/definitions.h deleted file mode 100644 index 9e0bca65..00000000 --- a/bsp_q7s/memory/definitions.h +++ /dev/null @@ -1,26 +0,0 @@ -#ifndef BSP_Q7S_MEMORY_DEFINITIONS_H_ -#define BSP_Q7S_MEMORY_DEFINITIONS_H_ - -#include - -namespace sd { - -enum SdState: uint8_t { - OFF = 0, - ON = 1, - // A mounted SD card is on as well - MOUNTED = 2 -}; - -enum SdCard: uint8_t { - SLOT_0 = 0, - SLOT_1 = 1, - BOTH, - NONE -}; - -} - - - -#endif /* BSP_Q7S_MEMORY_DEFINITIONS_H_ */ diff --git a/bsp_q7s/memory/scratchApi.cpp b/bsp_q7s/memory/scratchApi.cpp index 08d59df1..83bc8239 100644 --- a/bsp_q7s/memory/scratchApi.cpp +++ b/bsp_q7s/memory/scratchApi.cpp @@ -1,49 +1,50 @@ #include "scratchApi.h" ReturnValue_t scratch::writeString(std::string name, std::string string) { - std::ostringstream oss; - oss << "xsc_scratch write " << name << " \"" << string << "\""; - int result = std::system(oss.str().c_str()); - if(result != 0) { - utility::handleSystemError(result, "scratch::writeString"); - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_OK; + std::ostringstream oss; + oss << "xsc_scratch write " << name << " \"" << string << "\""; + int result = std::system(oss.str().c_str()); + if (result != 0) { + utility::handleSystemError(result, "scratch::writeString"); + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t scratch::readString(std::string key, std::string &string) { - std::ifstream file; - std::string filename; - ReturnValue_t result = readToFile(key, file, filename); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } + std::ifstream file; + std::string filename; + ReturnValue_t result = readToFile(key, file, filename); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } - std::string line; - if (not std::getline(file, line)) { - std::remove(filename.c_str()); - return HasReturnvaluesIF::RETURN_FAILED; - } + std::string line; + if (not std::getline(file, line)) { + std::remove(filename.c_str()); + return HasReturnvaluesIF::RETURN_FAILED; + } - size_t pos = line.find("="); - if(pos == std::string::npos) { - sif::warning << "scratch::readNumber: Output file format invalid, " - "no \"=\" found" << std::endl; - // Could not find value - std::remove(filename.c_str()); - return KEY_NOT_FOUND; - } - string = line.substr(pos + 1); - return HasReturnvaluesIF::RETURN_OK; + size_t pos = line.find("="); + if (pos == std::string::npos) { + sif::warning << "scratch::readNumber: Output file format invalid, " + "no \"=\" found" + << std::endl; + // Could not find value + std::remove(filename.c_str()); + return KEY_NOT_FOUND; + } + string = line.substr(pos + 1); + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t scratch::clearValue(std::string key) { - std::ostringstream oss; - oss << "xsc_scratch clear " << key; - int result = std::system(oss.str().c_str()); - if(result != 0) { - utility::handleSystemError(result, "scratch::clearValue"); - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_OK; + std::ostringstream oss; + oss << "xsc_scratch clear " << key; + int result = std::system(oss.str().c_str()); + if (result != 0) { + utility::handleSystemError(result, "scratch::clearValue"); + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; } diff --git a/bsp_q7s/memory/scratchApi.h b/bsp_q7s/memory/scratchApi.h index ee19e084..babd26dc 100644 --- a/bsp_q7s/memory/scratchApi.h +++ b/bsp_q7s/memory/scratchApi.h @@ -1,17 +1,17 @@ #ifndef BSP_Q7S_MEMORY_SCRATCHAPI_H_ #define BSP_Q7S_MEMORY_SCRATCHAPI_H_ +#include +#include +#include +#include +#include + #include "fsfw/returnvalues/HasReturnvaluesIF.h" #include "fsfw/serviceinterface/ServiceInterface.h" #include "linux/utility/utility.h" #include "returnvalues/classIds.h" -#include -#include -#include -#include -#include - /** * @brief API for the scratch buffer */ @@ -48,7 +48,7 @@ ReturnValue_t readString(std::string key, std::string& string); * @param num Number. Template allows to set signed, unsigned and floating point numbers * @return */ -template::value>::type> +template ::value>::type> inline ReturnValue_t writeNumber(std::string key, T num) noexcept; /** @@ -59,90 +59,88 @@ inline ReturnValue_t writeNumber(std::string key, T num) noexcept; * @param num * @return */ -template::value>::type> +template ::value>::type> inline ReturnValue_t readNumber(std::string key, T& num) noexcept; - // Anonymous namespace namespace { static uint8_t counter = 0; ReturnValue_t readToFile(std::string name, std::ifstream& file, std::string& filename) { - using namespace std; - filename = "/tmp/sro" + std::to_string(counter++); - ostringstream oss; - oss << "xsc_scratch read " << name << " > " << filename; + using namespace std; + filename = "/tmp/sro" + std::to_string(counter++); + ostringstream oss; + oss << "xsc_scratch read " << name << " > " << filename; - int result = std::system(oss.str().c_str()); - if(result != 0) { - if(result == 256) { - sif::warning << "scratch::readNumber: 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"); - std::remove(filename.c_str()); - return HasReturnvaluesIF::RETURN_FAILED; - } + int result = std::system(oss.str().c_str()); + if (result != 0) { + if (result == 256) { + sif::warning << "scratch::readNumber: 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"); + std::remove(filename.c_str()); + return HasReturnvaluesIF::RETURN_FAILED; } - file.open(filename); - return HasReturnvaluesIF::RETURN_OK; + } + file.open(filename); + return HasReturnvaluesIF::RETURN_OK; } -} // End of anonymous namespace +} // End of anonymous namespace -template::value>::type> +template ::value>::type> inline ReturnValue_t writeNumber(std::string key, T num) noexcept { - std::ostringstream oss; - oss << "xsc_scratch write " << key << " " << std::to_string(num); - int result = std::system(oss.str().c_str()); - if(result != 0) { - utility::handleSystemError(result, "scratch::writeNumber"); - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_OK; + std::ostringstream oss; + oss << "xsc_scratch write " << key << " " << std::to_string(num); + int result = std::system(oss.str().c_str()); + if (result != 0) { + utility::handleSystemError(result, "scratch::writeNumber"); + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; } -template::value>::type> +template ::value>::type> inline ReturnValue_t readNumber(std::string key, T& num) noexcept { - using namespace std; - ifstream file; - std::string filename; - ReturnValue_t result = readToFile(key, file, filename); - if(result != HasReturnvaluesIF::RETURN_OK) { - std::remove(filename.c_str()); - return result; - } - - string line; - if (not std::getline(file, line)) { - std::remove(filename.c_str()); - return HasReturnvaluesIF::RETURN_FAILED; - } - - size_t pos = line.find("="); - if(pos == string::npos) { - sif::warning << "scratch::readNumber: Output file format invalid, " - "no \"=\" found" << std::endl; - // Could not find value - std::remove(filename.c_str()); - return KEY_NOT_FOUND; - } - std::string valueAsString = line.substr(pos + 1); - try { - num = std::stoi(valueAsString); - } - catch(std::invalid_argument& e) { - sif::warning << "scratch::readNumber: stoi call failed with " << e.what() << std::endl; - } - + using namespace std; + ifstream file; + std::string filename; + ReturnValue_t result = readToFile(key, file, filename); + if (result != HasReturnvaluesIF::RETURN_OK) { std::remove(filename.c_str()); - return HasReturnvaluesIF::RETURN_OK; + return result; + } + + string line; + if (not std::getline(file, line)) { + std::remove(filename.c_str()); + return HasReturnvaluesIF::RETURN_FAILED; + } + + size_t pos = line.find("="); + if (pos == string::npos) { + sif::warning << "scratch::readNumber: Output file format invalid, " + "no \"=\" found" + << std::endl; + // Could not find value + std::remove(filename.c_str()); + return KEY_NOT_FOUND; + } + std::string valueAsString = line.substr(pos + 1); + try { + num = std::stoi(valueAsString); + } catch (std::invalid_argument& e) { + sif::warning << "scratch::readNumber: stoi call failed with " << e.what() << std::endl; + } + + std::remove(filename.c_str()); + return HasReturnvaluesIF::RETURN_OK; } -} +} // namespace scratch #endif /* BSP_Q7S_MEMORY_SCRATCHAPI_H_ */ diff --git a/bsp_q7s/simple/CMakeLists.txt b/bsp_q7s/simple/CMakeLists.txt index 399a1dd3..77cbd076 100644 --- a/bsp_q7s/simple/CMakeLists.txt +++ b/bsp_q7s/simple/CMakeLists.txt @@ -1,3 +1,3 @@ -target_sources(${TARGET_NAME} PRIVATE +target_sources(${SIMPLE_OBSW_NAME} PRIVATE simple.cpp ) diff --git a/bsp_q7s/simple/simple.cpp b/bsp_q7s/simple/simple.cpp index 960aa7db..1362ef23 100644 --- a/bsp_q7s/simple/simple.cpp +++ b/bsp_q7s/simple/simple.cpp @@ -1,4 +1,6 @@ #include "simple.h" + +#include "iostream" #include "q7sConfig.h" #if Q7S_SIMPLE_ADD_FILE_SYSTEM_TEST == 1 @@ -6,16 +8,13 @@ #endif int simple::simple() { - cout << "-- Q7S Simple Application --" << endl; + std::cout << "-- Q7S Simple Application --" << std::endl; #if Q7S_SIMPLE_ADD_FILE_SYSTEM_TEST == 1 - { - FileSystemTest fileSystemTest; - } + { FileSystemTest fileSystemTest; } #endif #if TE0720_GPIO_TEST #endif - return 0; + return 0; } - diff --git a/bsp_q7s/spi/Q7sSpiComIF.cpp b/bsp_q7s/spi/Q7sSpiComIF.cpp index 23dbe551..84552503 100644 --- a/bsp_q7s/spi/Q7sSpiComIF.cpp +++ b/bsp_q7s/spi/Q7sSpiComIF.cpp @@ -1,9 +1,5 @@ #include -Q7sSpiComIF::Q7sSpiComIF(object_id_t objectId, GpioIF* gpioComIF) : - SpiComIF(objectId, gpioComIF) { -} - -Q7sSpiComIF::~Q7sSpiComIF() { -} +Q7sSpiComIF::Q7sSpiComIF(object_id_t objectId, GpioIF* gpioComIF) : SpiComIF(objectId, gpioComIF) {} +Q7sSpiComIF::~Q7sSpiComIF() {} diff --git a/bsp_q7s/spi/Q7sSpiComIF.h b/bsp_q7s/spi/Q7sSpiComIF.h index a10d63dd..def754ab 100644 --- a/bsp_q7s/spi/Q7sSpiComIF.h +++ b/bsp_q7s/spi/Q7sSpiComIF.h @@ -3,7 +3,6 @@ #include - /** * @brief This additional communication interface is required because the SPI busses behind the * devices "/dev/spi2.0" and "dev/spidev3.0" are multiplexed to one SPI interface. @@ -17,17 +16,17 @@ * the SPI interface. The multiplexing is performed via a GPIO connected to a VHDL * module responsible for switching between the to SPI peripherals. */ -class Q7sSpiComIF: public SpiComIF { -public: - /** - * @brief Constructor - * - * @param objectId - * @param gpioComIF - * @param gpioSwitchId The gpio ID of the GPIO connected to the SPI mux module in the PL. - */ - Q7sSpiComIF(object_id_t objectId, GpioIF* gpioComIF, gpioId_t gpioSwitchId); - virtual ~Q7sSpiComIF(); +class Q7sSpiComIF : public SpiComIF { + public: + /** + * @brief Constructor + * + * @param objectId + * @param gpioComIF + * @param gpioSwitchId The gpio ID of the GPIO connected to the SPI mux module in the PL. + */ + Q7sSpiComIF(object_id_t objectId, GpioIF* gpioComIF, gpioId_t gpioSwitchId); + virtual ~Q7sSpiComIF(); }; #endif /* BSP_Q7S_SPI_Q7SSPICOMIF_H_ */ diff --git a/cmake/HardwareOsPostConfig.cmake b/cmake/HardwareOsPostConfig.cmake index 2492b9bb..e7fb257a 100644 --- a/cmake/HardwareOsPostConfig.cmake +++ b/cmake/HardwareOsPostConfig.cmake @@ -3,7 +3,7 @@ function(post_source_hw_os_config) if(LINK_LWIP) message(STATUS "Linking against ${LIB_LWIP_NAME} lwIP library") if(LIB_LWIP_NAME) - target_link_libraries(${TARGET_NAME} PUBLIC + target_link_libraries(${OBSW_NAME} PUBLIC ${LIB_LWIP_NAME} ) else() @@ -12,7 +12,7 @@ if(LINK_LWIP) endif() if(LINKER_SCRIPT) - target_link_options(${TARGET_NAME} PRIVATE + add_link_options( -T${LINKER_SCRIPT} ) endif() @@ -35,20 +35,20 @@ if(CMAKE_VERBOSE) endif() # Generator expression. Can be used to set different C, CXX and ASM flags. -target_compile_options(${TARGET_NAME} PRIVATE +add_compile_options( $<$:${C_DEFS} ${C_FLAGS}> $<$:${CXX_DEFS} ${CXX_FLAGS}> $<$:${ASM_FLAGS}> ) -set(STRIPPED_TARGET_NAME ${TARGET_NAME}-stripped) +set(STRIPPED_OBSW_NAME ${OBSW_BIN_NAME}-stripped) add_custom_command( - TARGET ${TARGET_NAME} + TARGET ${OBSW_NAME} POST_BUILD - COMMAND ${CMAKE_STRIP} --strip-all ${TARGET_NAME} -o ${STRIPPED_TARGET_NAME} - BYPRODUCTS ${STRIPPED_TARGET_NAME} - COMMENT "Generating stripped executable ${STRIPPED_TARGET_NAME}.." + COMMAND ${CMAKE_STRIP} --strip-all ${OBSW_BIN_NAME} -o ${STRIPPED_OBSW_NAME} + BYPRODUCTS ${STRIPPED_OBSW_NAME} + COMMENT "Generating stripped executable ${STRIPPED_OBSW_NAME}.." ) endfunction() \ No newline at end of file diff --git a/cmake/HardwareOsPreConfig.cmake b/cmake/HardwareOsPreConfig.cmake index 3ff67565..88df808c 100644 --- a/cmake/HardwareOsPreConfig.cmake +++ b/cmake/HardwareOsPreConfig.cmake @@ -47,7 +47,7 @@ if(CMAKE_CROSSCOMPILING) set_property(CACHE TGT_BSP PROPERTY STRINGS - "arm/q7s" "arm/raspberrypi" + "arm/q7s" "arm/raspberrypi" "arm/egse" ) endif() @@ -57,6 +57,8 @@ if(TGT_BSP) set(BSP_PATH "bsp_linux_board") elseif(TGT_BSP MATCHES "arm/q7s") set(BSP_PATH "bsp_q7s") + elseif(TGT_BSP MATCHES "arm/egse") + set(BSP_PATH "bsp_egse") else() message(WARNING "CMake not configured for this target!") message(FATAL_ERROR "Target: ${TGT_BSP}!") diff --git a/cmake/PreProjectConfig.cmake b/cmake/PreProjectConfig.cmake index 9f1790bb..fa50baf3 100644 --- a/cmake/PreProjectConfig.cmake +++ b/cmake/PreProjectConfig.cmake @@ -9,6 +9,7 @@ if(DEFINED TGT_BSP) endif() endif() + # Disable compiler checks for cross-compiling. if(FSFW_OSAL MATCHES linux AND TGT_BSP) if(TGT_BSP MATCHES "arm/q7s") @@ -16,7 +17,7 @@ if(FSFW_OSAL MATCHES linux AND TGT_BSP) "${CMAKE_SCRIPT_PATH}/Q7SCrossCompileConfig.cmake" PARENT_SCOPE ) - elseif(TGT_BSP MATCHES "arm/raspberrypi") + elseif(TGT_BSP MATCHES "arm/raspberrypi" OR TGT_BSP MATCHES "arm/egse") if(NOT DEFINED ENV{LINUX_ROOTFS}) if(NOT DEFINED LINUX_ROOTFS) message(WARNING "No LINUX_ROOTFS environmental or CMake variable set!") diff --git a/cmake/Q7SCrossCompileConfig.cmake b/cmake/Q7SCrossCompileConfig.cmake index d4d05f4e..db05c8f0 100644 --- a/cmake/Q7SCrossCompileConfig.cmake +++ b/cmake/Q7SCrossCompileConfig.cmake @@ -81,12 +81,23 @@ set(CMAKE_PREFIX_PATH # "${SYSROOT_PATH}/usr/lib/${CROSS_COMPILE}" ) +set(C_FLAGS + -mcpu=cortex-a9 + -mfpu=neon-vfpv3 + -mfloat-abi=hard + ${COMMON_FLAGS} + -lgpiod + -lxiphos +) + +string (REPLACE ";" " " C_FLAGS "${C_FLAGS}") + set(CMAKE_C_FLAGS - "-mcpu=cortex-a9 -mfpu=neon-vfpv3 -mfloat-abi=hard ${COMMON_FLAGS} -lgpiod" + ${C_FLAGS} CACHE STRING "C flags for Q7S" ) set(CMAKE_CXX_FLAGS - "${CMAKE_C_FLAGS}" + "${CMAKE_C_FLAGS}" CACHE STRING "CPP flags for Q7S" ) diff --git a/cmake/scripts/Host/make-debug-cfg.sh b/cmake/scripts/Host/make-debug-cfg.sh index 3bda2da2..de0487ea 100755 --- a/cmake/scripts/Host/make-debug-cfg.sh +++ b/cmake/scripts/Host/make-debug-cfg.sh @@ -15,7 +15,7 @@ if [ "${counter}" -ge 5 ];then exit 1 fi -build_generator="Unix Makefiles" +build_generator="make" os_fsfw="host" builddir="build-Debug-Host" if [ "${OS}" = "Windows_NT" ]; then diff --git a/cmake/scripts/Host/make-release-cfg.sh b/cmake/scripts/Host/make-release-cfg.sh index eb0a9f57..5114f490 100755 --- a/cmake/scripts/Host/make-release-cfg.sh +++ b/cmake/scripts/Host/make-release-cfg.sh @@ -15,7 +15,7 @@ if [ "${counter}" -ge 5 ];then exit 1 fi -build_generator="Unix Makefiles" +build_generator="make" os_fsfw="host" builddir="build-Release-Host" if [ "${OS}" = "Windows_NT" ]; then diff --git a/cmake/scripts/Host/ninja-debug-cfg.sh b/cmake/scripts/Host/ninja-debug-cfg.sh index d1627174..80a5687f 100755 --- a/cmake/scripts/Host/ninja-debug-cfg.sh +++ b/cmake/scripts/Host/ninja-debug-cfg.sh @@ -15,7 +15,7 @@ if [ "${counter}" -ge 5 ];then exit 1 fi -build_generator="Ninja" +build_generator="ninja" os_fsfw="host" builddir="build-Debug-Host" if [ "${OS}" = "Windows_NT" ]; then diff --git a/cmake/scripts/Linux/make-debug-cfg.sh b/cmake/scripts/Linux/make-debug-cfg.sh index e2130416..2207a2e8 100755 --- a/cmake/scripts/Linux/make-debug-cfg.sh +++ b/cmake/scripts/Linux/make-debug-cfg.sh @@ -15,7 +15,7 @@ if [ "${counter}" -ge 5 ];then exit 1 fi -build_generator="Unix Makefiles" +build_generator="make" os_fsfw="linux" builddir="build-Debug-Host" if [ "${OS}" = "Windows_NT" ]; then diff --git a/cmake/scripts/Linux/ninja-debug-cfg.sh b/cmake/scripts/Linux/ninja-debug-cfg.sh index 905612e0..23ebc25d 100755 --- a/cmake/scripts/Linux/ninja-debug-cfg.sh +++ b/cmake/scripts/Linux/ninja-debug-cfg.sh @@ -15,7 +15,7 @@ if [ "${counter}" -ge 5 ];then exit 1 fi -build_generator="Ninja" +build_generator="ninja" os_fsfw="linux" builddir="build-Debug-Host" if [ "${OS}" = "Windows_NT" ]; then diff --git a/cmake/scripts/Q7S/make-debug-cfg.sh b/cmake/scripts/Q7S/make-debug-cfg.sh index c0807320..f3cfd81c 100755 --- a/cmake/scripts/Q7S/make-debug-cfg.sh +++ b/cmake/scripts/Q7S/make-debug-cfg.sh @@ -18,13 +18,11 @@ fi os_fsfw="linux" tgt_bsp="arm/q7s" build_dir="build-Debug-Q7S" -build_generator="" +build_generator="make" if [ "${OS}" = "Windows_NT" ]; then - build_generator="MinGW Makefiles" python="py" # Could be other OS but this works for now. else - build_generator="Unix Makefiles" python="python3" fi diff --git a/cmake/scripts/Q7S/make-release-cfg.sh b/cmake/scripts/Q7S/make-release-cfg.sh index c421f336..233bf263 100755 --- a/cmake/scripts/Q7S/make-release-cfg.sh +++ b/cmake/scripts/Q7S/make-release-cfg.sh @@ -17,19 +17,17 @@ fi os_fsfw="linux" tgt_bsp="arm/q7s" -build_dir="build-Debug-Q7S" -build_generator="" +build_dir="build-Release-Q7S" +build_generator="make" if [ "${OS}" = "Windows_NT" ]; then - build_generator="MinGW Makefiles" python="py" # Could be other OS but this works for now. else - build_generator="Unix Makefiles" python="python3" fi echo "Running command (without the leading +):" set -x # Print command -${python} ${cfg_script_name} -o "${os_fsfw}" -g "${build_generator}" -b "debug" -t "${tgt_bsp}" \ +${python} ${cfg_script_name} -o "${os_fsfw}" -g "${build_generator}" -b "release" -t "${tgt_bsp}" \ -l"${build_dir}" # set +x diff --git a/cmake/scripts/Q7S/ninja-debug-cfg.sh b/cmake/scripts/Q7S/ninja-debug-cfg.sh index 9a6b35c8..bd9ebb4e 100755 --- a/cmake/scripts/Q7S/ninja-debug-cfg.sh +++ b/cmake/scripts/Q7S/ninja-debug-cfg.sh @@ -18,7 +18,7 @@ fi os_fsfw="linux" tgt_bsp="arm/q7s" build_dir="build-Debug-Q7S" -build_generator="Ninja" +build_generator="ninja" if [ "${OS}" = "Windows_NT" ]; then python="py" # Could be other OS but this works for now. diff --git a/cmake/scripts/Q7S/ninja-release-cfg.sh b/cmake/scripts/Q7S/ninja-release-cfg.sh index a9c82d54..c9972c89 100755 --- a/cmake/scripts/Q7S/ninja-release-cfg.sh +++ b/cmake/scripts/Q7S/ninja-release-cfg.sh @@ -18,7 +18,7 @@ fi os_fsfw="linux" tgt_bsp="arm/q7s" build_dir="build-Release-Q7S" -build_generator="Ninja" +build_generator="ninja" if [ "${OS}" = "Windows_NT" ]; then python="py" # Could be other OS but this works for now. diff --git a/cmake/scripts/Q7S/q7s-env-win.sh b/cmake/scripts/Q7S/q7s-env-win.sh new file mode 100644 index 00000000..2cbc0bab --- /dev/null +++ b/cmake/scripts/Q7S/q7s-env-win.sh @@ -0,0 +1,49 @@ +#!/bin/sh +# Run with: source q7s-env-win-sh [OPTIONS] +function help () { + echo "source q7s-env-win-sh [options] -t|--toolchain= -s|--sysroot=" +} + +TOOLCHAIN_PATH="/c/Xilinx/Vitis/2019.2/gnu/aarch32/nt/gcc-arm-linux-gnueabi/bin" +SYSROOT="/c/Users/${USER}/eive-software/cortexa9hf-neon-xiphos-linux-gnueabi" + +for i in "$@"; do + case $i in + -t=*|--toolchain=*) + TOOLCHAIN_PATH="${i#*=}" + shift + ;; + -s=*|--sysroot=*) + SYSROOT="${i#*=}" + shift + ;; + -h|--help) + help + shift + ;; + -*|--*) + echo "Unknown option $i" + help + return + ;; + *) + ;; + esac +done + +if [ -d "$TOOLCHAIN_PATH" ]; then + export PATH=$PATH:"/c/Xilinx/Vitis/2019.2/gnu/aarch32/nt/gcc-arm-linux-gnueabi/bin" + export CROSS_COMPILE="arm-linux-gnueabihf" + echo "Set toolchain path to /c/Xilinx/Vitis/2019.2/gnu/aarch32/nt/gcc-arm-linux-gnueabi/bin" +else + echo "Toolchain path $TOOLCHAIN_PATH does not exist" + return +fi + +if [ -d "$SYSROOT" ]; then + export Q7S_SYSROOT=$SYSROOT + echo "Set sysroot path to $SYSROOT" +else + echo "Sysroot path $SYSROOT does not exist" + return +fi \ No newline at end of file diff --git a/cmake/scripts/Q7S/q7s-env.sh b/cmake/scripts/Q7S/q7s-env.sh new file mode 100755 index 00000000..818ff213 --- /dev/null +++ b/cmake/scripts/Q7S/q7s-env.sh @@ -0,0 +1,7 @@ +#!/bin/bash -i +export PATH=$PATH:"$HOME/EIVE/gcc-arm-8.3-2019.03-x86_64-arm-linux-gnueabihf/bin" +export CROSS_COMPILE="arm-linux-gnueabihf" + +export Q7S_SYSROOT="$HOME/Xilinx/cortexa9hf-neon-xiphos-linux-gnueabi" +export CONSOLE_PREFIX="[Q7S ENV]" +/bin/bash diff --git a/cmake/scripts/Q7S/simple/make-simple-debug-cfg.sh b/cmake/scripts/Q7S/simple/make-simple-debug-cfg.sh deleted file mode 100755 index 93f4a087..00000000 --- a/cmake/scripts/Q7S/simple/make-simple-debug-cfg.sh +++ /dev/null @@ -1,36 +0,0 @@ -#!/bin/sh -counter=0 -cfg_script_name="cmake-build-cfg.py" -while [ ${counter} -lt 5 ] -do - cd .. - if [ -f ${cfg_script_name} ];then - break - fi - counter=$((counter=counter + 1)) -done - -if [ "${counter}" -ge 5 ];then - echo "${cfg_script_name} not found in upper directories!" - exit 1 -fi - -os_fsfw="linux" -tgt_bsp="arm/q7s" -build_dir="build-Simple-Q7S" -build_generator="" -definitions="BUILD_Q7S_SIMPLE_MODE=On" -if [ "${OS}" = "Windows_NT" ]; then - build_generator="MinGW Makefiles" - python="py" -# Could be other OS but this works for now. -else - build_generator="Unix Makefiles" - python="python3" -fi - -echo "Running command (without the leading +):" -set -x # Print command -${python} ${cfg_script_name} -o "${os_fsfw}" -g "${build_generator}" -b "debug" -t "${tgt_bsp}" \ - -l "${build_dir}" -d "${definitions}" -# set +x diff --git a/cmake/scripts/Q7S/unix_path_helper.sh b/cmake/scripts/Q7S/unix_path_helper.sh deleted file mode 100644 index 296bfdd8..00000000 --- a/cmake/scripts/Q7S/unix_path_helper.sh +++ /dev/null @@ -1,6 +0,0 @@ -#!/bin/sh -export PATH=$PATH:"/opt/Xilinx/SDK/2018.2/gnu/aarch32/lin/gcc-arm-linux-gnueabi/bin" -export CROSS_COMPILE="arm-linux-gnueabihf" - -export Q7S_SYSROOT="$HOME/Xilinx/cortexa9hf-neon-xiphos-linux-gnueabi" - diff --git a/cmake/scripts/Q7S/watchdog/make-debug-cfg.sh b/cmake/scripts/Q7S/watchdog/make-debug-cfg.sh deleted file mode 100755 index 0f829fea..00000000 --- a/cmake/scripts/Q7S/watchdog/make-debug-cfg.sh +++ /dev/null @@ -1,37 +0,0 @@ -#!/bin/sh -counter=0 -cfg_script_name="cmake-build-cfg.py" -while [ ${counter} -lt 5 ] -do - cd .. - if [ -f ${cfg_script_name} ];then - break - fi - counter=$((counter=counter + 1)) -done - -if [ "${counter}" -ge 5 ];then - echo "${cfg_script_name} not found in upper directories!" - exit 1 -fi - -os_fsfw="linux" -tgt_bsp="arm/q7s" -build_dir="build-Debug-Watchdog" -build_generator="" -definitions="EIVE_BUILD_WATCHDOG=ON" -if [ "${OS}" = "Windows_NT" ]; then - build_generator="MinGW Makefiles" - python="py" -# Could be other OS but this works for now. -else - build_generator="Unix Makefiles" - python="python3" -fi - -echo "Running command (without the leading +):" -set -x # Print command -${python} ${cfg_script_name} -o "${os_fsfw}" -g "${build_generator}" -b "debug" -t "${tgt_bsp}" \ - -d "${definitions}" -l"${build_dir}" -# set +x - diff --git a/cmake/scripts/Q7S/watchdog/make-release-cfg.sh b/cmake/scripts/Q7S/watchdog/make-release-cfg.sh deleted file mode 100755 index c8df73d5..00000000 --- a/cmake/scripts/Q7S/watchdog/make-release-cfg.sh +++ /dev/null @@ -1,36 +0,0 @@ -#!/bin/sh -counter=0 -while [ ${counter} -lt 5 ] -do - cd .. - if [ -f "cmake_build_config.py" ];then - break - fi - counter=$((counter=counter + 1)) -done - -if [ "${counter}" -ge 5 ];then - echo "cmake_build_config.py not found in upper directories!" - exit 1 -fi - -os_fsfw="linux" -tgt_bsp="arm/q7s" -build_dir="build-Release-Watchdog" -build_generator="" -definitions="EIVE_BUILD_WATCHDOG=ON" -if [ "${OS}" = "Windows_NT" ]; then - build_generator="MinGW Makefiles" - python="py" -# Could be other OS but this works for now. -else - build_generator="Unix Makefiles" - python="python3" -fi - -echo "Running command (without the leading +):" -set -x # Print command -${python} cmake_build_config.py -o "${os_fsfw}" -g "${build_generator}" -b "release" -t "${tgt_bsp}" \ - -d "${definitions} -l"${build_dir}" -# set +x - diff --git a/cmake/scripts/Q7S/watchdog/ninja-debug-cfg.sh b/cmake/scripts/Q7S/watchdog/ninja-debug-cfg.sh deleted file mode 100755 index ed23bb6a..00000000 --- a/cmake/scripts/Q7S/watchdog/ninja-debug-cfg.sh +++ /dev/null @@ -1,35 +0,0 @@ -#!/bin/sh -counter=0 -cfg_script_name="cmake-build-cfg.py" -while [ ${counter} -lt 5 ] -do - cd .. - if [ -f ${cfg_script_name} ];then - break - fi - counter=$((counter=counter + 1)) -done - -if [ "${counter}" -ge 5 ];then - echo "${cfg_script_name} not found in upper directories!" - exit 1 -fi - -os_fsfw="linux" -tgt_bsp="arm/q7s" -build_dir="build-Debug-Watchdog" -build_generator="Ninja" -definitions="EIVE_BUILD_WATCHDOG=ON" -if [ "${OS}" = "Windows_NT" ]; then - python="py" -# Could be other OS but this works for now. -else - python="python3" -fi - -echo "Running command (without the leading +):" -set -x # Print command -${python} ${cfg_script_name} -o "${os_fsfw}" -g "${build_generator}" -b "debug" -t "${tgt_bsp}" \ - -d "${definitions}" -l "${build_dir}" -# set +x - diff --git a/cmake/scripts/Q7S/watchdog/ninja-release-cfg.sh b/cmake/scripts/Q7S/watchdog/ninja-release-cfg.sh deleted file mode 100755 index d8f5e18e..00000000 --- a/cmake/scripts/Q7S/watchdog/ninja-release-cfg.sh +++ /dev/null @@ -1,35 +0,0 @@ -#!/bin/sh -counter=0 -cfg_script_name="cmake-build-cfg.py" -while [ ${counter} -lt 5 ] -do - cd .. - if [ -f ${cfg_script_name} ];then - break - fi - counter=$((counter=counter + 1)) -done - -if [ "${counter}" -ge 5 ];then - echo "${cfg_script_name} not found in upper directories!" - exit 1 -fi - -os_fsfw="linux" -tgt_bsp="arm/q7s" -build_dir="build-Release-Watchdog" -build_generator="Ninja" -definitions="EIVE_BUILD_WATCHDOG=ON" -if [ "${OS}" = "Windows_NT" ]; then - python="py" -# Could be other OS but this works for now. -else - python="python3" -fi - -echo "Running command (without the leading +):" -set -x # Print command -${python} ${cfg_script_name} -o "${os_fsfw}" -g "${build_generator}" -b "release" -t "${tgt_bsp}" \ - -d "${definitions}" -l"${build_dir}" -# set +x - diff --git a/cmake/scripts/Q7S/win_path_helper_xilinx_tools.sh b/cmake/scripts/Q7S/win_path_helper_xilinx_tools.sh deleted file mode 100644 index a8352331..00000000 --- a/cmake/scripts/Q7S/win_path_helper_xilinx_tools.sh +++ /dev/null @@ -1,5 +0,0 @@ -#!/bin/sh -export PATH=$PATH:"/c/Xilinx/SDK/2018.2/gnu/aarch32/nt/gcc-arm-linux-gnueabi/bin" -export CROSS_COMPILE="arm-linux-gnueabihf" - -export Q7S_SYSROOT="/c/Users/${USER}/Documents/EIVE/cortexa9hf-neon-xiphos-linux-gnueabi" diff --git a/cmake/scripts/RPi/make-debug-cfg.sh b/cmake/scripts/RPi/make-debug-cfg.sh index 3b95ceee..f4d006c3 100755 --- a/cmake/scripts/RPi/make-debug-cfg.sh +++ b/cmake/scripts/RPi/make-debug-cfg.sh @@ -18,14 +18,12 @@ fi os_fsfw="linux" tgt_bsp="arm/raspberrypi" -build_generator="" +build_generator="make" build_dir="build-Debug-RPi" if [ "${OS}" = "Windows_NT" ]; then - build_generator="MinGW Makefiles" python="py" # Could be other OS but this works for now. else - build_generator="Unix Makefiles" python="python3" fi diff --git a/cmake/scripts/RPi/ninja-debug-cfg.sh b/cmake/scripts/RPi/ninja-debug-cfg.sh index 4cfb9854..13096fd6 100755 --- a/cmake/scripts/RPi/ninja-debug-cfg.sh +++ b/cmake/scripts/RPi/ninja-debug-cfg.sh @@ -17,7 +17,7 @@ fi os_fsfw="linux" tgt_bsp="arm/raspberrypi" -build_generator="Ninja" +build_generator="ninja" build_dir="build-Debug-RPi" if [ "${OS}" = "Windows_NT" ]; then python="py" diff --git a/cmake/scripts/cmake-build-cfg.py b/cmake/scripts/cmake-build-cfg.py index e3259fd4..5d1b1048 100755 --- a/cmake/scripts/cmake-build-cfg.py +++ b/cmake/scripts/cmake-build-cfg.py @@ -29,7 +29,9 @@ def main(): "Information)", default="debug" ) parser.add_argument("-l", "--builddir", type=str, help="Specify build directory.") - parser.add_argument("-g", "--generator", type=str, help="CMake Generator") + parser.add_argument( + "-g", "--generator", type=str, help="CMake Generator", choices=['make', 'ninja'] + ) parser.add_argument( "-d", "--defines", help="Additional custom defines passed to CMake (supply without -D prefix!)", @@ -56,7 +58,15 @@ def main(): if args.generator is None: generator_cmake_arg = "" else: - generator_cmake_arg = f"-G \"{args.generator}\"" + if args.generator == 'make': + if os.name == 'nt': + generator_cmake_arg = '-G "MinGW Makefiles"' + else: + generator_cmake_arg = '-G "Unix Makefiles"' + elif args.generator == 'ninja': + generator_cmake_arg = '-G Ninja' + else: + generator_cmake_arg = args.generator if args.buildtype == "debug": cmake_build_type = "Debug" diff --git a/cmake/scripts/egse/egse_path_helper_win.sh b/cmake/scripts/egse/egse_path_helper_win.sh new file mode 100644 index 00000000..4bda17b0 --- /dev/null +++ b/cmake/scripts/egse/egse_path_helper_win.sh @@ -0,0 +1,13 @@ +#!/bin/sh +# Script to set path to raspberry pi toolchain +# Run script with: source egse_path_helper_win.sh +TOOLCHAIN_PATH="/c/SysGCC/raspberry/bin" +if [ $# -eq 1 ];then + export PATH=$PATH:"$1" +else + export PATH=$PATH:$TOOLCHAIN_PATH +fi + +echo "Path of toolchain set to $TOOLCHAIN_PATH" +export CROSS_COMPILE="arm-linux-gnueabihf" +export RASPBERRY_VERSION="4" \ No newline at end of file diff --git a/cmake/scripts/Q7S/simple/ninja-simple-debug-cfg.sh b/cmake/scripts/egse/make-debug-cfg.sh old mode 100755 new mode 100644 similarity index 80% rename from cmake/scripts/Q7S/simple/ninja-simple-debug-cfg.sh rename to cmake/scripts/egse/make-debug-cfg.sh index c1805eff..9a611373 --- a/cmake/scripts/Q7S/simple/ninja-simple-debug-cfg.sh +++ b/cmake/scripts/egse/make-debug-cfg.sh @@ -15,11 +15,11 @@ if [ "${counter}" -ge 5 ];then exit 1 fi + os_fsfw="linux" -tgt_bsp="arm/q7s" -build_dir="build-Simple-Q7S" -build_generator="Ninja" -definitions="BUILD_Q7S_SIMPLE_MODE=On" +tgt_bsp="arm/egse" +build_generator="make" +build_dir="build-Debug-egse" if [ "${OS}" = "Windows_NT" ]; then python="py" # Could be other OS but this works for now. @@ -30,6 +30,5 @@ fi echo "Running command (without the leading +):" set -x # Print command ${python} ${cfg_script_name} -o "${os_fsfw}" -g "${build_generator}" -b "debug" -t "${tgt_bsp}" \ - -l "${build_dir}" -d "${definitions}" + -l"${build_dir}" # set +x - diff --git a/common/config/CMakeLists.txt b/common/config/CMakeLists.txt index f38f2c50..00848561 100644 --- a/common/config/CMakeLists.txt +++ b/common/config/CMakeLists.txt @@ -1,3 +1,7 @@ -target_include_directories(${TARGET_NAME} PRIVATE +target_include_directories(${OBSW_NAME} PRIVATE ${CMAKE_CURRENT_SOURCE_DIR} +) + +target_sources(${OBSW_NAME} PRIVATE + commonConfig.cpp ) \ No newline at end of file diff --git a/common/config/OBSWVersion.h b/common/config/OBSWVersion.h index 5e9b1b9c..f719a274 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 7 +#define SW_SUBVERSION 9 #define SW_REVISION 0 #endif /* COMMON_CONFIG_OBSWVERSION_H_ */ diff --git a/common/config/ccsdsConfig.h b/common/config/ccsdsConfig.h new file mode 100644 index 00000000..8466a9fa --- /dev/null +++ b/common/config/ccsdsConfig.h @@ -0,0 +1,15 @@ +#ifndef COMMON_CONFIG_CCSDSCONFIG_H_ +#define COMMON_CONFIG_CCSDSCONFIG_H_ + +namespace ccsds { +enum { + VC0, + VC1, + VC2, + VC3 +}; +} + + + +#endif /* COMMON_CONFIG_CCSDSCONFIG_H_ */ diff --git a/common/config/commonClassIds.h b/common/config/commonClassIds.h index 793cb1ba..01f186a4 100644 --- a/common/config/commonClassIds.h +++ b/common/config/commonClassIds.h @@ -7,8 +7,6 @@ namespace CLASS_ID { enum commonClassIds: uint8_t { COMMON_CLASS_ID_START = FW_CLASS_ID_COUNT, - MGM_LIS3MDL, //MGMLIS3 - MGM_RM3100, //MGMRM3100 PCDU_HANDLER, //PCDU HEATER_HANDLER, //HEATER SYRLINKS_HANDLER, //SYRLINKS @@ -19,9 +17,17 @@ enum commonClassIds: uint8_t { 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 + SA_DEPL_HANDLER, //SADPL COMMON_CLASS_ID_END // [EXPORT] : [END] }; diff --git a/common/config/commonConfig.cpp b/common/config/commonConfig.cpp new file mode 100644 index 00000000..31674512 --- /dev/null +++ b/common/config/commonConfig.cpp @@ -0,0 +1,5 @@ +#include "commonConfig.h" +#include "tmtc/apid.h" +#include "fsfw/tmtcpacket/SpacePacket.h" + +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 52b5dd45..6d74884f 100644 --- a/common/config/commonConfig.h.in +++ b/common/config/commonConfig.h.in @@ -1,10 +1,29 @@ #ifndef COMMON_CONFIG_COMMONCONFIG_H_ #define COMMON_CONFIG_COMMONCONFIG_H_ +#include + #define OBSW_ADD_LWGPS_TEST 0 +// Disable this for mission code. It allows exchanging TMTC packets via the Ethernet port +#define OBSW_ADD_TCPIP_BRIDGE 1 + // Use TCP instead of UDP for the TMTC bridge. This allows using the TMTC client locally // because UDP packets are not allowed in the VPN +// This will cause the OBSW to initialize the TMTC bridge responsible for exchanging data with the +// CCSDS IP Cores. #define OBSW_USE_TMTC_TCP_BRIDGE 1 +namespace common { +extern const uint16_t PUS_PACKET_ID; + +static constexpr uint32_t CCSDS_HANDLER_QUEUE_SIZE = 50; +static constexpr uint8_t NUMBER_OF_VIRTUAL_CHANNELS = 4; +static constexpr uint8_t VC0_QUEUE_SIZE = 50; +static constexpr uint8_t VC1_QUEUE_SIZE = 50; +static constexpr uint8_t VC2_QUEUE_SIZE = 50; +static constexpr uint8_t VC3_QUEUE_SIZE = 50; + +} + #endif /* COMMON_CONFIG_COMMONCONFIG_H_ */ diff --git a/common/config/commonObjects.h b/common/config/commonObjects.h index e44e0a1a..6cc90be9 100644 --- a/common/config/commonObjects.h +++ b/common/config/commonObjects.h @@ -11,6 +11,10 @@ enum commonObjects: uint32_t { 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, @@ -22,6 +26,7 @@ enum commonObjects: uint32_t { 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, @@ -32,6 +37,7 @@ enum commonObjects: uint32_t { GYRO_1_L3G_HANDLER = 0x44120111, GYRO_2_ADIS_HANDLER = 0x44120212, GYRO_3_L3G_HANDLER = 0x44120313, + PLPCDU_HANDLER = 0x44300000, IMTQ_HANDLER = 0x44140014, PLOC_MPSOC_HANDLER = 0x44330015, @@ -41,49 +47,50 @@ enum commonObjects: uint32_t { * 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_IC3 = 0x44420016, - RTD_IC4 = 0x44420017, - RTD_IC5 = 0x44420018, - RTD_IC6 = 0x44420019, - RTD_IC7 = 0x44420020, - RTD_IC8 = 0x44420021, - RTD_IC9 = 0x44420022, - RTD_IC10 = 0x44420023, - RTD_IC11 = 0x44420024, - RTD_IC12 = 0x44420025, - RTD_IC13 = 0x44420026, - RTD_IC14 = 0x44420027, - RTD_IC15 = 0x44420028, - RTD_IC16 = 0x44420029, - RTD_IC17 = 0x44420030, - RTD_IC18 = 0x44420031, + 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, - SUS_1 = 0x44120032, - SUS_2 = 0x44120033, - SUS_3 = 0x44120034, - SUS_4 = 0x44120035, - SUS_5 = 0x44120036, - SUS_6 = 0x44120037, - SUS_7 = 0x44120038, - SUS_8 = 0x44120039, - SUS_9 = 0x44120040, - SUS_10 = 0x44120041, - SUS_11 = 0x44120042, - SUS_12 = 0x44120043, - SUS_13 = 0x44120044, + 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, - GPS0_HANDLER = 0x44130045, - GPS1_HANDLER = 0x44130146, + GPS_CONTROLLER = 0x44130045, RW1 = 0x44120047, RW2 = 0x44120148, RW3 = 0x44120249, RW4 = 0x44120350, - START_TRACKER = 0x44130001, + STAR_TRACKER = 0x44130001, PLOC_UPDATER = 0x44330000, - PLOC_MEMORY_DUMPER = 0x44330001 + PLOC_MEMORY_DUMPER = 0x44330001, + STR_HELPER = 0x44330002, + AXI_PTME_CONFIG = 44330003, + PTME_CONFIG = 44330004, }; } diff --git a/common/config/commonSubsystemIds.h b/common/config/commonSubsystemIds.h index 58ebac66..9f293ec6 100644 --- a/common/config/commonSubsystemIds.h +++ b/common/config/commonSubsystemIds.h @@ -6,8 +6,6 @@ namespace SUBSYSTEM_ID { enum: uint8_t { COMMON_SUBSYSTEM_ID_START = FW_SUBSYSTEM_ID_RANGE, - MGM_LIS3MDL = 106, - MGM_RM3100 = 107, PCDU_HANDLER = 108, HEATER_HANDLER = 109, SA_DEPL_HANDLER = 110, @@ -19,6 +17,9 @@ enum: uint8_t { FILE_SYSTEM = 116, PLOC_UPDATER = 117, PLOC_MEMORY_DUMPER = 118, + PDEC_HANDLER = 119, + STR_HELPER = 120, + PL_PCDU_HANDLER = 121, COMMON_SUBSYSTEM_ID_END }; } diff --git a/common/config/devConf.h b/common/config/devConf.h index fbd9763b..8a35a0fa 100644 --- a/common/config/devConf.h +++ b/common/config/devConf.h @@ -12,20 +12,28 @@ namespace spi { // Default values, changing them is not supported for now static constexpr uint32_t DEFAULT_LIS3_SPEED = 976'000; -static constexpr uint32_t LIS3_TRANSITION_DELAY = 10000; +static constexpr uint32_t LIS3_TRANSITION_DELAY = 5000; static constexpr spi::SpiModes DEFAULT_LIS3_MODE = spi::SpiModes::MODE_3; static constexpr uint32_t DEFAULT_RM3100_SPEED = 976'000; -static constexpr uint32_t RM3100_TRANSITION_DELAY = 10000; +static constexpr uint32_t RM3100_TRANSITION_DELAY = 5000; static constexpr spi::SpiModes DEFAULT_RM3100_MODE = spi::SpiModes::MODE_3; static constexpr uint32_t DEFAULT_L3G_SPEED = 976'000; -static constexpr uint32_t L3G_TRANSITION_DELAY = 10000; +static constexpr uint32_t L3G_TRANSITION_DELAY = 5000; static constexpr spi::SpiModes DEFAULT_L3G_MODE = spi::SpiModes::MODE_3; -static constexpr uint32_t DEFAULT_MAX_1227_SPEED = 3'900'000; +/** + * Some MAX1227 could not be reached with frequencies around 4 MHz. Maybe this is caused by + * the decoder and buffer circuits. Thus frequency is here defined to 1 MHz. + */ +static const uint32_t SUS_MAX1227_SPI_FREQ = 976'000; + +static constexpr uint32_t DEFAULT_MAX_1227_SPEED = 976'000; static constexpr spi::SpiModes DEFAULT_MAX_1227_MODE = spi::SpiModes::MODE_3; +static constexpr uint32_t PL_PCDU_MAX_1227_SPEED = 976'000; + static constexpr uint32_t DEFAULT_ADIS16507_SPEED = 976'000; static constexpr spi::SpiModes DEFAULT_ADIS16507_MODE = spi::SpiModes::MODE_3; @@ -33,6 +41,7 @@ static constexpr uint32_t RW_SPEED = 300'000; static constexpr spi::SpiModes RW_MODE = spi::SpiModes::MODE_0; static constexpr uint32_t RTD_SPEED = 2'000'000; +static constexpr spi::SpiModes RTD_MODE = spi::SpiModes::MODE_3; } @@ -41,9 +50,9 @@ namespace uart { static constexpr size_t HYPERION_GPS_REPLY_MAX_BUFFER = 1024; static constexpr uint32_t SYRLINKS_BAUD = 38400; static constexpr uint32_t GNSS_BAUD = 9600; -static constexpr uint32_t PLOC_MPSOC_BAUD = 115200; +static constexpr uint32_t PLOC_MPSOC_BAUD = 921600; static constexpr uint32_t PLOC_SUPERVISOR_BAUD = 115200; -static constexpr uint32_t STAR_TRACKER_BAUD = 115200; +static constexpr uint32_t STAR_TRACKER_BAUD = 921600; } diff --git a/common/config/devices/gpioIds.h b/common/config/devices/gpioIds.h new file mode 100644 index 00000000..e6f42eb4 --- /dev/null +++ b/common/config/devices/gpioIds.h @@ -0,0 +1,126 @@ +#ifndef FSFWCONFIG_DEVICES_GPIOIDS_H_ +#define FSFWCONFIG_DEVICES_GPIOIDS_H_ + +#include + +namespace gpioIds { +enum gpioId_t { + HEATER_0, + HEATER_1, + HEATER_2, + HEATER_3, + HEATER_4, + HEATER_5, + HEATER_6, + HEATER_7, + DEPLSA1, + DEPLSA2, + + MGM_0_LIS3_CS, + MGM_1_RM3100_CS, + GYRO_0_ADIS_CS, + GYRO_1_L3G_CS, + GYRO_2_ADIS_CS, + GYRO_3_L3G_CS, + MGM_2_LIS3_CS, + MGM_3_RM3100_CS, + + GNSS_0_NRESET, + GNSS_1_NRESET, + GNSS_0_ENABLE, + GNSS_1_ENABLE, + GNSS_SELECT, + + GYRO_0_ENABLE, + GYRO_2_ENABLE, + + TEST_ID_0, + TEST_ID_1, + + RTD_IC_3, + RTD_IC_4, + RTD_IC_5, + RTD_IC_6, + RTD_IC_7, + RTD_IC_8, + RTD_IC_9, + RTD_IC_10, + RTD_IC_11, + RTD_IC_12, + RTD_IC_13, + RTD_IC_14, + RTD_IC_15, + RTD_IC_16, + RTD_IC_17, + RTD_IC_18, + + CS_SUS_0, + CS_SUS_1, + CS_SUS_2, + CS_SUS_3, + CS_SUS_4, + CS_SUS_5, + CS_SUS_6, + CS_SUS_7, + CS_SUS_8, + CS_SUS_9, + CS_SUS_10, + CS_SUS_11, + + SPI_MUX_BIT_0, + SPI_MUX_BIT_1, + SPI_MUX_BIT_2, + SPI_MUX_BIT_3, + SPI_MUX_BIT_4, + SPI_MUX_BIT_5, + + CS_RAD_SENSOR, + ENABLE_RADFET, + + PAPB_BUSY_N, + PAPB_EMPTY, + + EN_RW1, + EN_RW2, + EN_RW3, + EN_RW4, + + CS_RW1, + CS_RW2, + CS_RW3, + CS_RW4, + + EN_RW_CS, + + SPI_MUX, + + VC0_PAPB_EMPTY, + VC0_PAPB_BUSY, + VC1_PAPB_EMPTY, + VC1_PAPB_BUSY, + VC2_PAPB_EMPTY, + VC2_PAPB_BUSY, + VC3_PAPB_EMPTY, + VC3_PAPB_BUSY, + + PDEC_RESET, + + RS485_EN_TX_DATA, + RS485_EN_TX_CLOCK, + RS485_EN_RX_DATA, + RS485_EN_RX_CLOCK, + + BIT_RATE_SEL, + + PLPCDU_ENB_VBAT0, + PLPCDU_ENB_VBAT1, + PLPCDU_ENB_DRO, + PLPCDU_ENB_X8, + PLPCDU_ENB_TX, + PLPCDU_ENB_HPA, + PLPCDU_ENB_MPA, + PLPCDU_ADC_CS +}; +} + +#endif /* FSFWCONFIG_DEVICES_GPIOIDS_H_ */ diff --git a/linux/fsfwconfig/devices/heaterSwitcherList.h b/common/config/devices/heaterSwitcherList.h similarity index 100% rename from linux/fsfwconfig/devices/heaterSwitcherList.h rename to common/config/devices/heaterSwitcherList.h diff --git a/common/config/devices/powerSwitcherList.h b/common/config/devices/powerSwitcherList.h new file mode 100644 index 00000000..45428a2e --- /dev/null +++ b/common/config/devices/powerSwitcherList.h @@ -0,0 +1,60 @@ +#ifndef FSFWCONFIG_DEVICES_POWERSWITCHERLIST_H_ +#define FSFWCONFIG_DEVICES_POWERSWITCHERLIST_H_ + +#include "OBSWConfig.h" + +#include + +namespace pcduSwitches { + /* Switches are uint8_t datatype and go from 0 to 255 */ + enum SwitcherList: uint8_t { + Q7S, + PAYLOAD_PCDU_CH1, + RW, + TCS_BOARD_8V_HEATER_IN, + SUS_REDUNDANT, + DEPLOYMENT_MECHANISM, + PAYLOAD_PCDU_CH6, + ACS_BOARD_SIDE_B, + PAYLOAD_CAMERA, + TCS_BOARD_3V3, + SYRLINKS, + STAR_TRACKER, + MGT, + SUS_NOMINAL, + SOLAR_CELL_EXP, + PLOC, + ACS_BOARD_SIDE_A, + NUMBER_OF_SWITCHES + }; + + static const uint8_t ON = 1; + static const uint8_t OFF = 0; + + /* Output states after reboot of the PDUs */ + static const uint8_t INIT_STATE_Q7S = ON; + static const uint8_t INIT_STATE_PAYLOAD_PCDU_CH1 = OFF; + static const uint8_t INIT_STATE_RW = OFF; +#if BOARD_TE0720 == 1 + /* Because the TE0720 is not connected to the PCDU, this switch is always on */ + static const uint8_t INIT_STATE_TCS_BOARD_8V_HEATER_IN = ON; +#else + static const uint8_t INIT_STATE_TCS_BOARD_8V_HEATER_IN = OFF; +#endif + static const uint8_t INIT_STATE_SUS_REDUNDANT = OFF; + static const uint8_t INIT_STATE_DEPLOYMENT_MECHANISM = OFF; + static const uint8_t INIT_STATE_PAYLOAD_PCDU_CH6 = OFF; + static const uint8_t INIT_STATE_ACS_BOARD_SIDE_B = OFF; + static const uint8_t INIT_STATE_PAYLOAD_CAMERA = OFF; + static const uint8_t INIT_STATE_TCS_BOARD_3V3 = OFF; + static const uint8_t INIT_STATE_SYRLINKS = OFF; + static const uint8_t INIT_STATE_STAR_TRACKER = OFF; + static const uint8_t INIT_STATE_MGT = OFF; + static const uint8_t INIT_STATE_SUS_NOMINAL = OFF; + static const uint8_t INIT_STATE_SOLAR_CELL_EXP = OFF; + static const uint8_t INIT_STATE_PLOC = OFF; + static const uint8_t INIT_STATE_ACS_BOARD_SIDE_A = OFF; +} + + +#endif /* FSFWCONFIG_DEVICES_POWERSWITCHERLIST_H_ */ diff --git a/common/config/lwgps_opts.h b/common/config/lwgps_opts.h index 20632d6f..2be39f1d 100644 --- a/common/config/lwgps_opts.h +++ b/common/config/lwgps_opts.h @@ -41,4 +41,8 @@ * copy & replace here settings you want to change values */ +#ifndef __DOXYGEN__ +#define __DOXYGEN__ 0 +#endif + #endif /* LWGPS_HDR_OPTS_H */ diff --git a/linux/fsfwconfig/tmtc/apid.h b/common/config/tmtc/apid.h similarity index 100% rename from linux/fsfwconfig/tmtc/apid.h rename to common/config/tmtc/apid.h diff --git a/fsfw b/fsfw index e1a85b47..73f0b9c0 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit e1a85b47c5018590e58b9b1130b1754b0079450f +Subproject commit 73f0b9c0dc3995e2b1f11694ae1018953e7e62b1 diff --git a/generators/bsp_q7s_events.csv b/generators/bsp_q7s_events.csv index a5bbcde4..fa39dd9b 100644 --- a/generators/bsp_q7s_events.csv +++ b/generators/bsp_q7s_events.csv @@ -1,106 +1,141 @@ -2200;STORE_SEND_WRITE_FAILED;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -2201;STORE_WRITE_FAILED;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -2202;STORE_SEND_READ_FAILED;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -2203;STORE_READ_FAILED;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -2204;UNEXPECTED_MSG;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -2205;STORING_FAILED;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -2206;TM_DUMP_FAILED;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -2207;STORE_INIT_FAILED;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -2208;STORE_INIT_EMPTY;INFO;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -2209;STORE_CONTENT_CORRUPTED;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -2210;STORE_INITIALIZE;INFO;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -2211;INIT_DONE;INFO;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -2212;DUMP_FINISHED;INFO;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -2213;DELETION_FINISHED;INFO;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -2214;DELETION_FAILED;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -2215;AUTO_CATALOGS_SENDING_FAILED;INFO;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -2600;GET_DATA_FAILED;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/storagemanager/StorageManagerIF.h -2601;STORE_DATA_FAILED;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/storagemanager/StorageManagerIF.h -2800;DEVICE_BUILDING_COMMAND_FAILED;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -2801;DEVICE_SENDING_COMMAND_FAILED;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -2802;DEVICE_REQUESTING_REPLY_FAILED;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -2803;DEVICE_READING_REPLY_FAILED;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -2804;DEVICE_INTERPRETING_REPLY_FAILED;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -2805;DEVICE_MISSED_REPLY;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -2806;DEVICE_UNKNOWN_REPLY;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -2807;DEVICE_UNREQUESTED_REPLY;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -2808;INVALID_DEVICE_COMMAND;LOW;Indicates a SW bug in child class.;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -2809;MONITORING_LIMIT_EXCEEDED;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -2810;MONITORING_AMBIGUOUS;HIGH;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -4201;FUSE_CURRENT_HIGH;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/power/Fuse.h -4202;FUSE_WENT_OFF;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/power/Fuse.h -4204;POWER_ABOVE_HIGH_LIMIT;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/power/Fuse.h -4205;POWER_BELOW_LOW_LIMIT;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/power/Fuse.h -4300;SWITCH_WENT_OFF;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/power/PowerSwitchIF.h -5000;HEATER_ON;INFO;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/thermal/Heater.h -5001;HEATER_OFF;INFO;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/thermal/Heater.h -5002;HEATER_TIMEOUT;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/thermal/Heater.h -5003;HEATER_STAYED_ON;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/thermal/Heater.h -5004;HEATER_STAYED_OFF;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/thermal/Heater.h -5200;TEMP_SENSOR_HIGH;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/thermal/AbstractTemperatureSensor.h -5201;TEMP_SENSOR_LOW;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/thermal/AbstractTemperatureSensor.h -5202;TEMP_SENSOR_GRADIENT;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/thermal/AbstractTemperatureSensor.h -5901;COMPONENT_TEMP_LOW;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/thermal/ThermalComponentIF.h -5902;COMPONENT_TEMP_HIGH;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/thermal/ThermalComponentIF.h -5903;COMPONENT_TEMP_OOL_LOW;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/thermal/ThermalComponentIF.h -5904;COMPONENT_TEMP_OOL_HIGH;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/thermal/ThermalComponentIF.h -5905;TEMP_NOT_IN_OP_RANGE;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/thermal/ThermalComponentIF.h -7101;FDIR_CHANGED_STATE;INFO;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/fdir/FailureIsolationBase.h -7102;FDIR_STARTS_RECOVERY;MEDIUM;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/fdir/FailureIsolationBase.h -7103;FDIR_TURNS_OFF_DEVICE;MEDIUM;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/fdir/FailureIsolationBase.h -7201;MONITOR_CHANGED_STATE;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/monitoring/MonitoringIF.h -7202;VALUE_BELOW_LOW_LIMIT;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/monitoring/MonitoringIF.h -7203;VALUE_ABOVE_HIGH_LIMIT;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/monitoring/MonitoringIF.h -7204;VALUE_OUT_OF_RANGE;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/monitoring/MonitoringIF.h -7301;SWITCHING_TM_FAILED;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datapool/HkSwitchHelper.h -7400;CHANGING_MODE;INFO;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/modes/HasModesIF.h -7401;MODE_INFO;INFO;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/modes/HasModesIF.h -7402;FALLBACK_FAILED;HIGH;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/modes/HasModesIF.h -7403;MODE_TRANSITION_FAILED;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/modes/HasModesIF.h -7404;CANT_KEEP_MODE;HIGH;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/modes/HasModesIF.h -7405;OBJECT_IN_INVALID_MODE;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/modes/HasModesIF.h -7406;FORCING_MODE;MEDIUM;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/modes/HasModesIF.h -7407;MODE_CMD_REJECTED;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/modes/HasModesIF.h -7506;HEALTH_INFO;INFO;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/health/HasHealthIF.h -7507;CHILD_CHANGED_HEALTH;INFO;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/health/HasHealthIF.h -7508;CHILD_PROBLEMS;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/health/HasHealthIF.h -7509;OVERWRITING_HEALTH;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/health/HasHealthIF.h -7510;TRYING_RECOVERY;MEDIUM;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/health/HasHealthIF.h -7511;RECOVERY_STEP;MEDIUM;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/health/HasHealthIF.h -7512;RECOVERY_DONE;MEDIUM;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/health/HasHealthIF.h -7900;RF_AVAILABLE;INFO;A RF available signal was detected. P1: raw RFA state, P2: 0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/DataLinkLayer.h -7901;RF_LOST;INFO;A previously found RF available signal was lost. P1: raw RFA state, P2: 0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/DataLinkLayer.h -7902;BIT_LOCK;INFO;A Bit Lock signal. Was detected. P1: raw BLO state, P2: 0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/DataLinkLayer.h -7903;BIT_LOCK_LOST;INFO;A previously found Bit Lock signal was lost. P1: raw BLO state, P2: 0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/DataLinkLayer.h -7905;FRAME_PROCESSING_FAILED;LOW;The CCSDS Board could not interpret a TC;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/DataLinkLayer.h -8900;CLOCK_SET;INFO;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/pus/Service9TimeManagement.h -8901;CLOCK_SET_FAILURE;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/pus/Service9TimeManagement.h -9700;TEST;INFO;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/pus/Service17Test.h -10600;CHANGE_OF_SETUP_PARAMETER;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/MGMHandlerLIS3MDL.h -11101;MEMORY_READ_RPT_CRC_FAILURE;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/PlocMPSoCHandler.h -11102;ACK_FAILURE;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/PlocMPSoCHandler.h -11103;EXE_FAILURE;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/PlocMPSoCHandler.h -11104;CRC_FAILURE_EVENT;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/PlocMPSoCHandler.h -11201;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;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/IMTQHandler.h -11202;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;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/IMTQHandler.h -11203;SELF_TEST_ADC_FAILURE;LOW;Get self test result returns failure in measurement of current and temperature. P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/IMTQHandler.h -11204;SELF_TEST_PWM_FAILURE;LOW;Get self test result returns PWM failure which concerns the coil actuation. P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/IMTQHandler.h -11205;SELF_TEST_TC_FAILURE;LOW;Get self test result returns TC failure (system 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;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/IMTQHandler.h -11206;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;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/IMTQHandler.h -11207;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;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/IMTQHandler.h -11208;INVALID_ERROR_BYTE;LOW;Received invalid error byte. This indicates an error of the communication link between IMTQ and OBC.;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/IMTQHandler.h -11301;ERROR_STATE;HIGH;Reaction wheel signals an error state;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/RwHandler.h -11501;SUPV_MEMORY_READ_RPT_CRC_FAILURE;LOW;PLOC supervisor crc failure in telemetry packet;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/PlocSupervisorHandler.h -11502;SUPV_ACK_FAILURE;LOW;PLOC supervisor received acknowledgment failure report;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/PlocSupervisorHandler.h -11503;SUPV_EXE_FAILURE;LOW;PLOC received execution failure report;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/PlocSupervisorHandler.h -11504;SUPV_CRC_FAILURE_EVENT;LOW;PLOC supervisor reply has invalid crc;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/PlocSupervisorHandler.h -11600;SANITIZATION_FAILED;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/memory/SdCardManager.h -11700;UPDATE_FILE_NOT_EXISTS;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/PlocUpdater.h -11701;ACTION_COMMANDING_FAILED;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/PlocUpdater.h -11702;UPDATE_AVAILABLE_FAILED;LOW;Supervisor handler replied action message indicating a command execution failure of the update available command;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/PlocUpdater.h -11703;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);C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/PlocUpdater.h -11704;UPDATE_VERIFY_FAILED;LOW;Supervisor failed to execute the update verify command.;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/PlocUpdater.h -11705;UPDATE_FINISHED;INFO;MPSoC update successful completed;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/PlocUpdater.h -11800;SEND_MRAM_DUMP_FAILED;LOW;;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/PlocMemoryDumper.h -11801;MRAM_DUMP_FAILED;LOW;Received completion failure report form PLOC supervisor handler P1: MRAM start address of failing dump command;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/PlocMemoryDumper.h -11802;MRAM_DUMP_FINISHED;LOW;MRAM dump finished successfully;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/PlocMemoryDumper.h +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 +2203;0x089b;STORE_READ_FAILED;LOW;;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +2204;0x089c;UNEXPECTED_MSG;LOW;;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +2205;0x089d;STORING_FAILED;LOW;;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +2206;0x089e;TM_DUMP_FAILED;LOW;;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +2207;0x089f;STORE_INIT_FAILED;LOW;;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +2208;0x08a0;STORE_INIT_EMPTY;INFO;;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +2209;0x08a1;STORE_CONTENT_CORRUPTED;LOW;;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +2210;0x08a2;STORE_INITIALIZE;INFO;;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +2211;0x08a3;INIT_DONE;INFO;;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +2212;0x08a4;DUMP_FINISHED;INFO;;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +2213;0x08a5;DELETION_FINISHED;INFO;;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +2214;0x08a6;DELETION_FAILED;LOW;;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +2215;0x08a7;AUTO_CATALOGS_SENDING_FAILED;INFO;;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +2600;0x0a28;GET_DATA_FAILED;LOW;;fsfw/src/fsfw/storagemanager/StorageManagerIF.h +2601;0x0a29;STORE_DATA_FAILED;LOW;;fsfw/src/fsfw/storagemanager/StorageManagerIF.h +2800;0x0af0;DEVICE_BUILDING_COMMAND_FAILED;LOW;;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +2801;0x0af1;DEVICE_SENDING_COMMAND_FAILED;LOW;;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +2802;0x0af2;DEVICE_REQUESTING_REPLY_FAILED;LOW;;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +2803;0x0af3;DEVICE_READING_REPLY_FAILED;LOW;;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +2804;0x0af4;DEVICE_INTERPRETING_REPLY_FAILED;LOW;;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +2805;0x0af5;DEVICE_MISSED_REPLY;LOW;;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +2806;0x0af6;DEVICE_UNKNOWN_REPLY;LOW;;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +2807;0x0af7;DEVICE_UNREQUESTED_REPLY;LOW;;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +2808;0x0af8;INVALID_DEVICE_COMMAND;LOW;Indicates a SW bug in child class.;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +2809;0x0af9;MONITORING_LIMIT_EXCEEDED;LOW;;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +2810;0x0afa;MONITORING_AMBIGUOUS;HIGH;;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +2811;0x0afb;DEVICE_WANTS_HARD_REBOOT;HIGH;;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +4201;0x1069;FUSE_CURRENT_HIGH;LOW;;fsfw/src/fsfw/power/Fuse.h +4202;0x106a;FUSE_WENT_OFF;LOW;;fsfw/src/fsfw/power/Fuse.h +4204;0x106c;POWER_ABOVE_HIGH_LIMIT;LOW;;fsfw/src/fsfw/power/Fuse.h +4205;0x106d;POWER_BELOW_LOW_LIMIT;LOW;;fsfw/src/fsfw/power/Fuse.h +4300;0x10cc;SWITCH_WENT_OFF;LOW;;fsfw/src/fsfw/power/PowerSwitchIF.h +5000;0x1388;HEATER_ON;INFO;;fsfw/src/fsfw/thermal/Heater.h +5001;0x1389;HEATER_OFF;INFO;;fsfw/src/fsfw/thermal/Heater.h +5002;0x138a;HEATER_TIMEOUT;LOW;;fsfw/src/fsfw/thermal/Heater.h +5003;0x138b;HEATER_STAYED_ON;LOW;;fsfw/src/fsfw/thermal/Heater.h +5004;0x138c;HEATER_STAYED_OFF;LOW;;fsfw/src/fsfw/thermal/Heater.h +5200;0x1450;TEMP_SENSOR_HIGH;LOW;;fsfw/src/fsfw/thermal/AbstractTemperatureSensor.h +5201;0x1451;TEMP_SENSOR_LOW;LOW;;fsfw/src/fsfw/thermal/AbstractTemperatureSensor.h +5202;0x1452;TEMP_SENSOR_GRADIENT;LOW;;fsfw/src/fsfw/thermal/AbstractTemperatureSensor.h +5901;0x170d;COMPONENT_TEMP_LOW;LOW;;fsfw/src/fsfw/thermal/ThermalComponentIF.h +5902;0x170e;COMPONENT_TEMP_HIGH;LOW;;fsfw/src/fsfw/thermal/ThermalComponentIF.h +5903;0x170f;COMPONENT_TEMP_OOL_LOW;LOW;;fsfw/src/fsfw/thermal/ThermalComponentIF.h +5904;0x1710;COMPONENT_TEMP_OOL_HIGH;LOW;;fsfw/src/fsfw/thermal/ThermalComponentIF.h +5905;0x1711;TEMP_NOT_IN_OP_RANGE;LOW;;fsfw/src/fsfw/thermal/ThermalComponentIF.h +7101;0x1bbd;FDIR_CHANGED_STATE;INFO;;fsfw/src/fsfw/fdir/FailureIsolationBase.h +7102;0x1bbe;FDIR_STARTS_RECOVERY;MEDIUM;;fsfw/src/fsfw/fdir/FailureIsolationBase.h +7103;0x1bbf;FDIR_TURNS_OFF_DEVICE;MEDIUM;;fsfw/src/fsfw/fdir/FailureIsolationBase.h +7201;0x1c21;MONITOR_CHANGED_STATE;LOW;;fsfw/src/fsfw/monitoring/MonitoringIF.h +7202;0x1c22;VALUE_BELOW_LOW_LIMIT;LOW;;fsfw/src/fsfw/monitoring/MonitoringIF.h +7203;0x1c23;VALUE_ABOVE_HIGH_LIMIT;LOW;;fsfw/src/fsfw/monitoring/MonitoringIF.h +7204;0x1c24;VALUE_OUT_OF_RANGE;LOW;;fsfw/src/fsfw/monitoring/MonitoringIF.h +7400;0x1ce8;CHANGING_MODE;INFO;;fsfw/src/fsfw/modes/HasModesIF.h +7401;0x1ce9;MODE_INFO;INFO;;fsfw/src/fsfw/modes/HasModesIF.h +7402;0x1cea;FALLBACK_FAILED;HIGH;;fsfw/src/fsfw/modes/HasModesIF.h +7403;0x1ceb;MODE_TRANSITION_FAILED;LOW;;fsfw/src/fsfw/modes/HasModesIF.h +7404;0x1cec;CANT_KEEP_MODE;HIGH;;fsfw/src/fsfw/modes/HasModesIF.h +7405;0x1ced;OBJECT_IN_INVALID_MODE;LOW;;fsfw/src/fsfw/modes/HasModesIF.h +7406;0x1cee;FORCING_MODE;MEDIUM;;fsfw/src/fsfw/modes/HasModesIF.h +7407;0x1cef;MODE_CMD_REJECTED;LOW;;fsfw/src/fsfw/modes/HasModesIF.h +7506;0x1d52;HEALTH_INFO;INFO;;fsfw/src/fsfw/health/HasHealthIF.h +7507;0x1d53;CHILD_CHANGED_HEALTH;INFO;;fsfw/src/fsfw/health/HasHealthIF.h +7508;0x1d54;CHILD_PROBLEMS;LOW;;fsfw/src/fsfw/health/HasHealthIF.h +7509;0x1d55;OVERWRITING_HEALTH;LOW;;fsfw/src/fsfw/health/HasHealthIF.h +7510;0x1d56;TRYING_RECOVERY;MEDIUM;;fsfw/src/fsfw/health/HasHealthIF.h +7511;0x1d57;RECOVERY_STEP;MEDIUM;;fsfw/src/fsfw/health/HasHealthIF.h +7512;0x1d58;RECOVERY_DONE;MEDIUM;;fsfw/src/fsfw/health/HasHealthIF.h +7900;0x1edc;RF_AVAILABLE;INFO;A RF available signal was detected. P1: raw RFA state, P2: 0;fsfw/src/fsfw/datalinklayer/DataLinkLayer.h +7901;0x1edd;RF_LOST;INFO;A previously found RF available signal was lost. P1: raw RFA state, P2: 0;fsfw/src/fsfw/datalinklayer/DataLinkLayer.h +7902;0x1ede;BIT_LOCK;INFO;A Bit Lock signal. Was detected. P1: raw BLO state, P2: 0;fsfw/src/fsfw/datalinklayer/DataLinkLayer.h +7903;0x1edf;BIT_LOCK_LOST;INFO;A previously found Bit Lock signal was lost. P1: raw BLO state, P2: 0;fsfw/src/fsfw/datalinklayer/DataLinkLayer.h +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 +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 +10900;0x2a94;GPIO_PULL_HIGH_FAILED;LOW;;mission/devices/HeaterHandler.h +10901;0x2a95;GPIO_PULL_LOW_FAILED;LOW;;mission/devices/HeaterHandler.h +10902;0x2a96;SWITCH_ALREADY_ON;LOW;;mission/devices/HeaterHandler.h +10903;0x2a97;SWITCH_ALREADY_OFF;LOW;;mission/devices/HeaterHandler.h +10904;0x2a98;MAIN_SWITCH_TIMEOUT;LOW;;mission/devices/HeaterHandler.h +11000;0x2af8;MAIN_SWITCH_ON_TIMEOUT;LOW;;mission/devices/SolarArrayDeploymentHandler.h +11001;0x2af9;MAIN_SWITCH_OFF_TIMEOUT;LOW;;mission/devices/SolarArrayDeploymentHandler.h +11002;0x2afa;DEPLOYMENT_FAILED;HIGH;;mission/devices/SolarArrayDeploymentHandler.h +11003;0x2afb;DEPL_SA1_GPIO_SWTICH_ON_FAILED;HIGH;;mission/devices/SolarArrayDeploymentHandler.h +11004;0x2afc;DEPL_SA2_GPIO_SWTICH_ON_FAILED;HIGH;;mission/devices/SolarArrayDeploymentHandler.h +11101;0x2b5d;MEMORY_READ_RPT_CRC_FAILURE;LOW;;mission/devices/PlocMPSoCHandler.h +11102;0x2b5e;ACK_FAILURE;LOW;;mission/devices/PlocMPSoCHandler.h +11103;0x2b5f;EXE_FAILURE;LOW;;mission/devices/PlocMPSoCHandler.h +11104;0x2b60;CRC_FAILURE_EVENT;LOW;;mission/devices/PlocMPSoCHandler.h +11201;0x2bc1;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 +11202;0x2bc2;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 +11203;0x2bc3;SELF_TEST_ADC_FAILURE;LOW;Get self test result returns failure in measurement of current and temperature. 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 +11204;0x2bc4;SELF_TEST_PWM_FAILURE;LOW;Get self test result returns PWM failure which concerns the coil actuation. 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 +11205;0x2bc5;SELF_TEST_TC_FAILURE;LOW;Get self test result returns TC failure (system 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 +11206;0x2bc6;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 +11207;0x2bc7;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 +11208;0x2bc8;INVALID_ERROR_BYTE;LOW;Received invalid error byte. This indicates an error of the communication link between IMTQ and OBC.;mission/devices/IMTQHandler.h +11301;0x2c25;ERROR_STATE;HIGH;Reaction wheel signals an error state;mission/devices/RwHandler.h +11401;0x2c89;BOOTING_FIRMWARE_FAILED;LOW;Failed to boot firmware;linux/devices/startracker/StarTrackerHandler.h +11402;0x2c8a;BOOTING_BOOTLOADER_FAILED;LOW;Failed to boot star tracker into bootloader mode;linux/devices/startracker/StarTrackerHandler.h +11501;0x2ced;SUPV_MEMORY_READ_RPT_CRC_FAILURE;LOW;PLOC supervisor crc failure in telemetry packet;bsp_q7s/devices/PlocSupervisorHandler.h +11502;0x2cee;SUPV_ACK_FAILURE;LOW;PLOC supervisor received acknowledgment failure report;bsp_q7s/devices/PlocSupervisorHandler.h +11503;0x2cef;SUPV_EXE_FAILURE;LOW;PLOC received execution failure report;bsp_q7s/devices/PlocSupervisorHandler.h +11504;0x2cf0;SUPV_CRC_FAILURE_EVENT;LOW;PLOC supervisor reply has invalid crc;bsp_q7s/devices/PlocSupervisorHandler.h +11600;0x2d50;ALLOC_FAILURE;MEDIUM;;bsp_q7s/core/CoreController.h +11601;0x2d51;REBOOT_SW;MEDIUM; Software reboot occured. Can also be a systemd reboot. P1: Current Chip, P2: Current Copy;bsp_q7s/core/CoreController.h +11603;0x2d53;REBOOT_HW;MEDIUM;;bsp_q7s/core/CoreController.h +11700;0x2db4;UPDATE_FILE_NOT_EXISTS;LOW;;bsp_q7s/devices/PlocUpdater.h +11701;0x2db5;ACTION_COMMANDING_FAILED;LOW;Failed to send command to supervisor handler P1: Return value of CommandActionHelper::commandAction P2: Action ID of command to send;bsp_q7s/devices/PlocUpdater.h +11702;0x2db6;UPDATE_AVAILABLE_FAILED;LOW;Supervisor handler replied action message indicating a command execution failure of the update available command;bsp_q7s/devices/PlocUpdater.h +11703;0x2db7;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);bsp_q7s/devices/PlocUpdater.h +11704;0x2db8;UPDATE_VERIFY_FAILED;LOW;Supervisor failed to execute the update verify command.;bsp_q7s/devices/PlocUpdater.h +11705;0x2db9;UPDATE_FINISHED;INFO;MPSoC update successful completed;bsp_q7s/devices/PlocUpdater.h +11800;0x2e18;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;bsp_q7s/devices/PlocMemoryDumper.h +11801;0x2e19;MRAM_DUMP_FAILED;LOW;Received completion failure report form PLOC supervisor handler P1: MRAM start address of failing dump command;bsp_q7s/devices/PlocMemoryDumper.h +11802;0x2e1a;MRAM_DUMP_FINISHED;LOW;MRAM dump finished successfully;bsp_q7s/devices/PlocMemoryDumper.h +11901;0x2e7d;INVALID_TC_FRAME;HIGH;;linux/obc/PdecHandler.h +11902;0x2e7e;INVALID_FAR;HIGH;Read invalid FAR from PDEC after startup;linux/obc/PdecHandler.h +11903;0x2e7f;CARRIER_LOCK;INFO;Carrier lock detected;linux/obc/PdecHandler.h +11904;0x2e80;BIT_LOCK_PDEC;INFO;Bit lock detected (data valid);linux/obc/PdecHandler.h +12000;0x2ee0;IMAGE_UPLOAD_FAILED;LOW;Image upload failed;linux/devices/startracker/StrHelper.h +12001;0x2ee1;IMAGE_DOWNLOAD_FAILED;LOW;Image download failed;linux/devices/startracker/StrHelper.h +12002;0x2ee2;IMAGE_UPLOAD_SUCCESSFUL;LOW;Uploading image to star tracker was successfulop;linux/devices/startracker/StrHelper.h +12003;0x2ee3;IMAGE_DOWNLOAD_SUCCESSFUL;LOW;Image download was successful;linux/devices/startracker/StrHelper.h +12004;0x2ee4;FLASH_WRITE_SUCCESSFUL;LOW;Finished flash write procedure successfully;linux/devices/startracker/StrHelper.h +12005;0x2ee5;FLASH_READ_SUCCESSFUL;LOW;Finished flash read procedure successfully;linux/devices/startracker/StrHelper.h +12006;0x2ee6;FLASH_READ_FAILED;LOW;Flash read procedure failed;linux/devices/startracker/StrHelper.h +12007;0x2ee7;FIRMWARE_UPDATE_SUCCESSFUL;LOW;Firmware update was successful;linux/devices/startracker/StrHelper.h +12008;0x2ee8;FIRMWARE_UPDATE_FAILED;LOW;Firmware update failed;linux/devices/startracker/StrHelper.h +12009;0x2ee9;STR_HELPER_READING_REPLY_FAILED;LOW;Failed to read communication interface reply data P1: Return code of failed communication interface read call P1: Upload/download position for which the read call failed;linux/devices/startracker/StrHelper.h +12010;0x2eea;STR_HELPER_COM_ERROR;LOW;Unexpected stop of decoding sequence P1: Return code of failed communication interface read call P1: Upload/download position for which the read call failed;linux/devices/startracker/StrHelper.h +12011;0x2eeb;STR_HELPER_NO_REPLY;LOW;Star tracker did not send replies (maybe device is powered off) P1: Position of upload or download packet for which no reply was sent;linux/devices/startracker/StrHelper.h +12012;0x2eec;STR_HELPER_DEC_ERROR;LOW;Error during decoding of received reply occurred P1: Return value of decoding function P2: Position of upload/download packet, or address of flash write/read request;linux/devices/startracker/StrHelper.h +12013;0x2eed;POSITION_MISMATCH;LOW;Position mismatch P1: The expected position and thus the position for which the image upload/download failed;linux/devices/startracker/StrHelper.h +12014;0x2eee;STR_HELPER_FILE_NOT_EXISTS;LOW;Specified file does not exist P1: Internal state of str helper;linux/devices/startracker/StrHelper.h +12015;0x2eef;STR_HELPER_SENDING_PACKET_FAILED;LOW;;linux/devices/startracker/StrHelper.h +12016;0x2ef0;STR_HELPER_REQUESTING_MSG_FAILED;LOW;;linux/devices/startracker/StrHelper.h diff --git a/generators/bsp_q7s_objects.csv b/generators/bsp_q7s_objects.csv index 4930f7a0..a0c0a6dc 100644 --- a/generators/bsp_q7s_objects.csv +++ b/generators/bsp_q7s_objects.csv @@ -4,19 +4,18 @@ 0x43400001;THERMAL_CONTROLLER 0x44120006;MGM_0_LIS3_HANDLER 0x44120010;GYRO_0_ADIS_HANDLER -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;SUS_12 -0x44120044;SUS_13 +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 0x44120047;RW1 0x44120107;MGM_1_RM3100_HANDLER 0x44120111;GYRO_1_L3G_HANDLER @@ -27,40 +26,42 @@ 0x44120309;MGM_3_RM3100_HANDLER 0x44120313;GYRO_3_L3G_HANDLER 0x44120350;RW4 -0x44130001;START_TRACKER -0x44130045;GPS0_HANDLER -0x44130146;GPS1_HANDLER +0x44130001;STAR_TRACKER +0x44130045;GPS_CONTROLLER 0x44140014;IMTQ_HANDLER 0x442000A1;PCDU_HANDLER 0x44250000;P60DOCK_HANDLER 0x44250001;PDU1_HANDLER 0x44250002;PDU2_HANDLER 0x44250003;ACU_HANDLER +0x44260000;BPX_BATT_HANDLER +0x44300000;PLPCDU_HANDLER 0x443200A5;RAD_SENSOR 0x44330000;PLOC_UPDATER 0x44330001;PLOC_MEMORY_DUMPER +0x44330002;STR_HELPER 0x44330015;PLOC_MPSOC_HANDLER 0x44330016;PLOC_SUPERVISOR_HANDLER 0x444100A2;SOLAR_ARRAY_DEPL_HANDLER 0x444100A4;HEATER_HANDLER 0x44420004;TMP1075_HANDLER_1 0x44420005;TMP1075_HANDLER_2 -0x44420016;RTD_IC3 -0x44420017;RTD_IC4 -0x44420018;RTD_IC5 -0x44420019;RTD_IC6 -0x44420020;RTD_IC7 -0x44420021;RTD_IC8 -0x44420022;RTD_IC9 -0x44420023;RTD_IC10 -0x44420024;RTD_IC11 -0x44420025;RTD_IC12 -0x44420026;RTD_IC13 -0x44420027;RTD_IC14 -0x44420028;RTD_IC15 -0x44420029;RTD_IC16 -0x44420030;RTD_IC17 -0x44420031;RTD_IC18 +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 0x445300A3;SYRLINKS_HK_HANDLER 0x49000000;ARDUINO_COM_IF 0x49010005;GPIO_IF @@ -73,6 +74,10 @@ 0x50000300;TMTC_BRIDGE 0x50000400;TMTC_POLLING_TASK 0x50000500;FILE_SYSTEM_HANDLER +0x50000550;SDC_MANAGER +0x50000600;PTME +0x50000700;PDEC_HANDLER +0x50000800;CCSDS_HANDLER 0x51000500;PUS_SERVICE_6 0x53000000;FSFW_OBJECTS_START 0x53000001;PUS_SERVICE_1_VERIFICATION @@ -85,6 +90,7 @@ 0x53000020;PUS_SERVICE_20_PARAMETERS 0x53000200;PUS_SERVICE_200_MODE_MGMT 0x53000201;PUS_SERVICE_201_HEALTH +0x53001000;CFDP_PACKET_DISTRIBUTOR 0x53010000;HEALTH_TABLE 0x53010100;MODE_STORE 0x53030000;EVENT_MANAGER @@ -96,6 +102,7 @@ 0x53ffffff;FSFW_OBJECTS_END 0x54000010;SPI_TEST 0x54000020;UART_TEST +0x54000030;I2C_TEST 0x5400AFFE;DUMMY_HANDLER 0x5400CAFE;DUMMY_INTERFACE 0x54123456;LIBGPIOD_TEST diff --git a/generators/bsp_q7s_returnvalues.csv b/generators/bsp_q7s_returnvalues.csv index 2b87317d..447da5e9 100644 --- a/generators/bsp_q7s_returnvalues.csv +++ b/generators/bsp_q7s_returnvalues.csv @@ -1,461 +1,545 @@ 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 -0x5e00;GOMS_PacketTooLong;;0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/GomspaceDeviceHandler.h;GOM_SPACE_HANDLER -0x5e01;GOMS_InvalidTableId;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/GomspaceDeviceHandler.h;GOM_SPACE_HANDLER -0x5e02;GOMS_InvalidAddress;;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/GomspaceDeviceHandler.h;GOM_SPACE_HANDLER -0x5e03;GOMS_InvalidParamSize;;3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/GomspaceDeviceHandler.h;GOM_SPACE_HANDLER -0x5e04;GOMS_InvalidPayloadSize;;4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/GomspaceDeviceHandler.h;GOM_SPACE_HANDLER -0x5e05;GOMS_UnknownReplyId;;5;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/GomspaceDeviceHandler.h;GOM_SPACE_HANDLER -0x50a0;IMTQ_InvalidCommandCode;;0xA0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/IMTQHandler.h;IMTQ_HANDLER -0x50a1;IMTQ_ParameterMissing;;0xA1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/IMTQHandler.h;IMTQ_HANDLER -0x50a2;IMTQ_ParameterInvalid;;0xA2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/IMTQHandler.h;IMTQ_HANDLER -0x50a3;IMTQ_CcUnavailable;;0xA3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/IMTQHandler.h;IMTQ_HANDLER -0x50a4;IMTQ_InternalProcessingError;;0xA4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/IMTQHandler.h;IMTQ_HANDLER -0x50a5;IMTQ_RejectedWithoutReason;;0xA5;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/IMTQHandler.h;IMTQ_HANDLER -0x50a6;IMTQ_CmdErrUnknown;;0xA6;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/IMTQHandler.h;IMTQ_HANDLER -0x50a7;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;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/IMTQHandler.h;IMTQ_HANDLER -0x53a0;PLMP_CrcFailure;;0xA0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/PlocMPSoCHandler.h;PLOC_MPSOC_HANDLER -0x53a1;PLMP_ReceivedAckFailure;;0xA1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/PlocMPSoCHandler.h;PLOC_MPSOC_HANDLER -0x53a2;PLMP_ReceivedExeFailure;;0xA2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/PlocMPSoCHandler.h;PLOC_MPSOC_HANDLER -0x53a3;PLMP_InvalidApid;;0xA3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/PlocMPSoCHandler.h;PLOC_MPSOC_HANDLER -0x54a0;PLSV_CrcFailure;Space Packet received from PLOC supervisor has invalid CRC;0xA0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER -0x54a1;PLSV_ReceivedAckFailure;Received ACK failure reply from PLOC supervisor;0xA1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER -0x54a2;PLSV_ReceivedExeFailure;Received execution failure reply from PLOC supervisor;0xA2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER -0x54a3;PLSV_InvalidApid;Received space packet with invalid APID from PLOC supervisor;0xA3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER -0x54a4;PLSV_GetTimeFailure;Failed to read current system time;0xA4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER -0x54a5;PLSV_InvalidUartComIf;Invalid communication interface specified;0xA5;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER -0x54a6;PLSV_InvalidWatchdog;Received command with invalid watchdog parameter. Valid watchdogs are 0 for PS, 1 for PL and 2 for INT;0xA6;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER -0x54a7;PLSV_InvalidWatchdogTimeout;Received watchdog timeout config command with invalid timeout. Valid timeouts must be in the range between 1000 and 360000 ms.;0xA7;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER -0x54a8;PLSV_InvalidLatchupId;Received latchup config command with invalid latchup ID;0xA8;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER -0x54a9;PLSV_SweepPeriodTooSmall;Received set adc sweep period command with invalid sweep period. Must be larger than 21.;0xA9;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER -0x54aa;PLSV_InvalidTestParam;Receive auto EM test command with invalid test param. Valid params are 1 and 2.;0xAA;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER -0x54ab;PLSV_MramPacketParsingFailure;Returned when scanning for MRAM dump packets failed.;0xAB;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER -0x54ac;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);0xAC;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER -0x54ad;PLSV_NoMramPacket;Expect reception of an MRAM dump packet but received space packet with other apid.;0xAD;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER -0x57a0;PLUD_UpdaterBusy;Updater is already performing an update;0xA0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/PlocUpdater.h;PLOC_UPDATER -0x57a1;PLUD_NameTooLong;Received update command with invalid path string (too long).;0xA1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/PlocUpdater.h;PLOC_UPDATER -0x57a2;PLUD_SdNotMounted;Received command to initiate update but SD card with update image not mounted.;0xA2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/PlocUpdater.h;PLOC_UPDATER -0x57a3;PLUD_FileNotExists;Update file received with update command does not exist.;0xA3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/PlocUpdater.h;PLOC_UPDATER -0x51b0;RWHA_SpiWriteFailure;;0xB0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/RwHandler.h;RW_HANDLER -0x51b1;RWHA_SpiReadFailure;Used by the spi send function to tell a failing read call;0xB1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/RwHandler.h;RW_HANDLER -0x51b2;RWHA_MissingStartSign;Can be used by the HDLC decoding mechanism to inform about a missing start sign 0x7E;0xB2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/RwHandler.h;RW_HANDLER -0x51b3;RWHA_InvalidSubstitute;Can be used by the HDLC decoding mechanism to inform about an invalid substitution combination;0xB3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/RwHandler.h;RW_HANDLER -0x51b4;RWHA_MissingEndSign;HDLC decoding mechanism never receives the end sign 0x7E;0xB4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/RwHandler.h;RW_HANDLER -0x51b5;RWHA_NoReply;Reaction wheel only responds with empty frames.;0xB5;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/RwHandler.h;RW_HANDLER -0x51a0;RWHA_InvalidSpeed;Action Message with invalid speed was received. Valid speeds must be in the range of [-65000; 1000] or [1000; 65000];0xA0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/RwHandler.h;RW_HANDLER -0x51a1;RWHA_InvalidRampTime;Action Message with invalid ramp time was received.;0xA1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/RwHandler.h;RW_HANDLER -0x51a2;RWHA_SetSpeedCommandInvalidLength;Received set speed command has invalid length. Should be 6.;0xA2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/RwHandler.h;RW_HANDLER -0x51a3;RWHA_ExecutionFailed;Command execution failed;0xA3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/RwHandler.h;RW_HANDLER -0x51a4;RWHA_CrcError;Reaction wheel reply has invalid crc;0xA4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/RwHandler.h;RW_HANDLER -0x52b0;STRH_CrcFailure;Received reply with invalid CRC;0xB0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/StarTrackerHandler.h;STR_HANDLER -0x52a0;STRH_TmReplyError;Result code of tm reply indicates an error;0xA0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/StarTrackerHandler.h;STR_HANDLER -0x4fa0;SYRLINKS_CrcFailure;;0xA0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/SyrlinksHkHandler.h;SYRLINKS_HANDLER -0x4fa1;SYRLINKS_UartFraminOrParityErrorAck;;0xA1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/SyrlinksHkHandler.h;SYRLINKS_HANDLER -0x4fa2;SYRLINKS_BadCharacterAck;;0xA2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/SyrlinksHkHandler.h;SYRLINKS_HANDLER -0x4fa3;SYRLINKS_BadParameterValueAck;;0xA3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/SyrlinksHkHandler.h;SYRLINKS_HANDLER -0x4fa4;SYRLINKS_BadEndOfFrameAck;;0xA4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/SyrlinksHkHandler.h;SYRLINKS_HANDLER -0x4fa5;SYRLINKS_UnknownCommandIdAck;;0xA5;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/SyrlinksHkHandler.h;SYRLINKS_HANDLER -0x4fa6;SYRLINKS_BadCrcAck;;0xA6;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/SyrlinksHkHandler.h;SYRLINKS_HANDLER -0x4fa7;SYRLINKS_ReplyWrongSize;;0xA7;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/SyrlinksHkHandler.h;SYRLINKS_HANDLER -0x4fa8;SYRLINKS_MissingStartFrameCharacter;;0xA8;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/SyrlinksHkHandler.h;SYRLINKS_HANDLER -0x4401;HGIO_UnknownGpioId;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/hal/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h;HAL_GPIO -0x4402;HGIO_DriveGpioFailure;;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/hal/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h;HAL_GPIO -0x4403;HGIO_GpioTypeFailure;;3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/hal/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h;HAL_GPIO -0x4404;HGIO_GpioInvalidInstance;;4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/hal/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h;HAL_GPIO -0x4100;HSPI_HalTimeoutRetval;;0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/hal/src/fsfw_hal/stm32h7/spi/spiDefinitions.h;HAL_SPI -0x4101;HSPI_HalBusyRetval;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/hal/src/fsfw_hal/stm32h7/spi/spiDefinitions.h;HAL_SPI -0x4102;HSPI_HalErrorRetval;;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/hal/src/fsfw_hal/stm32h7/spi/spiDefinitions.h;HAL_SPI -0x4201;HURT_UartReadFailure;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/hal/src/fsfw_hal/linux/uart/UartComIF.h;HAL_UART -0x4202;HURT_UartReadSizeMissmatch;;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/hal/src/fsfw_hal/linux/uart/UartComIF.h;HAL_UART -0x4203;HURT_UartRxBufferTooSmall;;3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/hal/src/fsfw_hal/linux/uart/UartComIF.h;HAL_UART -0x3101;CF_ObjectHasNoFunctions;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/action/CommandsActionsIF.h;COMMANDS_ACTIONS_IF -0x3102;CF_AlreadyCommanding;;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/action/CommandsActionsIF.h;COMMANDS_ACTIONS_IF -0x3201;HF_IsBusy;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/action/HasActionsIF.h;HAS_ACTIONS_IF -0x3202;HF_InvalidParameters;;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/action/HasActionsIF.h;HAS_ACTIONS_IF -0x3203;HF_ExecutionFinished;;3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/action/HasActionsIF.h;HAS_ACTIONS_IF -0x3204;HF_InvalidActionId;;4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/action/HasActionsIF.h;HAS_ACTIONS_IF -0x1101;AL_Full;;0x01;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/container/ArrayList.h;ARRAY_LIST -0x1801;FF_Full;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/container/FIFOBase.h;FIFO_CLASS -0x1802;FF_Empty;;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/container/FIFOBase.h;FIFO_CLASS -0x1501;FM_KeyAlreadyExists;;0x01;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/container/FixedMap.h;FIXED_MAP -0x1502;FM_MapFull;;0x02;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/container/FixedMap.h;FIXED_MAP -0x1503;FM_KeyDoesNotExist;;0x03;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/container/FixedMap.h;FIXED_MAP -0x1601;FMM_MapFull;;0x01;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/container/FixedOrderedMultimap.h;FIXED_MULTIMAP -0x1602;FMM_KeyDoesNotExist;;0x02;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/container/FixedOrderedMultimap.h;FIXED_MULTIMAP -0x36a1;SGP4_InvalidEccentricity;;0xA1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/coordinates/Sgp4Propagator.h;SGP4PROPAGATOR_CLASS -0x36a2;SGP4_InvalidMeanMotion;;0xA2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/coordinates/Sgp4Propagator.h;SGP4PROPAGATOR_CLASS -0x36a3;SGP4_InvalidPerturbationElements;;0xA3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/coordinates/Sgp4Propagator.h;SGP4PROPAGATOR_CLASS -0x36a4;SGP4_InvalidSemiLatusRectum;;0xA4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/coordinates/Sgp4Propagator.h;SGP4PROPAGATOR_CLASS -0x36a5;SGP4_InvalidEpochElements;;0xA5;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/coordinates/Sgp4Propagator.h;SGP4PROPAGATOR_CLASS -0x36a6;SGP4_SatelliteHasDecayed;;0xA6;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/coordinates/Sgp4Propagator.h;SGP4PROPAGATOR_CLASS -0x36b1;SGP4_TleTooOld;;0xB1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/coordinates/Sgp4Propagator.h;SGP4PROPAGATOR_CLASS -0x36b2;SGP4_TleNotInitialized;;0xB2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/coordinates/Sgp4Propagator.h;SGP4PROPAGATOR_CLASS -0x2b01;CCS_BcIsSetVrCommand;;0x01;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2b02;CCS_BcIsUnlockCommand;;0x02;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2bb0;CCS_BcIllegalCommand;;0xB0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2bb1;CCS_BoardReadingNotFinished;;0xB1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2bf0;CCS_NsPositiveW;;0xF0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2bf1;CCS_NsNegativeW;;0xF1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2bf2;CCS_NsLockout;;0xF2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2bf3;CCS_FarmInLockout;;0xF3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2bf4;CCS_FarmInWait;;0xF4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2be0;CCS_WrongSymbol;;0xE0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2be1;CCS_DoubleStart;;0xE1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2be2;CCS_StartSymbolMissed;;0xE2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2be3;CCS_EndWithoutStart;;0xE3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2be4;CCS_TooLarge;;0xE4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2be5;CCS_TooShort;;0xE5;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2be6;CCS_WrongTfVersion;;0xE6;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2be7;CCS_WrongSpacecraftId;;0xE7;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2be8;CCS_NoValidFrameType;;0xE8;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2be9;CCS_CrcFailed;;0xE9;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2bea;CCS_VcNotFound;;0xEA;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2beb;CCS_ForwardingFailed;;0xEB;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2bec;CCS_ContentTooLarge;;0xEC;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2bed;CCS_ResidualData;;0xED;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2bee;CCS_DataCorrupted;;0xEE;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2bef;CCS_IllegalSegmentationFlag;;0xEF;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2bd0;CCS_IllegalFlagCombination;;0xD0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2bd1;CCS_ShorterThanHeader;;0xD1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2bd2;CCS_TooShortBlockedPacket;;0xD2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x2bd3;CCS_TooShortMapExtraction;;0xD3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h;CCSDS_HANDLER_IF -0x801;DPS_InvalidParameterDefinition;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datapool/DataSetIF.h;DATA_SET_CLASS -0x802;DPS_SetWasAlreadyRead;;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datapool/DataSetIF.h;DATA_SET_CLASS -0x803;DPS_CommitingWithoutReading;;3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datapool/DataSetIF.h;DATA_SET_CLASS -0x804;DPS_DataSetUninitialised;;4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datapool/DataSetIF.h;DATA_SET_CLASS -0x805;DPS_DataSetFull;;5;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datapool/DataSetIF.h;DATA_SET_CLASS -0x806;DPS_PoolVarNull;;6;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datapool/DataSetIF.h;DATA_SET_CLASS -0x3ba0;PVA_InvalidReadWriteMode;;0xA0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datapool/PoolVariableIF.h;POOL_VARIABLE_IF -0x3ba1;PVA_InvalidPoolEntry;;0xA1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datapool/PoolVariableIF.h;POOL_VARIABLE_IF -0x3c00;HKM_QueueOrDestinationInvalid;;0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h;HOUSEKEEPING_MANAGER -0x3c01;HKM_WrongHkPacketType;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h;HOUSEKEEPING_MANAGER -0x3c02;HKM_ReportingStatusUnchanged;;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h;HOUSEKEEPING_MANAGER -0x3c03;HKM_PeriodicHelperInvalid;;3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h;HOUSEKEEPING_MANAGER -0x3c04;HKM_PoolobjectNotFound;;4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h;HOUSEKEEPING_MANAGER -0x3c05;HKM_DatasetNotFound;;5;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h;HOUSEKEEPING_MANAGER -0x3a00;LPIF_PoolEntryNotFound;;0x00;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datapoollocal/localPoolDefinitions.h;LOCAL_POOL_OWNER_IF -0x3a01;LPIF_PoolEntryTypeConflict;;0x01;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datapoollocal/localPoolDefinitions.h;LOCAL_POOL_OWNER_IF -0x1201;AB_NeedSecondStep;;0x01;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/AssemblyBase.h;ASSEMBLY_BASE -0x1202;AB_NeedToReconfigure;;0x02;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/AssemblyBase.h;ASSEMBLY_BASE -0x1203;AB_ModeFallback;;0x03;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/AssemblyBase.h;ASSEMBLY_BASE -0x1204;AB_ChildNotCommandable;;0x04;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/AssemblyBase.h;ASSEMBLY_BASE -0x1205;AB_NeedToChangeHealth;;0x05;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/AssemblyBase.h;ASSEMBLY_BASE -0x12a1;AB_NotEnoughChildrenInCorrectState;;0xa1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/AssemblyBase.h;ASSEMBLY_BASE -0x3301;DC_NoReplyReceived;;0x01;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h;DEVICE_COMMUNICATION_IF -0x3302;DC_ProtocolError;;0x02;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h;DEVICE_COMMUNICATION_IF -0x3303;DC_Nullpointer;;0x03;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h;DEVICE_COMMUNICATION_IF -0x3304;DC_InvalidCookieType;;0x04;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h;DEVICE_COMMUNICATION_IF -0x3305;DC_NotActive;;0x05;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h;DEVICE_COMMUNICATION_IF -0x3306;DC_TooMuchData;;0x06;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h;DEVICE_COMMUNICATION_IF -0x3a0;DHB_InvalidChannel;;0xA0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h;DEVICE_HANDLER_BASE -0x3b0;DHB_AperiodicReply;;0xB0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h;DEVICE_HANDLER_BASE -0x3b1;DHB_IgnoreReplyData;;0xB1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h;DEVICE_HANDLER_BASE -0x3b2;DHB_IgnoreFullPacket;;0xB2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h;DEVICE_HANDLER_BASE -0x3c0;DHB_NothingToSend;;0xC0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h;DEVICE_HANDLER_BASE -0x3c2;DHB_CommandMapError;;0xC2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h;DEVICE_HANDLER_BASE -0x3d0;DHB_NoSwitch;;0xD0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h;DEVICE_HANDLER_BASE -0x3e0;DHB_ChildTimeout;;0xE0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h;DEVICE_HANDLER_BASE -0x3e1;DHB_SwitchFailed;;0xE1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h;DEVICE_HANDLER_BASE -0x26a0;DHI_NoCommandData;;0xA0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26a1;DHI_CommandNotSupported;;0xA1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26a2;DHI_CommandAlreadySent;;0xA2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26a3;DHI_CommandWasNotSent;;0xA3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26a4;DHI_CantSwitchAddress;;0xA4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26a5;DHI_WrongModeForCommand;;0xA5;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26a6;DHI_Timeout;;0xA6;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26a7;DHI_Busy;;0xA7;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26a8;DHI_NoReplyExpected;;0xA8;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26a9;DHI_NonOpTemperature;;0xA9;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26aa;DHI_CommandNotImplemented;;0xAA;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26b0;DHI_ChecksumError;;0xB0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26b1;DHI_LengthMissmatch;;0xB1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26b2;DHI_InvalidData;;0xB2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26b3;DHI_ProtocolError;;0xB3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26c0;DHI_DeviceDidNotExecute;;0xC0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26c1;DHI_DeviceReportedError;;0xC1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26c2;DHI_UnknownDeviceReply;;0xC2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26c3;DHI_DeviceReplyInvalid;;0xC3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26d0;DHI_InvalidCommandParameter;;0xD0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x26d1;DHI_InvalidNumberOrLengthOfParameters;;0xD1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h;DEVICE_HANDLER_IF -0x2401;EV_ListenerNotFound;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/events/EventManagerIF.h;EVENT_MANAGER_IF -0x2500;FDI_YourFault;;0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h;HANDLES_FAILURES_IF -0x2501;FDI_MyFault;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h;HANDLES_FAILURES_IF -0x2502;FDI_ConfirmLater;;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h;HANDLES_FAILURES_IF -0x2301;MT_TooDetailedRequest;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/globalfunctions/matching/MatchTree.h;MATCH_TREE_CLASS -0x2302;MT_TooGeneralRequest;;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/globalfunctions/matching/MatchTree.h;MATCH_TREE_CLASS -0x2303;MT_NoMatch;;3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/globalfunctions/matching/MatchTree.h;MATCH_TREE_CLASS -0x2304;MT_Full;;4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/globalfunctions/matching/MatchTree.h;MATCH_TREE_CLASS -0x2305;MT_NewNodeCreated;;5;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/globalfunctions/matching/MatchTree.h;MATCH_TREE_CLASS -0x2e01;ASC_TooLongForTargetType;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/globalfunctions/AsciiConverter.h;ASCII_CONVERTER -0x2e02;ASC_InvalidCharacters;;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/globalfunctions/AsciiConverter.h;ASCII_CONVERTER -0x2e03;ASC_BufferTooSmall;;0x3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/globalfunctions/AsciiConverter.h;ASCII_CONVERTER -0x3d01;DLEE_StreamTooShort;;0x01;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/globalfunctions/DleEncoder.h;DLE_ENCODER -0x3d02;DLEE_DecodingError;;0x02;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/globalfunctions/DleEncoder.h;DLE_ENCODER -0x1701;HHI_ObjectNotHealthy;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/health/HasHealthIF.h;HAS_HEALTH_IF -0x1702;HHI_InvalidHealthState;;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/health/HasHealthIF.h;HAS_HEALTH_IF -0xf01;CM_UnknownCommand;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/ipc/CommandMessageIF.h;COMMAND_MESSAGE -0x3801;MQI_Empty;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/ipc/MessageQueueIF.h;MESSAGE_QUEUE_IF -0x3802;MQI_Full;No space left for more messages;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/ipc/MessageQueueIF.h;MESSAGE_QUEUE_IF -0x3803;MQI_NoReplyPartner;Returned if a reply method was called without partner;3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/ipc/MessageQueueIF.h;MESSAGE_QUEUE_IF -0x3804;MQI_DestinationInvalid;Returned if the target destination is invalid.;4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/ipc/MessageQueueIF.h;MESSAGE_QUEUE_IF -0x3701;MUX_NotEnoughResources;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/ipc/MutexIF.h;MUTEX_IF -0x3702;MUX_InsufficientMemory;;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/ipc/MutexIF.h;MUTEX_IF -0x3703;MUX_NoPrivilege;;3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/ipc/MutexIF.h;MUTEX_IF -0x3704;MUX_WrongAttributeSetting;;4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/ipc/MutexIF.h;MUTEX_IF -0x3705;MUX_MutexAlreadyLocked;;5;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/ipc/MutexIF.h;MUTEX_IF -0x3706;MUX_MutexNotFound;;6;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/ipc/MutexIF.h;MUTEX_IF -0x3707;MUX_MutexMaxLocks;;7;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/ipc/MutexIF.h;MUTEX_IF -0x3708;MUX_CurrThreadAlreadyOwnsMutex;;8;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/ipc/MutexIF.h;MUTEX_IF -0x3709;MUX_CurrThreadDoesNotOwnMutex;;9;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/ipc/MutexIF.h;MUTEX_IF -0x370a;MUX_MutexTimeout;;10;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/ipc/MutexIF.h;MUTEX_IF -0x370b;MUX_MutexInvalidId;;11;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/ipc/MutexIF.h;MUTEX_IF -0x370c;MUX_MutexDestroyedWhileWaiting;;12;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/ipc/MutexIF.h;MUTEX_IF -0x4000;FILS_GenericFileError;;0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/memory/HasFileSystemIF.h;FILE_SYSTEM -0x4001;FILS_IsBusy;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/memory/HasFileSystemIF.h;FILE_SYSTEM -0x4002;FILS_InvalidParameters;;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/memory/HasFileSystemIF.h;FILE_SYSTEM -0x4005;FILS_FileDoesNotExist;;5;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/memory/HasFileSystemIF.h;FILE_SYSTEM -0x4006;FILS_FileAlreadyExists;;6;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/memory/HasFileSystemIF.h;FILE_SYSTEM -0x4007;FILS_FileLocked;;7;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/memory/HasFileSystemIF.h;FILE_SYSTEM -0x400a;FILS_DirectoryDoesNotExist;;10;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/memory/HasFileSystemIF.h;FILE_SYSTEM -0x400b;FILS_DirectoryAlreadyExists;;11;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/memory/HasFileSystemIF.h;FILE_SYSTEM -0x400c;FILS_DirectoryNotEmpty;;12;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/memory/HasFileSystemIF.h;FILE_SYSTEM -0x400f;FILS_SequencePacketMissingWrite;;15;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/memory/HasFileSystemIF.h;FILE_SYSTEM -0x4010;FILS_SequencePacketMissingRead;;16;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/memory/HasFileSystemIF.h;FILE_SYSTEM -0x601;PP_DoItMyself;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/memory/HasMemoryIF.h;HAS_MEMORY_IF -0x602;PP_PointsToVariable;;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/memory/HasMemoryIF.h;HAS_MEMORY_IF -0x603;PP_PointsToMemory;;3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/memory/HasMemoryIF.h;HAS_MEMORY_IF -0x604;PP_ActivityCompleted;;4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/memory/HasMemoryIF.h;HAS_MEMORY_IF -0x605;PP_PointsToVectorUint8;;5;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/memory/HasMemoryIF.h;HAS_MEMORY_IF -0x606;PP_PointsToVectorUint16;;6;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/memory/HasMemoryIF.h;HAS_MEMORY_IF -0x607;PP_PointsToVectorUint32;;7;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/memory/HasMemoryIF.h;HAS_MEMORY_IF -0x608;PP_PointsToVectorFloat;;8;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/memory/HasMemoryIF.h;HAS_MEMORY_IF -0x6a0;PP_DumpNotSupported;;0xA0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/memory/HasMemoryIF.h;HAS_MEMORY_IF -0x6e0;PP_InvalidSize;;0xE0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/memory/HasMemoryIF.h;HAS_MEMORY_IF -0x6e1;PP_InvalidAddress;;0xE1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/memory/HasMemoryIF.h;HAS_MEMORY_IF -0x6e2;PP_InvalidContent;;0xE2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/memory/HasMemoryIF.h;HAS_MEMORY_IF -0x6e3;PP_UnalignedAccess;;0xE3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/memory/HasMemoryIF.h;HAS_MEMORY_IF -0x6e4;PP_WriteProtected;;0xE4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/memory/HasMemoryIF.h;HAS_MEMORY_IF -0x13e0;MH_UnknownCmd;;0xE0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/memory/MemoryHelper.h;MEMORY_HELPER -0x13e1;MH_InvalidAddress;;0xE1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/memory/MemoryHelper.h;MEMORY_HELPER -0x13e2;MH_InvalidSize;;0xE2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/memory/MemoryHelper.h;MEMORY_HELPER -0x13e3;MH_StateMismatch;;0xE3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/memory/MemoryHelper.h;MEMORY_HELPER -0xe01;HM_InvalidMode;;0x01;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/modes/HasModesIF.h;HAS_MODES_IF -0xe02;HM_TransNotAllowed;;0x02;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/modes/HasModesIF.h;HAS_MODES_IF -0xe03;HM_InTransition;;0x03;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/modes/HasModesIF.h;HAS_MODES_IF -0xe04;HM_InvalidSubmode;;0x04;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/modes/HasModesIF.h;HAS_MODES_IF -0x3001;LIM_Unchecked;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/monitoring/MonitoringIF.h;LIMITS_IF -0x3002;LIM_Invalid;;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/monitoring/MonitoringIF.h;LIMITS_IF -0x3003;LIM_Unselected;;3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/monitoring/MonitoringIF.h;LIMITS_IF -0x3004;LIM_BelowLowLimit;;4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/monitoring/MonitoringIF.h;LIMITS_IF -0x3005;LIM_AboveHighLimit;;5;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/monitoring/MonitoringIF.h;LIMITS_IF -0x3006;LIM_UnexpectedValue;;6;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/monitoring/MonitoringIF.h;LIMITS_IF -0x3007;LIM_OutOfRange;;7;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/monitoring/MonitoringIF.h;LIMITS_IF -0x30a0;LIM_FirstSample;;0xA0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/monitoring/MonitoringIF.h;LIMITS_IF -0x30e0;LIM_InvalidSize;;0xE0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/monitoring/MonitoringIF.h;LIMITS_IF -0x30e1;LIM_WrongType;;0xE1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/monitoring/MonitoringIF.h;LIMITS_IF -0x30e2;LIM_WrongPid;;0xE2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/monitoring/MonitoringIF.h;LIMITS_IF -0x30e3;LIM_WrongLimitId;;0xE3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/monitoring/MonitoringIF.h;LIMITS_IF -0x30ee;LIM_MonitorNotFound;;0xEE;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/monitoring/MonitoringIF.h;LIMITS_IF -0x1a01;TRC_NotEnoughSensors;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/monitoring/TriplexMonitor.h;TRIPLE_REDUNDACY_CHECK -0x1a02;TRC_LowestValueOol;;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/monitoring/TriplexMonitor.h;TRIPLE_REDUNDACY_CHECK -0x1a03;TRC_HighestValueOol;;3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/monitoring/TriplexMonitor.h;TRIPLE_REDUNDACY_CHECK -0x1a04;TRC_BothValuesOol;;4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/monitoring/TriplexMonitor.h;TRIPLE_REDUNDACY_CHECK -0x1a05;TRC_DuplexOol;;5;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/monitoring/TriplexMonitor.h;TRIPLE_REDUNDACY_CHECK -0x201;OM_InsertionFailed;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/objectmanager/ObjectManagerIF.h;OBJECT_MANAGER_IF -0x202;OM_NotFound;;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/objectmanager/ObjectManagerIF.h;OBJECT_MANAGER_IF -0x203;OM_ChildInitFailed;;3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/objectmanager/ObjectManagerIF.h;OBJECT_MANAGER_IF -0x204;OM_InternalErrReporterUninit;;4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/objectmanager/ObjectManagerIF.h;OBJECT_MANAGER_IF -0x2901;IEC_NoConfigurationTable;;0x01;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x2902;IEC_NoCpuTable;;0x02;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x2903;IEC_InvalidWorkspaceAddress;;0x03;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x2904;IEC_TooLittleWorkspace;;0x04;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x2905;IEC_WorkspaceAllocation;;0x05;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x2906;IEC_InterruptStackTooSmall;;0x06;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x2907;IEC_ThreadExitted;;0x07;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x2908;IEC_InconsistentMpInformation;;0x08;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x2909;IEC_InvalidNode;;0x09;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x290a;IEC_NoMpci;;0x0a;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x290b;IEC_BadPacket;;0x0b;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x290c;IEC_OutOfPackets;;0x0c;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x290d;IEC_OutOfGlobalObjects;;0x0d;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x290e;IEC_OutOfProxies;;0x0e;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x290f;IEC_InvalidGlobalId;;0x0f;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x2910;IEC_BadStackHook;;0x10;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x2911;IEC_BadAttributes;;0x11;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x2912;IEC_ImplementationKeyCreateInconsistency;;0x12;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x2913;IEC_ImplementationBlockingOperationCancel;;0x13;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x2914;IEC_MutexObtainFromBadState;;0x14;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x2915;IEC_UnlimitedAndMaximumIs0;;0x15;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/osal/InternalErrorCodes.h;INTERNAL_ERROR_CODES -0x2d01;HPA_InvalidIdentifierId;;0x01;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/parameters/HasParametersIF.h;HAS_PARAMETERS_IF -0x2d02;HPA_InvalidDomainId;;0x02;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/parameters/HasParametersIF.h;HAS_PARAMETERS_IF -0x2d03;HPA_InvalidValue;;0x03;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/parameters/HasParametersIF.h;HAS_PARAMETERS_IF -0x2d05;HPA_ReadOnly;;0x05;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/parameters/HasParametersIF.h;HAS_PARAMETERS_IF -0x2c01;PAW_UnknownDatatype;;0x01;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/parameters/ParameterWrapper.h;PARAMETER_WRAPPER -0x2c02;PAW_DatatypeMissmatch;;0x02;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/parameters/ParameterWrapper.h;PARAMETER_WRAPPER -0x2c03;PAW_Readonly;;0x03;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/parameters/ParameterWrapper.h;PARAMETER_WRAPPER -0x2c04;PAW_TooBig;;0x04;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/parameters/ParameterWrapper.h;PARAMETER_WRAPPER -0x2c05;PAW_SourceNotSet;;0x05;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/parameters/ParameterWrapper.h;PARAMETER_WRAPPER -0x2c06;PAW_OutOfBounds;;0x06;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/parameters/ParameterWrapper.h;PARAMETER_WRAPPER -0x2c07;PAW_NotSet;;0x07;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/parameters/ParameterWrapper.h;PARAMETER_WRAPPER -0x2c08;PAW_ColumnOrRowsZero;;0x08;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/parameters/ParameterWrapper.h;PARAMETER_WRAPPER -0x2f01;POS_InPowerTransition;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/power/PowerSwitcher.h;POWER_SWITCHER -0x2f02;POS_SwitchStateMismatch;;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/power/PowerSwitcher.h;POWER_SWITCHER -0x501;PS_SwitchOn;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/power/PowerSwitchIF.h;POWER_SWITCH_IF -0x500;PS_SwitchOff;;0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/power/PowerSwitchIF.h;POWER_SWITCH_IF -0x502;PS_SwitchTimeout;;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/power/PowerSwitchIF.h;POWER_SWITCH_IF -0x503;PS_FuseOn;;3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/power/PowerSwitchIF.h;POWER_SWITCH_IF -0x504;PS_FuseOff;;4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/power/PowerSwitchIF.h;POWER_SWITCH_IF -0x4e1;RMP_CommandNoDescriptorsAvailable;;0xE1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4e2;RMP_CommandBufferFull;;0xE2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4e3;RMP_CommandChannelOutOfRange;;0xE3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4e6;RMP_CommandChannelDeactivated;;0xE6;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4e7;RMP_CommandPortOutOfRange;;0xE7;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4e8;RMP_CommandPortInUse;;0xE8;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4e9;RMP_CommandNoChannel;;0xE9;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4ea;RMP_NoHwCrc;;0xEA;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4d0;RMP_ReplyNoReply;;0xD0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4d1;RMP_ReplyNotSent;;0xD1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4d2;RMP_ReplyNotYetSent;;0xD2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4d3;RMP_ReplyMissmatch;;0xD3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4d4;RMP_ReplyTimeout;;0xD4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4c0;RMP_ReplyInterfaceBusy;;0xC0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4c1;RMP_ReplyTransmissionError;;0xC1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4c2;RMP_ReplyInvalidData;;0xC2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4c3;RMP_ReplyNotSupported;;0xC3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4f0;RMP_LinkDown;;0xF0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4f1;RMP_SpwCredit;;0xF1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4f2;RMP_SpwEscape;;0xF2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4f3;RMP_SpwDisconnect;;0xF3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4f4;RMP_SpwParity;;0xF4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4f5;RMP_SpwWriteSync;;0xF5;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4f6;RMP_SpwInvalidAddress;;0xF6;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4f7;RMP_SpwEarlyEop;;0xF7;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4f8;RMP_SpwDma;;0xF8;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x4f9;RMP_SpwLinkError;;0xF9;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x400;RMP_ReplyOk;;0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x401;RMP_ReplyGeneralErrorCode;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x402;RMP_ReplyUnusedPacketTypeOrCommandCode;;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x403;RMP_ReplyInvalidKey;;3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x404;RMP_ReplyInvalidDataCrc;;4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x405;RMP_ReplyEarlyEop;;5;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x406;RMP_ReplyTooMuchData;;6;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x407;RMP_ReplyEep;;7;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x408;RMP_ReplyReserved;;8;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x409;RMP_ReplyVerifyBufferOverrun;;9;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x40a;RMP_ReplyCommandNotImplementedOrNotAuthorised;;10;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x40b;RMP_ReplyRmwDataLengthError;;11;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x40c;RMP_ReplyInvalidTargetLogicalAddress;;12;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/rmap/RMAP.h;RMAP_CHANNEL -0x1401;SE_BufferTooShort;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/serialize/SerializeIF.h;SERIALIZE_IF -0x1402;SE_StreamTooShort;;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/serialize/SerializeIF.h;SERIALIZE_IF -0x1403;SE_TooManyElements;;3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/serialize/SerializeIF.h;SERIALIZE_IF -0x2701;SM_DataTooLarge;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/storagemanager/StorageManagerIF.h;STORAGE_MANAGER_IF -0x2702;SM_DataStorageFull;;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/storagemanager/StorageManagerIF.h;STORAGE_MANAGER_IF -0x2703;SM_IllegalStorageId;;3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/storagemanager/StorageManagerIF.h;STORAGE_MANAGER_IF -0x2704;SM_DataDoesNotExist;;4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/storagemanager/StorageManagerIF.h;STORAGE_MANAGER_IF -0x2705;SM_IllegalAddress;;5;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/storagemanager/StorageManagerIF.h;STORAGE_MANAGER_IF -0x2706;SM_PoolTooLarge;;6;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/storagemanager/StorageManagerIF.h;STORAGE_MANAGER_IF -0xc02;MS_InvalidEntry;;0x02;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h;MODE_STORE_IF -0xc03;MS_TooManyElements;;0x03;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h;MODE_STORE_IF -0xc04;MS_CantStoreEmpty;;0x04;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h;MODE_STORE_IF -0xd01;SS_SequenceAlreadyExists;;0x01;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/subsystem/Subsystem.h;SUBSYSTEM -0xd02;SS_TableAlreadyExists;;0x02;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/subsystem/Subsystem.h;SUBSYSTEM -0xd03;SS_TableDoesNotExist;;0x03;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/subsystem/Subsystem.h;SUBSYSTEM -0xd04;SS_TableOrSequenceLengthInvalid;;0x04;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/subsystem/Subsystem.h;SUBSYSTEM -0xd05;SS_SequenceDoesNotExist;;0x05;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/subsystem/Subsystem.h;SUBSYSTEM -0xd06;SS_TableContainsInvalidObjectId;;0x06;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/subsystem/Subsystem.h;SUBSYSTEM -0xd07;SS_FallbackSequenceDoesNotExist;;0x07;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/subsystem/Subsystem.h;SUBSYSTEM -0xd08;SS_NoTargetTable;;0x08;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/subsystem/Subsystem.h;SUBSYSTEM -0xd09;SS_SequenceOrTableTooLong;;0x09;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/subsystem/Subsystem.h;SUBSYSTEM -0xd0b;SS_IsFallbackSequence;;0x0B;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/subsystem/Subsystem.h;SUBSYSTEM -0xd0c;SS_AccessDenied;;0x0C;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/subsystem/Subsystem.h;SUBSYSTEM -0xd0e;SS_TableInUse;;0x0E;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/subsystem/Subsystem.h;SUBSYSTEM -0xda1;SS_TargetTableNotReached;;0xA1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/subsystem/Subsystem.h;SUBSYSTEM -0xda2;SS_TableCheckFailed;;0xA2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/subsystem/Subsystem.h;SUBSYSTEM -0xb01;SB_ChildNotFound;;0x01;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/subsystem/SubsystemBase.h;SUBSYSTEM_BASE -0xb02;SB_ChildInfoUpdated;;0x02;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/subsystem/SubsystemBase.h;SUBSYSTEM_BASE -0xb03;SB_ChildDoesntHaveModes;;0x03;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/subsystem/SubsystemBase.h;SUBSYSTEM_BASE -0xb04;SB_CouldNotInsertChild;;0x04;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/subsystem/SubsystemBase.h;SUBSYSTEM_BASE -0xb05;SB_TableContainsInvalidObjectId;;0x05;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/subsystem/SubsystemBase.h;SUBSYSTEM_BASE -0x3901;SPH_SemaphoreTimeout;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tasks/SemaphoreIF.h;SEMAPHORE_IF -0x3902;SPH_SemaphoreNotOwned;;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tasks/SemaphoreIF.h;SEMAPHORE_IF -0x3903;SPH_SemaphoreInvalid;;3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tasks/SemaphoreIF.h;SEMAPHORE_IF -0x1c01;TCD_PacketLost;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tcdistribution/TcDistributor.h;PACKET_DISTRIBUTION -0x1c02;TCD_DestinationNotFound;;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tcdistribution/TcDistributor.h;PACKET_DISTRIBUTION -0x1c03;TCD_ServiceIdAlreadyExists;;3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tcdistribution/TcDistributor.h;PACKET_DISTRIBUTION -0x1b00;TCC_IllegalApid;;0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tcdistribution/TcPacketCheck.h;TC_PACKET_CHECK -0x1b01;TCC_IncompletePacket;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tcdistribution/TcPacketCheck.h;TC_PACKET_CHECK -0x1b02;TCC_IncorrectChecksum;;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tcdistribution/TcPacketCheck.h;TC_PACKET_CHECK -0x1b03;TCC_IllegalPacketType;;3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tcdistribution/TcPacketCheck.h;TC_PACKET_CHECK -0x1b04;TCC_IllegalPacketSubtype;;4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tcdistribution/TcPacketCheck.h;TC_PACKET_CHECK -0x1b05;TCC_IncorrectPrimaryHeader;;5;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tcdistribution/TcPacketCheck.h;TC_PACKET_CHECK -0x1b06;TCC_IncorrectSecondaryHeader;;6;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tcdistribution/TcPacketCheck.h;TC_PACKET_CHECK -0x2801;TC_InvalidTargetState;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/thermal/ThermalComponentIF.h;THERMAL_COMPONENT_IF -0x28f1;TC_AboveOperationalLimit;;0xF1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/thermal/ThermalComponentIF.h;THERMAL_COMPONENT_IF -0x28f2;TC_BelowOperationalLimit;;0xF2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/thermal/ThermalComponentIF.h;THERMAL_COMPONENT_IF -0x1000;TIM_UnsupportedTimeFormat;;0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/timemanager/CCSDSTime.h;CCSDS_TIME_HELPER_CLASS -0x1001;TIM_NotEnoughInformationForTargetFormat;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/timemanager/CCSDSTime.h;CCSDS_TIME_HELPER_CLASS -0x1002;TIM_LengthMismatch;;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/timemanager/CCSDSTime.h;CCSDS_TIME_HELPER_CLASS -0x1003;TIM_InvalidTimeFormat;;3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/timemanager/CCSDSTime.h;CCSDS_TIME_HELPER_CLASS -0x1004;TIM_InvalidDayOfYear;;4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/timemanager/CCSDSTime.h;CCSDS_TIME_HELPER_CLASS -0x1005;TIM_TimeDoesNotFitFormat;;5;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/timemanager/CCSDSTime.h;CCSDS_TIME_HELPER_CLASS -0x3501;TSI_BadTimestamp;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/timemanager/TimeStamperIF.h;TIME_STAMPER_IF -0x2001;TMB_Busy;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h;TM_STORE_BACKEND_IF -0x2002;TMB_Full;;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h;TM_STORE_BACKEND_IF -0x2003;TMB_Empty;;3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h;TM_STORE_BACKEND_IF -0x2004;TMB_NullRequested;;4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h;TM_STORE_BACKEND_IF -0x2005;TMB_TooLarge;;5;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h;TM_STORE_BACKEND_IF -0x2006;TMB_NotReady;;6;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h;TM_STORE_BACKEND_IF -0x2007;TMB_DumpError;;7;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h;TM_STORE_BACKEND_IF -0x2008;TMB_CrcError;;8;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h;TM_STORE_BACKEND_IF -0x2009;TMB_Timeout;;9;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h;TM_STORE_BACKEND_IF -0x200a;TMB_IdlePacketFound;;10;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h;TM_STORE_BACKEND_IF -0x200b;TMB_TelecommandFound;;11;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h;TM_STORE_BACKEND_IF -0x200c;TMB_NoPusATm;;12;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h;TM_STORE_BACKEND_IF -0x200d;TMB_TooSmall;;13;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h;TM_STORE_BACKEND_IF -0x200e;TMB_BlockNotFound;;14;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h;TM_STORE_BACKEND_IF -0x200f;TMB_InvalidRequest;;15;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h;TM_STORE_BACKEND_IF -0x2101;TMF_Busy;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h;TM_STORE_FRONTEND_IF -0x2102;TMF_LastPacketFound;;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h;TM_STORE_FRONTEND_IF -0x2103;TMF_StopFetch;;3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h;TM_STORE_FRONTEND_IF -0x2104;TMF_Timeout;;4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h;TM_STORE_FRONTEND_IF -0x2105;TMF_TmChannelFull;;5;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h;TM_STORE_FRONTEND_IF -0x2106;TMF_NotStored;;6;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h;TM_STORE_FRONTEND_IF -0x2107;TMF_AllDeleted;;7;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h;TM_STORE_FRONTEND_IF -0x2108;TMF_InvalidData;;8;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h;TM_STORE_FRONTEND_IF -0x2109;TMF_NotReady;;9;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h;TM_STORE_FRONTEND_IF -0x1d01;PUS_ActivityStarted;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h;ACCEPTS_TELECOMMANDS_IF -0x1d02;PUS_InvalidSubservice;;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h;ACCEPTS_TELECOMMANDS_IF -0x1d03;PUS_IllegalApplicationData;;3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h;ACCEPTS_TELECOMMANDS_IF -0x1d04;PUS_SendTmFailed;;4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h;ACCEPTS_TELECOMMANDS_IF -0x1d05;PUS_Timeout;;5;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h;ACCEPTS_TELECOMMANDS_IF -0x1f01;CSB_ExecutionComplete;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h;COMMAND_SERVICE_BASE -0x1f02;CSB_NoStepMessage;;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h;COMMAND_SERVICE_BASE -0x1f03;CSB_ObjectBusy;;3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h;COMMAND_SERVICE_BASE -0x1f04;CSB_Busy;;4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h;COMMAND_SERVICE_BASE -0x1f05;CSB_InvalidTc;;5;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h;COMMAND_SERVICE_BASE -0x1f06;CSB_InvalidObject;;6;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h;COMMAND_SERVICE_BASE -0x1f07;CSB_InvalidReply;;7;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h;COMMAND_SERVICE_BASE -0x6100;SCBU_KeyNotFound;;0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/memory/scratchApi.h;SCRATCH_BUFFER -0x6000;SDMA_AlreadyOn;;0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/memory/SdCardManager.h;SD_CARD_MANAGER -0x6001;SDMA_UnknownGpioId;;1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/linux/archive/gpio/LinuxLibgpioIF.h;SD_CARD_MANAGER -0x6002;SDMA_DriveGpioFailure;;2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/linux/archive/gpio/LinuxLibgpioIF.h;SD_CARD_MANAGER -0x600a;SDMA_StatusFileNexists;;10;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/memory/SdCardManager.h;SD_CARD_MANAGER -0x600b;SDMA_StatusFileFormatInvalid;;11;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/memory/SdCardManager.h;SD_CARD_MANAGER -0x600c;SDMA_MountError;;12;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/memory/SdCardManager.h;SD_CARD_MANAGER -0x600d;SDMA_UnmountError;;13;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/memory/SdCardManager.h;SD_CARD_MANAGER -0x600e;SDMA_SystemCallError;;14;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/memory/SdCardManager.h;SD_CARD_MANAGER -0x6003;SDMA_GpioTypeFailure;;3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/linux/archive/gpio/LinuxLibgpioIF.h;SD_CARD_MANAGER -0x6004;SDMA_GpioInvalidInstance;;4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/linux/archive/gpio/LinuxLibgpioIF.h;SD_CARD_MANAGER -0x4ea1;HEATER_CommandNotSupported;;0xA1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/linux/devices/HeaterHandler.h;HEATER_HANDLER -0x4ea2;HEATER_InitFailed;;0xA2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/linux/devices/HeaterHandler.h;HEATER_HANDLER -0x4ea3;HEATER_InvalidSwitchNr;;0xA3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/linux/devices/HeaterHandler.h;HEATER_HANDLER -0x4ea4;HEATER_MainSwitchSetTimeout;;0xA4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/linux/devices/HeaterHandler.h;HEATER_HANDLER -0x4ea5;HEATER_CommandAlreadyWaiting;;0xA5;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/linux/devices/HeaterHandler.h;HEATER_HANDLER -0x5fa0;SADPL_CommandNotSupported;;0xA0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/linux/devices/SolarArrayDeploymentHandler.h;SA_DEPL_HANDLER -0x5fa1;SADPL_DeploymentAlreadyExecuting;;0xA1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/linux/devices/SolarArrayDeploymentHandler.h;SA_DEPL_HANDLER -0x5fa2;SADPL_MainSwitchTimeoutFailure;;0xA2;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/linux/devices/SolarArrayDeploymentHandler.h;SA_DEPL_HANDLER -0x5fa3;SADPL_SwitchingDeplSa1Failed;;0xA3;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/linux/devices/SolarArrayDeploymentHandler.h;SA_DEPL_HANDLER -0x5fa4;SADPL_SwitchingDeplSa2Failed;;0xA4;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/linux/devices/SolarArrayDeploymentHandler.h;SA_DEPL_HANDLER -0x55a0;SUSS_ErrorUnlockMutex;;0xA0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/linux/devices/SusHandler.h;SUS_HANDLER -0x55a1;SUSS_ErrorLockMutex;;0xA1;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/linux/devices/SusHandler.h;SUS_HANDLER -0x56a0;IPCI_PapbBusy;;0xA0;C:\Users\jakob\Work\EIVE\Q7S\Software\eive_obsw/linux/obc/CCSDSIPCoreBridge.h;CCSDS_IP_CORE_BRIDGE +0x64a0;NVMB_KeyNotExists;Specified key does not exist in json file;0xA0;mission/memory/NVMParameterBase.h;NVM_PARAM_BASE +0x57a0;PLMP_CrcFailure;;0xA0;mission/devices/PlocMPSoCHandler.h;PLOC_MPSOC_HANDLER +0x57a1;PLMP_ReceivedAckFailure;;0xA1;mission/devices/PlocMPSoCHandler.h;PLOC_MPSOC_HANDLER +0x57a2;PLMP_ReceivedExeFailure;;0xA2;mission/devices/PlocMPSoCHandler.h;PLOC_MPSOC_HANDLER +0x57a3;PLMP_InvalidApid;;0xA3;mission/devices/PlocMPSoCHandler.h;PLOC_MPSOC_HANDLER +0x59a0;SUSS_ErrorUnlockMutex;;0xA0;mission/devices/SusHandler.h;SUS_HANDLER +0x59a1;SUSS_ErrorLockMutex;;0xA1;mission/devices/SusHandler.h;SUS_HANDLER +0x65a0;SADPL_CommandNotSupported;;0xA0;mission/devices/SolarArrayDeploymentHandler.h;SA_DEPL_HANDLER +0x65a1;SADPL_DeploymentAlreadyExecuting;;0xA1;mission/devices/SolarArrayDeploymentHandler.h;SA_DEPL_HANDLER +0x65a2;SADPL_MainSwitchTimeoutFailure;;0xA2;mission/devices/SolarArrayDeploymentHandler.h;SA_DEPL_HANDLER +0x65a3;SADPL_SwitchingDeplSa1Failed;;0xA3;mission/devices/SolarArrayDeploymentHandler.h;SA_DEPL_HANDLER +0x65a4;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 +0x5e00;GOMS_PacketTooLong;;0;mission/devices/GomspaceDeviceHandler.h;GOM_SPACE_HANDLER +0x5e01;GOMS_InvalidTableId;;1;mission/devices/GomspaceDeviceHandler.h;GOM_SPACE_HANDLER +0x5e02;GOMS_InvalidAddress;;2;mission/devices/GomspaceDeviceHandler.h;GOM_SPACE_HANDLER +0x5e03;GOMS_InvalidParamSize;;3;mission/devices/GomspaceDeviceHandler.h;GOM_SPACE_HANDLER +0x5e04;GOMS_InvalidPayloadSize;;4;mission/devices/GomspaceDeviceHandler.h;GOM_SPACE_HANDLER +0x5e05;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 +0x61a0;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 +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 +0x6d00; SCBU_KeyNotFound;;0;bsp_q7s/memory/scratchApi.h;SCRATCH_BUFFER +0x6c00; SDMA_OpOngoing;;0;bsp_q7s/memory/SdCardManager.h;SD_CARD_MANAGER +0x6c01; SDMA_AlreadyOn;;1;bsp_q7s/memory/SdCardManager.h;SD_CARD_MANAGER +0x6c02; SDMA_AlreadyMounted;;2;bsp_q7s/memory/SdCardManager.h;SD_CARD_MANAGER +0x6c03; SDMA_AlreadyOff;;3;bsp_q7s/memory/SdCardManager.h;SD_CARD_MANAGER +0x6c0a; SDMA_StatusFileNexists;;10;bsp_q7s/memory/SdCardManager.h;SD_CARD_MANAGER +0x6c0b; SDMA_StatusFileFormatInvalid;;11;bsp_q7s/memory/SdCardManager.h;SD_CARD_MANAGER +0x6c0c; SDMA_MountError;;12;bsp_q7s/memory/SdCardManager.h;SD_CARD_MANAGER +0x6c0d; SDMA_UnmountError;;13;bsp_q7s/memory/SdCardManager.h;SD_CARD_MANAGER +0x6c0e; SDMA_SystemCallError;;14;bsp_q7s/memory/SdCardManager.h;SD_CARD_MANAGER +0x6c0f; SDMA_PopenCallError;;15;bsp_q7s/memory/SdCardManager.h;SD_CARD_MANAGER +0x58a0;PLSV_CrcFailure;Space Packet received from PLOC supervisor has invalid CRC;0xA0;bsp_q7s/devices/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER +0x58a1;PLSV_ReceivedAckFailure;Received ACK failure reply from PLOC supervisor;0xA1;bsp_q7s/devices/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER +0x58a2;PLSV_ReceivedExeFailure;Received execution failure reply from PLOC supervisor;0xA2;bsp_q7s/devices/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER +0x58a3;PLSV_InvalidApid;Received space packet with invalid APID from PLOC supervisor;0xA3;bsp_q7s/devices/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER +0x58a4;PLSV_GetTimeFailure;Failed to read current system time;0xA4;bsp_q7s/devices/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER +0x58a5;PLSV_InvalidUartComIf;Invalid communication interface specified;0xA5;bsp_q7s/devices/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER +0x58a6;PLSV_InvalidWatchdog;Received command with invalid watchdog parameter. Valid watchdogs are 0 for PS, 1 for PL and 2 for INT;0xA6;bsp_q7s/devices/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER +0x58a7;PLSV_InvalidWatchdogTimeout;Received watchdog timeout config command with invalid timeout. Valid timeouts must be in the range between 1000 and 360000 ms.;0xA7;bsp_q7s/devices/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER +0x58a8;PLSV_InvalidLatchupId;Received latchup config command with invalid latchup ID;0xA8;bsp_q7s/devices/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER +0x58a9;PLSV_SweepPeriodTooSmall;Received set adc sweep period command with invalid sweep period. Must be larger than 21.;0xA9;bsp_q7s/devices/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER +0x58aa;PLSV_InvalidTestParam;Receive auto EM test command with invalid test param. Valid params are 1 and 2.;0xAA;bsp_q7s/devices/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER +0x58ab;PLSV_MramPacketParsingFailure;Returned when scanning for MRAM dump packets failed.;0xAB;bsp_q7s/devices/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER +0x58ac;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);0xAC;bsp_q7s/devices/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER +0x58ad;PLSV_NoMramPacket;Expect reception of an MRAM dump packet but received space packet with other apid.;0xAD;bsp_q7s/devices/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER +0x58ae;PLSV_PathDoesNotExist;Path to PLOC directory on SD card does not exist;0xAE;bsp_q7s/devices/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER +0x58af;PLSV_MramFileNotExists;MRAM dump file does not exists. The file should actually already have been created with the reception of the first dump packet.;0xAF;bsp_q7s/devices/PlocSupervisorHandler.h;PLOC_SUPERVISOR_HANDLER +0x5ca0;PLUD_UpdaterBusy;Updater is already performing an update;0xA0;bsp_q7s/devices/PlocUpdater.h;PLOC_UPDATER +0x5ca1;PLUD_NameTooLong;Received update command with invalid path string (too long).;0xA1;bsp_q7s/devices/PlocUpdater.h;PLOC_UPDATER +0x5ca2;PLUD_SdNotMounted;Received command to initiate update but SD card with update image not mounted.;0xA2;bsp_q7s/devices/PlocUpdater.h;PLOC_UPDATER +0x5ca3;PLUD_FileNotExists;Update file received with update command does not exist.;0xA3;bsp_q7s/devices/PlocUpdater.h;PLOC_UPDATER +0x5fa0;PLMEMDUMP_MramAddressTooHigh;The capacity of the MRAM amounts to 512 kB. Thus the maximum address must not be higher than 0x7d000.;0xA0;bsp_q7s/devices/PlocMemoryDumper.h;PLOC_MEMORY_DUMPER +0x5fa1;PLMEMDUMP_MramInvalidAddressCombination;The specified end address is lower than the start address;0xA1;bsp_q7s/devices/PlocMemoryDumper.h;PLOC_MEMORY_DUMPER +0x6301;JSONBASE_JsonFileNotExists;Specified json file does not exist;1;linux/devices/startracker/ArcsecJsonParamBase.h;ARCSEC_JSON_BASE +0x6302;JSONBASE_SetNotExists;Requested set does not exist in json file;2;linux/devices/startracker/ArcsecJsonParamBase.h;ARCSEC_JSON_BASE +0x6303;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 +0x5da0;STRHLP_SdNotMounted;SD card specified in path string not mounted;0xA0;linux/devices/startracker/StrHelper.h;STR_HELPER +0x5da1;STRHLP_FileNotExists;Specified file does not exist on filesystem;0xA1;linux/devices/startracker/StrHelper.h;STR_HELPER +0x5da2;STRHLP_PathNotExists;Specified path does not exist;0xA2;linux/devices/startracker/StrHelper.h;STR_HELPER +0x5da3;STRHLP_FileCreationFailed;Failed to create download image or read flash file;0xA3;linux/devices/startracker/StrHelper.h;STR_HELPER +0x5da4;STRHLP_RegionMismatch;Region in flash write/read reply does not match expected region;0xA4;linux/devices/startracker/StrHelper.h;STR_HELPER +0x5da5;STRHLP_AddressMismatch;Address in flash write/read reply does not match expected address;0xA5;linux/devices/startracker/StrHelper.h;STR_HELPER +0x5da6;STRHLP_LengthMismatch;Length in flash write/read reply does not match expected length;0xA6;linux/devices/startracker/StrHelper.h;STR_HELPER +0x5da7;STRHLP_StatusError;Status field in reply signals error;0xA7;linux/devices/startracker/StrHelper.h;STR_HELPER +0x5da8;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 +0x5ba0;PTME_UnknownVcId;;0xA0;linux/obc/Ptme.h;PTME +0x60a0;PDEC_AbandonedCltu;;0xA0;linux/obc/PdecHandler.h;PDEC_HANDLER +0x60a1;PDEC_FrameDirty;;0xA1;linux/obc/PdecHandler.h;PDEC_HANDLER +0x60a2;PDEC_FrameIllegalMultipleReasons;;0xA2;linux/obc/PdecHandler.h;PDEC_HANDLER +0x60a3;PDEC_AdDiscardedLockout;;0xA3;linux/obc/PdecHandler.h;PDEC_HANDLER +0x60a4;PDEC_AdDiscardedWait;;0xA4;linux/obc/PdecHandler.h;PDEC_HANDLER +0x60a5;PDEC_AdDiscardedNsVs;;0xA5;linux/obc/PdecHandler.h;PDEC_HANDLER +0x60b0;PDEC_CommandNotImplemented;Received action message with unknown action id;0xB0;linux/obc/PdecHandler.h;PDEC_HANDLER +0x60a6;PDEC_NoReport;;0xA6;linux/obc/PdecHandler.h;PDEC_HANDLER +0x60a7;PDEC_ErrorVersionNumber;;0xA7;linux/obc/PdecHandler.h;PDEC_HANDLER +0x60a8;PDEC_IllegalCombination;;0xA8;linux/obc/PdecHandler.h;PDEC_HANDLER +0x60a9;PDEC_InvalidScId;;0xA9;linux/obc/PdecHandler.h;PDEC_HANDLER +0x60aa;PDEC_InvalidVcIdMsb;;0xAA;linux/obc/PdecHandler.h;PDEC_HANDLER +0x60ab;PDEC_InvalidVcIdLsb;;0xAB;linux/obc/PdecHandler.h;PDEC_HANDLER +0x60ac;PDEC_NsNotZero;;0xAC;linux/obc/PdecHandler.h;PDEC_HANDLER +0x60ae;PDEC_InvalidBcCc;;0xAE;linux/obc/PdecHandler.h;PDEC_HANDLER +0x62a0;RS_RateNotSupported;The commanded rate is not supported by the current FPGA design;0xA0;linux/obc/PtmeConfig.h;RATE_SETTER +0x62a1;RS_BadBitRate;Bad bitrate has been commanded (e.g. 0);0xA1;linux/obc/PtmeConfig.h;RATE_SETTER +0x62a2;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 +0x62a3;RS_TxManipulatorConfigFailed;Failed to change configuration bit of tx clock manipulator;0xA3;linux/obc/PtmeConfig.h;RATE_SETTER +0x5aa0;IPCI_PapbBusy;;0xA0;linux/archive/tmtc/CCSDSIPCoreBridge.h;CCSDS_IP_CORE_BRIDGE +0x5a01;IPCI_UnknownGpioId;;1;linux/archive/gpio/LinuxLibgpioIF.h;CCSDS_IP_CORE_BRIDGE +0x5a02;IPCI_DriveGpioFailure;;2;linux/archive/gpio/LinuxLibgpioIF.h;CCSDS_IP_CORE_BRIDGE +0x5a03;IPCI_GpioTypeFailure;;3;linux/archive/gpio/LinuxLibgpioIF.h;CCSDS_IP_CORE_BRIDGE +0x5a04;IPCI_GpioInvalidInstance;;4;linux/archive/gpio/LinuxLibgpioIF.h;CCSDS_IP_CORE_BRIDGE diff --git a/generators/definitions.py b/generators/definitions.py index 528c3019..321d2f5b 100644 --- a/generators/definitions.py +++ b/generators/definitions.py @@ -2,9 +2,18 @@ import os import enum from pathlib import Path -PATH_VAR_ROOT = Path(os.path.abspath(os.curdir)) -ROOT_DIR = PATH_VAR_ROOT.absolute() -OBSW_ROOT_DIR = PATH_VAR_ROOT.parent.absolute() + +def determine_obsw_root_path() -> str: + for _ in range(5): + if os.path.exists("CMakeLists.txt"): + return os.path.abspath(os.curdir) + else: + os.chdir("..") + + +PATH_VAR_ROOT = os.path.dirname(os.path.realpath(__file__)) +ROOT_DIR = PATH_VAR_ROOT +OBSW_ROOT_DIR = Path(determine_obsw_root_path()) DATABASE_NAME = "eive_mod.db" diff --git a/generators/events/event_parser.py b/generators/events/event_parser.py index 62b26af4..7b6b86c8 100644 --- a/generators/events/event_parser.py +++ b/generators/events/event_parser.py @@ -3,12 +3,17 @@ Event exporter. """ import datetime import time +import os -from fsfwgen.events.event_parser import handle_csv_export, handle_cpp_export, \ - SubsystemDefinitionParser, EventParser +from fsfwgen.events.event_parser import ( + handle_csv_export, + handle_cpp_export, + SubsystemDefinitionParser, + EventParser, +) from fsfwgen.parserbase.file_list_parser import FileListParser from fsfwgen.utility.printer import PrettyPrinter -from fsfwgen.utility.file_management import copy_file, move_file +from fsfwgen.utility.file_management import copy_file from fsfwgen.core import get_console_logger from definitions import BspType, ROOT_DIR, OBSW_ROOT_DIR @@ -25,15 +30,17 @@ MOVE_CSV_FILE = True PARSE_HOST_BSP = True -CPP_FILENAME = f'{__package__}/translateEvents.cpp' -CPP_H_FILENAME = f'{__package__}/translateEvents.h' +# 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" BSP_SELECT = BspType.BSP_Q7S BSP_DIR_NAME = BSP_SELECT.value -CSV_FILENAME = f"{BSP_SELECT.value}_events.csv" -CSV_MOVE_DESTINATION = f'{ROOT_DIR}' +# 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" if BSP_SELECT == BspType.BSP_Q7S or BSP_SELECT == BspType.BSP_LINUX_BOARD: FSFW_CONFIG_ROOT = f"{OBSW_ROOT_DIR}/linux/fsfwconfig" @@ -47,16 +54,20 @@ FILE_SEPARATOR = ";" SUBSYSTEM_DEFINITION_DESTINATIONS = [ f"{FSFW_CONFIG_ROOT}/events/subsystemIdRanges.h", f"{OBSW_ROOT_DIR}/fsfw/src/fsfw/events/fwSubsystemIdRanges.h", - f"{OBSW_ROOT_DIR}/common/config/commonSubsystemIds.h" + f"{OBSW_ROOT_DIR}/common/config/commonSubsystemIds.h", ] 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}/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}/linux/", ] def parse_events( - generate_csv: bool = True, generate_cpp: bool = True, print_events: bool = True + generate_csv: bool = True, generate_cpp: bool = True, print_events: bool = True ): LOGGER.info("EventParser: Parsing events: ") # Small delay for clean printout @@ -71,13 +82,18 @@ def parse_events( handle_csv_export( file_name=CSV_FILENAME, event_list=event_list, file_separator=FILE_SEPARATOR ) + copy_file(filename=CSV_FILENAME, destination=CSV_COPY_DEST, delete_existing_file=True) + if generate_cpp: handle_cpp_export( - event_list=event_list, date_string=DATE_STRING_FULL, file_name=CPP_FILENAME, - generate_header=GENERATE_CPP_H, header_file_name=CPP_H_FILENAME + event_list=event_list, + date_string=DATE_STRING_FULL, + file_name=CPP_FILENAME, + generate_header=GENERATE_CPP_H, + header_file_name=CPP_H_FILENAME, ) if COPY_CPP_FILE: - LOGGER.info(f'EventParser: Copying file to {CPP_COPY_DESTINATION}') + LOGGER.info(f"EventParser: Copying file to {CPP_COPY_DESTINATION}") copy_file(CPP_FILENAME, CPP_COPY_DESTINATION) copy_file(CPP_H_FILENAME, CPP_COPY_DESTINATION) @@ -85,7 +101,7 @@ def parse_events( def generate_event_list() -> list: subsystem_parser = SubsystemDefinitionParser(SUBSYSTEM_DEFINITION_DESTINATIONS) subsystem_table = subsystem_parser.parse_files() - LOGGER.info(f'Found {len(subsystem_table)} subsystem definitions.') + LOGGER.info(f"Found {len(subsystem_table)} subsystem definitions.") PrettyPrinter.pprint(subsystem_table) event_header_parser = FileListParser(HEADER_DEFINITION_DESTINATIONS) event_headers = event_header_parser.parse_header_files( @@ -94,8 +110,9 @@ def generate_event_list() -> list: # PrettyPrinter.pprint(event_headers) # myEventList = parseHeaderFiles(subsystem_table, event_headers) event_parser = EventParser(event_headers, subsystem_table) + 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') + LOGGER.info(f"Found {len(event_list)} entries") return event_list diff --git a/generators/events/translateEvents.cpp b/generators/events/translateEvents.cpp index 9d817651..4b46ede3 100644 --- a/generators/events/translateEvents.cpp +++ b/generators/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** - * @brief Auto-generated event translation file. Contains 106 translations. + * @brief Auto-generated event translation file. Contains 141 translations. * @details - * Generated on: 2021-08-31 10:50:10 + * Generated on: 2022-03-04 15:13:02 */ #include "translateEvents.h" @@ -34,6 +34,7 @@ const char *DEVICE_UNREQUESTED_REPLY_STRING = "DEVICE_UNREQUESTED_REPLY"; const char *INVALID_DEVICE_COMMAND_STRING = "INVALID_DEVICE_COMMAND"; const char *MONITORING_LIMIT_EXCEEDED_STRING = "MONITORING_LIMIT_EXCEEDED"; const char *MONITORING_AMBIGUOUS_STRING = "MONITORING_AMBIGUOUS"; +const char *DEVICE_WANTS_HARD_REBOOT_STRING = "DEVICE_WANTS_HARD_REBOOT"; const char *FUSE_CURRENT_HIGH_STRING = "FUSE_CURRENT_HIGH"; const char *FUSE_WENT_OFF_STRING = "FUSE_WENT_OFF"; const char *POWER_ABOVE_HIGH_LIMIT_STRING = "POWER_ABOVE_HIGH_LIMIT"; @@ -59,7 +60,6 @@ const char *MONITOR_CHANGED_STATE_STRING = "MONITOR_CHANGED_STATE"; const char *VALUE_BELOW_LOW_LIMIT_STRING = "VALUE_BELOW_LOW_LIMIT"; const char *VALUE_ABOVE_HIGH_LIMIT_STRING = "VALUE_ABOVE_HIGH_LIMIT"; const char *VALUE_OUT_OF_RANGE_STRING = "VALUE_OUT_OF_RANGE"; -const char *SWITCHING_TM_FAILED_STRING = "SWITCHING_TM_FAILED"; const char *CHANGING_MODE_STRING = "CHANGING_MODE"; const char *MODE_INFO_STRING = "MODE_INFO"; const char *FALLBACK_FAILED_STRING = "FALLBACK_FAILED"; @@ -84,6 +84,16 @@ const char *CLOCK_SET_STRING = "CLOCK_SET"; const char *CLOCK_SET_FAILURE_STRING = "CLOCK_SET_FAILURE"; const char *TEST_STRING = "TEST"; const char *CHANGE_OF_SETUP_PARAMETER_STRING = "CHANGE_OF_SETUP_PARAMETER"; +const char *GPIO_PULL_HIGH_FAILED_STRING = "GPIO_PULL_HIGH_FAILED"; +const char *GPIO_PULL_LOW_FAILED_STRING = "GPIO_PULL_LOW_FAILED"; +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 *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"; +const char *DEPL_SA1_GPIO_SWTICH_ON_FAILED_STRING = "DEPL_SA1_GPIO_SWTICH_ON_FAILED"; +const char *DEPL_SA2_GPIO_SWTICH_ON_FAILED_STRING = "DEPL_SA2_GPIO_SWTICH_ON_FAILED"; 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"; @@ -97,11 +107,15 @@ 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 *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 *SANITIZATION_FAILED_STRING = "SANITIZATION_FAILED"; +const char *ALLOC_FAILURE_STRING = "ALLOC_FAILURE"; +const char *REBOOT_SW_STRING = "REBOOT_SW"; +const char *REBOOT_HW_STRING = "REBOOT_HW"; 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"; @@ -111,223 +125,314 @@ 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"; +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 *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"; +const char *IMAGE_DOWNLOAD_SUCCESSFUL_STRING = "IMAGE_DOWNLOAD_SUCCESSFUL"; +const char *FLASH_WRITE_SUCCESSFUL_STRING = "FLASH_WRITE_SUCCESSFUL"; +const char *FLASH_READ_SUCCESSFUL_STRING = "FLASH_READ_SUCCESSFUL"; +const char *FLASH_READ_FAILED_STRING = "FLASH_READ_FAILED"; +const char *FIRMWARE_UPDATE_SUCCESSFUL_STRING = "FIRMWARE_UPDATE_SUCCESSFUL"; +const char *FIRMWARE_UPDATE_FAILED_STRING = "FIRMWARE_UPDATE_FAILED"; +const char *STR_HELPER_READING_REPLY_FAILED_STRING = "STR_HELPER_READING_REPLY_FAILED"; +const char *STR_HELPER_COM_ERROR_STRING = "STR_HELPER_COM_ERROR"; +const char *STR_HELPER_NO_REPLY_STRING = "STR_HELPER_NO_REPLY"; +const char *STR_HELPER_DEC_ERROR_STRING = "STR_HELPER_DEC_ERROR"; +const char *POSITION_MISMATCH_STRING = "POSITION_MISMATCH"; +const char *STR_HELPER_FILE_NOT_EXISTS_STRING = "STR_HELPER_FILE_NOT_EXISTS"; +const char *STR_HELPER_SENDING_PACKET_FAILED_STRING = "STR_HELPER_SENDING_PACKET_FAILED"; +const char *STR_HELPER_REQUESTING_MSG_FAILED_STRING = "STR_HELPER_REQUESTING_MSG_FAILED"; -const char * translateEvents(Event event) { - switch( (event & 0xffff) ) { - case(2200): - return STORE_SEND_WRITE_FAILED_STRING; - case(2201): - return STORE_WRITE_FAILED_STRING; - case(2202): - return STORE_SEND_READ_FAILED_STRING; - case(2203): - return STORE_READ_FAILED_STRING; - case(2204): - return UNEXPECTED_MSG_STRING; - case(2205): - return STORING_FAILED_STRING; - case(2206): - return TM_DUMP_FAILED_STRING; - case(2207): - return STORE_INIT_FAILED_STRING; - case(2208): - return STORE_INIT_EMPTY_STRING; - case(2209): - return STORE_CONTENT_CORRUPTED_STRING; - case(2210): - return STORE_INITIALIZE_STRING; - case(2211): - return INIT_DONE_STRING; - case(2212): - return DUMP_FINISHED_STRING; - case(2213): - return DELETION_FINISHED_STRING; - case(2214): - return DELETION_FAILED_STRING; - case(2215): - return AUTO_CATALOGS_SENDING_FAILED_STRING; - case(2600): - return GET_DATA_FAILED_STRING; - case(2601): - return STORE_DATA_FAILED_STRING; - case(2800): - return DEVICE_BUILDING_COMMAND_FAILED_STRING; - case(2801): - return DEVICE_SENDING_COMMAND_FAILED_STRING; - case(2802): - return DEVICE_REQUESTING_REPLY_FAILED_STRING; - case(2803): - return DEVICE_READING_REPLY_FAILED_STRING; - case(2804): - return DEVICE_INTERPRETING_REPLY_FAILED_STRING; - case(2805): - return DEVICE_MISSED_REPLY_STRING; - case(2806): - return DEVICE_UNKNOWN_REPLY_STRING; - case(2807): - return DEVICE_UNREQUESTED_REPLY_STRING; - case(2808): - return INVALID_DEVICE_COMMAND_STRING; - case(2809): - return MONITORING_LIMIT_EXCEEDED_STRING; - case(2810): - return MONITORING_AMBIGUOUS_STRING; - case(4201): - return FUSE_CURRENT_HIGH_STRING; - case(4202): - return FUSE_WENT_OFF_STRING; - case(4204): - return POWER_ABOVE_HIGH_LIMIT_STRING; - case(4205): - return POWER_BELOW_LOW_LIMIT_STRING; - case(4300): - return SWITCH_WENT_OFF_STRING; - case(5000): - return HEATER_ON_STRING; - case(5001): - return HEATER_OFF_STRING; - case(5002): - return HEATER_TIMEOUT_STRING; - case(5003): - return HEATER_STAYED_ON_STRING; - case(5004): - return HEATER_STAYED_OFF_STRING; - case(5200): - return TEMP_SENSOR_HIGH_STRING; - case(5201): - return TEMP_SENSOR_LOW_STRING; - case(5202): - return TEMP_SENSOR_GRADIENT_STRING; - case(5901): - return COMPONENT_TEMP_LOW_STRING; - case(5902): - return COMPONENT_TEMP_HIGH_STRING; - case(5903): - return COMPONENT_TEMP_OOL_LOW_STRING; - case(5904): - return COMPONENT_TEMP_OOL_HIGH_STRING; - case(5905): - return TEMP_NOT_IN_OP_RANGE_STRING; - case(7101): - return FDIR_CHANGED_STATE_STRING; - case(7102): - return FDIR_STARTS_RECOVERY_STRING; - case(7103): - return FDIR_TURNS_OFF_DEVICE_STRING; - case(7201): - return MONITOR_CHANGED_STATE_STRING; - case(7202): - return VALUE_BELOW_LOW_LIMIT_STRING; - case(7203): - return VALUE_ABOVE_HIGH_LIMIT_STRING; - case(7204): - return VALUE_OUT_OF_RANGE_STRING; - case(7301): - return SWITCHING_TM_FAILED_STRING; - case(7400): - return CHANGING_MODE_STRING; - case(7401): - return MODE_INFO_STRING; - case(7402): - return FALLBACK_FAILED_STRING; - case(7403): - return MODE_TRANSITION_FAILED_STRING; - case(7404): - return CANT_KEEP_MODE_STRING; - case(7405): - return OBJECT_IN_INVALID_MODE_STRING; - case(7406): - return FORCING_MODE_STRING; - case(7407): - return MODE_CMD_REJECTED_STRING; - case(7506): - return HEALTH_INFO_STRING; - case(7507): - return CHILD_CHANGED_HEALTH_STRING; - case(7508): - return CHILD_PROBLEMS_STRING; - case(7509): - return OVERWRITING_HEALTH_STRING; - case(7510): - return TRYING_RECOVERY_STRING; - case(7511): - return RECOVERY_STEP_STRING; - case(7512): - return RECOVERY_DONE_STRING; - case(7900): - return RF_AVAILABLE_STRING; - case(7901): - return RF_LOST_STRING; - case(7902): - return BIT_LOCK_STRING; - case(7903): - return BIT_LOCK_LOST_STRING; - case(7905): - return FRAME_PROCESSING_FAILED_STRING; - case(8900): - return CLOCK_SET_STRING; - case(8901): - return CLOCK_SET_FAILURE_STRING; - case(9700): - return TEST_STRING; - case(10600): - return CHANGE_OF_SETUP_PARAMETER_STRING; - case(11101): - return MEMORY_READ_RPT_CRC_FAILURE_STRING; - case(11102): - return ACK_FAILURE_STRING; - case(11103): - return EXE_FAILURE_STRING; - case(11104): - return CRC_FAILURE_EVENT_STRING; - case(11201): - return SELF_TEST_I2C_FAILURE_STRING; - case(11202): - return SELF_TEST_SPI_FAILURE_STRING; - case(11203): - return SELF_TEST_ADC_FAILURE_STRING; - case(11204): - return SELF_TEST_PWM_FAILURE_STRING; - case(11205): - return SELF_TEST_TC_FAILURE_STRING; - case(11206): - return SELF_TEST_MTM_RANGE_FAILURE_STRING; - case(11207): - return SELF_TEST_COIL_CURRENT_FAILURE_STRING; - case(11208): - return INVALID_ERROR_BYTE_STRING; - case(11301): - return ERROR_STATE_STRING; - case(11501): - return SUPV_MEMORY_READ_RPT_CRC_FAILURE_STRING; - case(11502): - return SUPV_ACK_FAILURE_STRING; - case(11503): - return SUPV_EXE_FAILURE_STRING; - case(11504): - return SUPV_CRC_FAILURE_EVENT_STRING; - case(11600): - return SANITIZATION_FAILED_STRING; - case(11700): - return UPDATE_FILE_NOT_EXISTS_STRING; - case(11701): - return ACTION_COMMANDING_FAILED_STRING; - case(11702): - return UPDATE_AVAILABLE_FAILED_STRING; - case(11703): - return UPDATE_TRANSFER_FAILED_STRING; - case(11704): - return UPDATE_VERIFY_FAILED_STRING; - case(11705): - return UPDATE_FINISHED_STRING; - case(11800): - return SEND_MRAM_DUMP_FAILED_STRING; - case(11801): - return MRAM_DUMP_FAILED_STRING; - case(11802): - return MRAM_DUMP_FINISHED_STRING; - default: - return "UNKNOWN_EVENT"; - } - return 0; +const char *translateEvents(Event event) { + switch ((event & 0xFFFF)) { + case (2200): + return STORE_SEND_WRITE_FAILED_STRING; + case (2201): + return STORE_WRITE_FAILED_STRING; + case (2202): + return STORE_SEND_READ_FAILED_STRING; + case (2203): + return STORE_READ_FAILED_STRING; + case (2204): + return UNEXPECTED_MSG_STRING; + case (2205): + return STORING_FAILED_STRING; + case (2206): + return TM_DUMP_FAILED_STRING; + case (2207): + return STORE_INIT_FAILED_STRING; + case (2208): + return STORE_INIT_EMPTY_STRING; + case (2209): + return STORE_CONTENT_CORRUPTED_STRING; + case (2210): + return STORE_INITIALIZE_STRING; + case (2211): + return INIT_DONE_STRING; + case (2212): + return DUMP_FINISHED_STRING; + case (2213): + return DELETION_FINISHED_STRING; + case (2214): + return DELETION_FAILED_STRING; + case (2215): + return AUTO_CATALOGS_SENDING_FAILED_STRING; + case (2600): + return GET_DATA_FAILED_STRING; + case (2601): + return STORE_DATA_FAILED_STRING; + case (2800): + return DEVICE_BUILDING_COMMAND_FAILED_STRING; + case (2801): + return DEVICE_SENDING_COMMAND_FAILED_STRING; + case (2802): + return DEVICE_REQUESTING_REPLY_FAILED_STRING; + case (2803): + return DEVICE_READING_REPLY_FAILED_STRING; + case (2804): + return DEVICE_INTERPRETING_REPLY_FAILED_STRING; + case (2805): + return DEVICE_MISSED_REPLY_STRING; + case (2806): + return DEVICE_UNKNOWN_REPLY_STRING; + case (2807): + return DEVICE_UNREQUESTED_REPLY_STRING; + case (2808): + return INVALID_DEVICE_COMMAND_STRING; + case (2809): + return MONITORING_LIMIT_EXCEEDED_STRING; + case (2810): + return MONITORING_AMBIGUOUS_STRING; + case (2811): + return DEVICE_WANTS_HARD_REBOOT_STRING; + case (4201): + return FUSE_CURRENT_HIGH_STRING; + case (4202): + return FUSE_WENT_OFF_STRING; + case (4204): + return POWER_ABOVE_HIGH_LIMIT_STRING; + case (4205): + return POWER_BELOW_LOW_LIMIT_STRING; + case (4300): + return SWITCH_WENT_OFF_STRING; + case (5000): + return HEATER_ON_STRING; + case (5001): + return HEATER_OFF_STRING; + case (5002): + return HEATER_TIMEOUT_STRING; + case (5003): + return HEATER_STAYED_ON_STRING; + case (5004): + return HEATER_STAYED_OFF_STRING; + case (5200): + return TEMP_SENSOR_HIGH_STRING; + case (5201): + return TEMP_SENSOR_LOW_STRING; + case (5202): + return TEMP_SENSOR_GRADIENT_STRING; + case (5901): + return COMPONENT_TEMP_LOW_STRING; + case (5902): + return COMPONENT_TEMP_HIGH_STRING; + case (5903): + return COMPONENT_TEMP_OOL_LOW_STRING; + case (5904): + return COMPONENT_TEMP_OOL_HIGH_STRING; + case (5905): + return TEMP_NOT_IN_OP_RANGE_STRING; + case (7101): + return FDIR_CHANGED_STATE_STRING; + case (7102): + return FDIR_STARTS_RECOVERY_STRING; + case (7103): + return FDIR_TURNS_OFF_DEVICE_STRING; + case (7201): + return MONITOR_CHANGED_STATE_STRING; + case (7202): + return VALUE_BELOW_LOW_LIMIT_STRING; + case (7203): + return VALUE_ABOVE_HIGH_LIMIT_STRING; + case (7204): + return VALUE_OUT_OF_RANGE_STRING; + case (7400): + return CHANGING_MODE_STRING; + case (7401): + return MODE_INFO_STRING; + case (7402): + return FALLBACK_FAILED_STRING; + case (7403): + return MODE_TRANSITION_FAILED_STRING; + case (7404): + return CANT_KEEP_MODE_STRING; + case (7405): + return OBJECT_IN_INVALID_MODE_STRING; + case (7406): + return FORCING_MODE_STRING; + case (7407): + return MODE_CMD_REJECTED_STRING; + case (7506): + return HEALTH_INFO_STRING; + case (7507): + return CHILD_CHANGED_HEALTH_STRING; + case (7508): + return CHILD_PROBLEMS_STRING; + case (7509): + return OVERWRITING_HEALTH_STRING; + case (7510): + return TRYING_RECOVERY_STRING; + case (7511): + return RECOVERY_STEP_STRING; + case (7512): + return RECOVERY_DONE_STRING; + case (7900): + return RF_AVAILABLE_STRING; + case (7901): + return RF_LOST_STRING; + case (7902): + return BIT_LOCK_STRING; + case (7903): + return BIT_LOCK_LOST_STRING; + case (7905): + return FRAME_PROCESSING_FAILED_STRING; + case (8900): + return CLOCK_SET_STRING; + case (8901): + return CLOCK_SET_FAILURE_STRING; + case (9700): + return TEST_STRING; + case (10600): + return CHANGE_OF_SETUP_PARAMETER_STRING; + case (10900): + return GPIO_PULL_HIGH_FAILED_STRING; + case (10901): + return GPIO_PULL_LOW_FAILED_STRING; + case (10902): + return SWITCH_ALREADY_ON_STRING; + case (10903): + return SWITCH_ALREADY_OFF_STRING; + case (10904): + return MAIN_SWITCH_TIMEOUT_STRING; + case (11000): + return MAIN_SWITCH_ON_TIMEOUT_STRING; + case (11001): + return MAIN_SWITCH_OFF_TIMEOUT_STRING; + case (11002): + return DEPLOYMENT_FAILED_STRING; + case (11003): + return DEPL_SA1_GPIO_SWTICH_ON_FAILED_STRING; + case (11004): + return DEPL_SA2_GPIO_SWTICH_ON_FAILED_STRING; + case (11101): + return MEMORY_READ_RPT_CRC_FAILURE_STRING; + case (11102): + return ACK_FAILURE_STRING; + case (11103): + return EXE_FAILURE_STRING; + case (11104): + return CRC_FAILURE_EVENT_STRING; + case (11201): + return SELF_TEST_I2C_FAILURE_STRING; + case (11202): + return SELF_TEST_SPI_FAILURE_STRING; + case (11203): + return SELF_TEST_ADC_FAILURE_STRING; + case (11204): + return SELF_TEST_PWM_FAILURE_STRING; + case (11205): + return SELF_TEST_TC_FAILURE_STRING; + case (11206): + return SELF_TEST_MTM_RANGE_FAILURE_STRING; + case (11207): + return SELF_TEST_COIL_CURRENT_FAILURE_STRING; + case (11208): + return INVALID_ERROR_BYTE_STRING; + case (11301): + return ERROR_STATE_STRING; + case (11401): + return BOOTING_FIRMWARE_FAILED_STRING; + case (11402): + return BOOTING_BOOTLOADER_FAILED_STRING; + case (11501): + return SUPV_MEMORY_READ_RPT_CRC_FAILURE_STRING; + case (11502): + return SUPV_ACK_FAILURE_STRING; + case (11503): + return SUPV_EXE_FAILURE_STRING; + case (11504): + return SUPV_CRC_FAILURE_EVENT_STRING; + case (11600): + return ALLOC_FAILURE_STRING; + case (11601): + return REBOOT_SW_STRING; + case (11603): + return REBOOT_HW_STRING; + case (11700): + return UPDATE_FILE_NOT_EXISTS_STRING; + case (11701): + return ACTION_COMMANDING_FAILED_STRING; + case (11702): + return UPDATE_AVAILABLE_FAILED_STRING; + case (11703): + return UPDATE_TRANSFER_FAILED_STRING; + case (11704): + return UPDATE_VERIFY_FAILED_STRING; + case (11705): + return UPDATE_FINISHED_STRING; + case (11800): + return SEND_MRAM_DUMP_FAILED_STRING; + case (11801): + return MRAM_DUMP_FAILED_STRING; + case (11802): + return MRAM_DUMP_FINISHED_STRING; + case (11901): + return INVALID_TC_FRAME_STRING; + case (11902): + return INVALID_FAR_STRING; + case (11903): + return CARRIER_LOCK_STRING; + case (11904): + return BIT_LOCK_PDEC_STRING; + case (12000): + return IMAGE_UPLOAD_FAILED_STRING; + case (12001): + return IMAGE_DOWNLOAD_FAILED_STRING; + case (12002): + return IMAGE_UPLOAD_SUCCESSFUL_STRING; + case (12003): + return IMAGE_DOWNLOAD_SUCCESSFUL_STRING; + case (12004): + return FLASH_WRITE_SUCCESSFUL_STRING; + case (12005): + return FLASH_READ_SUCCESSFUL_STRING; + case (12006): + return FLASH_READ_FAILED_STRING; + case (12007): + return FIRMWARE_UPDATE_SUCCESSFUL_STRING; + case (12008): + return FIRMWARE_UPDATE_FAILED_STRING; + case (12009): + return STR_HELPER_READING_REPLY_FAILED_STRING; + case (12010): + return STR_HELPER_COM_ERROR_STRING; + case (12011): + return STR_HELPER_NO_REPLY_STRING; + case (12012): + return STR_HELPER_DEC_ERROR_STRING; + case (12013): + return POSITION_MISMATCH_STRING; + case (12014): + return STR_HELPER_FILE_NOT_EXISTS_STRING; + case (12015): + return STR_HELPER_SENDING_PACKET_FAILED_STRING; + case (12016): + return STR_HELPER_REQUESTING_MSG_FAILED_STRING; + default: + return "UNKNOWN_EVENT"; + } + return 0; } diff --git a/generators/events/translateEvents.h b/generators/events/translateEvents.h index bdabb21b..99554317 100644 --- a/generators/events/translateEvents.h +++ b/generators/events/translateEvents.h @@ -3,6 +3,6 @@ #include "fsfw/events/Event.h" -const char * translateEvents(Event event); +const char *translateEvents(Event event); #endif /* FSFWCONFIG_EVENTS_TRANSLATEEVENTS_H_ */ diff --git a/generators/fsfwgen b/generators/fsfwgen index 636670f7..c5ef1783 160000 --- a/generators/fsfwgen +++ b/generators/fsfwgen @@ -1 +1 @@ -Subproject commit 636670f7a0075533974ca0a668efa9b623a52749 +Subproject commit c5ef1783a3b082c0e88561bd91bc3ee0f459fafc diff --git a/generators/fsfwgen.py b/generators/fsfwgen.py index 04c38d24..3d6c1038 100755 --- a/generators/fsfwgen.py +++ b/generators/fsfwgen.py @@ -4,26 +4,31 @@ import time from objects.objects import parse_objects from events.event_parser import parse_events from returnvalues.returnvalues_parser import parse_returnvalues -from fsfwgen.core import return_generic_args_parser, init_printout, get_console_logger, ParserTypes +from fsfwgen.core import ( + return_generic_args_parser, + init_printout, + get_console_logger, + ParserTypes, +) LOGGER = get_console_logger() def main(): - init_printout(project_string='EIVE') + init_printout(project_string="EIVE") parser = return_generic_args_parser() args = parser.parse_args() - if args.type == 'objects': - LOGGER.info(f'Generating objects data..') + if args.type == "objects": + LOGGER.info(f"Generating objects data..") time.sleep(0.05) parse_objects() - elif args.type == 'events': - LOGGER.info(f'Generating event data') + elif args.type == "events": + LOGGER.info(f"Generating event data") time.sleep(0.05) parse_events() - elif args.type == 'returnvalues': - LOGGER.info('Generating returnvalue data') + elif args.type == "returnvalues": + LOGGER.info("Generating returnvalue data") time.sleep(0.05) parse_returnvalues() pass diff --git a/generators/objects/objects.py b/generators/objects/objects.py index 194ee9da..3ea80e8e 100644 --- a/generators/objects/objects.py +++ b/generators/objects/objects.py @@ -2,13 +2,18 @@ Object exporter. """ import datetime +import os from fsfwgen.core import get_console_logger -from fsfwgen.objects.objects import sql_object_exporter, ObjectDefinitionParser, \ - write_translation_file, \ - export_object_file, write_translation_header_file +from fsfwgen.objects.objects import ( + sql_object_exporter, + ObjectDefinitionParser, + write_translation_file, + export_object_file, + write_translation_header_file, +) from fsfwgen.utility.printer import PrettyPrinter -from fsfwgen.utility.file_management import copy_file, move_file +from fsfwgen.utility.file_management import copy_file from definitions import BspType, DATABASE_NAME, OBSW_ROOT_DIR, ROOT_DIR @@ -34,16 +39,18 @@ else: EXPORT_TO_SQL = True CPP_COPY_DESTINATION = f"{FSFW_CONFIG_ROOT}/objects/" -CSV_MOVE_DESTINATION = f"{ROOT_DIR}" -CPP_FILENAME = f'{__package__}/translateObjects.cpp' -CPP_H_FILENAME = f'{__package__}/translateObjects.h' -CSV_OBJECT_FILENAME = f"{BSP_SELECT.value}_objects.csv" +CPP_FILENAME = f"{os.path.dirname(os.path.realpath(__file__))}//translateObjects.cpp" +CPP_H_FILENAME = f"{os.path.dirname(os.path.realpath(__file__))}//translateObjects.h" +CSV_OBJECT_FILENAME = f"{ROOT_DIR}/{BSP_SELECT.value}_objects.csv" +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 = f'{OBSW_ROOT_DIR}/fsfw/src/fsfw/objectmanager/frameworkObjects.h' -COMMON_OBJECTS_PATH = f'{OBSW_ROOT_DIR}/common/config/commonObjects.h' +FRAMEWORK_OBJECT_PATH = ( + f"{OBSW_ROOT_DIR}/fsfw/src/fsfw/objectmanager/frameworkObjects.h" +) +COMMON_OBJECTS_PATH = f"{OBSW_ROOT_DIR}/common/config/commonObjects.h" OBJECTS_DEFINITIONS = [OBJECTS_PATH, FRAMEWORK_OBJECT_PATH, COMMON_OBJECTS_PATH] SQL_DELETE_OBJECTS_CMD = """ @@ -70,35 +77,46 @@ def parse_objects(print_object_list: bool = True): subsystem_definitions = object_parser.parse_files() # id_subsystem_definitions.update(framework_subsystem_definitions) list_items = sorted(subsystem_definitions.items()) - LOGGER.info(f'ObjectParser: Number of objects: {len(list_items)}') + LOGGER.info(f"ObjectParser: Number of objects: {len(list_items)}") if print_object_list: PrettyPrinter.pprint(list_items) handle_file_export(list_items) if EXPORT_TO_SQL: - LOGGER.info('ObjectParser: Exporting to SQL') + LOGGER.info("ObjectParser: Exporting to SQL") sql_object_exporter( - object_table=list_items, delete_cmd=SQL_DELETE_OBJECTS_CMD, + object_table=list_items, + delete_cmd=SQL_DELETE_OBJECTS_CMD, insert_cmd=SQL_INSERT_INTO_OBJECTS_CMD, - create_cmd=SQL_CREATE_OBJECTS_CMD, db_filename=f"{ROOT_DIR}/{DATABASE_NAME}" + create_cmd=SQL_CREATE_OBJECTS_CMD, + db_filename=f"{ROOT_DIR}/{DATABASE_NAME}", ) def handle_file_export(list_items): if GENERATE_CPP: - LOGGER.info('ObjectParser: Generating translation C++ file') + LOGGER.info("ObjectParser: Generating C++ translation file") write_translation_file( - filename=CPP_FILENAME, list_of_entries=list_items, date_string_full=DATE_STRING_FULL + filename=CPP_FILENAME, + list_of_entries=list_items, + date_string_full=DATE_STRING_FULL, ) if COPY_CPP: - print("ObjectParser: Copying object file to " + CPP_COPY_DESTINATION) + LOGGER.info("ObjectParser: Copying object file to " + CPP_COPY_DESTINATION) copy_file(CPP_FILENAME, CPP_COPY_DESTINATION) if GENERATE_HEADER: write_translation_header_file(filename=CPP_H_FILENAME) copy_file(filename=CPP_H_FILENAME, destination=CPP_COPY_DESTINATION) if GENERATE_CSV: - print("ObjectParser: Generating text export.") + LOGGER.info("ObjectParser: Generating text export") export_object_file( - filename=CSV_OBJECT_FILENAME, object_list=list_items, file_separator=FILE_SEPARATOR + filename=CSV_OBJECT_FILENAME, + object_list=list_items, + file_separator=FILE_SEPARATOR, + ) + copy_file( + filename=CSV_OBJECT_FILENAME, + destination=CSV_COPY_DEST, + delete_existing_file=True ) diff --git a/generators/objects/translateObjects.cpp b/generators/objects/translateObjects.cpp index 23a232c8..b0b6d55d 100644 --- a/generators/objects/translateObjects.cpp +++ b/generators/objects/translateObjects.cpp @@ -1,8 +1,8 @@ /** - * @brief Auto-generated object translation file. + * @brief Auto-generated object translation file. * @details - * Contains 105 translations. - * Generated on: 2021-08-31 10:31:24 + * Contains 112 translations. + * Generated on: 2022-03-04 15:13:13 */ #include "translateObjects.h" @@ -12,6 +12,7 @@ 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"; @@ -23,8 +24,6 @@ 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_12_STRING = "SUS_12"; -const char *SUS_13_STRING = "SUS_13"; 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"; @@ -35,40 +34,42 @@ const char *RW3_STRING = "RW3"; const char *MGM_3_RM3100_HANDLER_STRING = "MGM_3_RM3100_HANDLER"; const char *GYRO_3_L3G_HANDLER_STRING = "GYRO_3_L3G_HANDLER"; const char *RW4_STRING = "RW4"; -const char *START_TRACKER_STRING = "START_TRACKER"; -const char *GPS0_HANDLER_STRING = "GPS0_HANDLER"; -const char *GPS1_HANDLER_STRING = "GPS1_HANDLER"; +const char *STAR_TRACKER_STRING = "STAR_TRACKER"; +const char *GPS_CONTROLLER_STRING = "GPS_CONTROLLER"; const char *IMTQ_HANDLER_STRING = "IMTQ_HANDLER"; const char *PCDU_HANDLER_STRING = "PCDU_HANDLER"; const char *P60DOCK_HANDLER_STRING = "P60DOCK_HANDLER"; const char *PDU1_HANDLER_STRING = "PDU1_HANDLER"; const char *PDU2_HANDLER_STRING = "PDU2_HANDLER"; const char *ACU_HANDLER_STRING = "ACU_HANDLER"; +const char *BPX_BATT_HANDLER_STRING = "BPX_BATT_HANDLER"; +const char *PLPCDU_HANDLER_STRING = "PLPCDU_HANDLER"; const char *RAD_SENSOR_STRING = "RAD_SENSOR"; 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_HANDLER_STRING = "PLOC_MPSOC_HANDLER"; const char *PLOC_SUPERVISOR_HANDLER_STRING = "PLOC_SUPERVISOR_HANDLER"; 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_IC3_STRING = "RTD_IC3"; -const char *RTD_IC4_STRING = "RTD_IC4"; -const char *RTD_IC5_STRING = "RTD_IC5"; -const char *RTD_IC6_STRING = "RTD_IC6"; -const char *RTD_IC7_STRING = "RTD_IC7"; -const char *RTD_IC8_STRING = "RTD_IC8"; -const char *RTD_IC9_STRING = "RTD_IC9"; -const char *RTD_IC10_STRING = "RTD_IC10"; -const char *RTD_IC11_STRING = "RTD_IC11"; -const char *RTD_IC12_STRING = "RTD_IC12"; -const char *RTD_IC13_STRING = "RTD_IC13"; -const char *RTD_IC14_STRING = "RTD_IC14"; -const char *RTD_IC15_STRING = "RTD_IC15"; -const char *RTD_IC16_STRING = "RTD_IC16"; -const char *RTD_IC17_STRING = "RTD_IC17"; -const char *RTD_IC18_STRING = "RTD_IC18"; +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 *SYRLINKS_HK_HANDLER_STRING = "SYRLINKS_HK_HANDLER"; const char *ARDUINO_COM_IF_STRING = "ARDUINO_COM_IF"; const char *GPIO_IF_STRING = "GPIO_IF"; @@ -81,6 +82,10 @@ const char *PUS_PACKET_DISTRIBUTOR_STRING = "PUS_PACKET_DISTRIBUTOR"; const char *TMTC_BRIDGE_STRING = "TMTC_BRIDGE"; const char *TMTC_POLLING_TASK_STRING = "TMTC_POLLING_TASK"; const char *FILE_SYSTEM_HANDLER_STRING = "FILE_SYSTEM_HANDLER"; +const char *SDC_MANAGER_STRING = "SDC_MANAGER"; +const char *PTME_STRING = "PTME"; +const char *PDEC_HANDLER_STRING = "PDEC_HANDLER"; +const char *CCSDS_HANDLER_STRING = "CCSDS_HANDLER"; const char *PUS_SERVICE_6_STRING = "PUS_SERVICE_6"; const char *FSFW_OBJECTS_START_STRING = "FSFW_OBJECTS_START"; const char *PUS_SERVICE_1_VERIFICATION_STRING = "PUS_SERVICE_1_VERIFICATION"; @@ -93,6 +98,7 @@ 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"; const char *PUS_SERVICE_201_HEALTH_STRING = "PUS_SERVICE_201_HEALTH"; +const char *CFDP_PACKET_DISTRIBUTOR_STRING = "CFDP_PACKET_DISTRIBUTOR"; const char *HEALTH_TABLE_STRING = "HEALTH_TABLE"; const char *MODE_STORE_STRING = "MODE_STORE"; const char *EVENT_MANAGER_STRING = "EVENT_MANAGER"; @@ -104,6 +110,7 @@ const char *TIME_STAMPER_STRING = "TIME_STAMPER"; 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_HANDLER_STRING = "DUMMY_HANDLER"; const char *DUMMY_INTERFACE_STRING = "DUMMY_INTERFACE"; const char *LIBGPIOD_TEST_STRING = "LIBGPIOD_TEST"; @@ -112,220 +119,234 @@ 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"; -const char* translateObject(object_id_t object) { - switch( (object & 0xFFFFFFFF) ) { - case 0x00005060: - return P60DOCK_TEST_TASK_STRING; - case 0x43000003: - return CORE_CONTROLLER_STRING; - case 0x43100002: - return ACS_CONTROLLER_STRING; - case 0x43400001: - return THERMAL_CONTROLLER_STRING; - case 0x44120006: - return MGM_0_LIS3_HANDLER_STRING; - case 0x44120010: - return GYRO_0_ADIS_HANDLER_STRING; - case 0x44120032: - return SUS_1_STRING; - case 0x44120033: - return SUS_2_STRING; - case 0x44120034: - return SUS_3_STRING; - case 0x44120035: - return SUS_4_STRING; - case 0x44120036: - return SUS_5_STRING; - case 0x44120037: - return SUS_6_STRING; - case 0x44120038: - return SUS_7_STRING; - case 0x44120039: - return SUS_8_STRING; - case 0x44120040: - return SUS_9_STRING; - case 0x44120041: - return SUS_10_STRING; - case 0x44120042: - return SUS_11_STRING; - case 0x44120043: - return SUS_12_STRING; - case 0x44120044: - return SUS_13_STRING; - case 0x44120047: - return RW1_STRING; - case 0x44120107: - return MGM_1_RM3100_HANDLER_STRING; - case 0x44120111: - return GYRO_1_L3G_HANDLER_STRING; - case 0x44120148: - return RW2_STRING; - case 0x44120208: - return MGM_2_LIS3_HANDLER_STRING; - case 0x44120212: - return GYRO_2_ADIS_HANDLER_STRING; - case 0x44120249: - return RW3_STRING; - case 0x44120309: - return MGM_3_RM3100_HANDLER_STRING; - case 0x44120313: - return GYRO_3_L3G_HANDLER_STRING; - case 0x44120350: - return RW4_STRING; - case 0x44130001: - return START_TRACKER_STRING; - case 0x44130045: - return GPS0_HANDLER_STRING; - case 0x44130146: - return GPS1_HANDLER_STRING; - case 0x44140014: - return IMTQ_HANDLER_STRING; - case 0x442000A1: - return PCDU_HANDLER_STRING; - case 0x44250000: - return P60DOCK_HANDLER_STRING; - case 0x44250001: - return PDU1_HANDLER_STRING; - case 0x44250002: - return PDU2_HANDLER_STRING; - case 0x44250003: - return ACU_HANDLER_STRING; - case 0x443200A5: - return RAD_SENSOR_STRING; - case 0x44330000: - return PLOC_UPDATER_STRING; - case 0x44330001: - return PLOC_MEMORY_DUMPER_STRING; - case 0x44330015: - return PLOC_MPSOC_HANDLER_STRING; - case 0x44330016: - return PLOC_SUPERVISOR_HANDLER_STRING; - case 0x444100A2: - return SOLAR_ARRAY_DEPL_HANDLER_STRING; - case 0x444100A4: - return HEATER_HANDLER_STRING; - case 0x44420004: - return TMP1075_HANDLER_1_STRING; - case 0x44420005: - return TMP1075_HANDLER_2_STRING; - case 0x44420016: - return RTD_IC3_STRING; - case 0x44420017: - return RTD_IC4_STRING; - case 0x44420018: - return RTD_IC5_STRING; - case 0x44420019: - return RTD_IC6_STRING; - case 0x44420020: - return RTD_IC7_STRING; - case 0x44420021: - return RTD_IC8_STRING; - case 0x44420022: - return RTD_IC9_STRING; - case 0x44420023: - return RTD_IC10_STRING; - case 0x44420024: - return RTD_IC11_STRING; - case 0x44420025: - return RTD_IC12_STRING; - case 0x44420026: - return RTD_IC13_STRING; - case 0x44420027: - return RTD_IC14_STRING; - case 0x44420028: - return RTD_IC15_STRING; - case 0x44420029: - return RTD_IC16_STRING; - case 0x44420030: - return RTD_IC17_STRING; - case 0x44420031: - return RTD_IC18_STRING; - case 0x445300A3: - return SYRLINKS_HK_HANDLER_STRING; - case 0x49000000: - return ARDUINO_COM_IF_STRING; - case 0x49010005: - return GPIO_IF_STRING; - case 0x49020004: - return SPI_COM_IF_STRING; - case 0x49030003: - return UART_COM_IF_STRING; - case 0x49040002: - return I2C_COM_IF_STRING; - case 0x49050001: - return CSP_COM_IF_STRING; - case 0x50000100: - return CCSDS_PACKET_DISTRIBUTOR_STRING; - case 0x50000200: - return PUS_PACKET_DISTRIBUTOR_STRING; - case 0x50000300: - return TMTC_BRIDGE_STRING; - case 0x50000400: - return TMTC_POLLING_TASK_STRING; - case 0x50000500: - return FILE_SYSTEM_HANDLER_STRING; - case 0x51000500: - return PUS_SERVICE_6_STRING; - case 0x53000000: - return FSFW_OBJECTS_START_STRING; - case 0x53000001: - return PUS_SERVICE_1_VERIFICATION_STRING; - case 0x53000002: - return PUS_SERVICE_2_DEVICE_ACCESS_STRING; - case 0x53000003: - return PUS_SERVICE_3_HOUSEKEEPING_STRING; - case 0x53000005: - return PUS_SERVICE_5_EVENT_REPORTING_STRING; - case 0x53000008: - return PUS_SERVICE_8_FUNCTION_MGMT_STRING; - case 0x53000009: - return PUS_SERVICE_9_TIME_MGMT_STRING; - case 0x53000017: - return PUS_SERVICE_17_TEST_STRING; - case 0x53000020: - return PUS_SERVICE_20_PARAMETERS_STRING; - case 0x53000200: - return PUS_SERVICE_200_MODE_MGMT_STRING; - case 0x53000201: - return PUS_SERVICE_201_HEALTH_STRING; - case 0x53010000: - return HEALTH_TABLE_STRING; - case 0x53010100: - return MODE_STORE_STRING; - case 0x53030000: - return EVENT_MANAGER_STRING; - case 0x53040000: - return INTERNAL_ERROR_REPORTER_STRING; - case 0x534f0100: - return TC_STORE_STRING; - case 0x534f0200: - return TM_STORE_STRING; - case 0x534f0300: - return IPC_STORE_STRING; - case 0x53500010: - return TIME_STAMPER_STRING; - case 0x53ffffff: - return FSFW_OBJECTS_END_STRING; - case 0x54000010: - return SPI_TEST_STRING; - case 0x54000020: - return UART_TEST_STRING; - case 0x5400AFFE: - return DUMMY_HANDLER_STRING; - case 0x5400CAFE: - return DUMMY_INTERFACE_STRING; - case 0x54123456: - return LIBGPIOD_TEST_STRING; - case 0x54694269: - return TEST_TASK_STRING; - case 0x73000100: - return TM_FUNNEL_STRING; - case 0x73500000: - return CCSDS_IP_CORE_BRIDGE_STRING; - case 0xFFFFFFFF: - return NO_OBJECT_STRING; - default: - return "UNKNOWN_OBJECT"; - } - return 0; +const char *translateObject(object_id_t object) { + switch ((object & 0xFFFFFFFF)) { + case 0x00005060: + return P60DOCK_TEST_TASK_STRING; + case 0x43000003: + return CORE_CONTROLLER_STRING; + case 0x43100002: + return ACS_CONTROLLER_STRING; + case 0x43400001: + return THERMAL_CONTROLLER_STRING; + case 0x44120006: + return MGM_0_LIS3_HANDLER_STRING; + case 0x44120010: + return GYRO_0_ADIS_HANDLER_STRING; + case 0x44120032: + return SUS_0_STRING; + case 0x44120033: + return SUS_1_STRING; + case 0x44120034: + return SUS_2_STRING; + case 0x44120035: + return SUS_3_STRING; + case 0x44120036: + return SUS_4_STRING; + case 0x44120037: + return SUS_5_STRING; + case 0x44120038: + return SUS_6_STRING; + case 0x44120039: + return SUS_7_STRING; + case 0x44120040: + return SUS_8_STRING; + case 0x44120041: + return SUS_9_STRING; + case 0x44120042: + return SUS_10_STRING; + case 0x44120043: + return SUS_11_STRING; + case 0x44120047: + return RW1_STRING; + case 0x44120107: + return MGM_1_RM3100_HANDLER_STRING; + case 0x44120111: + return GYRO_1_L3G_HANDLER_STRING; + case 0x44120148: + return RW2_STRING; + case 0x44120208: + return MGM_2_LIS3_HANDLER_STRING; + case 0x44120212: + return GYRO_2_ADIS_HANDLER_STRING; + case 0x44120249: + return RW3_STRING; + case 0x44120309: + return MGM_3_RM3100_HANDLER_STRING; + case 0x44120313: + return GYRO_3_L3G_HANDLER_STRING; + case 0x44120350: + return RW4_STRING; + case 0x44130001: + return STAR_TRACKER_STRING; + case 0x44130045: + return GPS_CONTROLLER_STRING; + case 0x44140014: + return IMTQ_HANDLER_STRING; + case 0x442000A1: + return PCDU_HANDLER_STRING; + case 0x44250000: + return P60DOCK_HANDLER_STRING; + case 0x44250001: + return PDU1_HANDLER_STRING; + case 0x44250002: + return PDU2_HANDLER_STRING; + case 0x44250003: + return ACU_HANDLER_STRING; + case 0x44260000: + return BPX_BATT_HANDLER_STRING; + case 0x44300000: + return PLPCDU_HANDLER_STRING; + case 0x443200A5: + return RAD_SENSOR_STRING; + case 0x44330000: + return PLOC_UPDATER_STRING; + case 0x44330001: + return PLOC_MEMORY_DUMPER_STRING; + case 0x44330002: + return STR_HELPER_STRING; + case 0x44330015: + return PLOC_MPSOC_HANDLER_STRING; + case 0x44330016: + return PLOC_SUPERVISOR_HANDLER_STRING; + case 0x444100A2: + return SOLAR_ARRAY_DEPL_HANDLER_STRING; + case 0x444100A4: + return HEATER_HANDLER_STRING; + case 0x44420004: + return TMP1075_HANDLER_1_STRING; + case 0x44420005: + return TMP1075_HANDLER_2_STRING; + case 0x44420016: + return RTD_IC_3_STRING; + case 0x44420017: + return RTD_IC_4_STRING; + case 0x44420018: + return RTD_IC_5_STRING; + case 0x44420019: + return RTD_IC_6_STRING; + case 0x44420020: + return RTD_IC_7_STRING; + case 0x44420021: + return RTD_IC_8_STRING; + case 0x44420022: + return RTD_IC_9_STRING; + case 0x44420023: + return RTD_IC_10_STRING; + case 0x44420024: + return RTD_IC_11_STRING; + case 0x44420025: + return RTD_IC_12_STRING; + case 0x44420026: + return RTD_IC_13_STRING; + case 0x44420027: + return RTD_IC_14_STRING; + case 0x44420028: + return RTD_IC_15_STRING; + case 0x44420029: + return RTD_IC_16_STRING; + case 0x44420030: + return RTD_IC_17_STRING; + case 0x44420031: + return RTD_IC_18_STRING; + case 0x445300A3: + return SYRLINKS_HK_HANDLER_STRING; + case 0x49000000: + return ARDUINO_COM_IF_STRING; + case 0x49010005: + return GPIO_IF_STRING; + case 0x49020004: + return SPI_COM_IF_STRING; + case 0x49030003: + return UART_COM_IF_STRING; + case 0x49040002: + return I2C_COM_IF_STRING; + case 0x49050001: + return CSP_COM_IF_STRING; + case 0x50000100: + return CCSDS_PACKET_DISTRIBUTOR_STRING; + case 0x50000200: + return PUS_PACKET_DISTRIBUTOR_STRING; + case 0x50000300: + return TMTC_BRIDGE_STRING; + case 0x50000400: + return TMTC_POLLING_TASK_STRING; + case 0x50000500: + return FILE_SYSTEM_HANDLER_STRING; + case 0x50000550: + return SDC_MANAGER_STRING; + case 0x50000600: + return PTME_STRING; + case 0x50000700: + return PDEC_HANDLER_STRING; + case 0x50000800: + return CCSDS_HANDLER_STRING; + case 0x51000500: + return PUS_SERVICE_6_STRING; + case 0x53000000: + return FSFW_OBJECTS_START_STRING; + case 0x53000001: + return PUS_SERVICE_1_VERIFICATION_STRING; + case 0x53000002: + return PUS_SERVICE_2_DEVICE_ACCESS_STRING; + case 0x53000003: + return PUS_SERVICE_3_HOUSEKEEPING_STRING; + case 0x53000005: + return PUS_SERVICE_5_EVENT_REPORTING_STRING; + case 0x53000008: + return PUS_SERVICE_8_FUNCTION_MGMT_STRING; + case 0x53000009: + return PUS_SERVICE_9_TIME_MGMT_STRING; + case 0x53000017: + return PUS_SERVICE_17_TEST_STRING; + case 0x53000020: + return PUS_SERVICE_20_PARAMETERS_STRING; + case 0x53000200: + return PUS_SERVICE_200_MODE_MGMT_STRING; + case 0x53000201: + return PUS_SERVICE_201_HEALTH_STRING; + case 0x53001000: + return CFDP_PACKET_DISTRIBUTOR_STRING; + case 0x53010000: + return HEALTH_TABLE_STRING; + case 0x53010100: + return MODE_STORE_STRING; + case 0x53030000: + return EVENT_MANAGER_STRING; + case 0x53040000: + return INTERNAL_ERROR_REPORTER_STRING; + case 0x534f0100: + return TC_STORE_STRING; + case 0x534f0200: + return TM_STORE_STRING; + case 0x534f0300: + return IPC_STORE_STRING; + case 0x53500010: + return TIME_STAMPER_STRING; + case 0x53ffffff: + return FSFW_OBJECTS_END_STRING; + case 0x54000010: + return SPI_TEST_STRING; + case 0x54000020: + return UART_TEST_STRING; + case 0x54000030: + return I2C_TEST_STRING; + case 0x5400AFFE: + return DUMMY_HANDLER_STRING; + case 0x5400CAFE: + return DUMMY_INTERFACE_STRING; + case 0x54123456: + return LIBGPIOD_TEST_STRING; + case 0x54694269: + return TEST_TASK_STRING; + case 0x73000100: + return TM_FUNNEL_STRING; + case 0x73500000: + return CCSDS_IP_CORE_BRIDGE_STRING; + case 0xFFFFFFFF: + return NO_OBJECT_STRING; + default: + return "UNKNOWN_OBJECT"; + } + return 0; } diff --git a/generators/objects/translateObjects.h b/generators/objects/translateObjects.h index dbf5b468..257912f4 100644 --- a/generators/objects/translateObjects.h +++ b/generators/objects/translateObjects.h @@ -3,6 +3,6 @@ #include -const char* translateObject(object_id_t object); +const char *translateObject(object_id_t object); #endif /* FSFWCONFIG_OBJECTS_TRANSLATEOBJECTS_H_ */ diff --git a/generators/requirements.txt b/generators/requirements.txt new file mode 100644 index 00000000..0aa54598 --- /dev/null +++ b/generators/requirements.txt @@ -0,0 +1 @@ +colorlog>=5.0.0 diff --git a/generators/returnvalues/returnvalues_parser.py b/generators/returnvalues/returnvalues_parser.py index eadb035f..48d929ea 100644 --- a/generators/returnvalues/returnvalues_parser.py +++ b/generators/returnvalues/returnvalues_parser.py @@ -5,11 +5,13 @@ :brief: Part of the MOD export tools for the SOURCE project by KSat. TODO: Integrate into Parser Structure instead of calling this file (no cpp file generated yet) :details: -Returnvalue exporter. -To use MySQLdb, run pip install mysqlclient or install in IDE. On Windows, Build Tools installation might be necessary. +Return Value exporter. +To use MySQLdb, run pip install mysqlclient or install in IDE. On Windows, Build Tools +installation might be necessary. :data: 21.11.2019 """ from fsfwgen.core 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.utility.sql_writer import SqlWriter @@ -19,38 +21,40 @@ from definitions import BspType, DATABASE_NAME, ROOT_DIR, OBSW_ROOT_DIR LOGGER = get_console_logger() EXPORT_TO_FILE = True -MOVE_CSV_FILE = True +COPY_CSV_FILE = True EXPORT_TO_SQL = True PRINT_TABLES = True -FILE_SEPARATOR = ';' +FILE_SEPARATOR = ";" MAX_STRING_LENGTH = 32 BSP_SELECT = BspType.BSP_Q7S BSP_DIR_NAME = BSP_SELECT.value -CSV_RETVAL_FILENAME = f'{BSP_SELECT.value}_returnvalues.csv' -CSV_MOVE_DESTINATION = f'{ROOT_DIR}' +CSV_RETVAL_FILENAME = f"{ROOT_DIR}/{BSP_SELECT.value}_returnvalues.csv" +CSV_COPY_DEST = 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: - FSFW_CONFIG_ROOT = f'{OBSW_ROOT_DIR}/linux/fsfwconfig' + FSFW_CONFIG_ROOT = f"{OBSW_ROOT_DIR}/linux/fsfwconfig" ADD_LINUX_FOLDER = True else: - FSFW_CONFIG_ROOT = f'{OBSW_ROOT_DIR}/{BSP_DIR_NAME}/fsfwconfig' + FSFW_CONFIG_ROOT = f"{OBSW_ROOT_DIR}/{BSP_DIR_NAME}/fsfwconfig" BSP_PATH = f"{OBSW_ROOT_DIR}/{BSP_DIR_NAME}" INTERFACE_DEFINITION_FILES = [ - f'{OBSW_ROOT_DIR}/fsfw/src/fsfw/returnvalues/FwClassIds.h', - f'{OBSW_ROOT_DIR}/common/config/commonClassIds.h', - f'{FSFW_CONFIG_ROOT}/returnvalues/classIds.h' + f"{OBSW_ROOT_DIR}/fsfw/src/fsfw/returnvalues/FwClassIds.h", + f"{OBSW_ROOT_DIR}/common/config/commonClassIds.h", + f"{FSFW_CONFIG_ROOT}/returnvalues/classIds.h", ] RETURNVALUE_SOURCES = [ - f'{OBSW_ROOT_DIR}/mission/', f'{OBSW_ROOT_DIR}/fsfw/', f'{BSP_PATH}' + f"{OBSW_ROOT_DIR}/mission/", + f"{OBSW_ROOT_DIR}/fsfw/", + f"{BSP_PATH}", ] if ADD_LINUX_FOLDER: - RETURNVALUE_SOURCES.append(f'{OBSW_ROOT_DIR}/linux') + RETURNVALUE_SOURCES.append(f"{OBSW_ROOT_DIR}/linux") SQL_DELETE_RETURNVALUES_CMD = """ DROP TABLE IF EXISTS Returnvalues @@ -76,16 +80,24 @@ VALUES(?,?,?,?,?) def parse_returnvalues(): returnvalue_table = generate_returnvalue_table() if EXPORT_TO_FILE: - ReturnValueParser.export_to_file(CSV_RETVAL_FILENAME, returnvalue_table, FILE_SEPARATOR) - # if MOVE_CSV_FILE: - # move_file(file_name=CSV_RETVAL_FILENAME, destination=CSV_MOVE_DESTINATION) + ReturnValueParser.export_to_file( + CSV_RETVAL_FILENAME, returnvalue_table, FILE_SEPARATOR + ) + if COPY_CSV_FILE: + copy_file( + filename=CSV_RETVAL_FILENAME, + destination=CSV_COPY_DEST, + delete_existing_file=True + ) if EXPORT_TO_SQL: - LOGGER.info('ReturnvalueParser: Exporting to SQL') - sql_retval_exporter(returnvalue_table, db_filename=f"{ROOT_DIR}/{DATABASE_NAME}") + LOGGER.info("ReturnvalueParser: Exporting to SQL") + sql_retval_exporter( + returnvalue_table, db_filename=f"{ROOT_DIR}/{DATABASE_NAME}" + ) def generate_returnvalue_table(): - """ Core function to parse for the return values """ + """Core function to parse for the return values""" interface_parser = InterfaceParser( file_list=INTERFACE_DEFINITION_FILES, print_table=PRINT_TABLES ) @@ -93,6 +105,7 @@ def generate_returnvalue_table(): header_parser = FileListParser(RETURNVALUE_SOURCES) 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 returnvalue_parser.set_moving_window_mode(moving_window_size=7) returnvalue_table = returnvalue_parser.parse_files(True) LOGGER.info(f"ReturnvalueParser: Found {len(returnvalue_table)} returnvalues") @@ -104,10 +117,8 @@ def sql_retval_exporter(returnvalue_table, db_filename: str): 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])) + SQL_INSERT_RETURNVALUES_CMD, + (entry[0], entry[1][2], entry[1][4], entry[1][3], entry[1][1]), + ) sql_writer.commit() sql_writer.close() diff --git a/linux/archive/gpio/GpioCookie.cpp b/linux/archive/gpio/GpioCookie.cpp deleted file mode 100644 index c729502b..00000000 --- a/linux/archive/gpio/GpioCookie.cpp +++ /dev/null @@ -1,34 +0,0 @@ -#include "GpioCookie.h" -#include - -GpioCookie::GpioCookie() { -} - -ReturnValue_t GpioCookie::addGpio(gpioId_t gpioId, GpioBase* gpioConfig){ - if (gpioConfig == nullptr) { - sif::debug << "GpioCookie::addGpio: gpioConfig is nullpointer" << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; - } - auto gpioMapIter = gpioMap.find(gpioId); - if(gpioMapIter == gpioMap.end()) { - auto statusPair = gpioMap.emplace(gpioId, gpioConfig); - if (statusPair.second == false) { -#if FSFW_VERBOSE_LEVEL >= 1 - sif::error << "GpioCookie::addGpio: Failed to add GPIO " << gpioId << - " to GPIO map" << std::endl; -#endif - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_OK; - } -#if FSFW_VERBOSE_LEVEL >= 1 - sif::error << "GpioCookie::addGpio: GPIO already exists in GPIO map " << std::endl; -#endif - return HasReturnvaluesIF::RETURN_FAILED; -} - -GpioMap GpioCookie::getGpioMap() const { - return gpioMap; -} - -GpioCookie::~GpioCookie() {} diff --git a/linux/archive/gpio/GpioIF.h b/linux/archive/gpio/GpioIF.h deleted file mode 100644 index 75feb3ce..00000000 --- a/linux/archive/gpio/GpioIF.h +++ /dev/null @@ -1,54 +0,0 @@ -#ifndef LINUX_GPIO_GPIOIF_H_ -#define LINUX_GPIO_GPIOIF_H_ - -#include "gpioDefinitions.h" -#include -#include - -class GpioCookie; - -/** - * @brief This class defines the interface for objects requiring the control - * over GPIOs. - * @author J. Meier - */ -class GpioIF : public HasReturnvaluesIF { -public: - - virtual ~GpioIF() {}; - - /** - * @brief Called by the GPIO using object. - * @param cookie Cookie specifying informations of the GPIOs required - * by a object. - */ - virtual ReturnValue_t addGpios(GpioCookie* cookie) = 0; - - /** - * @brief By implementing this function a child must provide the - * functionality to pull a certain GPIO to high logic level. - * - * @param gpioId A unique number which specifies the GPIO to drive. - * @return Returns RETURN_OK for success. This should never return RETURN_FAILED. - */ - virtual ReturnValue_t pullHigh(gpioId_t gpioId) = 0; - - /** - * @brief By implementing this function a child must provide the - * functionality to pull a certain GPIO to low logic level. - * - * @param gpioId A unique number which specifies the GPIO to drive. - */ - virtual ReturnValue_t pullLow(gpioId_t gpioId) = 0; - - /** - * @brief This function requires a child to implement the functionality to read the state of - * an ouput or input gpio. - * - * @param gpioId A unique number which specifies the GPIO to read. - * @param gpioState State of GPIO will be written to this pointer. - */ - virtual ReturnValue_t readGpio(gpioId_t gpioId, int* gpioState) = 0; -}; - -#endif /* LINUX_GPIO_GPIOIF_H_ */ diff --git a/linux/archive/gpio/LinuxLibgpioIF.cpp b/linux/archive/gpio/LinuxLibgpioIF.cpp deleted file mode 100644 index 92ffa63c..00000000 --- a/linux/archive/gpio/LinuxLibgpioIF.cpp +++ /dev/null @@ -1,302 +0,0 @@ -#include "LinuxLibgpioIF.h" -#include "GpioCookie.h" - -#include -#include - -#include -#include -#include - - -LinuxLibgpioIF::LinuxLibgpioIF(object_id_t objectId) : SystemObject(objectId) { - struct gpiod_chip* chip = gpiod_chip_open_by_label("/amba_pl/gpio@42030000"); - - sif::debug << chip->name << std::endl; -} - -LinuxLibgpioIF::~LinuxLibgpioIF() { -} - -ReturnValue_t LinuxLibgpioIF::addGpios(GpioCookie* gpioCookie) { - ReturnValue_t result; - if(gpioCookie == nullptr) { - sif::error << "LinuxLibgpioIF::initialize: Invalid cookie" << std::endl; - return RETURN_FAILED; - } - - GpioMap mapToAdd = gpioCookie->getGpioMap(); - - /* Check whether this ID already exists in the map and remove duplicates */ - result = checkForConflicts(mapToAdd); - if (result != RETURN_OK){ - return result; - } - - result = configureGpios(mapToAdd); - if (result != RETURN_OK) { - return RETURN_FAILED; - } - - /* Register new GPIOs in gpioMap */ - gpioMap.insert(mapToAdd.begin(), mapToAdd.end()); - - return RETURN_OK; -} - -ReturnValue_t LinuxLibgpioIF::configureGpios(GpioMap& mapToAdd) { - for(auto& gpioConfig: mapToAdd) { - switch(gpioConfig.second->gpioType) { - case(gpio::GpioTypes::NONE): { - return GPIO_INVALID_INSTANCE; - } - case(gpio::GpioTypes::GPIOD_REGULAR): { - GpiodRegular* regularGpio = dynamic_cast(gpioConfig.second); - if(regularGpio == nullptr) { - return GPIO_INVALID_INSTANCE; - } - configureRegularGpio(gpioConfig.first, regularGpio); - break; - } - case(gpio::GpioTypes::CALLBACK): { - auto gpioCallback = dynamic_cast(gpioConfig.second); - if(gpioCallback->callback == nullptr) { - return GPIO_INVALID_INSTANCE; - } - gpioCallback->callback(gpioConfig.first, gpio::GpioOperation::WRITE, - gpioCallback->initValue, gpioCallback->callbackArgs); - } - } - } - return RETURN_OK; -} - -ReturnValue_t LinuxLibgpioIF::configureRegularGpio(gpioId_t gpioId, GpiodRegular *regularGpio) { - std::string chipname; - unsigned int lineNum; - struct gpiod_chip *chip; - gpio::Direction direction; - std::string consumer; - struct gpiod_line *lineHandle; - int result = 0; - - chipname = regularGpio->chipname; - chip = gpiod_chip_open_by_name(chipname.c_str()); - if (!chip) { - sif::error << "LinuxLibgpioIF::configureGpios: Failed to open chip " - << chipname << ". Gpio ID: " << gpioId << std::endl; - return RETURN_FAILED; - } - - lineNum = regularGpio->lineNum; - lineHandle = gpiod_chip_get_line(chip, lineNum); - if (!lineHandle) { - sif::error << "LinuxLibgpioIF::configureGpios: Failed to open line for GPIO with id " - << gpioId << std::endl; - gpiod_chip_close(chip); - return RETURN_FAILED; - } - - direction = regularGpio->direction; - consumer = regularGpio->consumer; - /* Configure direction and add a description to the GPIO */ - switch (direction) { - case(gpio::OUT): { - result = gpiod_line_request_output(lineHandle, consumer.c_str(), - regularGpio->initValue); - if (result < 0) { - sif::error << "LinuxLibgpioIF::configureGpios: Failed to request line " << lineNum << - " from GPIO instance with ID: " << gpioId << std::endl; - gpiod_line_release(lineHandle); - return RETURN_FAILED; - } - break; - } - case(gpio::IN): { - result = gpiod_line_request_input(lineHandle, consumer.c_str()); - if (result < 0) { - sif::error << "LinuxLibgpioIF::configureGpios: Failed to request line " - << lineNum << " from GPIO instance with ID: " << gpioId << std::endl; - gpiod_line_release(lineHandle); - return RETURN_FAILED; - } - break; - } - default: { - sif::error << "LinuxLibgpioIF::configureGpios: Invalid direction specified" - << std::endl; - return GPIO_INVALID_INSTANCE; - } - - } - /** - * Write line handle to GPIO configuration instance so it can later be used to set or - * read states of GPIOs. - */ - regularGpio->lineHandle = lineHandle; - return RETURN_OK; -} - -ReturnValue_t LinuxLibgpioIF::pullHigh(gpioId_t gpioId) { - gpioMapIter = gpioMap.find(gpioId); - if (gpioMapIter == gpioMap.end()) { - sif::warning << "LinuxLibgpioIF::driveGpio: Unknown GPIOD ID " << gpioId << std::endl; - return UNKNOWN_GPIO_ID; - } - - if(gpioMapIter->second->gpioType == gpio::GpioTypes::GPIOD_REGULAR) { - return driveGpio(gpioId, dynamic_cast(gpioMapIter->second), 1); - } - else { - auto gpioCallback = dynamic_cast(gpioMapIter->second); - if(gpioCallback->callback == nullptr) { - return GPIO_INVALID_INSTANCE; - } - gpioCallback->callback(gpioMapIter->first, gpio::GpioOperation::WRITE, - 1, gpioCallback->callbackArgs); - } - return GPIO_TYPE_FAILURE; -} - -ReturnValue_t LinuxLibgpioIF::pullLow(gpioId_t gpioId) { - gpioMapIter = gpioMap.find(gpioId); - if (gpioMapIter == gpioMap.end()) { - sif::warning << "LinuxLibgpioIF::driveGpio: Unknown GPIOD ID " << gpioId << std::endl; - return UNKNOWN_GPIO_ID; - } - - if(gpioMapIter->second->gpioType == gpio::GpioTypes::GPIOD_REGULAR) { - return driveGpio(gpioId, dynamic_cast(gpioMapIter->second), 0); - } - else { - auto gpioCallback = dynamic_cast(gpioMapIter->second); - if(gpioCallback->callback == nullptr) { - return GPIO_INVALID_INSTANCE; - } - gpioCallback->callback(gpioMapIter->first, gpio::GpioOperation::WRITE, - 0, gpioCallback->callbackArgs); - } - return GPIO_TYPE_FAILURE; -} - -ReturnValue_t LinuxLibgpioIF::driveGpio(gpioId_t gpioId, - GpiodRegular* regularGpio, unsigned int logicLevel) { - if(regularGpio == nullptr) { - return GPIO_TYPE_FAILURE; - } - - int result = gpiod_line_set_value(regularGpio->lineHandle, logicLevel); - if (result < 0) { - sif::warning << "LinuxLibgpioIF::driveGpio: Failed to pull GPIO with ID " << gpioId << - " to logic level " << logicLevel << std::endl; - return DRIVE_GPIO_FAILURE; - } - - return RETURN_OK; -} - -ReturnValue_t LinuxLibgpioIF::readGpio(gpioId_t gpioId, int* gpioState) { - gpioMapIter = gpioMap.find(gpioId); - if (gpioMapIter == gpioMap.end()){ - sif::warning << "LinuxLibgpioIF::readGpio: Unknown GPIOD ID " << gpioId << std::endl; - return UNKNOWN_GPIO_ID; - } - - if(gpioMapIter->second->gpioType == gpio::GpioTypes::GPIOD_REGULAR) { - GpiodRegular* regularGpio = dynamic_cast(gpioMapIter->second); - if(regularGpio == nullptr) { - return GPIO_TYPE_FAILURE; - } - *gpioState = gpiod_line_get_value(regularGpio->lineHandle); - } - else { - - } - - - return RETURN_OK; -} - -ReturnValue_t LinuxLibgpioIF::checkForConflicts(GpioMap& mapToAdd){ - ReturnValue_t status = HasReturnvaluesIF::RETURN_OK; - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - for(auto& gpioConfig: mapToAdd) { - switch(gpioConfig.second->gpioType) { - case(gpio::GpioTypes::GPIOD_REGULAR): { - auto regularGpio = dynamic_cast(gpioConfig.second); - if(regularGpio == nullptr) { - return GPIO_TYPE_FAILURE; - } - /* Check for conflicts and remove duplicates if necessary */ - result = checkForConflictsRegularGpio(gpioConfig.first, regularGpio, mapToAdd); - if(result != HasReturnvaluesIF::RETURN_OK) { - status = result; - } - break; - } - case(gpio::GpioTypes::CALLBACK): { - auto callbackGpio = dynamic_cast(gpioConfig.second); - if(callbackGpio == nullptr) { - return GPIO_TYPE_FAILURE; - } - /* Check for conflicts and remove duplicates if necessary */ - result = checkForConflictsCallbackGpio(gpioConfig.first, callbackGpio, mapToAdd); - if(result != HasReturnvaluesIF::RETURN_OK) { - status = result; - } - break; - } - default: { - - } - } - } - return status; -} - - -ReturnValue_t LinuxLibgpioIF::checkForConflictsRegularGpio(gpioId_t gpioIdToCheck, - GpiodRegular* gpioToCheck, GpioMap& mapToAdd) { - /* Cross check with private map */ - gpioMapIter = gpioMap.find(gpioIdToCheck); - if(gpioMapIter != gpioMap.end()) { - if(gpioMapIter->second->gpioType != gpio::GpioTypes::GPIOD_REGULAR) { - sif::warning << "LinuxLibgpioIF::checkForConflicts: ID already exists for different " - "GPIO type" << gpioIdToCheck << ". Removing duplicate." << std::endl; - mapToAdd.erase(gpioIdToCheck); - return HasReturnvaluesIF::RETURN_OK; - } - auto ownRegularGpio = dynamic_cast(gpioMapIter->second); - if(ownRegularGpio == nullptr) { - return GPIO_TYPE_FAILURE; - } - - /* Remove element from map to add because a entry for this GPIO - already exists */ - sif::warning << "LinuxLibgpioIF::checkForConflictsRegularGpio: Duplicate GPIO definition" - << " detected. Duplicate will be removed from map to add." << std::endl; - mapToAdd.erase(gpioIdToCheck); - } - return HasReturnvaluesIF::RETURN_OK; -} - -ReturnValue_t LinuxLibgpioIF::checkForConflictsCallbackGpio(gpioId_t gpioIdToCheck, - GpioCallback *callbackGpio, GpioMap& mapToAdd) { - /* Cross check with private map */ - gpioMapIter = gpioMap.find(gpioIdToCheck); - if(gpioMapIter != gpioMap.end()) { - if(gpioMapIter->second->gpioType != gpio::GpioTypes::CALLBACK) { - sif::warning << "LinuxLibgpioIF::checkForConflicts: ID already exists for different " - "GPIO type" << gpioIdToCheck << ". Removing duplicate." << std::endl; - mapToAdd.erase(gpioIdToCheck); - return HasReturnvaluesIF::RETURN_OK; - } - - /* Remove element from map to add because a entry for this GPIO - already exists */ - sif::warning << "LinuxLibgpioIF::checkForConflictsRegularGpio: Duplicate GPIO definition" - << " detected. Duplicate will be removed from map to add." << std::endl; - mapToAdd.erase(gpioIdToCheck); - } - return HasReturnvaluesIF::RETURN_OK; -} diff --git a/linux/archive/gpio/LinuxLibgpioIF.h b/linux/archive/gpio/LinuxLibgpioIF.h deleted file mode 100644 index 9c444e50..00000000 --- a/linux/archive/gpio/LinuxLibgpioIF.h +++ /dev/null @@ -1,77 +0,0 @@ -#ifndef LINUX_GPIO_LINUXLIBGPIOIF_H_ -#define LINUX_GPIO_LINUXLIBGPIOIF_H_ - -#include -#include -#include - -class GpioCookie; - -/** - * @brief This class implements the GpioIF for a linux based system. The - * implementation is based on the libgpiod lib which requires linux 4.8 - * or higher. - * @note The Petalinux SDK from Xilinx supports libgpiod since Petalinux - * 2019.1. - */ -class LinuxLibgpioIF : public GpioIF, public SystemObject { -public: - - static const uint8_t gpioRetvalId = CLASS_ID::LINUX_LIBGPIO_IF; - - static constexpr ReturnValue_t UNKNOWN_GPIO_ID = - HasReturnvaluesIF::makeReturnCode(gpioRetvalId, 1); - static constexpr ReturnValue_t DRIVE_GPIO_FAILURE = - HasReturnvaluesIF::makeReturnCode(gpioRetvalId, 2); - static constexpr ReturnValue_t GPIO_TYPE_FAILURE = - HasReturnvaluesIF::makeReturnCode(gpioRetvalId, 3); - static constexpr ReturnValue_t GPIO_INVALID_INSTANCE = - HasReturnvaluesIF::makeReturnCode(gpioRetvalId, 4); - - LinuxLibgpioIF(object_id_t objectId); - virtual ~LinuxLibgpioIF(); - - ReturnValue_t addGpios(GpioCookie* gpioCookie) override; - ReturnValue_t pullHigh(gpioId_t gpioId) override; - ReturnValue_t pullLow(gpioId_t gpioId) override; - ReturnValue_t readGpio(gpioId_t gpioId, int* gpioState) override; - -private: - /* Holds the information and configuration of all used GPIOs */ - GpioMap gpioMap; - GpioMapIter gpioMapIter; - - /** - * @brief This functions drives line of a GPIO specified by the GPIO ID. - * - * @param gpioId The GPIO ID of the GPIO to drive. - * @param logiclevel The logic level to set. O or 1. - */ - ReturnValue_t driveGpio(gpioId_t gpioId, GpiodRegularBase& regularGpio, unsigned int logiclevel); - - ReturnValue_t configureRegularGpio(gpioId_t gpioId, GpiodRegularBase& regularGpio); - - /** - * @brief This function checks if GPIOs are already registered and whether - * there exists a conflict in the GPIO configuration. E.g. the - * direction. - * - * @param mapToAdd The GPIOs which shall be added to the gpioMap. - * - * @return RETURN_OK if successful, otherwise RETURN_FAILED - */ - ReturnValue_t checkForConflicts(GpioMap& mapToAdd); - - ReturnValue_t checkForConflictsRegularGpio(gpioId_t gpiodId, GpiodRegular* regularGpio, - GpioMap& mapToAdd); - ReturnValue_t checkForConflictsCallbackGpio(gpioId_t gpiodId, GpioCallback* regularGpio, - GpioMap& mapToAdd); - - /** - * @brief Performs the initial configuration of all GPIOs specified in the GpioMap mapToAdd. - */ - ReturnValue_t configureGpios(GpioMap& mapToAdd); - -}; - -#endif /* LINUX_GPIO_LINUXLIBGPIOIF_H_ */ diff --git a/linux/archive/gpio/gpioDefinitions.h b/linux/archive/gpio/gpioDefinitions.h deleted file mode 100644 index 66c0b005..00000000 --- a/linux/archive/gpio/gpioDefinitions.h +++ /dev/null @@ -1,98 +0,0 @@ -#ifndef LINUX_GPIO_GPIODEFINITIONS_H_ -#define LINUX_GPIO_GPIODEFINITIONS_H_ - -#include -#include - -using gpioId_t = uint16_t; - -namespace gpio { - -enum Levels { - LOW = 0, - HIGH = 1 -}; - -enum Direction { - IN = 0, - OUT = 1 -}; - -enum GpioOperation { - READ, - WRITE -}; - -enum GpioTypes { - NONE, - GPIOD_REGULAR, - CALLBACK -}; - -static constexpr gpioId_t NO_GPIO = -1; -} - -/** - * @brief Struct containing information about the GPIO to use. This is - * required by the libgpiod to access and drive a GPIO. - * @param chipname String of the chipname specifying the group which contains the GPIO to - * access. E.g. gpiochip0. To detect names of GPIO groups run gpiodetect on - * the linux command line. - * @param lineNum The offset of the GPIO within the GPIO group. - * @param consumer Name of the consumer. Simply a description of the GPIO configuration. - * @param direction Specifies whether the GPIO should be used as in- or output. - * @param initValue Defines the initial state of the GPIO when configured as output. - * Only required for output GPIOs. - * @param lineHandle The handle returned by gpiod_chip_get_line will be later written to this - * pointer. - */ -class GpioBase { -public: - - GpioBase() = default; - - GpioBase(gpio::GpioTypes gpioType, std::string consumer, gpio::Direction direction, - int initValue): - gpioType(gpioType), consumer(consumer),direction(direction), initValue(initValue) {} - - virtual~ GpioBase() {}; - - /* Can be used to cast GpioBase to a concrete child implementation */ - gpio::GpioTypes gpioType = gpio::GpioTypes::NONE; - std::string consumer; - gpio::Direction direction = gpio::Direction::IN; - int initValue = 0; -}; - -class GpiodRegular: public GpioBase { -public: - GpiodRegular(): GpioBase(gpio::GpioTypes::GPIOD_REGULAR, std::string(), - gpio::Direction::IN, 0) {}; - - GpiodRegular(std::string chipname_, int lineNum_, std::string consumer_, - gpio::Direction direction_, int initValue_): - GpioBase(gpio::GpioTypes::GPIOD_REGULAR, consumer_, direction_, initValue_), - chipname(chipname_), lineNum(lineNum_) {} - std::string chipname; - int lineNum = 0; - struct gpiod_line* lineHandle = nullptr; -}; - -class GpioCallback: public GpioBase { -public: - GpioCallback(std::string consumer, gpio::Direction direction_, int initValue_, - void (* callback) (gpioId_t gpioId, gpio::GpioOperation gpioOp, int value, void* args), - void* callbackArgs): - GpioBase(gpio::GpioTypes::CALLBACK, consumer, direction_, initValue_), - callback(callback), callbackArgs(callbackArgs) {} - - void (* callback) (gpioId_t gpioId, gpio::GpioOperation gpioOp, - int value, void* args) = nullptr; - void* callbackArgs = nullptr; -}; - - -using GpioMap = std::unordered_map; -using GpioMapIter = GpioMap::iterator; - -#endif /* LINUX_GPIO_GPIODEFINITIONS_H_ */ diff --git a/linux/boardtest/CMakeLists.txt b/linux/boardtest/CMakeLists.txt index 0fa4e322..1fa4b290 100644 --- a/linux/boardtest/CMakeLists.txt +++ b/linux/boardtest/CMakeLists.txt @@ -1,4 +1,4 @@ -target_sources(${TARGET_NAME} PRIVATE +target_sources(${OBSW_NAME} PRIVATE LibgpiodTest.cpp I2cTestClass.cpp SpiTestClass.cpp diff --git a/linux/boardtest/I2cTestClass.cpp b/linux/boardtest/I2cTestClass.cpp index 66c16b33..1bd0aa52 100644 --- a/linux/boardtest/I2cTestClass.cpp +++ b/linux/boardtest/I2cTestClass.cpp @@ -1,8 +1,101 @@ -#include +#include "I2cTestClass.h" -I2cTestClass::I2cTestClass(object_id_t objectId): TestTask(objectId) { +#include +#include +#include +#include + +#include "fsfw/globalfunctions/arrayprinter.h" +#include "fsfw/serviceinterface.h" + +I2cTestClass::I2cTestClass(object_id_t objectId, std::string i2cdev) + : TestTask(objectId), i2cdev(i2cdev) { + mode = TestModes::BPX_BATTERY; +} + +ReturnValue_t I2cTestClass::initialize() { + if (mode == TestModes::BPX_BATTERY) { + battInit(); + } + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t I2cTestClass::performPeriodicAction() { - return HasReturnvaluesIF::RETURN_OK; + if (mode == TestModes::BPX_BATTERY) { + battPeriodic(); + } + return HasReturnvaluesIF::RETURN_OK; +} + +void I2cTestClass::battInit() { + sif::info << "I2cTestClass: BPX Initialization" << std::endl; + UnixFileGuard fileHelper(i2cdev, &bpxInfo.fd, O_RDWR, "I2cTestClass::sendMessage"); + if (fileHelper.getOpenResult() != HasReturnvaluesIF::RETURN_OK) { + sif::error << "Opening I2C device" << i2cdev << " failed" << std::endl; + return; + } + if (ioctl(bpxInfo.fd, I2C_SLAVE, bpxInfo.addr) < 0) { + sif::error << "Failed to acquire bus access and/or talk to slave" << std::endl; + } + cmdBuf[0] = BpxBattery::PORT_PING; + cmdBuf[1] = 0x42; + sendLen = 2; + ReturnValue_t result = i2cWrite(bpxInfo.fd, cmdBuf.data(), sendLen); + if (result != HasReturnvaluesIF::RETURN_OK) { + return; + } + // Receive back port, error byte and ping reply + recvLen = 3; + result = i2cRead(bpxInfo.fd, replyBuf.data(), recvLen); + if (result != HasReturnvaluesIF::RETURN_OK) { + return; + } + sif::info << "Ping reply:" << std::endl; + arrayprinter::print(replyBuf.data(), recvLen); + if (replyBuf[2] != 0x42) { + sif::warning << "Received ping reply not expected value 0x42" << std::endl; + } +} + +void I2cTestClass::battPeriodic() { + UnixFileGuard fileHelper(i2cdev, &bpxInfo.fd, O_RDWR, "I2cTestClass::sendMessage"); + if (fileHelper.getOpenResult() != HasReturnvaluesIF::RETURN_OK) { + sif::error << "Opening I2C device" << i2cdev << " failed" << std::endl; + return; + } + if (ioctl(bpxInfo.fd, I2C_SLAVE, bpxInfo.addr) < 0) { + sif::error << "Failed to acquire bus access and/or talk to slave" << std::endl; + } + cmdBuf[0] = BpxBattery::PORT_GET_HK; + sendLen = 1; + ReturnValue_t result = i2cWrite(bpxInfo.fd, cmdBuf.data(), sendLen); + if (result != HasReturnvaluesIF::RETURN_OK) { + return; + } + // Receive back HK set + recvLen = 23; + result = i2cRead(bpxInfo.fd, replyBuf.data(), recvLen); + if (result != HasReturnvaluesIF::RETURN_OK) { + return; + } + sif::info << "HK reply:" << std::endl; + arrayprinter::print(replyBuf.data(), recvLen); +} + +ReturnValue_t I2cTestClass::i2cWrite(int fd, uint8_t* data, size_t len) { + if (write(fd, data, len) != static_cast(len)) { + sif::error << "Failed to write to I2C bus" << std::endl; + sif::error << "Error " << errno << ": " << strerror(errno) << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t I2cTestClass::i2cRead(int fd, uint8_t* data, size_t len) { + if (read(fd, data, len) != static_cast(len)) { + sif::error << "Failed to read from I2C bus" << std::endl; + sif::error << "Error " << errno << ": " << strerror(errno) << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; } diff --git a/linux/boardtest/I2cTestClass.h b/linux/boardtest/I2cTestClass.h index 172a7f71..500243c5 100644 --- a/linux/boardtest/I2cTestClass.h +++ b/linux/boardtest/I2cTestClass.h @@ -3,15 +3,38 @@ #include -class I2cTestClass: public TestTask { -public: - I2cTestClass(object_id_t objectId); +#include +#include - ReturnValue_t performPeriodicAction() override; -private: +#include "mission/devices/devicedefinitions/BpxBatteryDefinitions.h" +class I2cTestClass : public TestTask { + public: + I2cTestClass(object_id_t objectId, std::string i2cdev); + + ReturnValue_t initialize() override; + ReturnValue_t performPeriodicAction() override; + + private: + enum TestModes { NONE, BPX_BATTERY }; + struct I2cInfo { + int addr = 0; + int fd = 0; + }; + + TestModes mode = TestModes::NONE; + void battInit(); + void battPeriodic(); + + I2cInfo bpxInfo = {.addr = 0x07, .fd = 0}; + std::string i2cdev; + size_t sendLen = 0; + size_t recvLen = 0; + std::array cmdBuf = {}; + std::array replyBuf = {}; + + ReturnValue_t i2cWrite(int fd, uint8_t* data, size_t len); + ReturnValue_t i2cRead(int fd, uint8_t* data, size_t len); }; - - #endif /* LINUX_BOARDTEST_I2CTESTCLASS_H_ */ diff --git a/linux/boardtest/LibgpiodTest.cpp b/linux/boardtest/LibgpiodTest.cpp index 8eb9b536..0c5ebe2a 100644 --- a/linux/boardtest/LibgpiodTest.cpp +++ b/linux/boardtest/LibgpiodTest.cpp @@ -1,135 +1,127 @@ #include "LibgpiodTest.h" +#include +#include +#include + #include "devices/gpioIds.h" -#include -#include -#include - -LibgpiodTest::LibgpiodTest(object_id_t objectId, object_id_t gpioIfobjectId, - GpioCookie* gpioCookie): - TestTask(objectId) { - - gpioInterface = ObjectManager::instance()->get(gpioIfobjectId); - if (gpioInterface == nullptr) { - sif::error << "LibgpiodTest::LibgpiodTest: Invalid Gpio interface." << std::endl; - } - gpioInterface->addGpios(gpioCookie); - testCase = TestCases::BLINK; +LibgpiodTest::LibgpiodTest(object_id_t objectId, object_id_t gpioIfobjectId, GpioCookie* gpioCookie) + : TestTask(objectId) { + gpioInterface = ObjectManager::instance()->get(gpioIfobjectId); + if (gpioInterface == nullptr) { + sif::error << "LibgpiodTest::LibgpiodTest: Invalid Gpio interface." << std::endl; + } + gpioInterface->addGpios(gpioCookie); + testCase = TestCases::BLINK; } -LibgpiodTest::~LibgpiodTest() { -} +LibgpiodTest::~LibgpiodTest() {} ReturnValue_t LibgpiodTest::performPeriodicAction() { - int gpioState; - ReturnValue_t result; + int gpioState; + ReturnValue_t result; - switch(testCase) { - case(TestCases::READ): { - result = gpioInterface->readGpio(gpioIds::TEST_ID_0, &gpioState); - if (result != RETURN_OK) { - sif::warning << "LibgpiodTest::performPeriodicAction: Failed to read gpio " - << std::endl; - return RETURN_FAILED; - } - else { - sif::debug << "LibgpiodTest::performPeriodicAction: MIO 0 state = " << gpioState - << std::endl; - } - break; + switch (testCase) { + case (TestCases::READ): { + result = gpioInterface->readGpio(gpioIds::TEST_ID_0, &gpioState); + if (result != RETURN_OK) { + sif::warning << "LibgpiodTest::performPeriodicAction: Failed to read gpio " << std::endl; + return RETURN_FAILED; + } else { + sif::debug << "LibgpiodTest::performPeriodicAction: MIO 0 state = " << gpioState + << std::endl; + } + break; } - case(TestCases::LOOPBACK): { - break; + case (TestCases::LOOPBACK): { + break; } - case(TestCases::BLINK): { - result = gpioInterface->readGpio(gpioIds::TEST_ID_0, &gpioState); + case (TestCases::BLINK): { + result = gpioInterface->readGpio(gpioIds::TEST_ID_0, &gpioState); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "LibgpiodTest::performPeriodicAction: Failed to read gpio " << std::endl; + return RETURN_FAILED; + } + if (gpioState == 1) { + result = gpioInterface->pullLow(gpioIds::TEST_ID_0); if (result != HasReturnvaluesIF::RETURN_OK) { - sif::warning << "LibgpiodTest::performPeriodicAction: Failed to read gpio " - << std::endl; - return RETURN_FAILED; + sif::warning << "LibgpiodTest::performPeriodicAction: Could not pull GPIO low!" + << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; } - if (gpioState == 1) { - result = gpioInterface->pullLow(gpioIds::TEST_ID_0); - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::warning << "LibgpiodTest::performPeriodicAction: Could not pull GPIO low!" - << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; - } - } - else if (gpioState == 0) { - result = gpioInterface->pullHigh(gpioIds::TEST_ID_0); - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::warning << "LibgpiodTest::performPeriodicAction: Could not pull GPIO high!" - << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; - } - } - else { - sif::warning << "LibgpiodTest::performPeriodicAction: Invalid GPIO state" << std::endl; + } else if (gpioState == 0) { + result = gpioInterface->pullHigh(gpioIds::TEST_ID_0); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "LibgpiodTest::performPeriodicAction: Could not pull GPIO high!" + << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; } + } else { + sif::warning << "LibgpiodTest::performPeriodicAction: Invalid GPIO state" << std::endl; + } - break; + break; } default: - sif::debug << "LibgpiodTest::performPeriodicAction: Invalid test case" << std::endl; - break; - } + sif::debug << "LibgpiodTest::performPeriodicAction: Invalid test case" << std::endl; + break; + } - - return RETURN_OK; + return RETURN_OK; } ReturnValue_t LibgpiodTest::performOneShotAction() { - int gpioState; - ReturnValue_t result; + int gpioState; + ReturnValue_t result; - switch(testCase) { - case(TestCases::READ): { - break; + switch (testCase) { + case (TestCases::READ): { + break; } - case(TestCases::BLINK): { - break; + case (TestCases::BLINK): { + break; } - case(TestCases::LOOPBACK): { - result = gpioInterface->pullHigh(gpioIds::TEST_ID_0); - if(result == HasReturnvaluesIF::RETURN_OK) { - sif::info << "LibgpiodTest::performOneShotAction: " - "GPIO pulled high successfully for loopback test" << std::endl; - } - else { - sif::warning << "LibgpiodTest::performOneShotAction: Could not pull GPIO high!" - << std::endl; - return HasReturnvaluesIF::RETURN_OK; - } - result = gpioInterface->readGpio(gpioIds::TEST_ID_1, &gpioState); - if(result == HasReturnvaluesIF::RETURN_OK and gpioState == 1) { - sif::info << "LibgpiodTest::performOneShotAction: " - "GPIO state read successfully and is high" << std::endl; - } - else { - sif::warning << "LibgpiodTest::performOneShotAction: GPIO read and is not high!" - << std::endl; - return HasReturnvaluesIF::RETURN_OK; - } + case (TestCases::LOOPBACK): { + result = gpioInterface->pullHigh(gpioIds::TEST_ID_0); + if (result == HasReturnvaluesIF::RETURN_OK) { + sif::info << "LibgpiodTest::performOneShotAction: " + "GPIO pulled high successfully for loopback test" + << std::endl; + } else { + sif::warning << "LibgpiodTest::performOneShotAction: Could not pull GPIO high!" + << std::endl; + return HasReturnvaluesIF::RETURN_OK; + } + result = gpioInterface->readGpio(gpioIds::TEST_ID_1, &gpioState); + if (result == HasReturnvaluesIF::RETURN_OK and gpioState == 1) { + sif::info << "LibgpiodTest::performOneShotAction: " + "GPIO state read successfully and is high" + << std::endl; + } else { + sif::warning << "LibgpiodTest::performOneShotAction: GPIO read and is not high!" + << std::endl; + return HasReturnvaluesIF::RETURN_OK; + } - result = gpioInterface->pullLow(gpioIds::TEST_ID_0); - if(result == HasReturnvaluesIF::RETURN_OK) { - sif::info << "LibgpiodTest::performOneShotAction: " - "GPIO pulled low successfully for loopback test" << std::endl; - } - result = gpioInterface->readGpio(gpioIds::TEST_ID_1, &gpioState); - if(result == HasReturnvaluesIF::RETURN_OK and gpioState == 0) { - sif::info << "LibgpiodTest::performOneShotAction: " - "GPIO state read successfully and is low" << std::endl; - } - else { - sif::warning << "LibgpiodTest::performOneShotAction: GPIO read and is not low!" - << std::endl; - return HasReturnvaluesIF::RETURN_OK; - } - break; + result = gpioInterface->pullLow(gpioIds::TEST_ID_0); + if (result == HasReturnvaluesIF::RETURN_OK) { + sif::info << "LibgpiodTest::performOneShotAction: " + "GPIO pulled low successfully for loopback test" + << std::endl; + } + result = gpioInterface->readGpio(gpioIds::TEST_ID_1, &gpioState); + if (result == HasReturnvaluesIF::RETURN_OK and gpioState == 0) { + sif::info << "LibgpiodTest::performOneShotAction: " + "GPIO state read successfully and is low" + << std::endl; + } else { + sif::warning << "LibgpiodTest::performOneShotAction: GPIO read and is not low!" + << std::endl; + return HasReturnvaluesIF::RETURN_OK; + } + break; } - } - return HasReturnvaluesIF::RETURN_OK; + } + return HasReturnvaluesIF::RETURN_OK; } diff --git a/linux/boardtest/LibgpiodTest.h b/linux/boardtest/LibgpiodTest.h index 718d0209..4fcaffdf 100644 --- a/linux/boardtest/LibgpiodTest.h +++ b/linux/boardtest/LibgpiodTest.h @@ -1,34 +1,31 @@ #ifndef TEST_TESTTASKS_LIBGPIODTEST_H_ #define TEST_TESTTASKS_LIBGPIODTEST_H_ -#include "TestTask.h" -#include -#include #include +#include +#include + +#include "TestTask.h" /** * @brief Test for the GPIO read implementation of the LinuxLibgpioIF. * @author J. Meier */ -class LibgpiodTest: public TestTask { -public: - enum TestCases { - READ = 0, - LOOPBACK = 1, - BLINK - }; +class LibgpiodTest : public TestTask { + public: + enum TestCases { READ = 0, LOOPBACK = 1, BLINK }; - TestCases testCase; + TestCases testCase; - LibgpiodTest(object_id_t objectId, object_id_t gpioIfobjectId, GpioCookie* gpioCookie); - virtual ~LibgpiodTest(); + LibgpiodTest(object_id_t objectId, object_id_t gpioIfobjectId, GpioCookie* gpioCookie); + virtual ~LibgpiodTest(); -protected: - ReturnValue_t performOneShotAction() override; - ReturnValue_t performPeriodicAction() override; + protected: + ReturnValue_t performOneShotAction() override; + ReturnValue_t performPeriodicAction() override; -private: - GpioIF* gpioInterface; + private: + GpioIF* gpioInterface; }; #endif /* TEST_TESTTASKS_LIBGPIODTEST_H_ */ diff --git a/linux/boardtest/SpiTestClass.cpp b/linux/boardtest/SpiTestClass.cpp index 8a340ecb..5287b6e9 100644 --- a/linux/boardtest/SpiTestClass.cpp +++ b/linux/boardtest/SpiTestClass.cpp @@ -1,509 +1,900 @@ #include "SpiTestClass.h" -#include "devices/gpioIds.h" - -#include +#include #include +#include #include #include - -#include -#include -#include #include - +#include +#include +#include #include -#include - -#include #include +#include + #include -SpiTestClass::SpiTestClass(object_id_t objectId, GpioIF* gpioIF): TestTask(objectId), -gpioIF(gpioIF) { - if(gpioIF == nullptr) { - sif::error << "SpiTestClass::SpiTestClass: Invalid GPIO ComIF!" << std::endl; - } - testMode = TestModes::MGM_LIS3MDL; - spiTransferStruct.rx_buf = reinterpret_cast<__u64>(recvBuffer.data()); - spiTransferStruct.tx_buf = reinterpret_cast<__u64>(sendBuffer.data()); +#if defined(XIPHOS_Q7S) +#include "busConf.h" +#endif +#include "devices/gpioIds.h" +#include "mission/devices/max1227.h" + +SpiTestClass::SpiTestClass(object_id_t objectId, GpioIF *gpioIF) + : TestTask(objectId), gpioIF(gpioIF) { + if (gpioIF == nullptr) { + sif::error << "SpiTestClass::SpiTestClass: Invalid GPIO ComIF!" << std::endl; + } + testMode = TestModes::MAX1227; + spiTransferStruct[0].rx_buf = reinterpret_cast<__u64>(recvBuffer.data()); + setSendBuffer(); } ReturnValue_t SpiTestClass::performOneShotAction() { - switch(testMode) { - case(TestModes::NONE): { - break; + switch (testMode) { + case (TestModes::NONE): { + break; } - case(TestModes::MGM_LIS3MDL): { - performLis3MdlTest(mgm0Lis3mdlChipSelect); - break; + case (TestModes::MGM_LIS3MDL): { + performLis3MdlTest(mgm0Lis3mdlChipSelect); + break; } - case(TestModes::MGM_RM3100): { - performRm3100Test(mgm1Rm3100ChipSelect); - break; + case (TestModes::MGM_RM3100): { + performRm3100Test(mgm1Rm3100ChipSelect); + break; } - case(TestModes::GYRO_L3GD20H): { - performL3gTest(gyro1L3gd20ChipSelect); - break; + case (TestModes::GYRO_L3GD20H): { + performL3gTest(gyro1L3gd20ChipSelect); + break; } + case (TestModes::MAX1227): { + performOneShotMax1227Test(); + break; } - return HasReturnvaluesIF::RETURN_OK; + } + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t SpiTestClass::performPeriodicAction() { - return HasReturnvaluesIF::RETURN_OK; + switch (testMode) { + case (TestModes::MAX1227): { + performPeriodicMax1227Test(); + break; + } + default: + break; + } + return HasReturnvaluesIF::RETURN_OK; } void SpiTestClass::performRm3100Test(uint8_t mgmId) { - /* Configure all SPI chip selects and pull them high */ - acsInit(); + /* Configure all SPI chip selects and pull them high */ + acsInit(); - /* Adapt accordingly */ - if(mgmId != mgm1Rm3100ChipSelect and mgmId != mgm3Rm3100ChipSelect) { - sif::warning << "SpiTestClass::performRm3100Test: Invalid MGM ID!" << std::endl; - } - gpioId_t currentGpioId = 0; - uint8_t chipSelectPin = mgmId; - if(chipSelectPin == mgm1Rm3100ChipSelect) { - currentGpioId = gpioIds::MGM_1_RM3100_CS; - } - else { - currentGpioId = gpioIds::MGM_3_RM3100_CS; - } - uint32_t rm3100speed = 976'000; - uint8_t rm3100revidReg = 0x36; - spi::SpiModes rm3100mode = spi::SpiModes::MODE_3; + /* Adapt accordingly */ + if (mgmId != mgm1Rm3100ChipSelect and mgmId != mgm3Rm3100ChipSelect) { + sif::warning << "SpiTestClass::performRm3100Test: Invalid MGM ID!" << std::endl; + } + gpioId_t currentGpioId = 0; + uint8_t chipSelectPin = mgmId; + if (chipSelectPin == mgm1Rm3100ChipSelect) { + currentGpioId = gpioIds::MGM_1_RM3100_CS; + } else { + currentGpioId = gpioIds::MGM_3_RM3100_CS; + } + uint32_t rm3100speed = 976'000; + uint8_t rm3100revidReg = 0x36; + spi::SpiModes rm3100mode = spi::SpiModes::MODE_3; #ifdef RASPBERRY_PI - std::string deviceName = "/dev/spidev0.0"; + std::string deviceName = "/dev/spidev0.0"; #else - std::string deviceName = "/dev/spidev2.0"; + std::string deviceName = "/dev/spidev2.0"; #endif - int fileDescriptor = 0; + int fileDescriptor = 0; + UnixFileGuard fileHelper(deviceName, &fileDescriptor, O_RDWR, "SpiComIF::initializeInterface"); + if (fileHelper.getOpenResult()) { + sif::error << "SpiTestClass::performRm3100Test: File descriptor could not be opened!" + << std::endl; + return; + } + setSpiSpeedAndMode(fileDescriptor, rm3100mode, rm3100speed); - UnixFileGuard fileHelper(deviceName, &fileDescriptor, O_RDWR, - "SpiComIF::initializeInterface"); - if(fileHelper.getOpenResult()) { - sif::error << "SpiTestClass::performRm3100Test: File descriptor could not be opened!" - << std::endl; - return; - } - setSpiSpeedAndMode(fileDescriptor, rm3100mode, rm3100speed); + uint8_t revId = readRegister(fileDescriptor, currentGpioId, rm3100revidReg); + sif::info << "SpiTestClass::performRm3100Test: Revision ID 0b" << std::bitset<8>(revId) + << std::endl; - uint8_t revId = readRegister(fileDescriptor, currentGpioId, rm3100revidReg); - sif::info << "SpiTestClass::performRm3100Test: Revision ID 0b" << std::bitset<8>(revId) << - std::endl; + /* Write configuration to CMM register */ + writeRegister(fileDescriptor, currentGpioId, 0x01, 0x75); + uint8_t cmmRegister = readRm3100Register(fileDescriptor, currentGpioId, 0x01); + sif::info << "SpiTestClass::performRm3100Test: CMM register value: " << std::hex << "0x" + << static_cast(cmmRegister) << std::dec << std::endl; - /* Write configuration to CMM register */ - writeRegister(fileDescriptor, currentGpioId, 0x01, 0x75); - uint8_t cmmRegister = readRm3100Register(fileDescriptor , currentGpioId, 0x01); - sif::info << "SpiTestClass::performRm3100Test: CMM register value: " << - std::hex << "0x" << static_cast(cmmRegister) << std::dec << std::endl; + /* Read the cycle count registers */ + uint8_t cycleCountsRaw[6]; + readMultipleRegisters(fileDescriptor, currentGpioId, 0x04, cycleCountsRaw, 6); - /* Read the cycle count registers */ - uint8_t cycleCountsRaw[6]; - readMultipleRegisters(fileDescriptor, currentGpioId, 0x04, cycleCountsRaw, 6); + uint16_t cycleCountX = cycleCountsRaw[0] << 8 | cycleCountsRaw[1]; + uint16_t cycleCountY = cycleCountsRaw[2] << 8 | cycleCountsRaw[3]; + uint16_t cycleCountZ = cycleCountsRaw[4] << 8 | cycleCountsRaw[5]; - uint16_t cycleCountX = cycleCountsRaw[0] << 8 | cycleCountsRaw[1]; - uint16_t cycleCountY = cycleCountsRaw[2] << 8 | cycleCountsRaw[3]; - uint16_t cycleCountZ = cycleCountsRaw[4] << 8 | cycleCountsRaw[5]; + sif::info << "Cycle count X: " << cycleCountX << std::endl; + sif::info << "Cycle count Y: " << cycleCountY << std::endl; + sif::info << "Cycle count z: " << cycleCountZ << std::endl; - sif::info << "Cycle count X: " << cycleCountX << std::endl; - sif::info << "Cycle count Y: " << cycleCountY << std::endl; - sif::info << "Cycle count z: " << cycleCountZ << std::endl; - - writeRegister(fileDescriptor, currentGpioId, 0x0B, 0x96); - uint8_t tmrcReg = readRm3100Register(fileDescriptor, currentGpioId, 0x0B); - sif::info << "SpiTestClass::performRm3100Test: TMRC register value: " << - std::hex << "0x" << static_cast(tmrcReg) << std::dec << std::endl; + writeRegister(fileDescriptor, currentGpioId, 0x0B, 0x96); + uint8_t tmrcReg = readRm3100Register(fileDescriptor, currentGpioId, 0x0B); + sif::info << "SpiTestClass::performRm3100Test: TMRC register value: " << std::hex << "0x" + << static_cast(tmrcReg) << std::dec << std::endl; + TaskFactory::delayTask(10); + uint8_t statusReg = readRm3100Register(fileDescriptor, currentGpioId, 0x34); + sif::info << "SpiTestClass::performRm3100Test: Status Register 0b" << std::bitset<8>(statusReg) + << std::endl; + /* This means that data is not ready */ + if ((statusReg & 0b1000'0000) == 0) { + sif::warning << "SpiTestClass::performRm3100Test: Data not ready!" << std::endl; TaskFactory::delayTask(10); uint8_t statusReg = readRm3100Register(fileDescriptor, currentGpioId, 0x34); - sif::info << "SpiTestClass::performRm3100Test: Status Register 0b" << - std::bitset<8>(statusReg) << std::endl; - /* This means that data is not ready */ - if((statusReg & 0b1000'0000) == 0) { - sif::warning << "SpiTestClass::performRm3100Test: Data not ready!" << std::endl; - TaskFactory::delayTask(10); - uint8_t statusReg = readRm3100Register(fileDescriptor, currentGpioId, 0x34); - if((statusReg & 0b1000'0000) == 0) { - return; - } + if ((statusReg & 0b1000'0000) == 0) { + return; } + } - uint32_t rm3100DefaultCycleCout = 0xC8; - /* Gain scales lineary with cycle count and is 38 for cycle count 100 */ - float rm3100Gain = rm3100DefaultCycleCout / 100.0 * 38.0; - float scaleFactor = 1 / rm3100Gain; - uint8_t rawValues[9]; - readMultipleRegisters(fileDescriptor, currentGpioId, 0x24, rawValues, 9); + uint32_t rm3100DefaultCycleCout = 0xC8; + /* Gain scales lineary with cycle count and is 38 for cycle count 100 */ + float rm3100Gain = rm3100DefaultCycleCout / 100.0 * 38.0; + float scaleFactor = 1 / rm3100Gain; + uint8_t rawValues[9]; + readMultipleRegisters(fileDescriptor, currentGpioId, 0x24, rawValues, 9); - /* The sensor generates 24 bit signed values */ - int32_t rawX = ((rawValues[0] << 24) | (rawValues[1] << 16) | (rawValues[2] << 8)) >> 8; - int32_t rawY = ((rawValues[3] << 24) | (rawValues[4] << 16) | (rawValues[5] << 8)) >> 8; - int32_t rawZ = ((rawValues[6] << 24) | (rawValues[7] << 16) | (rawValues[8] << 8)) >> 8; + /* The sensor generates 24 bit signed values */ + int32_t rawX = ((rawValues[0] << 24) | (rawValues[1] << 16) | (rawValues[2] << 8)) >> 8; + int32_t rawY = ((rawValues[3] << 24) | (rawValues[4] << 16) | (rawValues[5] << 8)) >> 8; + int32_t rawZ = ((rawValues[6] << 24) | (rawValues[7] << 16) | (rawValues[8] << 8)) >> 8; - float fieldStrengthX = rawX * scaleFactor; - float fieldStrengthY = rawY * scaleFactor; - float fieldStrengthZ = rawZ * scaleFactor; + float fieldStrengthX = rawX * scaleFactor; + float fieldStrengthY = rawY * scaleFactor; + float fieldStrengthZ = rawZ * scaleFactor; - sif::info << "RM3100 measured field strengths in microtesla:" << std::endl; - sif::info << "Field Strength X: " << fieldStrengthX << " uT" << std::endl; - sif::info << "Field Strength Y: " << fieldStrengthY << " uT" << std::endl; - sif::info << "Field Strength Z: " << fieldStrengthZ << " uT" << std::endl; + sif::info << "RM3100 measured field strengths in microtesla:" << std::endl; + sif::info << "Field Strength X: " << fieldStrengthX << " uT" << std::endl; + sif::info << "Field Strength Y: " << fieldStrengthY << " uT" << std::endl; + sif::info << "Field Strength Z: " << fieldStrengthZ << " uT" << std::endl; } void SpiTestClass::performLis3MdlTest(uint8_t lis3Id) { - /* Configure all SPI chip selects and pull them high */ - acsInit(); + /* Configure all SPI chip selects and pull them high */ + acsInit(); - /* Adapt accordingly */ - if(lis3Id != mgm0Lis3mdlChipSelect and lis3Id != mgm2Lis3mdlChipSelect) { - sif::warning << "SpiTestClass::performLis3MdlTest: Invalid MGM ID!" << std::endl; - } - gpioId_t currentGpioId = 0; - uint8_t chipSelectPin = lis3Id; - uint8_t whoAmIReg = 0b0000'1111; - uint8_t whoAmIRegExpectedVal = 0b0011'1101; - if(chipSelectPin == mgm0Lis3mdlChipSelect) { - currentGpioId = gpioIds::MGM_0_LIS3_CS; - } - else { - currentGpioId = gpioIds::MGM_2_LIS3_CS; - } - uint32_t spiSpeed = 10'000'000; - spi::SpiModes spiMode = spi::SpiModes::MODE_0; + /* Adapt accordingly */ + if (lis3Id != mgm0Lis3mdlChipSelect and lis3Id != mgm2Lis3mdlChipSelect) { + sif::warning << "SpiTestClass::performLis3MdlTest: Invalid MGM ID!" << std::endl; + } + gpioId_t currentGpioId = 0; + uint8_t chipSelectPin = lis3Id; + uint8_t whoAmIReg = 0b0000'1111; + uint8_t whoAmIRegExpectedVal = 0b0011'1101; + if (chipSelectPin == mgm0Lis3mdlChipSelect) { + currentGpioId = gpioIds::MGM_0_LIS3_CS; + } else { + currentGpioId = gpioIds::MGM_2_LIS3_CS; + } + uint32_t spiSpeed = 10'000'000; + spi::SpiModes spiMode = spi::SpiModes::MODE_0; #ifdef RASPBERRY_PI - std::string deviceName = "/dev/spidev0.0"; + std::string deviceName = "/dev/spidev0.0"; #else - std::string deviceName = "/dev/spidev2.0"; + std::string deviceName = "/dev/spidev2.0"; #endif - int fileDescriptor = 0; + int fileDescriptor = 0; - UnixFileGuard fileHelper(deviceName, &fileDescriptor, O_RDWR, - "SpiComIF::initializeInterface"); - if(fileHelper.getOpenResult()) { - sif::error << "SpiTestClass::performLis3Mdl3100Test: File descriptor could not be opened!" - << std::endl; - return; - } - setSpiSpeedAndMode(fileDescriptor, spiMode, spiSpeed); - spiTransferStruct.delay_usecs = 0; - - uint8_t whoAmIRegVal = readStmRegister(fileDescriptor, currentGpioId, whoAmIReg, false); - sif::info << "SpiTestClass::performLis3MdlTest: WHO AM I register 0b" << - std::bitset<8>(whoAmIRegVal) << std::endl; - if(whoAmIRegVal != whoAmIRegExpectedVal) { - sif::warning << "SpiTestClass::performLis3MdlTest: WHO AM I register invalid!" - << std::endl; - } + UnixFileGuard fileHelper(deviceName, &fileDescriptor, O_RDWR, "SpiComIF::initializeInterface"); + if (fileHelper.getOpenResult()) { + sif::error << "SpiTestClass::performLis3Mdl3100Test: File descriptor could not be opened!" + << std::endl; + return; + } + setSpiSpeedAndMode(fileDescriptor, spiMode, spiSpeed); + spiTransferStruct[0].delay_usecs = 0; + uint8_t whoAmIRegVal = readStmRegister(fileDescriptor, currentGpioId, whoAmIReg, false); + sif::info << "SpiTestClass::performLis3MdlTest: WHO AM I register 0b" + << std::bitset<8>(whoAmIRegVal) << std::endl; + if (whoAmIRegVal != whoAmIRegExpectedVal) { + sif::warning << "SpiTestClass::performLis3MdlTest: WHO AM I register invalid!" << std::endl; + } } - void SpiTestClass::performL3gTest(uint8_t l3gId) { - /* Configure all SPI chip selects and pull them high */ - acsInit(); + /* Configure all SPI chip selects and pull them high */ + acsInit(); - l3gId = gyro1L3gd20ChipSelect; + gpioId_t currentGpioId = 0; + uint8_t chipSelectPin = l3gId; + uint8_t whoAmIReg = 0b0000'1111; + uint8_t whoAmIRegExpectedVal = 0b1101'0111; - /* Adapt accordingly */ - if(l3gId != gyro1L3gd20ChipSelect and l3gId != gyro3L3gd20ChipSelect) { - sif::warning << "SpiTestClass::performLis3MdlTest: Invalid MGM ID!" << std::endl; - } - gpioId_t currentGpioId = 0; - uint8_t chipSelectPin = l3gId; - uint8_t whoAmIReg = 0b0000'1111; - uint8_t whoAmIRegExpectedVal = 0b1101'0111; - - if(chipSelectPin == gyro1L3gd20ChipSelect) { - currentGpioId = gpioIds::GYRO_1_L3G_CS; - } - else { - currentGpioId = gpioIds::GYRO_3_L3G_CS; - } - uint32_t spiSpeed = 3'900'000; - spi::SpiModes spiMode = spi::SpiModes::MODE_3; + if (chipSelectPin == gyro1L3gd20ChipSelect) { + currentGpioId = gpioIds::GYRO_1_L3G_CS; + } else { + currentGpioId = gpioIds::GYRO_3_L3G_CS; + } + uint32_t spiSpeed = 3'900'000; + spi::SpiModes spiMode = spi::SpiModes::MODE_3; #ifdef RASPBERRY_PI - std::string deviceName = "/dev/spidev0.0"; + std::string deviceName = "/dev/spidev0.0"; #else - std::string deviceName = "/dev/spidev2.0"; + std::string deviceName = "/dev/spidev2.0"; #endif - int fileDescriptor = 0; + int fileDescriptor = 0; - UnixFileGuard fileHelper(deviceName, &fileDescriptor, O_RDWR, - "SpiComIF::initializeInterface"); - if(fileHelper.getOpenResult()) { - sif::error << "SpiTestClass::performLis3Mdl3100Test: File descriptor could not be opened!" - << std::endl; - return; + UnixFileGuard fileHelper(deviceName, &fileDescriptor, O_RDWR, "SpiComIF::initializeInterface"); + if (fileHelper.getOpenResult()) { + sif::error << "SpiTestClass::performLis3Mdl3100Test: File descriptor could not be opened!" + << std::endl; + return; + } + setSpiSpeedAndMode(fileDescriptor, spiMode, spiSpeed); + uint8_t whoAmIRegVal = readStmRegister(fileDescriptor, currentGpioId, whoAmIReg, false); + sif::info << "SpiTestClass::performLis3MdlTest: WHO AM I register 0b" + << std::bitset<8>(whoAmIRegVal) << std::endl; + if (whoAmIRegVal != whoAmIRegExpectedVal) { + sif::warning << "SpiTestClass::performL3gTest: Read WHO AM I register invalid!" << std::endl; + } + + uint8_t ctrlReg1Addr = 0b0010'0000; + { + uint8_t commandRegs[5]; + commandRegs[0] = 0b0000'1111; + commandRegs[1] = 0x0; + commandRegs[2] = 0x0; + /* Configure big endian data format */ + commandRegs[3] = 0b0100'0000; + commandRegs[4] = 0x0; + writeMultipleStmRegisters(fileDescriptor, currentGpioId, ctrlReg1Addr, commandRegs, + sizeof(commandRegs)); + uint8_t readRegs[5]; + readMultipleRegisters(fileDescriptor, currentGpioId, ctrlReg1Addr, readRegs, sizeof(readRegs)); + for (uint8_t idx = 0; idx < sizeof(readRegs); idx++) { + if (readRegs[idx] != commandRegs[0]) { + sif::warning << "SpiTestClass::performL3gTest: Read control register " + << static_cast(idx + 1) << " not equal to configured value" << std::endl; + } } - setSpiSpeedAndMode(fileDescriptor, spiMode, spiSpeed); - uint8_t whoAmIRegVal = readStmRegister(fileDescriptor, currentGpioId, whoAmIReg, false); - sif::info << "SpiTestClass::performLis3MdlTest: WHO AM I register 0b" << - std::bitset<8>(whoAmIRegVal) << std::endl; - if(whoAmIRegVal != whoAmIRegExpectedVal) { - sif::warning << "SpiTestClass::performL3gTest: Read WHO AM I register invalid!" << - std::endl; + } + + uint8_t readOutBuffer[14]; + readMultipleStmRegisters(fileDescriptor, currentGpioId, ctrlReg1Addr, readOutBuffer, + sizeof(readOutBuffer)); + + uint8_t statusReg = readOutBuffer[7]; + sif::info << "SpiTestClass::performL3gTest: Status Register 0b" << std::bitset<8>(statusReg) + << std::endl; + + uint16_t l3gRange = 245; + float scaleFactor = static_cast(l3gRange) / INT16_MAX; + /* The sensor spits out little endian */ + int16_t angVelocRawX = (readOutBuffer[8] << 8) | readOutBuffer[9]; + int16_t angVelocRawY = (readOutBuffer[10] << 8) | readOutBuffer[11]; + int16_t angVelocRawZ = (readOutBuffer[12] << 8) | readOutBuffer[13]; + + float angVelocX = scaleFactor * angVelocRawX; + float angVelocY = scaleFactor * angVelocRawY; + float angVelocZ = scaleFactor * angVelocRawZ; + + sif::info << "Angular velocities for the L3GD20H in degrees per second:" << std::endl; + sif::info << "X: " << angVelocX << std::endl; + sif::info << "Y: " << angVelocY << std::endl; + sif::info << "Z: " << angVelocZ << std::endl; +} + +void SpiTestClass::performOneShotMax1227Test() { + using namespace max1227; + adcCfg.testRadSensorExtConvWithDelay = false; + adcCfg.testRadSensorIntConv = false; + + bool setAllSusOn = false; + bool susIntConv = false; + bool susExtConv = false; + if (setAllSusOn) { + for (uint8_t idx = 0; idx < 12; idx++) { + adcCfg.testSus[idx].doTest = true; } - - uint8_t ctrlReg1Addr = 0b0010'0000; - { - uint8_t commandRegs[5]; - commandRegs[0] = 0b0000'1111; - commandRegs[1] = 0x0; - commandRegs[2] = 0x0; - /* Configure big endian data format */ - commandRegs[3] = 0b0100'0000; - commandRegs[4] = 0x0; - writeMultipleStmRegisters(fileDescriptor, currentGpioId, ctrlReg1Addr, commandRegs, - sizeof(commandRegs)); - uint8_t readRegs[5]; - readMultipleRegisters(fileDescriptor, currentGpioId, ctrlReg1Addr, readRegs, - sizeof(readRegs)); - for(uint8_t idx = 0; idx < sizeof(readRegs); idx++) { - if(readRegs[idx] != commandRegs[0]) { - sif::warning << "SpiTestClass::performL3gTest: Read control register " << - static_cast(idx + 1) << " not equal to configured value" << std::endl; - } - } + } else { + for (uint8_t idx = 0; idx < 12; idx++) { + adcCfg.testSus[idx].doTest = false; } + } - uint8_t readOutBuffer[14]; - readMultipleStmRegisters(fileDescriptor, currentGpioId, ctrlReg1Addr, readOutBuffer, - sizeof(readOutBuffer)); + if (susIntConv) { + for (uint8_t idx = 0; idx < 12; idx++) { + adcCfg.testSus[idx].intConv = true; + } + } + if (susExtConv) { + for (uint8_t idx = 0; idx < 12; idx++) { + adcCfg.testSus[idx].extConv = true; + } + } - uint8_t statusReg = readOutBuffer[7]; - sif::info << "SpiTestClass::performL3gTest: Status Register 0b" << - std::bitset<8>(statusReg) << std::endl; + adcCfg.plPcduAdcExtConv = true; + adcCfg.plPcduAdcIntConv = false; + // Is problematic, don't know why + adcCfg.plPcduAdcExtConvAsOne = false; + performMax1227Test(); +} - uint16_t l3gRange = 245; - float scaleFactor = static_cast(l3gRange) / INT16_MAX; - /* The sensor spits out little endian */ - int16_t angVelocRawX = (readOutBuffer[8] << 8) | readOutBuffer[9]; - int16_t angVelocRawY = (readOutBuffer[10] << 8) | readOutBuffer[11]; - int16_t angVelocRawZ = (readOutBuffer[12] << 8) | readOutBuffer[13]; +void SpiTestClass::performPeriodicMax1227Test() { + using namespace max1227; + performMax1227Test(); +} - float angVelocX = scaleFactor * angVelocRawX; - float angVelocY = scaleFactor * angVelocRawY; - float angVelocZ = scaleFactor * angVelocRawZ; +void SpiTestClass::performMax1227Test() { +#ifdef XIPHOS_Q7S + std::string deviceName = q7s::SPI_DEFAULT_DEV; +#elif defined(RASPBERRY_PI) + std::string deviceName = ""; +#elif defined(EGSE) + std::string deviceName = ""; +#endif + int fd = 0; + UnixFileGuard fileHelper(deviceName, &fd, O_RDWR, "SpiComIF::initializeInterface"); + if (fileHelper.getOpenResult()) { + sif::error << "SpiTestClass::performLis3Mdl3100Test: File descriptor could not be opened!" + << std::endl; + return; + } + uint32_t spiSpeed = 976'000; + spi::SpiModes spiMode = spi::SpiModes::MODE_3; + setSpiSpeedAndMode(fd, spiMode, spiSpeed); - sif::info << "Angular velocities for the L3GD20H in degrees per second:" << std::endl; - sif::info << "X: " << angVelocX << std::endl; - sif::info << "Y: " << angVelocY << std::endl; - sif::info << "Z: " << angVelocZ << std::endl; + max1227RadSensorTest(fd); + int idx = 0; + bool firstTest = true; + for (auto &susCfg : adcCfg.testSus) { + if (susCfg.doTest) { + if (firstTest) { + firstTest = false; + sif::info << "---------- SUS ADC Values -----------" << std::endl; + } + sif::info << "SUS " << std::setw(2) << idx << ": "; + max1227SusTest(fd, susCfg); + } + idx++; + } + max1227PlPcduTest(fd); +} +void SpiTestClass::max1227RadSensorTest(int fd) { + using namespace max1227; + if (adcCfg.testRadSensorExtConvWithDelay) { + sendBuffer[0] = max1227::buildResetByte(true); + spiTransferStruct[0].len = 1; + transfer(fd, gpioIds::CS_RAD_SENSOR); + usleep(200); + sendBuffer[0] = max1227::buildSetupByte(ClkSel::EXT_CONV_EXT_TIMED, RefSel::INT_REF_WITH_WAKEUP, + DiffSel::NONE_0); + spiTransferStruct[0].len = 1; + transfer(fd, gpioIds::CS_RAD_SENSOR); + max1227::prepareExternallyClockedRead0ToN(sendBuffer.data(), 7, spiTransferStruct[0].len); + size_t tmpLen = spiTransferStruct[0].len; + spiTransferStruct[0].len = 1; + transfer(fd, gpioIds::CS_RAD_SENSOR); + std::memcpy(sendBuffer.data(), sendBuffer.data() + 1, tmpLen - 1); + spiTransferStruct[0].len = tmpLen - 1; + usleep(65); + transfer(fd, gpioIds::CS_RAD_SENSOR); + arrayprinter::print(recvBuffer.data(), 13, OutputType::HEX); + uint16_t adcRaw[8] = {}; + adcRaw[0] = (recvBuffer[0] << 8) | recvBuffer[1]; + adcRaw[1] = (recvBuffer[2] << 8) | recvBuffer[3]; + adcRaw[2] = (recvBuffer[4] << 8) | recvBuffer[5]; + adcRaw[3] = (recvBuffer[6] << 8) | recvBuffer[7]; + adcRaw[4] = (recvBuffer[8] << 8) | recvBuffer[9]; + adcRaw[5] = (recvBuffer[10] << 8) | recvBuffer[11]; + adcRaw[6] = (recvBuffer[12] << 8) | recvBuffer[13]; + adcRaw[7] = (recvBuffer[14] << 8) | recvBuffer[15]; + arrayprinter::print(recvBuffer.data(), 17, OutputType::HEX); + for (int idx = 0; idx < 8; idx++) { + sif::info << "ADC raw " << idx << ": " << adcRaw[idx] << std::endl; + } + max1227::prepareExternallyClockedTemperatureRead(sendBuffer.data(), spiTransferStruct[0].len); + spiTransferStruct[0].len = 1; + transfer(fd, gpioIds::CS_RAD_SENSOR); + usleep(65); + spiTransferStruct[0].len = 24; + std::memcpy(sendBuffer.data(), sendBuffer.data() + 1, 24); + transfer(fd, gpioIds::CS_RAD_SENSOR); + int16_t tempRaw = ((recvBuffer[22] & 0x0f) << 8) | recvBuffer[23]; + float temp = max1227::getTemperature(tempRaw); + sif::info << "Temperature: " << temp << std::endl; + } + if (adcCfg.testRadSensorIntConv) { + sendBuffer[0] = max1227::buildResetByte(false); + spiTransferStruct[0].len = 1; + transfer(fd, gpioIds::CS_RAD_SENSOR); + usleep(5); + // Now use internal conversion + sendBuffer[0] = max1227::buildSetupByte(ClkSel::INT_CONV_INT_TIMED_CNVST_AS_AIN, + RefSel::INT_REF_NO_WAKEUP, DiffSel::NONE_0); + spiTransferStruct[0].len = 1; + transfer(fd, gpioIds::CS_RAD_SENSOR); + usleep(10); + sendBuffer[0] = buildConvByte(ScanModes::CHANNELS_0_TO_N, 7, true); + spiTransferStruct[0].len = 1; + transfer(fd, gpioIds::CS_RAD_SENSOR); + + usleep(65); + spiTransferStruct[0].len = 18; + // Shift out zeros + shiftOutZeros(); + transfer(fd, gpioIds::CS_RAD_SENSOR); + setSendBuffer(); + + arrayprinter::print(recvBuffer.data(), 14); + uint16_t adcRaw[8] = {}; + int16_t tempRaw = ((recvBuffer[0] & 0x0f) << 8) | recvBuffer[1]; + sif::info << "Temperature: " << tempRaw * 0.125 << " C" << std::endl; + adcRaw[0] = (recvBuffer[2] << 8) | recvBuffer[3]; + adcRaw[1] = (recvBuffer[4] << 8) | recvBuffer[5]; + adcRaw[2] = (recvBuffer[6] << 8) | recvBuffer[7]; + adcRaw[3] = (recvBuffer[8] << 8) | recvBuffer[9]; + adcRaw[4] = (recvBuffer[10] << 8) | recvBuffer[11]; + adcRaw[5] = (recvBuffer[12] << 8) | recvBuffer[13]; + adcRaw[6] = (recvBuffer[14] << 8) | recvBuffer[15]; + adcRaw[7] = (recvBuffer[16] << 8) | recvBuffer[17]; + for (int idx = 0; idx < 8; idx++) { + sif::info << "ADC raw " << idx << ": " << adcRaw[idx] << std::endl; + } + } +} + +void SpiTestClass::max1227SusTest(int fd, SusTestCfg &cfg) { + using namespace max1227; + if (cfg.extConv) { + sendBuffer[0] = max1227::buildResetByte(false); + spiTransferStruct[0].len = 1; + transfer(fd, cfg.gpioId); + + usleep(65); + sendBuffer[0] = max1227::buildSetupByte(ClkSel::EXT_CONV_EXT_TIMED, RefSel::INT_REF_NO_WAKEUP, + DiffSel::NONE_0); + spiTransferStruct[0].len = 1; + transfer(fd, cfg.gpioId); + + max1227::prepareExternallyClockedRead0ToN(sendBuffer.data(), 5, spiTransferStruct[0].len); + transfer(fd, cfg.gpioId); + uint16_t adcRaw[6] = {}; + adcRaw[0] = (recvBuffer[1] << 8) | recvBuffer[2]; + adcRaw[1] = (recvBuffer[3] << 8) | recvBuffer[4]; + adcRaw[2] = (recvBuffer[5] << 8) | recvBuffer[6]; + adcRaw[3] = (recvBuffer[7] << 8) | recvBuffer[8]; + adcRaw[4] = (recvBuffer[9] << 8) | recvBuffer[10]; + adcRaw[5] = (recvBuffer[11] << 8) | recvBuffer[12]; + sif::info << "Ext Conv [" << std::hex << std::setw(3); + for (int idx = 0; idx < 5; idx++) { + sif::info << adcRaw[idx]; + if (idx < 6) { + sif::info << ","; + } + } + sif::info << std::dec << "]" << std::endl; // | Temperature: " << temp << " C" << std::endl; + } + if (cfg.intConv) { + sendBuffer[0] = max1227::buildResetByte(false); + spiTransferStruct[0].len = 1; + transfer(fd, cfg.gpioId); + usleep(65); + // Now use internal conversion + sendBuffer[0] = max1227::buildSetupByte(ClkSel::INT_CONV_INT_TIMED_CNVST_AS_AIN, + RefSel::INT_REF_NO_WAKEUP, DiffSel::NONE_0); + spiTransferStruct[0].len = 1; + transfer(fd, cfg.gpioId); + usleep(10); + sendBuffer[0] = buildConvByte(ScanModes::CHANNELS_0_TO_N, 5, true); + spiTransferStruct[0].len = 1; + transfer(fd, cfg.gpioId); + + usleep(65); + spiTransferStruct[0].len = 14; + // Shift out zeros + shiftOutZeros(); + transfer(fd, cfg.gpioId); + setSendBuffer(); + // arrayprinter::print(recvBuffer.data(), 14); + float temp = static_cast(((recvBuffer[0] & 0x0f) << 8) | recvBuffer[1]) * 0.125; + uint16_t adcRaw[6] = {}; + adcRaw[0] = (recvBuffer[2] << 8) | recvBuffer[3]; + adcRaw[1] = (recvBuffer[4] << 8) | recvBuffer[5]; + adcRaw[2] = (recvBuffer[6] << 8) | recvBuffer[7]; + adcRaw[3] = (recvBuffer[8] << 8) | recvBuffer[9]; + adcRaw[4] = (recvBuffer[10] << 8) | recvBuffer[11]; + adcRaw[5] = (recvBuffer[12] << 8) | recvBuffer[13]; + sif::info << "Int Conv [" << std::hex << std::setw(3); + for (int idx = 0; idx < 6; idx++) { + sif::info << adcRaw[idx]; + if (idx < 5) { + sif::info << ","; + } + } + sif::info << std::dec << "] | T[C] " << temp << std::endl; + } +} + +void SpiTestClass::max1227PlPcduTest(int fd) { + using namespace max1227; + if ((adcCfg.plPcduAdcExtConv or adcCfg.plPcduAdcIntConv or adcCfg.plPcduAdcExtConvAsOne) and + adcCfg.vbatSwitch) { + // This enables the ADC + ReturnValue_t result = gpioIF->pullHigh(gpioIds::PLPCDU_ENB_VBAT0); + if (result != HasReturnvaluesIF::RETURN_OK) { + return; + } + result = gpioIF->pullHigh(gpioIds::PLPCDU_ENB_VBAT1); + if (result != HasReturnvaluesIF::RETURN_OK) { + return; + } + adcCfg.vbatSwitch = false; + // Takes a bit of time until the ADC is usable + TaskFactory::delayTask(50); + sendBuffer[0] = max1227::buildResetByte(false); + spiTransferStruct[0].len = 1; + transfer(fd, gpioIds::PLPCDU_ADC_CS); + } + if (adcCfg.plPcduAdcExtConv) { + sendBuffer[0] = max1227::buildSetupByte(ClkSel::EXT_CONV_EXT_TIMED, RefSel::INT_REF_NO_WAKEUP, + DiffSel::NONE_0); + spiTransferStruct[0].len = 1; + transfer(fd, gpioIds::PLPCDU_ADC_CS); + uint8_t n = 11; + max1227::prepareExternallyClockedRead0ToN(sendBuffer.data(), n, spiTransferStruct[0].len); + size_t dummy = 0; + max1227::prepareExternallyClockedTemperatureRead(sendBuffer.data() + spiTransferStruct[0].len, + dummy); + // + 1 to account for temp conversion byte + spiTransferStruct[0].len += 1; + transfer(fd, gpioIds::PLPCDU_ADC_CS); + uint16_t adcRaw[n + 1] = {}; + for (uint8_t idx = 0; idx < n + 1; idx++) { + adcRaw[idx] = (recvBuffer[idx * 2 + 1] << 8) | recvBuffer[idx * 2 + 2]; + } + spiTransferStruct[0].len = 24; + // Shift out zeros + shiftOutZeros(); + transfer(fd, gpioIds::PLPCDU_ADC_CS); + setSendBuffer(); + int16_t tempRaw = ((recvBuffer[22] & 0x0f) << 8) | recvBuffer[23]; + sif::info << "PL PCDU ADC ext conv [" << std::hex << std::setfill('0'); + for (int idx = 0; idx < n + 1; idx++) { + sif::info << std::setw(3) << adcRaw[idx]; + if (idx < n) { + sif::info << ","; + } + } + sif::info << "]" << std::endl; + sif::info << "Temperature: " << max1227::getTemperature(tempRaw) << " C" << std::endl; + } + if (adcCfg.plPcduAdcExtConvAsOne) { + sendBuffer[0] = max1227::buildSetupByte(ClkSel::EXT_CONV_EXT_TIMED, RefSel::INT_REF_NO_WAKEUP, + DiffSel::NONE_0); + spiTransferStruct[0].len = 1; + transfer(fd, gpioIds::PLPCDU_ADC_CS); + uint8_t n = 11; + max1227::prepareExternallyClockedRead0ToN(sendBuffer.data(), n, spiTransferStruct[0].len); + max1227::prepareExternallyClockedTemperatureRead(sendBuffer.data() + spiTransferStruct[0].len, + spiTransferStruct[0].len); + transfer(fd, gpioIds::PLPCDU_ADC_CS); + uint16_t adcRaw[n + 1] = {}; + for (uint8_t idx = 0; idx < n + 1; idx++) { + adcRaw[idx] = (recvBuffer[idx * 2 + 1] << 8) | recvBuffer[idx * 2 + 2]; + } + int16_t tempRaw = ((recvBuffer[spiTransferStruct[0].len - 2] & 0x0f) << 8) | + recvBuffer[spiTransferStruct[0].len - 1]; + sif::info << "PL PCDU ADC ext conv [" << std::hex << std::setfill('0'); + for (int idx = 0; idx < n + 1; idx++) { + sif::info << std::setw(3) << adcRaw[idx]; + if (idx < n) { + sif::info << ","; + } + } + sif::info << "]" << std::endl; + sif::info << "Temperature: " << max1227::getTemperature(tempRaw) << " C" << std::endl; + } + if (adcCfg.plPcduAdcIntConv) { + sendBuffer[0] = max1227::buildResetByte(true); + spiTransferStruct[0].len = 1; + transfer(fd, gpioIds::PLPCDU_ADC_CS); + // Now use internal conversion + sendBuffer[0] = max1227::buildSetupByte(ClkSel::INT_CONV_INT_TIMED_CNVST_AS_AIN, + RefSel::INT_REF_NO_WAKEUP, DiffSel::NONE_0); + spiTransferStruct[0].len = 1; + transfer(fd, gpioIds::PLPCDU_ADC_CS); + usleep(10); + uint8_t n = 11; + sendBuffer[0] = buildConvByte(ScanModes::CHANNELS_0_TO_N, n, true); + spiTransferStruct[0].len = 1; + transfer(fd, gpioIds::PLPCDU_ADC_CS); + + usleep(65); + spiTransferStruct[0].len = 26; + // Shift out zeros + shiftOutZeros(); + transfer(fd, gpioIds::PLPCDU_ADC_CS); + setSendBuffer(); + uint16_t adcRaw[n + 1] = {}; + int16_t tempRaw = ((recvBuffer[0] & 0x0f) << 8) | recvBuffer[1]; + sif::info << "PL PCDU ADC int conv [" << std::hex << std::setfill('0'); + for (int idx = 0; idx < n + 1; idx++) { + adcRaw[idx] = (recvBuffer[idx * 2 + 2] << 8) | recvBuffer[idx * 2 + 3]; + sif::info << std::setw(3) << adcRaw[idx]; + if (idx < n) { + sif::info << ","; + } + } + sif::info << "]" << std::endl; + sif::info << "Temperature: " << max1227::getTemperature(tempRaw) << " C" << std::endl; + } } void SpiTestClass::acsInit() { - GpioCookie* gpioCookie = new GpioCookie(); + using namespace gpio; + GpioCookie *gpioCookie = new GpioCookie(); #ifdef RASPBERRY_PI - GpiodRegularByChip* gpio = nullptr; - std::string rpiGpioName = "gpiochip0"; - gpio = new GpiodRegularByChip(rpiGpioName, mgm0Lis3mdlChipSelect, "MGM_0_LIS3", - gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::MGM_0_LIS3_CS, gpio); + GpiodRegularByChip *gpio = nullptr; + std::string rpiGpioName = "gpiochip0"; + gpio = new GpiodRegularByChip(rpiGpioName, mgm0Lis3mdlChipSelect, "MGM_0_LIS3", Direction::OUT, + Levels::HIGH); + gpioCookie->addGpio(gpioIds::MGM_0_LIS3_CS, gpio); - gpio = new GpiodRegularByChip(rpiGpioName, mgm1Rm3100ChipSelect, "MGM_1_RM3100", - gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::MGM_1_RM3100_CS, gpio); + gpio = new GpiodRegularByChip(rpiGpioName, mgm1Rm3100ChipSelect, "MGM_1_RM3100", Direction::OUT, + Levels::HIGH); + gpioCookie->addGpio(gpioIds::MGM_1_RM3100_CS, gpio); - gpio = new GpiodRegularByChip(rpiGpioName, gyro0AdisChipSelect, "GYRO_0_ADIS", - gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::GYRO_0_ADIS_CS, gpio); + gpio = new GpiodRegularByChip(rpiGpioName, gyro0AdisChipSelect, "GYRO_0_ADIS", Direction::OUT, + Levels::HIGH); + gpioCookie->addGpio(gpioIds::GYRO_0_ADIS_CS, gpio); - gpio = new GpiodRegularByChip(rpiGpioName, gyro1L3gd20ChipSelect, "GYRO_1_L3G", - gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::GYRO_1_L3G_CS, gpio); + gpio = new GpiodRegularByChip(rpiGpioName, gyro1L3gd20ChipSelect, "GYRO_1_L3G", Direction::OUT, + Levels::HIGH); + gpioCookie->addGpio(gpioIds::GYRO_1_L3G_CS, gpio); - gpio = new GpiodRegularByChip(rpiGpioName, gyro3L3gd20ChipSelect, "GYRO_2_L3G", - gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::GYRO_3_L3G_CS, gpio); + gpio = new GpiodRegularByChip(rpiGpioName, gyro3L3gd20ChipSelect, "GYRO_2_L3G", Direction::OUT, + Levels::HIGH); + gpioCookie->addGpio(gpioIds::GYRO_3_L3G_CS, gpio); - gpio = new GpiodRegularByChip(rpiGpioName, mgm2Lis3mdlChipSelect, "MGM_2_LIS3", - gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::MGM_2_LIS3_CS, gpio); + gpio = new GpiodRegularByChip(rpiGpioName, mgm2Lis3mdlChipSelect, "MGM_2_LIS3", Direction::OUT, + Levels::HIGH); + gpioCookie->addGpio(gpioIds::MGM_2_LIS3_CS, gpio); - gpio = new GpiodRegularByChip(rpiGpioName, mgm3Rm3100ChipSelect, "MGM_3_RM3100", - gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::MGM_3_RM3100_CS, gpio); + gpio = new GpiodRegularByChip(rpiGpioName, mgm3Rm3100ChipSelect, "MGM_3_RM3100", Direction::OUT, + Levels::HIGH); + gpioCookie->addGpio(gpioIds::MGM_3_RM3100_CS, gpio); #elif defined(XIPHOS_Q7S) - GpiodRegularByLabel* gpio = nullptr; - gpio = new GpiodRegularByLabel(q7s::GPIO_ACS_BOARD_DEFAULT_LABEL, mgm0Lis3mdlChipSelect, - "MGM_0_LIS3", gpio::Direction::OUT, gpio::HIGH); - gpioCookie->addGpio(gpioIds::MGM_0_LIS3_CS, gpio); - gpio = new GpiodRegularByLabel(q7s::GPIO_ACS_BOARD_DEFAULT_LABEL, mgm1Rm3100ChipSelect, - "MGM_1_RM3100", gpio::Direction::OUT, gpio::HIGH); - gpioCookie->addGpio(gpioIds::MGM_1_RM3100_CS, gpio); - gpio = new GpiodRegularByLabel(q7s::GPIO_MGM2_LIS3_LABEL, mgm2Lis3mdlChipSelect, - "MGM_2_LIS3", gpio::Direction::OUT, gpio::HIGH); - gpioCookie->addGpio(gpioIds::MGM_2_LIS3_CS, gpio); - gpio = new GpiodRegularByLabel(q7s::GPIO_ACS_BOARD_DEFAULT_LABEL, mgm3Rm3100ChipSelect, - "MGM_3_RM3100", gpio::Direction::OUT, gpio::HIGH); - gpioCookie->addGpio(gpioIds::MGM_3_RM3100_CS, gpio); + GpiodRegularByLineName *gpio = nullptr; + gpio = new GpiodRegularByLineName(q7s::gpioNames::MGM_0_CS, "MGM_0_LIS3", Direction::OUT, + Levels::HIGH); + gpioCookie->addGpio(gpioIds::MGM_0_LIS3_CS, gpio); + gpio = new GpiodRegularByLineName(q7s::gpioNames::MGM_1_CS, "MGM_1_RM3100", Direction::OUT, + Levels::HIGH); + gpioCookie->addGpio(gpioIds::MGM_1_RM3100_CS, gpio); + gpio = new GpiodRegularByLineName(q7s::gpioNames::MGM_2_CS, "MGM_2_LIS3", Direction::OUT, + Levels::HIGH); + gpioCookie->addGpio(gpioIds::MGM_2_LIS3_CS, gpio); + gpio = new GpiodRegularByLineName(q7s::gpioNames::MGM_1_CS, "MGM_3_RM3100", Direction::OUT, + Levels::HIGH); + gpioCookie->addGpio(gpioIds::MGM_3_RM3100_CS, gpio); - gpio = new GpiodRegularByLabel(q7s::GPIO_GYRO_ADIS_LABEL, gyro0AdisChipSelect, - "GYRO_0_ADIS", gpio::Direction::OUT, gpio::HIGH); - gpioCookie->addGpio(gpioIds::GYRO_0_ADIS_CS, gpio); - gpio = new GpiodRegularByLabel(q7s::GPIO_ACS_BOARD_DEFAULT_LABEL, gyro1L3gd20ChipSelect, - "GYRO_1_L3G", gpio::Direction::OUT, gpio::HIGH); - gpioCookie->addGpio(gpioIds::GYRO_1_L3G_CS, gpio); - gpio = new GpiodRegularByLabel(q7s::GPIO_GYRO_ADIS_LABEL, gyro2AdisChipSelect, "GYRO_2_ADIS", - gpio::Direction::OUT, gpio::HIGH); - gpioCookie->addGpio(gpioIds::GYRO_2_ADIS_CS, gpio); - gpio = new GpiodRegularByLabel(q7s::GPIO_ACS_BOARD_DEFAULT_LABEL, gyro3L3gd20ChipSelect, - "GYRO_3_L3G", gpio::Direction::OUT, gpio::HIGH); - gpioCookie->addGpio(gpioIds::GYRO_3_L3G_CS, gpio); + gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_0_ADIS_CS, "GYRO_0_ADIS", Direction::OUT, + Levels::HIGH); + gpioCookie->addGpio(gpioIds::GYRO_0_ADIS_CS, gpio); + gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_1_L3G_CS, "GYRO_1_L3G", Direction::OUT, + Levels::HIGH); + gpioCookie->addGpio(gpioIds::GYRO_1_L3G_CS, gpio); + gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_2_ADIS_CS, "GYRO_2_ADIS", Direction::OUT, + Levels::HIGH); + gpioCookie->addGpio(gpioIds::GYRO_2_ADIS_CS, gpio); + gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_3_L3G_CS, "GYRO_3_L3G", Direction::OUT, + Levels::HIGH); + gpioCookie->addGpio(gpioIds::GYRO_3_L3G_CS, gpio); - // Enable pins must be pulled low for regular operations - gpio = new GpiodRegularByLabel(q7s::GPIO_FLEX_OBC1F_B0, q7s::GPIO_GYRO_0_ENABLE, - "GYRO_0_ENABLE", gpio::OUT, gpio::LOW); - gpioCookie->addGpio(gpioIds::GYRO_0_ENABLE, gpio); - gpio = new GpiodRegularByLabel(q7s::GPIO_3V3_OBC1C, q7s::GPIO_GYRO_2_ENABLE, - "GYRO_2_ENABLE", gpio::OUT, gpio::LOW); - gpioCookie->addGpio(gpioIds::GYRO_2_ENABLE, gpio); + // Enable pins must be pulled low for regular operations + gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_0_ENABLE, "GYRO_0_ENABLE", Direction::OUT, + Levels::LOW); + gpioCookie->addGpio(gpioIds::GYRO_0_ENABLE, gpio); + gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_0_ENABLE, "GYRO_2_ENABLE", Direction::OUT, + Levels::LOW); + gpioCookie->addGpio(gpioIds::GYRO_2_ENABLE, gpio); #endif - if (gpioIF != nullptr) { - gpioIF->addGpios(gpioCookie); - } + if (gpioIF != nullptr) { + gpioIF->addGpios(gpioCookie); + } } void SpiTestClass::setSpiSpeedAndMode(int spiFd, spi::SpiModes mode, uint32_t speed) { - int mode_test = SPI_MODE_3; - int retval = ioctl(spiFd, SPI_IOC_WR_MODE, &mode_test);//reinterpret_cast(&mode)); - if(retval != 0) { - utility::handleIoctlError("SpiTestClass::performRm3100Test: Setting SPI mode failed!"); + int modeUnix = 0; + switch (mode) { + case (spi::SpiModes::MODE_0): { + modeUnix = SPI_MODE_0; + break; } + case (spi::SpiModes::MODE_1): { + modeUnix = SPI_MODE_1; + break; + } + case (spi::SpiModes::MODE_2): { + modeUnix = SPI_MODE_2; + break; + } + case (spi::SpiModes::MODE_3): { + modeUnix = SPI_MODE_3; + break; + } + } - retval = ioctl(spiFd, SPI_IOC_WR_MAX_SPEED_HZ, &speed); - if(retval != 0) { - utility::handleIoctlError("SpiTestClass::performRm3100Test: Setting SPI speed failed!"); - } + int retval = ioctl(spiFd, SPI_IOC_WR_MODE, &modeUnix); // reinterpret_cast(&mode)); + if (retval != 0) { + utility::handleIoctlError("SpiTestClass::performRm3100Test: Setting SPI mode failed!"); + } + + retval = ioctl(spiFd, SPI_IOC_WR_MAX_SPEED_HZ, &speed); + if (retval != 0) { + utility::handleIoctlError("SpiTestClass::performRm3100Test: Setting SPI speed failed!"); + } } void SpiTestClass::writeRegister(int fd, gpioId_t chipSelect, uint8_t reg, uint8_t value) { - spiTransferStruct.len = 2; - sendBuffer[0] = reg; - sendBuffer[1] = value; + spiTransferStruct[0].len = 2; + sendBuffer[0] = reg; + sendBuffer[1] = value; - if(gpioIF != nullptr and chipSelect != gpio::NO_GPIO) { - gpioIF->pullLow(chipSelect); - } - int retval = ioctl(fd, SPI_IOC_MESSAGE(1), &spiTransferStruct); - if(retval < 0) { - utility::handleIoctlError("SpiTestClass::writeRegister: Write failed"); - } - if(gpioIF != nullptr and chipSelect != gpio::NO_GPIO) { - gpioIF->pullHigh(chipSelect); - } + if (gpioIF != nullptr and chipSelect != gpio::NO_GPIO) { + gpioIF->pullLow(chipSelect); + } + int retval = ioctl(fd, SPI_IOC_MESSAGE(1), &spiTransferStruct); + if (retval < 0) { + utility::handleIoctlError("SpiTestClass::writeRegister: Write failed"); + } + if (gpioIF != nullptr and chipSelect != gpio::NO_GPIO) { + gpioIF->pullHigh(chipSelect); + } } void SpiTestClass::writeStmRegister(int fd, gpioId_t chipSelect, uint8_t reg, uint8_t value, - bool autoIncrement) { - if(autoIncrement) { - reg |= STM_AUTO_INCR_MASK; - } - writeRegister(fd, chipSelect, reg, value); + bool autoIncrement) { + if (autoIncrement) { + reg |= STM_AUTO_INCR_MASK; + } + writeRegister(fd, chipSelect, reg, value); } void SpiTestClass::writeMultipleStmRegisters(int fd, gpioId_t chipSelect, uint8_t reg, - uint8_t *values, size_t len) { - if(values == nullptr) { - return; - } - - reg |= STM_AUTO_INCR_MASK; - /* Clear read mask */ - reg &= ~STM_READ_MASK; - writeMultipleRegisters(fd, chipSelect, reg, values, len); + uint8_t *values, size_t len) { + if (values == nullptr) { + return; + } + reg |= STM_AUTO_INCR_MASK; + /* Clear read mask */ + reg &= ~STM_READ_MASK; + writeMultipleRegisters(fd, chipSelect, reg, values, len); } -void SpiTestClass::writeMultipleRegisters(int fd, gpioId_t chipSelect, uint8_t reg, - uint8_t *values, size_t len) { - if(values == nullptr) { - return; - } +void SpiTestClass::writeMultipleRegisters(int fd, gpioId_t chipSelect, uint8_t reg, uint8_t *values, + size_t len) { + if (values == nullptr) { + return; + } - sendBuffer[0] = reg; - std::memcpy(sendBuffer.data() + 1, values, len); - spiTransferStruct.len = len + 1; + sendBuffer[0] = reg; + std::memcpy(sendBuffer.data() + 1, values, len); + spiTransferStruct[0].len = len + 1; - if(gpioIF != nullptr and chipSelect != gpio::NO_GPIO) { - gpioIF->pullLow(chipSelect); - } - int retval = ioctl(fd, SPI_IOC_MESSAGE(1), &spiTransferStruct); - if(retval < 0) { - utility::handleIoctlError("SpiTestClass::readRegister: Read failed"); - } - if(gpioIF != nullptr and chipSelect != gpio::NO_GPIO) { - gpioIF->pullHigh(chipSelect); - } + if (gpioIF != nullptr and chipSelect != gpio::NO_GPIO) { + gpioIF->pullLow(chipSelect); + } + int retval = ioctl(fd, SPI_IOC_MESSAGE(1), &spiTransferStruct); + if (retval < 0) { + utility::handleIoctlError("SpiTestClass::readRegister: Read failed"); + } + if (gpioIF != nullptr and chipSelect != gpio::NO_GPIO) { + gpioIF->pullHigh(chipSelect); + } } uint8_t SpiTestClass::readRm3100Register(int fd, gpioId_t chipSelect, uint8_t reg) { - return readStmRegister(fd, chipSelect, reg, false); + return readStmRegister(fd, chipSelect, reg, false); } +void SpiTestClass::readMultipleStmRegisters(int fd, gpioId_t chipSelect, uint8_t reg, + uint8_t *reply, size_t len) { + reg |= STM_AUTO_INCR_MASK; + readMultipleRegisters(fd, chipSelect, reg, reply, len); +} -void SpiTestClass::readMultipleStmRegisters(int fd, gpioId_t chipSelect, uint8_t reg, uint8_t *reply, - size_t len) { - reg |= STM_AUTO_INCR_MASK; - readMultipleRegisters(fd, chipSelect, reg, reply, len); +void SpiTestClass::shiftOutZeros() { spiTransferStruct[0].tx_buf = 0; } + +void SpiTestClass::setSendBuffer() { + spiTransferStruct[0].tx_buf = reinterpret_cast<__u64>(sendBuffer.data()); } void SpiTestClass::readMultipleRegisters(int fd, gpioId_t chipSelect, uint8_t reg, uint8_t *reply, - size_t len) { - if(reply == nullptr) { - return; - } + size_t len) { + if (reply == nullptr) { + return; + } - spiTransferStruct.len = len + 1; - sendBuffer[0] = reg | STM_READ_MASK; + spiTransferStruct[0].len = len + 1; + sendBuffer[0] = reg | STM_READ_MASK; - for(uint8_t idx = 0; idx < len ; idx ++) { - sendBuffer[idx + 1] = 0; - } + for (uint8_t idx = 0; idx < len; idx++) { + sendBuffer[idx + 1] = 0; + } - if(gpioIF != nullptr and chipSelect != gpio::NO_GPIO) { - gpioIF->pullLow(chipSelect); - } - int retval = ioctl(fd, SPI_IOC_MESSAGE(1), &spiTransferStruct); - if(retval < 0) { - utility::handleIoctlError("SpiTestClass::readRegister: Read failed"); - } - if(gpioIF != nullptr and chipSelect != gpio::NO_GPIO) { - gpioIF->pullHigh(chipSelect); - } - std::memcpy(reply, recvBuffer.data() + 1, len); + if (gpioIF != nullptr and chipSelect != gpio::NO_GPIO) { + gpioIF->pullLow(chipSelect); + } + int retval = ioctl(fd, SPI_IOC_MESSAGE(1), &spiTransferStruct); + if (retval < 0) { + utility::handleIoctlError("SpiTestClass::readRegister: Read failed"); + } + if (gpioIF != nullptr and chipSelect != gpio::NO_GPIO) { + gpioIF->pullHigh(chipSelect); + } + std::memcpy(reply, recvBuffer.data() + 1, len); } uint8_t SpiTestClass::readStmRegister(int fd, gpioId_t chipSelect, uint8_t reg, - bool autoIncrement) { - reg |= STM_READ_MASK; - if(autoIncrement) { - reg |= STM_AUTO_INCR_MASK; - } - return readRegister(fd, chipSelect, reg); + bool autoIncrement) { + reg |= STM_READ_MASK; + if (autoIncrement) { + reg |= STM_AUTO_INCR_MASK; + } + return readRegister(fd, chipSelect, reg); } - uint8_t SpiTestClass::readRegister(int fd, gpioId_t chipSelect, uint8_t reg) { - spiTransferStruct.len = 2; - sendBuffer[0] = reg; - sendBuffer[1] = 0; + spiTransferStruct[0].len = 2; + sendBuffer[0] = reg; + sendBuffer[1] = 0; - if(gpioIF != nullptr and chipSelect != gpio::NO_GPIO) { - gpioIF->pullLow(chipSelect); - } - int retval = ioctl(fd, SPI_IOC_MESSAGE(1), &spiTransferStruct); - if(retval < 0) { - utility::handleIoctlError("SpiTestClass::readRegister: Read failed"); - } - if(gpioIF != nullptr and chipSelect != gpio::NO_GPIO) { - gpioIF->pullHigh(chipSelect); - } - return recvBuffer[1]; + if (gpioIF != nullptr and chipSelect != gpio::NO_GPIO) { + gpioIF->pullLow(chipSelect); + } + int retval = ioctl(fd, SPI_IOC_MESSAGE(1), &spiTransferStruct); + if (retval < 0) { + utility::handleIoctlError("SpiTestClass::readRegister: Read failed"); + } + if (gpioIF != nullptr and chipSelect != gpio::NO_GPIO) { + gpioIF->pullHigh(chipSelect); + } + return recvBuffer[1]; +} + +ReturnValue_t SpiTestClass::transfer(int fd, gpioId_t chipSelect = gpio::NO_GPIO) { + int retval = 0; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + if (chipSelect != gpio::NO_GPIO) { + result = gpioIF->pullLow(chipSelect); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + } + + retval = ioctl(fd, SPI_IOC_MESSAGE(1), &spiTransferStruct); + if (retval < 0) { + utility::handleIoctlError("SpiTestClass::transfer: ioctl failed"); + return HasReturnvaluesIF::RETURN_FAILED; + } + + if (chipSelect != gpio::NO_GPIO) { + result = gpioIF->pullHigh(chipSelect); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + } + return HasReturnvaluesIF::RETURN_OK; } diff --git a/linux/boardtest/SpiTestClass.h b/linux/boardtest/SpiTestClass.h index 45a7cdd8..15675f1a 100644 --- a/linux/boardtest/SpiTestClass.h +++ b/linux/boardtest/SpiTestClass.h @@ -6,99 +6,117 @@ #if defined(XIPHOS_Q7S) #include "busConf.h" #endif - #include #include #include #include -class SpiTestClass: public TestTask { -public: - enum TestModes { - NONE, - MGM_LIS3MDL, - MGM_RM3100, - GYRO_L3GD20H, - }; - - TestModes testMode; - - SpiTestClass(object_id_t objectId, GpioIF* gpioIF); - - ReturnValue_t performOneShotAction() override; - ReturnValue_t performPeriodicAction() override; -private: - - GpioIF* gpioIF; - - std::array recvBuffer; - std::array sendBuffer; - struct spi_ioc_transfer spiTransferStruct = {}; - - void performRm3100Test(uint8_t mgmId); - void performLis3MdlTest(uint8_t lis3Id); - void performL3gTest(uint8_t l3gId); - - /* ACS board specific code which pulls all GPIOs high */ - void acsInit(); - - /* ACS board specific variables */ -#ifdef RASPBERRY_PI - uint8_t mgm0Lis3mdlChipSelect = gpio::MGM_0_BCM_PIN; - uint8_t mgm1Rm3100ChipSelect = gpio::MGM_1_BCM_PIN; - uint8_t mgm2Lis3mdlChipSelect = gpio::MGM_2_BCM_PIN; - uint8_t mgm3Rm3100ChipSelect = gpio::MGM_3_BCM_PIN; - - uint8_t gyro0AdisChipSelect = gpio::GYRO_0_BCM_PIN; - uint8_t gyro1L3gd20ChipSelect = gpio::GYRO_1_BCM_PIN; - uint8_t gyro2AdisChipSelect = gpio::GYRO_2_BCM_PIN; - uint8_t gyro3L3gd20ChipSelect = gpio::GYRO_3_BCM_PIN; -#elif defined(XIPHOS_Q7S) - uint8_t mgm0Lis3mdlChipSelect = q7s::GPIO_MGM_0_LIS3_CS; - uint8_t mgm1Rm3100ChipSelect = q7s::GPIO_MGM_1_RM3100_CS; - uint8_t gyro0AdisChipSelect = q7s::GPIO_GYRO_0_ADIS_CS; - uint8_t gyro2AdisChipSelect = q7s::GPIO_GYRO_2_ADIS_CS; - uint8_t gyro1L3gd20ChipSelect = q7s::GPIO_GYRO_1_L3G_CS; - uint8_t gyro3L3gd20ChipSelect = q7s::GPIO_GYRO_3_L3G_CS; - uint8_t mgm2Lis3mdlChipSelect = q7s::GPIO_MGM_2_LIS3_CS; - uint8_t mgm3Rm3100ChipSelect = q7s::GPIO_MGM_3_RM3100_CS; -#else - uint8_t mgm0Lis3mdlChipSelect = 0; - uint8_t mgm1Rm3100ChipSelect = 0; - uint8_t gyro0AdisResetLine = 0; - uint8_t gyro0AdisChipSelect = 0; - uint8_t gyro1L3gd20ChipSelect = 0; - uint8_t gyro2L3gd20ChipSelect = 0; - uint8_t mgm2Lis3mdlChipSelect = 0; - uint8_t mgm3Rm3100ChipSelect = 0; -#endif - - static constexpr uint8_t STM_READ_MASK = 0b1000'0000; - static constexpr uint8_t RM3100_READ_MASK = STM_READ_MASK; - static constexpr uint8_t STM_AUTO_INCR_MASK = 0b0100'0000; - - void setSpiSpeedAndMode(int spiFd, spi::SpiModes mode, uint32_t speed); - - void writeStmRegister(int fd, gpioId_t chipSelect, uint8_t reg, uint8_t value, - bool autoIncrement); - void writeMultipleStmRegisters(int fd, gpioId_t chipSelect, uint8_t reg, uint8_t* values, - size_t len); - void writeMultipleRegisters(int fd, gpioId_t chipSelect, uint8_t reg, uint8_t *values, - size_t len); - void writeRegister(int fd, gpioId_t chipSelect, uint8_t reg, uint8_t value); - - uint8_t readRm3100Register(int fd, gpioId_t chipSelect, uint8_t reg); - uint8_t readStmRegister(int fd, gpioId_t chipSelect, uint8_t reg, bool autoIncrement); - uint8_t readRegister(int fd, gpioId_t chipSelect, uint8_t reg); - void readMultipleStmRegisters(int fd, gpioId_t chipSelect, uint8_t reg, uint8_t *reply, - size_t len); - void readMultipleRegisters(int fd, gpioId_t chipSelect, uint8_t reg, - uint8_t* reply, size_t len); +#include "devices/gpioIds.h" +struct SusTestCfg { + SusTestCfg(bool doTest, gpioId_t gpioId) : gpioId(gpioId) {} + bool doTest = false; + const gpioId_t gpioId; + bool intConv = true; + bool extConv = false; }; +struct Max1227TestCfg { + bool testRadSensorExtConvWithDelay = false; + bool testRadSensorIntConv = false; + bool plPcduAdcExtConv = false; + bool plPcduAdcExtConvAsOne = false; + bool plPcduAdcIntConv = false; + bool vbatSwitch = true; + SusTestCfg testSus[12] = { + {false, gpioIds::CS_SUS_0}, {false, gpioIds::CS_SUS_1}, {false, gpioIds::CS_SUS_2}, + {false, gpioIds::CS_SUS_3}, {false, gpioIds::CS_SUS_4}, {false, gpioIds::CS_SUS_5}, + {false, gpioIds::CS_SUS_6}, {false, gpioIds::CS_SUS_7}, {false, gpioIds::CS_SUS_8}, + {false, gpioIds::CS_SUS_9}, {false, gpioIds::CS_SUS_10}, {false, gpioIds::CS_SUS_11}, + }; +}; +class SpiTestClass : public TestTask { + public: + enum TestModes { NONE, MGM_LIS3MDL, MGM_RM3100, GYRO_L3GD20H, MAX1227 }; + TestModes testMode; + + SpiTestClass(object_id_t objectId, GpioIF* gpioIF); + + ReturnValue_t performOneShotAction() override; + ReturnValue_t performPeriodicAction() override; + + private: + GpioIF* gpioIF; + Max1227TestCfg adcCfg = {}; + + std::array recvBuffer; + std::array sendBuffer; + struct spi_ioc_transfer spiTransferStruct[6] = {}; + + void performRm3100Test(uint8_t mgmId); + void performLis3MdlTest(uint8_t lis3Id); + void performL3gTest(uint8_t l3gId); + void performOneShotMax1227Test(); + void performPeriodicMax1227Test(); + void performMax1227Test(); + + /* ACS board specific code which pulls all GPIOs high */ + void acsInit(); + + /* ACS board specific variables */ +#ifdef RASPBERRY_PI + uint8_t mgm0Lis3mdlChipSelect = gpio::MGM_0_BCM_PIN; + uint8_t mgm1Rm3100ChipSelect = gpio::MGM_1_BCM_PIN; + uint8_t mgm2Lis3mdlChipSelect = gpio::MGM_2_BCM_PIN; + uint8_t mgm3Rm3100ChipSelect = gpio::MGM_3_BCM_PIN; + + uint8_t gyro0AdisChipSelect = gpio::GYRO_0_BCM_PIN; + uint8_t gyro1L3gd20ChipSelect = gpio::GYRO_1_BCM_PIN; + uint8_t gyro2AdisChipSelect = gpio::GYRO_2_BCM_PIN; + uint8_t gyro3L3gd20ChipSelect = gpio::GYRO_3_BCM_PIN; +#else + + uint8_t mgm0Lis3mdlChipSelect = 0; + uint8_t mgm1Rm3100ChipSelect = 0; + uint8_t gyro0AdisResetLine = 0; + uint8_t gyro0AdisChipSelect = 0; + uint8_t gyro1L3gd20ChipSelect = 0; + uint8_t gyro2L3gd20ChipSelect = 0; + uint8_t mgm2Lis3mdlChipSelect = 0; + uint8_t mgm3Rm3100ChipSelect = 0; +#endif + + static constexpr uint8_t STM_READ_MASK = 0b1000'0000; + static constexpr uint8_t RM3100_READ_MASK = STM_READ_MASK; + static constexpr uint8_t STM_AUTO_INCR_MASK = 0b0100'0000; + + void shiftOutZeros(); + void setSendBuffer(); + + void max1227RadSensorTest(int fd); + void max1227SusTest(int fd, SusTestCfg& cfg); + void max1227PlPcduTest(int fd); + + void setSpiSpeedAndMode(int spiFd, spi::SpiModes mode, uint32_t speed); + + void writeStmRegister(int fd, gpioId_t chipSelect, uint8_t reg, uint8_t value, + bool autoIncrement); + void writeMultipleStmRegisters(int fd, gpioId_t chipSelect, uint8_t reg, uint8_t* values, + size_t len); + void writeMultipleRegisters(int fd, gpioId_t chipSelect, uint8_t reg, uint8_t* values, + size_t len); + void writeRegister(int fd, gpioId_t chipSelect, uint8_t reg, uint8_t value); + ReturnValue_t transfer(int fd, gpioId_t chipSelect); + + uint8_t readRm3100Register(int fd, gpioId_t chipSelect, uint8_t reg); + uint8_t readStmRegister(int fd, gpioId_t chipSelect, uint8_t reg, bool autoIncrement); + uint8_t readRegister(int fd, gpioId_t chipSelect, uint8_t reg); + void readMultipleStmRegisters(int fd, gpioId_t chipSelect, uint8_t reg, uint8_t* reply, + size_t len); + void readMultipleRegisters(int fd, gpioId_t chipSelect, uint8_t reg, uint8_t* reply, size_t len); +}; #endif /* LINUX_BOARDTEST_SPITESTCLASS_H_ */ diff --git a/linux/boardtest/UartTestClass.cpp b/linux/boardtest/UartTestClass.cpp index e69f0e5f..9c51ed8a 100644 --- a/linux/boardtest/UartTestClass.cpp +++ b/linux/boardtest/UartTestClass.cpp @@ -1,114 +1,225 @@ #include "UartTestClass.h" -#if defined(RASPBERRY_PI) -#include "rpiConfig.h" -#elif defined(XIPHOS_Q7S) -#include "q7sConfig.h" + +#include // Error integer and strerror() function +#include // Contains file controls like O_RDWR +#include +#include // write(), read(), close() + +#include "OBSWConfig.h" +#include "fsfw/globalfunctions/CRC.h" +#include "fsfw/globalfunctions/DleEncoder.h" +#include "fsfw/globalfunctions/arrayprinter.h" +#include "fsfw/serviceinterface.h" +#include "mission/devices/devicedefinitions/SCEXDefinitions.h" + +#define GPS_REPLY_WIRETAPPING 0 + +#ifndef RPI_TEST_GPS_HANDLER +#define RPI_TEST_GPS_HANDLER 0 #endif -#include "fsfw/serviceinterface/ServiceInterface.h" - -#include "lwgps/lwgps.h" - -#include // Contains file controls like O_RDWR -#include // Error integer and strerror() function -#include // write(), read(), close() - -#define GPS_REPLY_WIRETAPPING 0 - -UartTestClass::UartTestClass(object_id_t objectId): TestTask(objectId) { -} +UartTestClass::UartTestClass(object_id_t objectId) : TestTask(objectId) { mode = TestModes::SCEX; } ReturnValue_t UartTestClass::initialize() { -#if RPI_TEST_GPS_DEVICE == 1 - int result = lwgps_init(&gpsData); - if(result == 0) { - sif::warning << "lwgps_init error: " << result << std::endl; - } - - /* Get file descriptor */ - serialPort = open("/dev/serial0", O_RDWR); - if(serialPort < 0) { - sif::warning << "open call failed with error [" << errno << ", " << strerror(errno) - << std::endl; - } - /* Setting up UART parameters */ - tty.c_cflag &= ~PARENB; // Clear parity bit - tty.c_cflag &= ~CSTOPB; // Clear stop field, only one stop bit used in communication - tty.c_cflag &= ~CSIZE; // Clear all the size bits - tty.c_cflag |= CS8; // 8 bits per byte - tty.c_cflag &= ~CRTSCTS; // Disable RTS/CTS hardware flow control - tty.c_cflag |= CREAD | CLOCAL; // Turn on READ & ignore ctrl lines (CLOCAL = 1) - // Use canonical mode for GPS device - tty.c_lflag |= ICANON; - tty.c_lflag &= ~ECHO; // Disable echo - tty.c_lflag &= ~ECHOE; // Disable erasure - tty.c_lflag &= ~ECHONL; // Disable new-line echo - tty.c_lflag &= ~ISIG; // Disable interpretation of INTR, QUIT and SUSP - tty.c_iflag &= ~(IXON | IXOFF | IXANY); // Turn off s/w flow ctrl - tty.c_iflag &= ~(IGNBRK|BRKINT|PARMRK|ISTRIP|INLCR|IGNCR|ICRNL); // Disable any special handling of received bytes - tty.c_oflag &= ~OPOST; // Prevent special interpretation of output bytes (e.g. newline chars) - tty.c_oflag &= ~ONLCR; // Prevent conversion of newline to carriage return/line feed - - // Non-blocking mode - tty.c_cc[VTIME] = 0; - tty.c_cc[VMIN] = 0; - - cfsetispeed(&tty, B9600); - cfsetospeed(&tty, B9600); - if (tcsetattr(serialPort, TCSANOW, &tty) != 0) { - sif::warning << "tcsetattr call failed with error [" << errno << ", " << - strerror(errno) << std::endl;; - } - // Flush received and unread data. Those are old NMEA strings which are not relevant anymore - tcflush(serialPort, TCIFLUSH); -#endif - return HasReturnvaluesIF::RETURN_OK; + if (mode == TestModes::GPS) { + gpsInit(); + } else if (mode == TestModes::SCEX) { + scexInit(); + } + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t UartTestClass::performOneShotAction() { -#if RPI_TEST_GPS_DEVICE == 1 -#endif - return HasReturnvaluesIF::RETURN_OK; -} +ReturnValue_t UartTestClass::performOneShotAction() { return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t UartTestClass::performPeriodicAction() { -#if RPI_TEST_GPS_DEVICE == 1 - int bytesRead = 0; - do { - bytesRead = read(serialPort, - reinterpret_cast(recBuf.data()), - static_cast(recBuf.size())); - if(bytesRead < 0) { - sif::warning << "UartTestClass::performPeriodicAction: read call failed with error [" << - errno << ", " << strerror(errno) << "]" << std::endl; - break; - } - else if(bytesRead >= static_cast(recBuf.size())) { - sif::debug << "UartTestClass::performPeriodicAction: " - "recv buffer might not be large enough" << std::endl; - } - else if(bytesRead > 0) { - // pass data to lwgps for processing -#if GPS_REPLY_WIRETAPPING == 1 - sif::info << recBuf.data() << std::endl; -#endif - int result = lwgps_process(&gpsData, recBuf.data(), bytesRead); - if(result == 0) { - sif::warning << "UartTestClass::performPeriodicAction: lwgps_process error" - << std::endl; - } - recvCnt++; - if(recvCnt == 6) { - recvCnt = 0; - sif::info << "GPS Data" << std::endl; - // Print messages - printf("Valid status: %d\n", gpsData.is_valid); - printf("Latitude: %f degrees\n", gpsData.latitude); - printf("Longitude: %f degrees\n", gpsData.longitude); - printf("Altitude: %f meters\n", gpsData.altitude); - } - } - } while(bytesRead > 0); -#endif - return HasReturnvaluesIF::RETURN_OK; + if (mode == TestModes::GPS) { + gpsPeriodic(); + } else if (mode == TestModes::SCEX) { + scexPeriodic(); + } + return HasReturnvaluesIF::RETURN_OK; +} + +void UartTestClass::gpsInit() { +#if RPI_TEST_GPS_HANDLER == 1 + int result = lwgps_init(&gpsData); + if (result == 0) { + sif::warning << "lwgps_init error: " << result << std::endl; + } + + /* Get file descriptor */ + serialPort = open("/dev/serial0", O_RDWR); + if (serialPort < 0) { + sif::warning << "open call failed with error [" << errno << ", " << strerror(errno) + << std::endl; + } + /* Setting up UART parameters */ + tty.c_cflag &= ~PARENB; // Clear parity bit + tty.c_cflag &= ~CSTOPB; // Clear stop field, only one stop bit used in communication + tty.c_cflag &= ~CSIZE; // Clear all the size bits + tty.c_cflag |= CS8; // 8 bits per byte + tty.c_cflag &= ~CRTSCTS; // Disable RTS/CTS hardware flow control + tty.c_cflag |= CREAD | CLOCAL; // Turn on READ & ignore ctrl lines (CLOCAL = 1) + // Use canonical mode for GPS device + tty.c_lflag |= ICANON; + tty.c_lflag &= ~ECHO; // Disable echo + tty.c_lflag &= ~ECHOE; // Disable erasure + tty.c_lflag &= ~ECHONL; // Disable new-line echo + tty.c_lflag &= ~ISIG; // Disable interpretation of INTR, QUIT and SUSP + tty.c_iflag &= ~(IXON | IXOFF | IXANY); // Turn off s/w flow ctrl + tty.c_iflag &= ~(IGNBRK | BRKINT | PARMRK | ISTRIP | INLCR | IGNCR | + ICRNL); // Disable any special handling of received bytes + tty.c_oflag &= ~OPOST; // Prevent special interpretation of output bytes (e.g. newline chars) + tty.c_oflag &= ~ONLCR; // Prevent conversion of newline to carriage return/line feed + + // Non-blocking mode + tty.c_cc[VTIME] = 0; + tty.c_cc[VMIN] = 0; + + cfsetispeed(&tty, B9600); + cfsetospeed(&tty, B9600); + if (tcsetattr(serialPort, TCSANOW, &tty) != 0) { + sif::warning << "tcsetattr call failed with error [" << errno << ", " << strerror(errno) + << std::endl; + ; + } + // Flush received and unread data. Those are old NMEA strings which are not relevant anymore + tcflush(serialPort, TCIFLUSH); +#endif +} + +void UartTestClass::gpsPeriodic() { +#if RPI_TEST_GPS_HANDLER == 1 + int bytesRead = 0; + do { + bytesRead = read(serialPort, reinterpret_cast(recBuf.data()), + static_cast(recBuf.size())); + if (bytesRead < 0) { + sif::warning << "UartTestClass::performPeriodicAction: read call failed with error [" << errno + << ", " << strerror(errno) << "]" << std::endl; + break; + } else if (bytesRead >= static_cast(recBuf.size())) { + sif::debug << "UartTestClass::performPeriodicAction: " + "recv buffer might not be large enough" + << std::endl; + } else if (bytesRead > 0) { + // pass data to lwgps for processing +#if GPS_REPLY_WIRETAPPING == 1 + sif::info << recBuf.data() << std::endl; +#endif + int result = lwgps_process(&gpsData, recBuf.data(), bytesRead); + if (result == 0) { + sif::warning << "UartTestClass::performPeriodicAction: lwgps_process error" << std::endl; + } + recvCnt++; + if (recvCnt == 6) { + recvCnt = 0; + sif::info << "GPS Data" << std::endl; + // Print messages + printf("Valid status: %d\n", gpsData.is_valid); + printf("Latitude: %f degrees\n", gpsData.latitude); + printf("Longitude: %f degrees\n", gpsData.longitude); + printf("Altitude: %f meters\n", gpsData.altitude); + } + } + } while (bytesRead > 0); +#endif +} + +void UartTestClass::scexInit() { +#if defined(RASPBERRY_PI) + std::string devname = "/dev/serial0"; +#else + std::string devname = "/dev/ul-scex"; +#endif + /* Get file descriptor */ + serialPort = open(devname.c_str(), O_RDWR); + if (serialPort < 0) { + sif::warning << "open call failed with error [" << errno << ", " << strerror(errno) + << std::endl; + return; + } + // Setting up UART parameters + tty.c_cflag &= ~PARENB; // Clear parity bit + tty.c_cflag &= ~CSTOPB; // Clear stop field, only one stop bit used in communication + tty.c_cflag &= ~CSIZE; // Clear all the size bits + tty.c_cflag |= CS8; // 8 bits per byte + tty.c_cflag &= ~CRTSCTS; // Disable RTS/CTS hardware flow control + tty.c_cflag |= CREAD | CLOCAL; // Turn on READ & ignore ctrl lines (CLOCAL = 1) + + // Use non-canonical mode and clear echo flag + tty.c_lflag &= ~(ICANON | ECHO); + + // Non-blocking mode, read until either line is 0.1 second idle or maximum of 255 bytes are + // received in one go + tty.c_cc[VTIME] = 1; // In units of 0.1 seconds + tty.c_cc[VMIN] = 255; // Read up to 255 bytes + + // Q7S UART Lite has fixed baud rate. For other linux systems, set baud rate here. +#if !defined(XIPHOS_Q7S) + if (cfsetispeed(&tty, B57600) != 0) { + sif::warning << "UartTestClass::scexInit: Setting baud rate failed" << std::endl; + } +#endif + + if (tcsetattr(serialPort, TCSANOW, &tty) != 0) { + sif::warning << "tcsetattr call failed with error [" << errno << ", " << strerror(errno) + << std::endl; + } + // Flush received and unread data + tcflush(serialPort, TCIFLUSH); +} + +void UartTestClass::scexPeriodic() { + sif::info << "UartTestClass::scexInit: Sending ping command to SCEX" << std::endl; + int result = prepareScexPing(); + if (result != 0) { + return; + }; + size_t bytesWritten = write(serialPort, cmdBuf.data(), encodedLen); + if (bytesWritten != encodedLen) { + sif::warning << "Sending ping command to solar experiment failed" << std::endl; + } + + // Read back reply immediately + int bytesRead = 0; + do { + bytesRead = read(serialPort, reinterpret_cast(recBuf.data()), + static_cast(recBuf.size())); + if (bytesRead < 0) { + sif::warning << "UartTestClass::performPeriodicAction: read call failed with error [" << errno + << ", " << strerror(errno) << "]" << std::endl; + break; + } else if (bytesRead >= static_cast(recBuf.size())) { + sif::debug << "UartTestClass::performPeriodicAction: recv buffer might not be large enough" + << std::endl; + } else if (bytesRead > 0) { + sif::info << "Received " << bytesRead + << " bytes from the Solar Cell Experiment:" << std::endl; + arrayprinter::print(recBuf.data(), bytesRead, OutputType::HEX, false); + } + } while (bytesRead > 0); +} + +int UartTestClass::prepareScexPing() { + std::array tmpCmdBuf = {}; + // Send ping command + tmpCmdBuf[0] = scex::CMD_PING; + // These two fields are the packet counter and the total packet count. Those are 1 and 1 for each + // telecommand so far + tmpCmdBuf[1] = 1; + tmpCmdBuf[2] = 1; + uint16_t userDataLen = 0; + tmpCmdBuf[3] = (userDataLen >> 8) & 0xff; + tmpCmdBuf[4] = userDataLen & 0xff; + uint16_t crc = CRC::crc16ccitt(tmpCmdBuf.data(), 5); + tmpCmdBuf[5] = (crc >> 8) & 0xff; + tmpCmdBuf[6] = crc & 0xff; + ReturnValue_t result = + dleEncoder.encode(tmpCmdBuf.data(), 7, cmdBuf.data(), cmdBuf.size(), &encodedLen, true); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "UartTestClass::scexInit: Encoding failed" << std::endl; + return -1; + } + return 0; } diff --git a/linux/boardtest/UartTestClass.h b/linux/boardtest/UartTestClass.h index aeb2c396..786d01ce 100644 --- a/linux/boardtest/UartTestClass.h +++ b/linux/boardtest/UartTestClass.h @@ -1,27 +1,44 @@ #ifndef LINUX_BOARDTEST_UARTTESTCLASS_H_ #define LINUX_BOARDTEST_UARTTESTCLASS_H_ -#include "test/testtasks/TestTask.h" -#include "lwgps/lwgps.h" +#include +#include // Contains POSIX terminal control definitions #include -#include // Contains POSIX terminal control definitions -class UartTestClass: public TestTask { -public: - UartTestClass(object_id_t objectId); +#include "lwgps/lwgps.h" +#include "test/testtasks/TestTask.h" - ReturnValue_t initialize() override; - ReturnValue_t performOneShotAction() override; - ReturnValue_t performPeriodicAction() override; -private: +class UartTestClass : public TestTask { + public: + UartTestClass(object_id_t objectId); - lwgps_t gpsData = {}; - struct termios tty = {}; - int serialPort = 0; - std::array recBuf; - uint8_t recvCnt = 0; + ReturnValue_t initialize() override; + ReturnValue_t performOneShotAction() override; + ReturnValue_t performPeriodicAction() override; + private: + enum TestModes { + GPS, + // Solar Cell Experiment + SCEX + }; + + void gpsInit(); + void gpsPeriodic(); + + void scexInit(); + void scexPeriodic(); + int prepareScexPing(); + TestModes mode = TestModes::GPS; + DleEncoder dleEncoder = DleEncoder(); + size_t encodedLen = 0; + lwgps_t gpsData = {}; + struct termios tty = {}; + int serialPort = 0; + std::array cmdBuf = {}; + std::array recBuf = {}; + uint8_t recvCnt = 0; }; #endif /* LINUX_BOARDTEST_UARTTESTCLASS_H_ */ diff --git a/linux/csp/CMakeLists.txt b/linux/csp/CMakeLists.txt index b5b2768e..f1ebb028 100644 --- a/linux/csp/CMakeLists.txt +++ b/linux/csp/CMakeLists.txt @@ -1,4 +1,4 @@ -target_sources(${TARGET_NAME} PUBLIC +target_sources(${OBSW_NAME} PUBLIC CspComIF.cpp CspCookie.cpp ) diff --git a/linux/csp/CspComIF.cpp b/linux/csp/CspComIF.cpp index 07fe63d3..fa372d4d 100644 --- a/linux/csp/CspComIF.cpp +++ b/linux/csp/CspComIF.cpp @@ -1,259 +1,246 @@ #include "CspComIF.h" -#include "CspCookie.h" -#include #include #include +#include -CspComIF::CspComIF(object_id_t objectId) : - SystemObject(objectId) { -} +#include "CspCookie.h" -CspComIF::~CspComIF() { -} +CspComIF::CspComIF(object_id_t objectId) : SystemObject(objectId) {} -ReturnValue_t CspComIF::initializeInterface(CookieIF *cookie) { - if(cookie == nullptr) { - return NULLPOINTER; - } +CspComIF::~CspComIF() {} - CspCookie* cspCookie = dynamic_cast(cookie); - if(cspCookie == nullptr) { - return NULLPOINTER; - } +ReturnValue_t CspComIF::initializeInterface(CookieIF* cookie) { + if (cookie == nullptr) { + return NULLPOINTER; + } - /* Perform CAN and CSP initialization only once */ - if(cspDeviceMap.empty()){ - sif::info << "Performing " << canInterface << " initialization.." << std::endl; + CspCookie* cspCookie = dynamic_cast(cookie); + if (cspCookie == nullptr) { + return NULLPOINTER; + } - /* Define the memory to allocate for the CSP stack */ - int buf_count = 10; - int buf_size = 300; - /* Init CSP and CSP buffer system */ - if (csp_init(cspOwnAddress) != CSP_ERR_NONE - || csp_buffer_init(buf_count, buf_size) != CSP_ERR_NONE) { - sif::error << "Failed to init CSP\r\n" << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; - } + /* Perform CAN and CSP initialization only once */ + if (cspDeviceMap.empty()) { + sif::info << "Performing " << canInterface << " initialization.." << std::endl; - int promisc = 0; // Set filter mode on - csp_iface_t *csp_if_ptr = &csp_if; - csp_if_ptr = csp_can_socketcan_init(canInterface, bitrate, promisc); - - /* Set default route and start router */ - uint8_t address = CSP_DEFAULT_ROUTE; - uint8_t netmask = 0; - uint8_t mac = CSP_NODE_MAC; - int result = csp_rtable_set(address, netmask, csp_if_ptr, mac); - if(result != CSP_ERR_NONE){ - sif::error << "Failed to add can interface to router table" - << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; - } - - /* Start the route task */ - unsigned int task_stack_size = 500; - unsigned int priority = 0; - result = csp_route_start_task(task_stack_size, priority); - if(result != CSP_ERR_NONE){ - sif::error << "Failed to start csp route task" << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; - } - sif::info << canInterface << " initialized successfully" << std::endl; - } - - uint8_t cspAddress = cspCookie->getCspAddress(); - uint16_t maxReplyLength = cspCookie->getMaxReplyLength(); - if(cspDeviceMap.find(cspAddress) == cspDeviceMap.end()){ - /* Insert device information in CSP map */ - cspDeviceMap.emplace(cspAddress, vectorBuffer(maxReplyLength)); - } - - return HasReturnvaluesIF::RETURN_OK; -} - -ReturnValue_t CspComIF::sendMessage(CookieIF *cookie, - const uint8_t * sendData, size_t sendLen) { - int result; - if(cookie == NULL){ - return HasReturnvaluesIF::RETURN_FAILED; - } - CspCookie* cspCookie = dynamic_cast (cookie); - if(cspCookie == NULL){ - return HasReturnvaluesIF::RETURN_FAILED; - } - - /* Extract csp port and bytes to query from command buffer */ - uint8_t cspPort; - uint16_t querySize = 0; - result = getPortAndQuerySize(&sendData, &sendLen, &cspPort, &querySize); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - uint8_t cspAddress = cspCookie->getCspAddress(); - switch(cspPort) { - case(Ports::CSP_PING): { - initiatePingRequest(cspAddress, querySize); - break; - } - case(Ports::CSP_REBOOT): { - csp_reboot(cspAddress); - break; - } - case(Ports::P60_PORT_GNDWDT_RESET): - case(Ports::P60_PORT_RPARAM): { - /* No CSP fixed port was selected. Send data to the specified port and - * wait for querySize number of bytes */ - result = cspTransfer(cspAddress, cspPort, sendData, sendLen, - querySize); - if(result != HasReturnvaluesIF::RETURN_OK){ - return HasReturnvaluesIF::RETURN_FAILED; - } - replySize = querySize; - break; - } - default: - sif::error << "CspComIF: Invalid port specified" << std::endl; - break; - } - return HasReturnvaluesIF::RETURN_OK; -} - -ReturnValue_t CspComIF::getSendSuccess(CookieIF *cookie) { - return HasReturnvaluesIF::RETURN_OK; -} - -ReturnValue_t CspComIF::requestReceiveMessage(CookieIF *cookie, - size_t requestLen) { - return HasReturnvaluesIF::RETURN_OK; -} - -ReturnValue_t CspComIF::readReceivedMessage(CookieIF *cookie, - uint8_t** buffer, size_t* size) { - if(cookie == NULL){ - return HasReturnvaluesIF::RETURN_FAILED; - } - CspCookie* cspCookie = dynamic_cast (cookie); - if(cspCookie == NULL){ - return HasReturnvaluesIF::RETURN_FAILED; - } - - uint8_t cspAddress = cspCookie->getCspAddress(); - - *buffer = cspDeviceMap[cspAddress].data(); - *size = replySize; - - return HasReturnvaluesIF::RETURN_OK; -} - -ReturnValue_t CspComIF::cspTransfer(uint8_t cspAddress, uint8_t cspPort, - const uint8_t* cmdBuffer, int cmdLen, uint16_t querySize) { - - uint32_t timeout_ms = 1000; - uint16_t bytesRead = 0; - int32_t expectedSize = (int32_t)querySize; - vectorBufferIter iter = cspDeviceMap.find(cspAddress); - if(iter == cspDeviceMap.end()){ - sif::error << "CSP device with address " << cspAddress << " no found in" - << " device map" << std::endl; - } - uint8_t* replyBuffer = iter->second.data(); - - csp_conn_t * conn = csp_connect(CSP_PRIO_HIGH, cspAddress, cspPort, 0, - CSP_O_NONE); - - csp_packet_t* commandPacket = (csp_packet_t*)csp_buffer_get(cmdLen); - if (commandPacket == NULL) { - sif::error << "CspComIF::cspTransfer: Failed to get memory for a csp packet from the csp " - << "stack" << std::endl; - csp_close(conn); - return RETURN_FAILED; + /* Define the memory to allocate for the CSP stack */ + int buf_count = 10; + int buf_size = 300; + /* Init CSP and CSP buffer system */ + if (csp_init(cspOwnAddress) != CSP_ERR_NONE || + csp_buffer_init(buf_count, buf_size) != CSP_ERR_NONE) { + sif::error << "Failed to init CSP\r\n" << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; } - memcpy(commandPacket->data, cmdBuffer, cmdLen); - commandPacket->length = cmdLen; + int promisc = 0; // Set filter mode on + csp_iface_t* csp_if_ptr = &csp_if; + csp_if_ptr = csp_can_socketcan_init(canInterface, bitrate, promisc); - if (!csp_send(conn, commandPacket, timeout_ms)) { - csp_buffer_free(commandPacket); - sif::error << "CspComIF::cspTransfer: Failed to send csp packet" << std::endl; - csp_close(conn); - return RETURN_FAILED; + /* Set default route and start router */ + uint8_t address = CSP_DEFAULT_ROUTE; + uint8_t netmask = 0; + uint8_t mac = CSP_NODE_MAC; + int result = csp_rtable_set(address, netmask, csp_if_ptr, mac); + if (result != CSP_ERR_NONE) { + sif::error << "Failed to add can interface to router table" << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; } - /* Return when no reply is expected */ - if (expectedSize == 0) { - return RETURN_OK; + /* Start the route task */ + unsigned int task_stack_size = 500; + unsigned int priority = 0; + result = csp_route_start_task(task_stack_size, priority); + if (result != CSP_ERR_NONE) { + sif::error << "Failed to start csp route task" << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; } + sif::info << canInterface << " initialized successfully" << std::endl; + } - csp_packet_t * reply; + uint8_t cspAddress = cspCookie->getCspAddress(); + uint16_t maxReplyLength = cspCookie->getMaxReplyLength(); + if (cspDeviceMap.find(cspAddress) == cspDeviceMap.end()) { + /* Insert device information in CSP map */ + cspDeviceMap.emplace(cspAddress, vectorBuffer(maxReplyLength)); + } + + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t CspComIF::sendMessage(CookieIF* cookie, const uint8_t* sendData, size_t sendLen) { + int result; + if (cookie == NULL) { + return HasReturnvaluesIF::RETURN_FAILED; + } + CspCookie* cspCookie = dynamic_cast(cookie); + if (cspCookie == NULL) { + return HasReturnvaluesIF::RETURN_FAILED; + } + + /* Extract csp port and bytes to query from command buffer */ + uint8_t cspPort; + uint16_t querySize = 0; + result = getPortAndQuerySize(&sendData, &sendLen, &cspPort, &querySize); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + uint8_t cspAddress = cspCookie->getCspAddress(); + switch (cspPort) { + case (Ports::CSP_PING): { + initiatePingRequest(cspAddress, querySize); + break; + } + case (Ports::CSP_REBOOT): { + csp_reboot(cspAddress); + break; + } + case (Ports::P60_PORT_GNDWDT_RESET): + case (Ports::P60_PORT_RPARAM): { + /* No CSP fixed port was selected. Send data to the specified port and + * wait for querySize number of bytes */ + result = cspTransfer(cspAddress, cspPort, sendData, sendLen, querySize); + if (result != HasReturnvaluesIF::RETURN_OK) { + return HasReturnvaluesIF::RETURN_FAILED; + } + replySize = querySize; + break; + } + default: + sif::error << "CspComIF: Invalid port specified" << std::endl; + break; + } + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t CspComIF::getSendSuccess(CookieIF* cookie) { return HasReturnvaluesIF::RETURN_OK; } + +ReturnValue_t CspComIF::requestReceiveMessage(CookieIF* cookie, size_t requestLen) { + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t CspComIF::readReceivedMessage(CookieIF* cookie, uint8_t** buffer, size_t* size) { + if (cookie == NULL) { + return HasReturnvaluesIF::RETURN_FAILED; + } + CspCookie* cspCookie = dynamic_cast(cookie); + if (cspCookie == NULL) { + return HasReturnvaluesIF::RETURN_FAILED; + } + + uint8_t cspAddress = cspCookie->getCspAddress(); + + *buffer = cspDeviceMap[cspAddress].data(); + *size = replySize; + + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t CspComIF::cspTransfer(uint8_t cspAddress, uint8_t cspPort, const uint8_t* cmdBuffer, + int cmdLen, uint16_t querySize) { + uint32_t timeout_ms = 1000; + uint16_t bytesRead = 0; + int32_t expectedSize = (int32_t)querySize; + vectorBufferIter iter = cspDeviceMap.find(cspAddress); + if (iter == cspDeviceMap.end()) { + sif::error << "CSP device with address " << cspAddress << " no found in" + << " device map" << std::endl; + } + uint8_t* replyBuffer = iter->second.data(); + + csp_conn_t* conn = csp_connect(CSP_PRIO_HIGH, cspAddress, cspPort, 0, CSP_O_NONE); + + csp_packet_t* commandPacket = (csp_packet_t*)csp_buffer_get(cmdLen); + if (commandPacket == NULL) { + sif::error << "CspComIF::cspTransfer: Failed to get memory for a csp packet from the csp " + << "stack" << std::endl; + csp_close(conn); + return RETURN_FAILED; + } + + memcpy(commandPacket->data, cmdBuffer, cmdLen); + commandPacket->length = cmdLen; + + if (!csp_send(conn, commandPacket, timeout_ms)) { + csp_buffer_free(commandPacket); + sif::error << "CspComIF::cspTransfer: Failed to send csp packet" << std::endl; + csp_close(conn); + return RETURN_FAILED; + } + + /* Return when no reply is expected */ + if (expectedSize == 0) { + return RETURN_OK; + } + + csp_packet_t* reply; + reply = csp_read(conn, timeout_ms); + if (reply == NULL) { + sif::error << "CspComIF::cspTransfer: Failed to read csp packet" << std::endl; + csp_close(conn); + return RETURN_FAILED; + } + memcpy(replyBuffer, reply->data, reply->length); + expectedSize = expectedSize - reply->length; + bytesRead += reply->length; + csp_buffer_free(reply); + while (expectedSize > 0) { reply = csp_read(conn, timeout_ms); if (reply == NULL) { - sif::error << "CspComIF::cspTransfer: Failed to read csp packet" << std::endl; - csp_close(conn); - return RETURN_FAILED; + sif::error << "CspComIF::cspTransfer: Failed to read csp packet" << std::endl; + csp_close(conn); + return RETURN_FAILED; } - memcpy(replyBuffer, reply->data, reply->length); + if ((reply->length + bytesRead) > iter->second.size()) { + sif::error << "CspComIF::cspTransfer: Reply buffer to short" << std::endl; + csp_buffer_free(reply); + csp_close(conn); + return RETURN_FAILED; + } + memcpy(replyBuffer + bytesRead, reply->data, reply->length); expectedSize = expectedSize - reply->length; bytesRead += reply->length; csp_buffer_free(reply); - while (expectedSize > 0) { - reply = csp_read(conn, timeout_ms); - if (reply == NULL) { - sif::error << "CspComIF::cspTransfer: Failed to read csp packet" << std::endl; - csp_close(conn); - return RETURN_FAILED; - } - if ((reply->length + bytesRead) > iter->second.size()) { - sif::error << "CspComIF::cspTransfer: Reply buffer to short" << std::endl; - csp_buffer_free(reply); - csp_close(conn); - return RETURN_FAILED; - } - memcpy(replyBuffer + bytesRead, reply->data, reply->length); - expectedSize = expectedSize - reply->length; - bytesRead += reply->length; - csp_buffer_free(reply); - } + } - if(expectedSize != 0){ - sif::error << "CspComIF::cspTransfer: Received more bytes than requested" << std::endl; - sif::debug << "CspComIF::cspTransfer: Received bytes: " << bytesRead << std::endl; - csp_close(conn); - return RETURN_FAILED; - } + if (expectedSize != 0) { + sif::error << "CspComIF::cspTransfer: Received more bytes than requested" << std::endl; + sif::debug << "CspComIF::cspTransfer: Received bytes: " << bytesRead << std::endl; + csp_close(conn); + return RETURN_FAILED; + } - csp_close(conn); + csp_close(conn); - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t CspComIF::getPortAndQuerySize(const uint8_t** sendData, - size_t* sendLen, uint8_t* cspPort, uint16_t* querySize) { - ReturnValue_t result = SerializeAdapter::deSerialize(cspPort, sendData, - sendLen, SerializeIF::Endianness::BIG); - if(result != HasReturnvaluesIF::RETURN_OK){ - sif::error << "CspComIF: Failed to deserialize CSP port from command " - << "buffer" << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; - } - SerializeAdapter::deSerialize(querySize, sendData, sendLen, - SerializeIF::Endianness::BIG); - if(result != HasReturnvaluesIF::RETURN_OK){ - sif::error << "CspComIF: Failed to deserialize querySize from command " - << "buffer" << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_OK; +ReturnValue_t CspComIF::getPortAndQuerySize(const uint8_t** sendData, size_t* sendLen, + uint8_t* cspPort, uint16_t* querySize) { + ReturnValue_t result = + SerializeAdapter::deSerialize(cspPort, sendData, sendLen, SerializeIF::Endianness::BIG); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "CspComIF: Failed to deserialize CSP port from command " + << "buffer" << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } + SerializeAdapter::deSerialize(querySize, sendData, sendLen, SerializeIF::Endianness::BIG); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "CspComIF: Failed to deserialize querySize from command " + << "buffer" << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; } -void CspComIF::initiatePingRequest(uint8_t cspAddress, uint16_t querySize){ - uint32_t timeout_ms = 500; - uint32_t replyTime = csp_ping(cspAddress, timeout_ms, querySize, - CSP_O_NONE); - sif::info << "Ping address: " << cspAddress << ", reply after " - << replyTime << " ms" << std::endl; - /* Store reply time in reply buffer * */ - uint8_t* replyBuffer = cspDeviceMap[cspAddress].data(); - memcpy(replyBuffer, &replyTime, sizeof(replyTime)); - replySize = sizeof(replyTime); +void CspComIF::initiatePingRequest(uint8_t cspAddress, uint16_t querySize) { + uint32_t timeout_ms = 500; + uint32_t replyTime = csp_ping(cspAddress, timeout_ms, querySize, CSP_O_NONE); + sif::info << "Ping address: " << cspAddress << ", reply after " << replyTime << " ms" + << std::endl; + /* Store reply time in reply buffer * */ + uint8_t* replyBuffer = cspDeviceMap[cspAddress].data(); + memcpy(replyBuffer, &replyTime, sizeof(replyTime)); + replySize = sizeof(replyTime); } diff --git a/linux/csp/CspComIF.h b/linux/csp/CspComIF.h index 4b8d323b..d36bbf4f 100644 --- a/linux/csp/CspComIF.h +++ b/linux/csp/CspComIF.h @@ -1,13 +1,13 @@ #ifndef LINUX_CSP_CSPCOMIF_H_ #define LINUX_CSP_CSPCOMIF_H_ +#include #include #include #include -#include -#include #include +#include /** * @brief This class serves as the communication interface to devices @@ -15,75 +15,65 @@ * in this implementation. * @author J. Meier */ -class CspComIF: public DeviceCommunicationIF, public SystemObject { -public: - CspComIF(object_id_t objectId); - virtual ~CspComIF(); +class CspComIF : public DeviceCommunicationIF, public SystemObject { + public: + CspComIF(object_id_t objectId); + virtual ~CspComIF(); - 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 **readData, size_t *readLen) override; + 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 **readData, size_t *readLen) override; -private: + private: + /** + * @brief This function initiates the CSP transfer. + * + * @param cspAddress The CSP address of the target device. + * @param cspPort The port of the target device. + * @param timeout The timeout to wait for csp_send and csp_read + * functions. Specifies how long the functions wait + * for a successful operation. + * @param cmdBuffer The data to send. + * @param cmdLen The number of bytes to send. + * @param querySize The size of the requested message. + */ + ReturnValue_t cspTransfer(uint8_t cspAddress, uint8_t cspPort, const uint8_t *cmdBuffer, + int cmdLen, uint16_t querySize); - /** - * @brief This function initiates the CSP transfer. - * - * @param cspAddress The CSP address of the target device. - * @param cspPort The port of the target device. - * @param timeout The timeout to wait for csp_send and csp_read - * functions. Specifies how long the functions wait - * for a successful operation. - * @param cmdBuffer The data to send. - * @param cmdLen The number of bytes to send. - * @param querySize The size of the requested message. - */ - ReturnValue_t cspTransfer(uint8_t cspAddress, uint8_t cspPort, - const uint8_t* cmdBuffer, int cmdLen, uint16_t querySize); + enum Ports { CSP_PING = 1, CSP_REBOOT = 4, P60_PORT_RPARAM = 7, P60_PORT_GNDWDT_RESET = 9 }; - enum Ports { - CSP_PING = 1, - CSP_REBOOT = 4, - P60_PORT_RPARAM = 7, - P60_PORT_GNDWDT_RESET = 9 - }; + typedef uint8_t node_t; + using vectorBuffer = std::vector; + using VectorBufferMap = std::unordered_map; + using vectorBufferIter = VectorBufferMap::iterator; + /* In this map assigns reply buffers to a CSP device */ + VectorBufferMap cspDeviceMap; - typedef uint8_t node_t; - using vectorBuffer = std::vector; - using VectorBufferMap = std::unordered_map; - using vectorBufferIter = VectorBufferMap::iterator; + uint16_t replySize = 0; - /* In this map assigns reply buffers to a CSP device */ - VectorBufferMap cspDeviceMap; + /* This is the CSP address of the OBC. */ + node_t cspOwnAddress = 1; - uint16_t replySize = 0; + /* Interface struct for csp protocol stack */ + csp_iface_t csp_if; - /* This is the CSP address of the OBC. */ - node_t cspOwnAddress = 1; + char canInterface[5] = "can0"; + int bitrate = 1000; - /* Interface struct for csp protocol stack */ - csp_iface_t csp_if; + /** + * @brief Function to extract the csp port and the query size from the + * command buffer. + */ + ReturnValue_t getPortAndQuerySize(const uint8_t **sendData, size_t *sendLen, uint8_t *cspPort, + uint16_t *querySize); - char canInterface[5] = "can0"; - int bitrate = 1000; - - /** - * @brief Function to extract the csp port and the query size from the - * command buffer. - */ - ReturnValue_t getPortAndQuerySize(const uint8_t** sendData, size_t* sendLen, - uint8_t* cspPort, uint16_t* querySize); - - /** - * @brief This function initiates the ping request. - */ - void initiatePingRequest(uint8_t cspAddress, uint16_t querySize); + /** + * @brief This function initiates the ping request. + */ + void initiatePingRequest(uint8_t cspAddress, uint16_t querySize); }; #endif /* LINUX_CSP_CSPCOMIF_H_ */ diff --git a/linux/csp/CspCookie.cpp b/linux/csp/CspCookie.cpp index 18cfabd2..39274908 100644 --- a/linux/csp/CspCookie.cpp +++ b/linux/csp/CspCookie.cpp @@ -1,16 +1,10 @@ #include "CspCookie.h" -CspCookie::CspCookie(uint16_t maxReplyLength_, uint8_t cspAddress_) : - maxReplyLength(maxReplyLength_), cspAddress(cspAddress_) { -} +CspCookie::CspCookie(uint16_t maxReplyLength_, uint8_t cspAddress_) + : maxReplyLength(maxReplyLength_), cspAddress(cspAddress_) {} -CspCookie::~CspCookie() { -} +CspCookie::~CspCookie() {} -uint16_t CspCookie::getMaxReplyLength(){ - return maxReplyLength; -} +uint16_t CspCookie::getMaxReplyLength() { return maxReplyLength; } -uint8_t CspCookie::getCspAddress(){ - return cspAddress; -} +uint8_t CspCookie::getCspAddress() { return cspAddress; } diff --git a/linux/csp/CspCookie.h b/linux/csp/CspCookie.h index 4514c257..e59f3d35 100644 --- a/linux/csp/CspCookie.h +++ b/linux/csp/CspCookie.h @@ -2,6 +2,7 @@ #define LINUX_CSP_CSPCOOKIE_H_ #include + #include /** @@ -9,19 +10,17 @@ * Protocol). * @author J. Meier */ -class CspCookie: public CookieIF { -public: +class CspCookie : public CookieIF { + public: + CspCookie(uint16_t maxReplyLength_, uint8_t cspAddress_); + virtual ~CspCookie(); - CspCookie(uint16_t maxReplyLength_, uint8_t cspAddress_); - virtual ~CspCookie(); + uint16_t getMaxReplyLength(); + uint8_t getCspAddress(); - uint16_t getMaxReplyLength(); - uint8_t getCspAddress(); - -private: - - uint16_t maxReplyLength; - uint8_t cspAddress; + private: + uint16_t maxReplyLength; + uint8_t cspAddress; }; #endif /* LINUX_CSP_CSPCOOKIE_H_ */ diff --git a/linux/devices/CMakeLists.txt b/linux/devices/CMakeLists.txt index 3871a6a6..7d39837d 100644 --- a/linux/devices/CMakeLists.txt +++ b/linux/devices/CMakeLists.txt @@ -1,5 +1,7 @@ -target_sources(${TARGET_NAME} PRIVATE - HeaterHandler.cpp - SolarArrayDeploymentHandler.cpp - SusHandler.cpp -) +if(EIVE_BUILD_GPSD_GPS_HANDLER) + target_sources(${OBSW_NAME} PRIVATE + GPSHyperionLinuxController.cpp + ) +endif() + +add_subdirectory(startracker) diff --git a/linux/devices/GPSHyperionLinuxController.cpp b/linux/devices/GPSHyperionLinuxController.cpp new file mode 100644 index 00000000..722eb8e0 --- /dev/null +++ b/linux/devices/GPSHyperionLinuxController.cpp @@ -0,0 +1,178 @@ +#include "GPSHyperionLinuxController.h" + +#include "OBSWConfig.h" +#include "fsfw/datapool/PoolReadGuard.h" +#include "fsfw/timemanager/Clock.h" + +#if FSFW_DEV_HYPERION_GPS_CREATE_NMEA_CSV == 1 +#include +#include +#endif +#include + +GPSHyperionLinuxController::GPSHyperionLinuxController(object_id_t objectId, object_id_t parentId, + bool debugHyperionGps) + : ExtendedControllerBase(objectId, objects::NO_OBJECT), + gpsSet(this), + myGpsmm(GPSD_SHARED_MEMORY, nullptr), + debugHyperionGps(debugHyperionGps) {} + +GPSHyperionLinuxController::~GPSHyperionLinuxController() {} + +void GPSHyperionLinuxController::performControlOperation() { +#ifdef FSFW_OSAL_LINUX + readGpsDataFromGpsd(); +#endif +} + +LocalPoolDataSetBase *GPSHyperionLinuxController::getDataSetHandle(sid_t sid) { return &gpsSet; } + +ReturnValue_t GPSHyperionLinuxController::checkModeCommand(Mode_t mode, Submode_t submode, + uint32_t *msToReachTheMode) { + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t GPSHyperionLinuxController::executeAction(ActionId_t actionId, + MessageQueueId_t commandedBy, + const uint8_t *data, size_t size) { + switch (actionId) { + case (GpsHyperion::TRIGGER_RESET_PIN): { + if (resetCallback != nullptr) { + PoolReadGuard pg(&gpsSet); + // Set HK entries invalid + gpsSet.setValidity(false, true); + resetCallback(resetCallbackArgs); + return HasActionsIF::EXECUTION_FINISHED; + } + return DeviceHandlerIF::COMMAND_NOT_IMPLEMENTED; + } + } + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t GPSHyperionLinuxController::initializeLocalDataPool( + localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) { + localDataPoolMap.emplace(GpsHyperion::ALTITUDE, new PoolEntry({0.0})); + localDataPoolMap.emplace(GpsHyperion::LONGITUDE, new PoolEntry({0.0})); + localDataPoolMap.emplace(GpsHyperion::LATITUDE, new PoolEntry({0.0})); + localDataPoolMap.emplace(GpsHyperion::SPEED, new PoolEntry({0.0})); + localDataPoolMap.emplace(GpsHyperion::YEAR, new PoolEntry()); + localDataPoolMap.emplace(GpsHyperion::MONTH, new PoolEntry()); + localDataPoolMap.emplace(GpsHyperion::DAY, new PoolEntry()); + localDataPoolMap.emplace(GpsHyperion::HOURS, new PoolEntry()); + localDataPoolMap.emplace(GpsHyperion::MINUTES, new PoolEntry()); + localDataPoolMap.emplace(GpsHyperion::SECONDS, new PoolEntry()); + localDataPoolMap.emplace(GpsHyperion::UNIX_SECONDS, new PoolEntry()); + localDataPoolMap.emplace(GpsHyperion::SATS_IN_USE, new PoolEntry()); + localDataPoolMap.emplace(GpsHyperion::SATS_IN_VIEW, new PoolEntry()); + localDataPoolMap.emplace(GpsHyperion::FIX_MODE, new PoolEntry()); +#if OBSW_ENABLE_PERIODIC_HK == 1 + poolManager.subscribeForPeriodicPacket(gpsSet.getSid(), true, 2.0, false); +#endif + return HasReturnvaluesIF::RETURN_OK; +} + +void GPSHyperionLinuxController::setResetPinTriggerFunction(gpioResetFunction_t resetCallback, + void *args) { + this->resetCallback = resetCallback; + resetCallbackArgs = args; +} + +ReturnValue_t GPSHyperionLinuxController::initialize() { + ReturnValue_t result = ExtendedControllerBase::initialize(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return result; +} + +ReturnValue_t GPSHyperionLinuxController::handleCommandMessage(CommandMessage *message) { + return ExtendedControllerBase::handleCommandMessage(message); +} + +#ifdef FSFW_OSAL_LINUX +void GPSHyperionLinuxController::readGpsDataFromGpsd() { + // The data from the device will generally be read all at once. Therefore, we + // can set all field here + if (not myGpsmm.is_open()) { + // Opening failed +#if FSFW_VERBOSE_LEVEL >= 1 + sif::warning << "GPSHyperionHandler::readGpsDataFromGpsd: Opening GPSMM failed" << std::endl; +#endif + } + gps_data_t *gps = nullptr; + gps = myGpsmm.read(); + if (gps == nullptr) { + sif::warning << "GPSHyperionHandler::readGpsDataFromGpsd: Reading GPS data failed" << std::endl; + } + PoolReadGuard pg(&gpsSet); + if (pg.getReadResult() != HasReturnvaluesIF::RETURN_OK) { +#if FSFW_VERBOSE_LEVEL >= 1 + sif::warning << "GPSHyperionHandler::readGpsDataFromGpsd: Reading dataset failed" << std::endl; +#endif + } + + // 0: Not seen, 1: No fix, 2: 2D-Fix, 3: 3D-Fix + gpsSet.fixMode.value = gps->fix.mode; + if (gps->fix.mode == 0 or gps->fix.mode == 1) { + gpsSet.setValidity(false, true); + } else if (gps->satellites_used > 0) { + gpsSet.setValidity(true, true); + } + + gpsSet.satInUse.value = gps->satellites_used; + gpsSet.satInView.value = gps->satellites_visible; + + if (std::isfinite(gps->fix.latitude)) { + // Negative latitude -> South direction + gpsSet.latitude.value = gps->fix.latitude; + } else { + gpsSet.latitude.setValid(false); + } + + if (std::isfinite(gps->fix.longitude)) { + // Negative longitude -> West direction + gpsSet.longitude.value = gps->fix.longitude; + } else { + gpsSet.longitude.setValid(false); + } + + if (std::isfinite(gps->fix.altitude)) { + gpsSet.altitude.value = gps->fix.altitude; + } else { + gpsSet.altitude.setValid(false); + } + + if (std::isfinite(gps->fix.speed)) { + gpsSet.speed.value = gps->fix.speed; + } else { + gpsSet.speed.setValid(false); + } + + gpsSet.unixSeconds.value = gps->fix.time.tv_sec; + timeval time = {}; + time.tv_sec = gpsSet.unixSeconds.value; + time.tv_usec = gps->fix.time.tv_nsec / 1000; + Clock::TimeOfDay_t timeOfDay = {}; + Clock::convertTimevalToTimeOfDay(&time, &timeOfDay); + gpsSet.year = timeOfDay.year; + gpsSet.month = timeOfDay.month; + gpsSet.day = timeOfDay.day; + gpsSet.hours = timeOfDay.hour; + gpsSet.minutes = timeOfDay.minute; + gpsSet.seconds = timeOfDay.second; + if (debugHyperionGps) { + sif::info << "-- Hyperion GPS Data --" << std::endl; + time_t timeRaw = gps->fix.time.tv_sec; + std::tm *time = gmtime(&timeRaw); + std::cout << "Time: " << std::put_time(time, "%c %Z") << std::endl; + std::cout << "Visible satellites: " << gps->satellites_visible << std::endl; + std::cout << "Satellites used: " << gps->satellites_used << std::endl; + std::cout << "Fix (0:Not Seen|1:No Fix|2:2D|3:3D): " << gps->fix.mode << std::endl; + std::cout << "Latitude: " << gps->fix.latitude << std::endl; + std::cout << "Longitude: " << gps->fix.longitude << std::endl; + std::cout << "Altitude(MSL): " << gps->fix.altMSL << std::endl; + std::cout << "Speed(m/s): " << gps->fix.speed << std::endl; + } +} +#endif diff --git a/linux/devices/GPSHyperionLinuxController.h b/linux/devices/GPSHyperionLinuxController.h new file mode 100644 index 00000000..3615cebd --- /dev/null +++ b/linux/devices/GPSHyperionLinuxController.h @@ -0,0 +1,55 @@ +#ifndef MISSION_DEVICES_GPSHYPERIONHANDLER_H_ +#define MISSION_DEVICES_GPSHYPERIONHANDLER_H_ + +#include "fsfw/FSFW.h" +#include "fsfw/controller/ExtendedControllerBase.h" +#include "fsfw/devicehandlers/DeviceHandlerBase.h" +#include "mission/devices/devicedefinitions/GPSDefinitions.h" + +#ifdef FSFW_OSAL_LINUX +#include +#include +#endif + +/** + * @brief Device handler for the Hyperion HT-GPS200 device + * @details + * Flight manual: + * https://egit.irs.uni-stuttgart.de/redmine/projects/eive-flight-manual/wiki/Hyperion_HT-GPS200 + * This device handler can only be used on Linux system where the gpsd daemon with shared memory + * export is running. + */ +class GPSHyperionLinuxController : public ExtendedControllerBase { + public: + GPSHyperionLinuxController(object_id_t objectId, object_id_t parentId, + bool debugHyperionGps = false); + virtual ~GPSHyperionLinuxController(); + + using gpioResetFunction_t = ReturnValue_t (*)(void* args); + + void setResetPinTriggerFunction(gpioResetFunction_t resetCallback, void* args); + ReturnValue_t handleCommandMessage(CommandMessage* message) override; + void performControlOperation() override; + LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override; + ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode, + uint32_t* msToReachTheMode) override; + ReturnValue_t executeAction(ActionId_t actionId, MessageQueueId_t commandedBy, + const uint8_t* data, size_t size) override; + ReturnValue_t initialize() override; + + protected: + gpioResetFunction_t resetCallback = nullptr; + void* resetCallbackArgs = nullptr; + + ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, + LocalDataPoolManager& poolManager) override; + + private: + GpsPrimaryDataset gpsSet; + gpsmm myGpsmm; + bool debugHyperionGps = false; + + void readGpsDataFromGpsd(); +}; + +#endif /* MISSION_DEVICES_GPSHYPERIONHANDLER_H_ */ diff --git a/linux/devices/HeaterHandler.cpp b/linux/devices/HeaterHandler.cpp deleted file mode 100644 index 60a60328..00000000 --- a/linux/devices/HeaterHandler.cpp +++ /dev/null @@ -1,373 +0,0 @@ -#include "HeaterHandler.h" -#include "devices/gpioIds.h" -#include "devices/powerSwitcherList.h" - -#include -#include -#include - -HeaterHandler::HeaterHandler(object_id_t setObjectId_, object_id_t gpioDriverId_, - CookieIF * gpioCookie_, object_id_t mainLineSwitcherObjectId_, uint8_t mainLineSwitch_) : - SystemObject(setObjectId_), gpioDriverId(gpioDriverId_), gpioCookie(gpioCookie_), - mainLineSwitcherObjectId(mainLineSwitcherObjectId_), mainLineSwitch(mainLineSwitch_), - actionHelper(this, nullptr) { - commandQueue = QueueFactory::instance()->createMessageQueue(cmdQueueSize, - MessageQueueMessage::MAX_MESSAGE_SIZE); -} - -HeaterHandler::~HeaterHandler() { -} - -ReturnValue_t HeaterHandler::performOperation(uint8_t operationCode) { - - if (operationCode == DeviceHandlerIF::PERFORM_OPERATION) { - readCommandQueue(); - handleActiveCommands(); - return RETURN_OK; - } - return RETURN_OK; -} - -ReturnValue_t HeaterHandler::initialize() { - ReturnValue_t result = SystemObject::initialize(); - if (result != RETURN_OK) { - return ObjectManagerIF::CHILD_INIT_FAILED; - } - - result = initializeHeaterMap(); - if (result != RETURN_OK) { - return ObjectManagerIF::CHILD_INIT_FAILED; - } - - gpioInterface = ObjectManager::instance()->get(gpioDriverId); - if (gpioInterface == nullptr) { - sif::error << "HeaterHandler::initialize: Invalid Gpio interface." << std::endl; - return ObjectManagerIF::CHILD_INIT_FAILED; - } - - result = gpioInterface->addGpios(dynamic_cast(gpioCookie)); - if (result != RETURN_OK) { - sif::error << "HeaterHandler::initialize: Failed to initialize Gpio interface" << std::endl; - return ObjectManagerIF::CHILD_INIT_FAILED; - } - - IPCStore = ObjectManager::instance()->get(objects::IPC_STORE); - if (IPCStore == nullptr) { - sif::error << "HeaterHandler::initialize: IPC store not set up in factory." << std::endl; - return ObjectManagerIF::CHILD_INIT_FAILED; - } - - if(mainLineSwitcherObjectId != objects::NO_OBJECT) { - mainLineSwitcher = ObjectManager::instance()->get(mainLineSwitcherObjectId); - if (mainLineSwitcher == nullptr) { - sif::error - << "HeaterHandler::initialize: Failed to get main line switcher. Make sure " - << "main line switcher object is initialized." << std::endl; - return ObjectManagerIF::CHILD_INIT_FAILED; - } - } - - result = actionHelper.initialize(commandQueue); - if (result != RETURN_OK) { - return ObjectManagerIF::CHILD_INIT_FAILED; - } - - return RETURN_OK; -} - -ReturnValue_t HeaterHandler::initializeHeaterMap(){ - HeaterCommandInfo_t heaterCommandInfo; - for(switchNr_t switchNr = 0; switchNr < heaterSwitches::NUMBER_OF_SWITCHES; switchNr++) { - std::pair status = heaterMap.emplace(switchNr, heaterCommandInfo); - if (status.second == false) { - sif::error << "HeaterHandler::initializeHeaterMap: Failed to initialize heater map" - << std::endl; - return RETURN_FAILED; - } - } - return RETURN_OK; -} - -void HeaterHandler::setInitialSwitchStates() { - for (switchNr_t switchNr = 0; switchNr < heaterSwitches::NUMBER_OF_SWITCHES; switchNr++) { - switchStates[switchNr] = OFF; - } -} - -void HeaterHandler::readCommandQueue() { - CommandMessage command; - ReturnValue_t result = commandQueue->receiveMessage(&command); - if (result != RETURN_OK) { - return; - } - - result = actionHelper.handleActionMessage(&command); - if (result == RETURN_OK) { - return; - } -} - -ReturnValue_t HeaterHandler::executeAction(ActionId_t actionId, - MessageQueueId_t commandedBy, const uint8_t* data, size_t size) { - ReturnValue_t result; - if (actionId != SWITCH_HEATER) { - result = COMMAND_NOT_SUPPORTED; - } else { - switchNr_t switchNr = *data; - HeaterMapIter heaterMapIter = heaterMap.find(switchNr); - if (heaterMapIter != heaterMap.end()) { - if (heaterMapIter->second.active) { - return COMMAND_ALREADY_WAITING; - } - heaterMapIter->second.action = *(data + 1); - heaterMapIter->second.active = true; - heaterMapIter->second.replyQueue = commandedBy; - } - else { - sif::error << "HeaterHandler::executeAction: Invalid switchNr" << std::endl; - return INVALID_SWITCH_NR; - } - result = RETURN_OK; - } - return result; -} - - -void HeaterHandler::sendSwitchCommand(uint8_t switchNr, - ReturnValue_t onOff) const { - - ReturnValue_t result; - store_address_t storeAddress; - uint8_t commandData[2]; - - switch(onOff) { - case PowerSwitchIF::SWITCH_ON: - commandData[0] = switchNr; - commandData[1] = SET_SWITCH_ON; - break; - case PowerSwitchIF::SWITCH_OFF: - commandData[0] = switchNr; - commandData[1] = SET_SWITCH_OFF; - break; - default: - sif::error << "HeaterHandler::sendSwitchCommand: Invalid switch request" - << std::endl; - break; - } - - result = IPCStore->addData(&storeAddress, commandData, sizeof(commandData)); - if (result == RETURN_OK) { - CommandMessage message; - ActionMessage::setCommand(&message, SWITCH_HEATER, storeAddress); - /* Send heater command to own command queue */ - result = commandQueue->sendMessage(commandQueue->getId(), &message, 0); - if (result != RETURN_OK) { - sif::debug << "HeaterHandler::sendSwitchCommand: Failed to send switch" - << "message" << std::endl; - } - } -} - -void HeaterHandler::handleActiveCommands(){ - - HeaterMapIter heaterMapIter = heaterMap.begin(); - for (; heaterMapIter != heaterMap.end(); heaterMapIter++) { - if (heaterMapIter->second.active) { - switch(heaterMapIter->second.action) { - case SET_SWITCH_ON: - handleSwitchOnCommand(heaterMapIter); - break; - case SET_SWITCH_OFF: - handleSwitchOffCommand(heaterMapIter); - break; - default: - sif::error << "HeaterHandler::handleActiveCommands: Invalid action commanded" - << std::endl; - break; - } - } - } -} - -void HeaterHandler::handleSwitchOnCommand(HeaterMapIter heaterMapIter) { - - ReturnValue_t result = RETURN_OK; - switchNr_t switchNr; - - /* Check if command waits for main switch being set on and whether the timeout has expired */ - if (heaterMapIter->second.waitMainSwitchOn - && heaterMapIter->second.mainSwitchCountdown.hasTimedOut()) { - //TODO - This requires the initiation of an FDIR procedure - triggerEvent(MAIN_SWITCH_TIMEOUT); - sif::error << "HeaterHandler::handleSwitchOnCommand: Main switch setting on timeout" - << std::endl; - heaterMapIter->second.active = false; - heaterMapIter->second.waitMainSwitchOn = false; - if (heaterMapIter->second.replyQueue != commandQueue->getId()) { - actionHelper.finish(false, heaterMapIter->second.replyQueue, - heaterMapIter->second.action, MAIN_SWITCH_SET_TIMEOUT ); - } - return; - } - - switchNr = heaterMapIter->first; - /* Check state of main line switch */ - ReturnValue_t mainSwitchState = mainLineSwitcher->getSwitchState(mainLineSwitch); - if (mainSwitchState == PowerSwitchIF::SWITCH_ON) { - if (!checkSwitchState(switchNr)) { - gpioId_t gpioId = getGpioIdFromSwitchNr(switchNr); - result = gpioInterface->pullHigh(gpioId); - if (result != RETURN_OK) { - sif::error << "HeaterHandler::handleSwitchOnCommand: Failed to pull gpio with id " - << gpioId << " high" << std::endl; - triggerEvent(GPIO_PULL_HIGH_FAILED, result); - } - else { - switchStates[switchNr] = ON; - } - } - else { - triggerEvent(SWITCH_ALREADY_ON, switchNr); - } - /* There is no need to send action finish replies if the sender was the - * HeaterHandler itself. */ - if (heaterMapIter->second.replyQueue != commandQueue->getId()) { - if(result == RETURN_OK) { - actionHelper.finish(true, heaterMapIter->second.replyQueue, - heaterMapIter->second.action, result); - } - else { - actionHelper.finish(false, heaterMapIter->second.replyQueue, - heaterMapIter->second.action, result); - } - - } - heaterMapIter->second.active = false; - heaterMapIter->second.waitMainSwitchOn = false; - } - else if (mainSwitchState == PowerSwitchIF::SWITCH_OFF - && heaterMapIter->second.waitMainSwitchOn) { - /* Just waiting for the main switch being set on */ - return; - } - else if (mainSwitchState == PowerSwitchIF::SWITCH_OFF) { - mainLineSwitcher->sendSwitchCommand(mainLineSwitch, - PowerSwitchIF::SWITCH_ON); - heaterMapIter->second.mainSwitchCountdown.setTimeout(mainLineSwitcher->getSwitchDelayMs()); - heaterMapIter->second.waitMainSwitchOn = true; - } - else { - sif::debug << "HeaterHandler::handleActiveCommands: Failed to get state of" - << " main line switch" << std::endl; - if (heaterMapIter->second.replyQueue != commandQueue->getId()) { - actionHelper.finish(false, heaterMapIter->second.replyQueue, - heaterMapIter->second.action, mainSwitchState); - } - heaterMapIter->second.active = false; - } -} - -void HeaterHandler::handleSwitchOffCommand(HeaterMapIter heaterMapIter) { - ReturnValue_t result = RETURN_OK; - switchNr_t switchNr = heaterMapIter->first; - /* Check whether switch is already off */ - if (checkSwitchState(switchNr)) { - gpioId_t gpioId = getGpioIdFromSwitchNr(switchNr); - result = gpioInterface->pullLow(gpioId); - if (result != RETURN_OK) { - sif::error << "HeaterHandler::handleSwitchOffCommand: Failed to pull gpio with id" - << gpioId << " low" << std::endl; - triggerEvent(GPIO_PULL_LOW_FAILED, result); - } - else { - switchStates[switchNr] = OFF; - /* When all switches are off, also main line switch will be turned off */ - if (allSwitchesOff()) { - mainLineSwitcher->sendSwitchCommand(mainLineSwitch, PowerSwitchIF::SWITCH_OFF); - } - } - } - else { - sif::info << "HeaterHandler::handleSwitchOffCommand: Switch already off" << std::endl; - triggerEvent(SWITCH_ALREADY_OFF, switchNr); - } - if (heaterMapIter->second.replyQueue != NO_COMMANDER) { - /* Report back switch command reply if necessary */ - if(result == HasReturnvaluesIF::RETURN_OK) { - actionHelper.finish(true, heaterMapIter->second.replyQueue, - heaterMapIter->second.action, result); - } - else { - actionHelper.finish(false, heaterMapIter->second.replyQueue, - heaterMapIter->second.action, result); - } - } - heaterMapIter->second.active = false; -} - -bool HeaterHandler::checkSwitchState(int switchNr) { - return switchStates[switchNr]; -} - -bool HeaterHandler::allSwitchesOff() { - bool allSwitchesOrd = false; - /* Or all switches. As soon one switch is on, allSwitchesOrd will be true */ - for (switchNr_t switchNr = 0; switchNr < heaterSwitches::NUMBER_OF_SWITCHES; switchNr++) { - allSwitchesOrd = allSwitchesOrd || switchStates[switchNr]; - } - return !allSwitchesOrd; -} - -gpioId_t HeaterHandler::getGpioIdFromSwitchNr(int switchNr) { - gpioId_t gpioId = 0xFFFF; - switch(switchNr) { - case heaterSwitches::HEATER_0: - gpioId = gpioIds::HEATER_0; - break; - case heaterSwitches::HEATER_1: - gpioId = gpioIds::HEATER_1; - break; - case heaterSwitches::HEATER_2: - gpioId = gpioIds::HEATER_2; - break; - case heaterSwitches::HEATER_3: - gpioId = gpioIds::HEATER_3; - break; - case heaterSwitches::HEATER_4: - gpioId = gpioIds::HEATER_4; - break; - case heaterSwitches::HEATER_5: - gpioId = gpioIds::HEATER_5; - break; - case heaterSwitches::HEATER_6: - gpioId = gpioIds::HEATER_6; - break; - case heaterSwitches::HEATER_7: - gpioId = gpioIds::HEATER_7; - break; - default: - sif::error << "HeaterHandler::getGpioIdFromSwitchNr: Unknown heater switch number" - << std::endl; - break; - } - return gpioId; -} - -MessageQueueId_t HeaterHandler::getCommandQueue() const { - return commandQueue->getId(); -} - -void HeaterHandler::sendFuseOnCommand(uint8_t fuseNr) const { -} - -ReturnValue_t HeaterHandler::getSwitchState( uint8_t switchNr ) const { - return 0; -} - -ReturnValue_t HeaterHandler::getFuseState( uint8_t fuseNr ) const { - return 0; -} - -uint32_t HeaterHandler::getSwitchDelayMs(void) const { - return 0; -} diff --git a/linux/devices/HeaterHandler.h b/linux/devices/HeaterHandler.h deleted file mode 100644 index b52e22d4..00000000 --- a/linux/devices/HeaterHandler.h +++ /dev/null @@ -1,177 +0,0 @@ -#ifndef MISSION_DEVICES_HEATERHANDLER_H_ -#define MISSION_DEVICES_HEATERHANDLER_H_ - -#include "devices/heaterSwitcherList.h" - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -/** - * @brief This class intends the control of heaters. - * - * @author J. Meier - */ -class HeaterHandler: public ExecutableObjectIF, - public PowerSwitchIF, - public SystemObject, - public HasActionsIF { -public: - static const uint8_t INTERFACE_ID = CLASS_ID::HEATER_HANDLER; - - static const ReturnValue_t COMMAND_NOT_SUPPORTED = MAKE_RETURN_CODE(0xA1); - static const ReturnValue_t INIT_FAILED = MAKE_RETURN_CODE(0xA2); - static const ReturnValue_t INVALID_SWITCH_NR = MAKE_RETURN_CODE(0xA3); - static const ReturnValue_t MAIN_SWITCH_SET_TIMEOUT = MAKE_RETURN_CODE(0xA4); - static const ReturnValue_t COMMAND_ALREADY_WAITING = MAKE_RETURN_CODE(0xA5); - - /** Device command IDs */ - static const DeviceCommandId_t SWITCH_HEATER = 0x0; - - HeaterHandler(object_id_t setObjectId, object_id_t gpioDriverId, CookieIF * gpioCookie, - object_id_t mainLineSwitcherObjectId, uint8_t mainLineSwitch); - - virtual ~HeaterHandler(); - - virtual ReturnValue_t performOperation(uint8_t operationCode = 0) override; - - virtual void sendSwitchCommand(uint8_t switchNr, ReturnValue_t onOff) const override; - virtual void sendFuseOnCommand(uint8_t fuseNr) const override; - /** - * @brief This function will be called from the Heater object to check - * the current switch state. - */ - virtual ReturnValue_t getSwitchState( uint8_t switchNr ) const override; - virtual ReturnValue_t getFuseState( uint8_t fuseNr ) const override; - virtual uint32_t getSwitchDelayMs(void) const override; - - virtual MessageQueueId_t getCommandQueue() const override; - virtual ReturnValue_t executeAction(ActionId_t actionId, MessageQueueId_t commandedBy, - const uint8_t* data, size_t size) override; - virtual ReturnValue_t initialize() override; - -private: - - static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::HEATER_HANDLER; - static const Event GPIO_PULL_HIGH_FAILED = MAKE_EVENT(0, severity::LOW); - static const Event GPIO_PULL_LOW_FAILED = MAKE_EVENT(1, severity::LOW); - static const Event SWITCH_ALREADY_ON = MAKE_EVENT(2, severity::LOW); - static const Event SWITCH_ALREADY_OFF = MAKE_EVENT(3, severity::LOW); - static const Event MAIN_SWITCH_TIMEOUT = MAKE_EVENT(4, severity::LOW); - - static const MessageQueueId_t NO_COMMANDER = 0; - - enum SwitchState : bool { - ON = true, - OFF = false - }; - - - /** - * @brief Struct holding information about a heater command to execute. - * - * @param action The action to perform. - * @param replyQueue The queue of the commander to which status replies - * will be sent. - * @param active True if command is waiting for execution, otherwise false. - * @param waitSwitchOn True if the command is waiting for the main switch being set on. - * @param mainSwitchCountdown Sets timeout to wait for main switch being set on. - */ - typedef struct HeaterCommandInfo { - uint8_t action; - MessageQueueId_t replyQueue; - bool active = false; - bool waitMainSwitchOn = false; - Countdown mainSwitchCountdown; - } HeaterCommandInfo_t; - - enum SwitchAction { - SET_SWITCH_OFF, - SET_SWITCH_ON - }; - - using switchNr_t = uint8_t; - using HeaterMap = std::unordered_map; - using HeaterMapIter = HeaterMap::iterator; - - HeaterMap heaterMap; - - bool switchStates[heaterSwitches::NUMBER_OF_SWITCHES]; - - /** Size of command queue */ - size_t cmdQueueSize = 20; - - /** - * The object ID of the GPIO driver which enables and disables the - * heaters. - */ - object_id_t gpioDriverId; - - CookieIF * gpioCookie; - - GpioIF* gpioInterface = nullptr; - - /** Queue to receive messages from other objects. */ - MessageQueueIF* commandQueue = nullptr; - - object_id_t mainLineSwitcherObjectId; - - /** Switch number of the heater power supply switch */ - uint8_t mainLineSwitch; - - /** - * Power switcher object which controls the 8V main line of the heater - * logic on the TCS board. - */ - PowerSwitchIF *mainLineSwitcher = nullptr; - - ActionHelper actionHelper; - - StorageManagerIF *IPCStore = nullptr; - - void readCommandQueue(); - - /** - * @brief Returns the state of a switch (ON - true, or OFF - false). - * @param switchNr The number of the switch to check. - */ - bool checkSwitchState(int switchNr); - - /** - * @brief Returns the ID of the GPIO related to a heater identified by the switch number - * which is defined in the heaterSwitches list. - */ - gpioId_t getGpioIdFromSwitchNr(int switchNr); - - /** - * @brief This function runs commands waiting for execution. - */ - void handleActiveCommands(); - - ReturnValue_t initializeHeaterMap(); - - /** - * @brief Sets all switches to OFF. - */ - void setInitialSwitchStates(); - - void handleSwitchOnCommand(HeaterMapIter heaterMapIter); - - void handleSwitchOffCommand(HeaterMapIter heaterMapIter); - - /** - * @brief Checks if all switches are off. - * @return True if all switches are off, otherwise false. - */ - bool allSwitchesOff(); - -}; - -#endif /* MISSION_DEVICES_HEATERHANDLER_H_ */ diff --git a/linux/devices/SolarArrayDeploymentHandler.cpp b/linux/devices/SolarArrayDeploymentHandler.cpp deleted file mode 100644 index eea546f6..00000000 --- a/linux/devices/SolarArrayDeploymentHandler.cpp +++ /dev/null @@ -1,202 +0,0 @@ -#include "SolarArrayDeploymentHandler.h" - -#include -#include - -#include -#include -#include - - -SolarArrayDeploymentHandler::SolarArrayDeploymentHandler(object_id_t setObjectId_, - object_id_t gpioDriverId_, CookieIF * gpioCookie_, object_id_t mainLineSwitcherObjectId_, - uint8_t mainLineSwitch_, gpioId_t deplSA1, gpioId_t deplSA2, uint32_t burnTimeMs) : - SystemObject(setObjectId_), gpioDriverId(gpioDriverId_), gpioCookie(gpioCookie_), - mainLineSwitcherObjectId(mainLineSwitcherObjectId_), mainLineSwitch(mainLineSwitch_), - deplSA1(deplSA1), deplSA2(deplSA2), burnTimeMs(burnTimeMs), actionHelper(this, nullptr) { - commandQueue = QueueFactory::instance()->createMessageQueue(cmdQueueSize, - MessageQueueMessage::MAX_MESSAGE_SIZE); -} - -SolarArrayDeploymentHandler::~SolarArrayDeploymentHandler() { -} - -ReturnValue_t SolarArrayDeploymentHandler::performOperation(uint8_t operationCode) { - - if (operationCode == DeviceHandlerIF::PERFORM_OPERATION) { - handleStateMachine(); - return RETURN_OK; - } - return RETURN_OK; -} - -ReturnValue_t SolarArrayDeploymentHandler::initialize() { - ReturnValue_t result = SystemObject::initialize(); - if (result != RETURN_OK) { - return ObjectManagerIF::CHILD_INIT_FAILED; - } - - gpioInterface = ObjectManager::instance()->get(gpioDriverId); - if (gpioInterface == nullptr) { - sif::error << "SolarArrayDeploymentHandler::initialize: Invalid Gpio interface." - << std::endl; - return ObjectManagerIF::CHILD_INIT_FAILED; - } - - result = gpioInterface->addGpios(dynamic_cast(gpioCookie)); - if (result != RETURN_OK) { - sif::error << "SolarArrayDeploymentHandler::initialize: Failed to initialize Gpio interface" - << std::endl; - return ObjectManagerIF::CHILD_INIT_FAILED; - } - - if (mainLineSwitcherObjectId != objects::NO_OBJECT) { - mainLineSwitcher = ObjectManager::instance()->get(mainLineSwitcherObjectId); - if (mainLineSwitcher == nullptr) { - sif::error - << "SolarArrayDeploymentHandler::initialize: Main line switcher failed to fetch object" - << "from object ID." << std::endl; - return ObjectManagerIF::CHILD_INIT_FAILED; - } - } - - result = actionHelper.initialize(commandQueue); - if (result != RETURN_OK) { - return ObjectManagerIF::CHILD_INIT_FAILED; - } - - return RETURN_OK; -} - -void SolarArrayDeploymentHandler::handleStateMachine() { - switch (stateMachine) { - case WAIT_ON_DELOYMENT_COMMAND: - readCommandQueue(); - break; - case SWITCH_8V_ON: - mainLineSwitcher->sendSwitchCommand(mainLineSwitch, PowerSwitchIF::SWITCH_ON); - mainSwitchCountdown.setTimeout(mainLineSwitcher->getSwitchDelayMs()); - stateMachine = WAIT_ON_8V_SWITCH; - break; - case WAIT_ON_8V_SWITCH: - performWaitOn8VActions(); - break; - case SWITCH_DEPL_GPIOS: - switchDeploymentTransistors(); - break; - case WAIT_ON_DEPLOYMENT_FINISH: - handleDeploymentFinish(); - break; - case WAIT_FOR_MAIN_SWITCH_OFF: - if (mainLineSwitcher->getSwitchState(mainLineSwitch) == PowerSwitchIF::SWITCH_OFF) { - stateMachine = WAIT_ON_DELOYMENT_COMMAND; - } else if (mainSwitchCountdown.hasTimedOut()) { - triggerEvent(MAIN_SWITCH_OFF_TIMEOUT); - sif::error << "SolarArrayDeploymentHandler::handleStateMachine: Failed to switch main" - << " switch off" << std::endl; - stateMachine = WAIT_ON_DELOYMENT_COMMAND; - } - break; - default: - sif::debug << "SolarArrayDeploymentHandler::handleStateMachine: Invalid state" << std::endl; - break; - } -} - -void SolarArrayDeploymentHandler::performWaitOn8VActions() { - if (mainLineSwitcher->getSwitchState(mainLineSwitch) == PowerSwitchIF::SWITCH_ON) { - stateMachine = SWITCH_DEPL_GPIOS; - } else { - if (mainSwitchCountdown.hasTimedOut()) { - triggerEvent(MAIN_SWITCH_ON_TIMEOUT); - actionHelper.finish(false, rememberCommanderId, DEPLOY_SOLAR_ARRAYS, - MAIN_SWITCH_TIMEOUT_FAILURE); - stateMachine = WAIT_ON_DELOYMENT_COMMAND; - } - } -} - -void SolarArrayDeploymentHandler::switchDeploymentTransistors() { - ReturnValue_t result = RETURN_OK; - result = gpioInterface->pullHigh(deplSA1); - if (result != RETURN_OK) { - sif::debug << "SolarArrayDeploymentHandler::handleStateMachine: Failed to pull solar" - " array deployment switch 1 high " << std::endl; - /* If gpio switch high failed, state machine is reset to wait for a command reinitiating - * the deployment sequence. */ - stateMachine = WAIT_ON_DELOYMENT_COMMAND; - triggerEvent(DEPL_SA1_GPIO_SWTICH_ON_FAILED); - actionHelper.finish(false, rememberCommanderId, DEPLOY_SOLAR_ARRAYS, - SWITCHING_DEPL_SA2_FAILED); - mainLineSwitcher->sendSwitchCommand(mainLineSwitch, PowerSwitchIF::SWITCH_OFF); - } - result = gpioInterface->pullHigh(deplSA2); - if (result != RETURN_OK) { - sif::debug << "SolarArrayDeploymentHandler::handleStateMachine: Failed to pull solar" - " array deployment switch 2 high " << std::endl; - stateMachine = WAIT_ON_DELOYMENT_COMMAND; - triggerEvent(DEPL_SA2_GPIO_SWTICH_ON_FAILED); - actionHelper.finish(false, rememberCommanderId, DEPLOY_SOLAR_ARRAYS, - SWITCHING_DEPL_SA2_FAILED); - mainLineSwitcher->sendSwitchCommand(mainLineSwitch, PowerSwitchIF::SWITCH_OFF); - } - deploymentCountdown.setTimeout(burnTimeMs); - stateMachine = WAIT_ON_DEPLOYMENT_FINISH; -} - -void SolarArrayDeploymentHandler::handleDeploymentFinish() { - ReturnValue_t result = RETURN_OK; - if (deploymentCountdown.hasTimedOut()) { - actionHelper.finish(true, rememberCommanderId, DEPLOY_SOLAR_ARRAYS, RETURN_OK); - result = gpioInterface->pullLow(deplSA1); - if (result != RETURN_OK) { - sif::debug << "SolarArrayDeploymentHandler::handleStateMachine: Failed to pull solar" - " array deployment switch 1 low " << std::endl; - } - result = gpioInterface->pullLow(deplSA2); - if (result != RETURN_OK) { - sif::debug << "SolarArrayDeploymentHandler::handleStateMachine: Failed to pull solar" - " array deployment switch 2 low " << std::endl; - } - mainLineSwitcher->sendSwitchCommand(mainLineSwitch, PowerSwitchIF::SWITCH_OFF); - mainSwitchCountdown.setTimeout(mainLineSwitcher->getSwitchDelayMs()); - stateMachine = WAIT_FOR_MAIN_SWITCH_OFF; - } -} - -void SolarArrayDeploymentHandler::readCommandQueue() { - CommandMessage command; - ReturnValue_t result = commandQueue->receiveMessage(&command); - if (result != RETURN_OK) { - return; - } - - result = actionHelper.handleActionMessage(&command); - if (result == RETURN_OK) { - return; - } -} - -ReturnValue_t SolarArrayDeploymentHandler::executeAction(ActionId_t actionId, - MessageQueueId_t commandedBy, const uint8_t* data, size_t size) { - ReturnValue_t result; - if (stateMachine != WAIT_ON_DELOYMENT_COMMAND) { - sif::error << "SolarArrayDeploymentHandler::executeAction: Received command while not in" - << "waiting-on-command-state" << std::endl; - return DEPLOYMENT_ALREADY_EXECUTING; - } - if (actionId != DEPLOY_SOLAR_ARRAYS) { - sif::error << "SolarArrayDeploymentHandler::executeAction: Received invalid command" - << std::endl; - result = COMMAND_NOT_SUPPORTED; - } else { - stateMachine = SWITCH_8V_ON; - rememberCommanderId = commandedBy; - result = RETURN_OK; - } - return result; -} - -MessageQueueId_t SolarArrayDeploymentHandler::getCommandQueue() const { - return commandQueue->getId(); -} diff --git a/linux/devices/SolarArrayDeploymentHandler.h b/linux/devices/SolarArrayDeploymentHandler.h deleted file mode 100644 index 5e573128..00000000 --- a/linux/devices/SolarArrayDeploymentHandler.h +++ /dev/null @@ -1,158 +0,0 @@ -#ifndef MISSION_DEVICES_SOLARARRAYDEPLOYMENT_H_ -#define MISSION_DEVICES_SOLARARRAYDEPLOYMENT_H_ - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -/** - * @brief This class is used to control the solar array deployment. - * - * @author J. Meier - */ -class SolarArrayDeploymentHandler: public ExecutableObjectIF, - public SystemObject, - public HasReturnvaluesIF, - public HasActionsIF { -public: - - static const DeviceCommandId_t DEPLOY_SOLAR_ARRAYS = 0x5; - - /** - * @brief constructor - * - * @param setObjectId The object id of the SolarArrayDeploymentHandler. - * @param gpioDriverId The id of the gpio com if. - * @param gpioCookie GpioCookie holding information about the gpios used to switch the - * transistors. - * @param mainLineSwitcherObjectId The object id of the object responsible for switching - * the 8V power source. This is normally the PCDU. - * @param mainLineSwitch The id of the main line switch. This is defined in - * powerSwitcherList.h. - * @param deplSA1 gpioId of the GPIO controlling the deployment 1 transistor. - * @param deplSA2 gpioId of the GPIO controlling the deployment 2 transistor. - * @param burnTimeMs Time duration the power will be applied to the burn wires. - */ - SolarArrayDeploymentHandler(object_id_t setObjectId, object_id_t gpioDriverId, - CookieIF * gpioCookie, object_id_t mainLineSwitcherObjectId, uint8_t mainLineSwitch, - gpioId_t deplSA1, gpioId_t deplSA2, uint32_t burnTimeMs); - - virtual ~SolarArrayDeploymentHandler(); - - virtual ReturnValue_t performOperation(uint8_t operationCode = 0) override; - - virtual MessageQueueId_t getCommandQueue() const override; - virtual ReturnValue_t executeAction(ActionId_t actionId, MessageQueueId_t commandedBy, - const uint8_t* data, size_t size) override; - virtual ReturnValue_t initialize() override; - -private: - - static const uint8_t INTERFACE_ID = CLASS_ID::SA_DEPL_HANDLER; - static const ReturnValue_t COMMAND_NOT_SUPPORTED = MAKE_RETURN_CODE(0xA0); - static const ReturnValue_t DEPLOYMENT_ALREADY_EXECUTING = MAKE_RETURN_CODE(0xA1); - static const ReturnValue_t MAIN_SWITCH_TIMEOUT_FAILURE = MAKE_RETURN_CODE(0xA2); - static const ReturnValue_t SWITCHING_DEPL_SA1_FAILED = MAKE_RETURN_CODE(0xA3); - static const ReturnValue_t SWITCHING_DEPL_SA2_FAILED = MAKE_RETURN_CODE(0xA4); - - static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::SA_DEPL_HANDLER; - static const Event MAIN_SWITCH_ON_TIMEOUT = MAKE_EVENT(0, severity::LOW); - static const Event MAIN_SWITCH_OFF_TIMEOUT = MAKE_EVENT(1, severity::LOW); - static const Event DEPLOYMENT_FAILED = MAKE_EVENT(2, severity::HIGH); - static const Event DEPL_SA1_GPIO_SWTICH_ON_FAILED = MAKE_EVENT(3, severity::HIGH); - static const Event DEPL_SA2_GPIO_SWTICH_ON_FAILED = MAKE_EVENT(4, severity::HIGH); - - - enum StateMachine { - WAIT_ON_DELOYMENT_COMMAND, - SWITCH_8V_ON, - WAIT_ON_8V_SWITCH, - SWITCH_DEPL_GPIOS, - WAIT_ON_DEPLOYMENT_FINISH, - WAIT_FOR_MAIN_SWITCH_OFF - }; - - StateMachine stateMachine = WAIT_ON_DELOYMENT_COMMAND; - - /** - * This countdown is used to check if the PCDU sets the 8V line on in the intended time. - */ - Countdown mainSwitchCountdown; - - /** - * This countdown is used to wait for the burn wire being successful cut. - */ - Countdown deploymentCountdown; - - - /** - * The message queue id of the component commanding an action will be stored in this variable. - * This is necessary to send later the action finish replies. - */ - MessageQueueId_t rememberCommanderId = 0; - - /** Size of command queue */ - size_t cmdQueueSize = 20; - - /** The object ID of the GPIO driver which switches the deployment transistors */ - object_id_t gpioDriverId; - - CookieIF * gpioCookie; - - /** Object id of the object responsible to switch the 8V power input. Typically the PCDU. */ - object_id_t mainLineSwitcherObjectId; - - /** Switch number of the 8V power switch */ - uint8_t mainLineSwitch; - - gpioId_t deplSA1; - gpioId_t deplSA2; - - GpioIF* gpioInterface = nullptr; - - /** Time duration switches are active to cut the burn wire */ - uint32_t burnTimeMs; - - /** Queue to receive messages from other objects. */ - MessageQueueIF* commandQueue = nullptr; - - /** - * After initialization this pointer will hold the reference to the main line switcher object. - */ - PowerSwitchIF *mainLineSwitcher = nullptr; - - ActionHelper actionHelper; - - void readCommandQueue(); - - /** - * @brief This function performs actions dependent on the current state. - */ - void handleStateMachine(); - - /** - * @brief This function polls the 8V switch state and changes the state machine when the - * switch has been enabled. - */ - void performWaitOn8VActions(); - - /** - * @brief This functions handles the switching of the solar array deployment transistors. - */ - void switchDeploymentTransistors(); - - /** - * @brief This function performs actions to finish the deployment. Essentially switches - * are turned of after the burn time has expired. - */ - void handleDeploymentFinish(); -}; - -#endif /* MISSION_DEVICES_SOLARARRAYDEPLOYMENT_H_ */ diff --git a/linux/devices/SusHandler.cpp b/linux/devices/SusHandler.cpp deleted file mode 100644 index 67263756..00000000 --- a/linux/devices/SusHandler.cpp +++ /dev/null @@ -1,230 +0,0 @@ -#include "SusHandler.h" -#include "OBSWConfig.h" - -#include -#include - -SusHandler::SusHandler(object_id_t objectId, object_id_t comIF, CookieIF * comCookie, - LinuxLibgpioIF* gpioComIF, gpioId_t chipSelectId) : - DeviceHandlerBase(objectId, comIF, comCookie), gpioComIF(gpioComIF), chipSelectId( - chipSelectId), dataset(this) { - if (comCookie == NULL) { - sif::error << "SusHandler: Invalid com cookie" << std::endl; - } - if (gpioComIF == NULL) { - sif::error << "SusHandler: Invalid GpioComIF" << std::endl; - } -} - -SusHandler::~SusHandler() { -} - -ReturnValue_t SusHandler::performOperation(uint8_t counter) { - - if (counter != FIRST_WRITE) { - DeviceHandlerBase::performOperation(counter); - return RETURN_OK; - } - - if (mode != MODE_NORMAL) { - DeviceHandlerBase::performOperation(DeviceHandlerIF::SEND_WRITE); - return RETURN_OK; - } - - /* If device is in normale mode the communication sequence is initiated here */ - if (communicationStep == CommunicationStep::IDLE) { - communicationStep = CommunicationStep::WRITE_SETUP; - } - - DeviceHandlerBase::performOperation(DeviceHandlerIF::SEND_WRITE); - - return RETURN_OK; -} - -ReturnValue_t SusHandler::initialize() { - ReturnValue_t result = RETURN_OK; - result = DeviceHandlerBase::initialize(); - if (result != RETURN_OK) { - return result; - } - auto spiComIF = dynamic_cast(communicationInterface); - if (spiComIF == nullptr) { - sif::debug << "SusHandler::initialize: Invalid communication interface" << std::endl; - return ObjectManagerIF::CHILD_INIT_FAILED; - } - spiMutex = spiComIF->getMutex(); - if (spiMutex == nullptr) { - sif::debug << "SusHandler::initialize: Failed to get spi mutex" << std::endl; - return ObjectManagerIF::CHILD_INIT_FAILED; - } - return RETURN_OK; -} - -void SusHandler::doStartUp(){ -#if OBSW_SWITCH_TO_NORMAL_MODE_AFTER_STARTUP == 1 - setMode(MODE_NORMAL); -#else - setMode(_MODE_TO_ON); -#endif -} - -void SusHandler::doShutDown(){ - setMode(_MODE_POWER_DOWN); -} - -ReturnValue_t SusHandler::buildNormalDeviceCommand( - DeviceCommandId_t * id) { - - if (communicationStep == CommunicationStep::IDLE) { - return NOTHING_TO_SEND; - } - - if (communicationStep == CommunicationStep::WRITE_SETUP) { - *id = SUS::WRITE_SETUP; - communicationStep = CommunicationStep::START_CONVERSIONS; - } - else if (communicationStep == CommunicationStep::START_CONVERSIONS) { - *id = SUS::START_CONVERSIONS; - communicationStep = CommunicationStep::READ_CONVERSIONS; - } - else if (communicationStep == CommunicationStep::READ_CONVERSIONS) { - *id = SUS::READ_CONVERSIONS; - communicationStep = CommunicationStep::IDLE; - } - return buildCommandFromCommand(*id, nullptr, 0); -} - -ReturnValue_t SusHandler::buildTransitionDeviceCommand( - DeviceCommandId_t * id){ - return HasReturnvaluesIF::RETURN_OK; -} - -ReturnValue_t SusHandler::buildCommandFromCommand( - DeviceCommandId_t deviceCommand, const uint8_t * commandData, - size_t commandDataLen) { - switch(deviceCommand) { - case(SUS::WRITE_SETUP): { - /** - * The sun sensor ADC is shutdown when CS is pulled high, so each time requesting a - * measurement the setup has to be rewritten. There must also be a little delay between - * the transmission of the setup byte and the first conversion. Thus the conversion - * will be performed in an extra step. - * Because the chip select is driven manually by the SusHandler the SPI bus must be - * protected with a mutex here. - */ - ReturnValue_t result = spiMutex->lockMutex(timeoutType, timeoutMs); - if(result == MutexIF::MUTEX_TIMEOUT) { - sif::error << "SusHandler::buildCommandFromCommand: Mutex timeout" << std::endl; - return ERROR_LOCK_MUTEX; - } - else if(result != HasReturnvaluesIF::RETURN_OK) { - sif::error << "SusHandler::buildCommandFromCommand: Failed to lock spi mutex" - << std::endl; - return ERROR_LOCK_MUTEX; - } - - gpioComIF->pullLow(chipSelectId); - cmdBuffer[0] = SUS::SETUP; - rawPacket = cmdBuffer; - rawPacketLen = 1; - return RETURN_OK; - } - case(SUS::START_CONVERSIONS): { - std::memset(cmdBuffer, 0, sizeof(cmdBuffer)); - cmdBuffer[0] = SUS::CONVERSION; - rawPacket = cmdBuffer; - rawPacketLen = 2; - return RETURN_OK; - } - case(SUS::READ_CONVERSIONS): { - std::memset(cmdBuffer, 0, sizeof(cmdBuffer)); - rawPacket = cmdBuffer; - rawPacketLen = SUS::SIZE_READ_CONVERSIONS; - return RETURN_OK; - } - default: - return DeviceHandlerIF::COMMAND_NOT_IMPLEMENTED; - } - return HasReturnvaluesIF::RETURN_FAILED; -} - -void SusHandler::fillCommandAndReplyMap() { - this->insertInCommandMap(SUS::WRITE_SETUP); - this->insertInCommandMap(SUS::START_CONVERSIONS); - this->insertInCommandAndReplyMap(SUS::READ_CONVERSIONS, 1, &dataset, SUS::SIZE_READ_CONVERSIONS); -} - -ReturnValue_t SusHandler::scanForReply(const uint8_t *start, - size_t remainingSize, DeviceCommandId_t *foundId, size_t *foundLen) { - *foundId = this->getPendingCommand(); - *foundLen = remainingSize; - return HasReturnvaluesIF::RETURN_OK; -} - -ReturnValue_t SusHandler::interpretDeviceReply(DeviceCommandId_t id, - const uint8_t *packet) { - switch (id) { - case SUS::READ_CONVERSIONS: { - PoolReadGuard readSet(&dataset); - dataset.temperatureCelcius = (*(packet) << 8 | *(packet + 1)) * 0.125; - dataset.ain0 = (*(packet + 2) << 8 | *(packet + 3)); - dataset.ain1 = (*(packet + 4) << 8 | *(packet + 5)); - dataset.ain2 = (*(packet + 6) << 8 | *(packet + 7)); - dataset.ain3 = (*(packet + 8) << 8 | *(packet + 9)); - dataset.ain4 = (*(packet + 10) << 8 | *(packet + 11)); - dataset.ain5 = (*(packet + 12) << 8 | *(packet + 13)); -#if OBSW_VERBOSE_LEVEL >= 1 && OBSW_DEBUG_SUS - sif::info << "SUS object id 0x" << std::hex << this->getObjectId() << ", Temperature: " - << dataset.temperatureCelcius << " °C" << std::endl; - sif::info << "SUS object id 0x" << std::hex << this->getObjectId() << ", AIN0: " - << std::dec << dataset.ain0 << std::endl; - sif::info << "SUS object id 0x" << std::hex << this->getObjectId() << ", AIN1: " - << std::dec << dataset.ain1 << std::endl; - sif::info << "SUS object id 0x" << std::hex << this->getObjectId() << ", AIN2: " - << std::dec << dataset.ain2 << std::endl; - sif::info << "SUS object id 0x" << std::hex << this->getObjectId() << ", AIN3: " - << std::dec << dataset.ain3 << std::endl; - sif::info << "SUS object id 0x" << std::hex << this->getObjectId() << ", AIN4: " - << std::dec << dataset.ain4 << std::endl; - sif::info << "SUS object id 0x" << std::hex << this->getObjectId() << ", AIN5: " - << std::dec << dataset.ain5 << std::endl; -#endif - /** SUS can now be shutdown and thus the SPI bus released again */ - gpioComIF->pullHigh(chipSelectId); - ReturnValue_t result = spiMutex->unlockMutex(); - if (result != RETURN_OK) { - sif::error << "SusHandler::interpretDeviceReply: Failed to unlock spi mutex" - << std::endl; - return ERROR_UNLOCK_MUTEX; - } - break; - } - default: { - sif::debug << "SusHandler::interpretDeviceReply: Unknown reply id" << std::endl; - return DeviceHandlerIF::UNKNOWN_DEVICE_REPLY; - } - - } - return HasReturnvaluesIF::RETURN_OK; -} - -void SusHandler::setNormalDatapoolEntriesInvalid(){ - -} - -uint32_t SusHandler::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo){ - return 1000; -} - -ReturnValue_t SusHandler::initializeLocalDataPool(localpool::DataPool& localDataPoolMap, - LocalDataPoolManager& poolManager) { - localDataPoolMap.emplace(SUS::TEMPERATURE_C, new PoolEntry( { 0.0 })); - localDataPoolMap.emplace(SUS::AIN0, new PoolEntry( { 0 })); - localDataPoolMap.emplace(SUS::AIN1, new PoolEntry( { 0 })); - localDataPoolMap.emplace(SUS::AIN2, new PoolEntry( { 0 })); - localDataPoolMap.emplace(SUS::AIN3, new PoolEntry( { 0 })); - localDataPoolMap.emplace(SUS::AIN4, new PoolEntry( { 0 })); - localDataPoolMap.emplace(SUS::AIN5, new PoolEntry( { 0 })); - return HasReturnvaluesIF::RETURN_OK; -} - diff --git a/linux/devices/SusHandler.h b/linux/devices/SusHandler.h deleted file mode 100644 index ca9a5c45..00000000 --- a/linux/devices/SusHandler.h +++ /dev/null @@ -1,80 +0,0 @@ -#ifndef MISSION_DEVICES_SUSHANDLER_H_ -#define MISSION_DEVICES_SUSHANDLER_H_ - -#include "devicedefinitions/SusDefinitions.h" -#include -#include - -/** - * @brief This is the device handler class for the SUS sensor. The sensor is - * based on the MAX1227 ADC. Details about the SUS electronic can be found at - * https://egit.irs.uni-stuttgart.de/eive/eive_dokumente/src/branch/master/400_Raumsegment/443_SunSensorDocumentation/release - * - * @details Datasheet of MAX1227: https://datasheets.maximintegrated.com/en/ds/MAX1227-MAX1231.pdf - * - * @note When adding a SusHandler to the polling sequence table make sure to add a slot with - * the executionStep FIRST_WRITE. Otherwise the communication sequence will never be - * started. - * - * @author J. Meier - */ -class SusHandler: public DeviceHandlerBase { -public: - - static const uint8_t FIRST_WRITE = 7; - - SusHandler(object_id_t objectId, object_id_t comIF, - CookieIF * comCookie, LinuxLibgpioIF* gpioComIF, gpioId_t chipSelectId); - virtual ~SusHandler(); - - virtual ReturnValue_t performOperation(uint8_t counter) override; - - virtual ReturnValue_t initialize() override; - -protected: - void doStartUp() override; - void doShutDown() override; - ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t * id) override; - ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t * id) override; - void fillCommandAndReplyMap() override; - ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, - const uint8_t * commandData,size_t commandDataLen) override; - ReturnValue_t scanForReply(const uint8_t *start, size_t remainingSize, - DeviceCommandId_t *foundId, size_t *foundLen) override; - ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, - const uint8_t *packet) override; - void setNormalDatapoolEntriesInvalid() override; - uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override; - ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, - LocalDataPoolManager& poolManager) override; - -private: - - static const uint8_t INTERFACE_ID = CLASS_ID::SUS_HANDLER; - - static const ReturnValue_t ERROR_UNLOCK_MUTEX = MAKE_RETURN_CODE(0xA0); - static const ReturnValue_t ERROR_LOCK_MUTEX = MAKE_RETURN_CODE(0xA1); - - enum class CommunicationStep { - IDLE, - WRITE_SETUP, - START_CONVERSIONS, - READ_CONVERSIONS - }; - - LinuxLibgpioIF* gpioComIF = nullptr; - - gpioId_t chipSelectId = gpio::NO_GPIO; - - SUS::SusDataset dataset; - - uint8_t cmdBuffer[SUS::MAX_CMD_SIZE]; - CommunicationStep communicationStep = CommunicationStep::IDLE; - - MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING; - uint32_t timeoutMs = 20; - - MutexIF* spiMutex = nullptr; -}; - -#endif /* MISSION_DEVICES_SUSHANDLER_H_ */ diff --git a/linux/devices/devicedefinitions/StarTrackerDefinitions.h b/linux/devices/devicedefinitions/StarTrackerDefinitions.h new file mode 100644 index 00000000..f7059c66 --- /dev/null +++ b/linux/devices/devicedefinitions/StarTrackerDefinitions.h @@ -0,0 +1,1511 @@ +#ifndef LINUX_DEVICES_DEVICEDEFINITIONS_STARTRACKER_DEFINITIONS_H_ +#define LINUX_DEVICES_DEVICEDEFINITIONS_STARTRACKER_DEFINITIONS_H_ + +#include +#include +#include +#include +#include + +#include "objects/systemObjectList.h" + +namespace startracker { + +/** This is the address of the star tracker */ +static const uint8_t ADDRESS = 33; + +static const uint8_t STATUS_OK = 0; + +enum PoolIds : lp_id_t { + TICKS_TIME_SET, + TIME_TIME_SET, + RUN_TIME, + UNIX_TIME, + TICKS_VERSION_SET, + TIME_VERSION_SET, + PROGRAM, + MAJOR, + MINOR, + TICKS_INTERFACE_SET, + TIME_INTERFACE_SET, + FRAME_COUNT, + CHECKSUM_ERROR_COUNT, + SET_PARAM_COUNT, + SET_PARAM_REPLY_COUNT, + PARAM_REQUEST_COUNT, + PARAM_REPLY_COUNT, + REQ_TM_COUNT, + TM_REPLY_COUNT, + ACTION_REQ_COUNT, + ACTION_REPLY_COUNT, + TICKS_POWER_SET, + TIME_POWER_SET, + MCU_CURRENT, + MCU_VOLTAGE, + FPGA_CORE_CURRENT, + FPGA_CORE_VOLTAGE, + FPGA_18_CURRENT, + FPGA_18_VOLTAGE, + FPGA_25_CURRENT, + FPGA_25_VOLTAGE, + CMV_21_CURRENT, + CMV_21_VOLTAGE, + CMV_PIX_CURRENT, + CMV_PIX_VOLTAGE, + CMV_33_CURRENT, + CMV_33_VOLTAGE, + CMV_RES_CURRENT, + CMV_RES_VOLTAGE, + TICKS_TEMPERATURE_SET, + TIME_TEMPERATURE_SET, + MCU_TEMPERATURE, + CMOS_TEMPERATURE, + FPGA_TEMPERATURE, + TICKS_SOLUTION_SET, + TIME_SOLUTION_SET, + CALI_QW, + CALI_QX, + CALI_QY, + CALI_QZ, + TRACK_CONFIDENCE, + TRACK_QW, + TRACK_QX, + TRACK_QY, + TRACK_QZ, + TRACK_REMOVED, + STARS_CENTROIDED, + STARS_MATCHED_DATABASE, + LISA_QW, + LISA_QX, + LISA_QY, + LISA_QZ, + LISA_PERC_CLOSE, + LISA_NR_CLOSE, + TRUST_WORTHY, + STABLE_COUNT, + SOLUTION_STRATEGY, + TICKS_HISTOGRAM_SET, + TIME_HISTOGRAM_SET, + HISTOGRAM_BINA0, + HISTOGRAM_BINA1, + HISTOGRAM_BINA2, + HISTOGRAM_BINA3, + HISTOGRAM_BINA4, + HISTOGRAM_BINA5, + HISTOGRAM_BINA6, + HISTOGRAM_BINA7, + HISTOGRAM_BINA8, + HISTOGRAM_BINB0, + HISTOGRAM_BINB1, + HISTOGRAM_BINB2, + HISTOGRAM_BINB3, + HISTOGRAM_BINB4, + HISTOGRAM_BINB5, + HISTOGRAM_BINB6, + HISTOGRAM_BINB7, + HISTOGRAM_BINB8, + HISTOGRAM_BINC0, + HISTOGRAM_BINC1, + HISTOGRAM_BINC2, + HISTOGRAM_BINC3, + HISTOGRAM_BINC4, + HISTOGRAM_BINC5, + HISTOGRAM_BINC6, + HISTOGRAM_BINC7, + HISTOGRAM_BINC8, + HISTOGRAM_BIND0, + HISTOGRAM_BIND1, + HISTOGRAM_BIND2, + HISTOGRAM_BIND3, + HISTOGRAM_BIND4, + HISTOGRAM_BIND5, + HISTOGRAM_BIND6, + HISTOGRAM_BIND7, + HISTOGRAM_BIND8, + CHKSUM, + CAMERA_MODE, + FOCALLENGTH, + EXPOSURE, + INTERVAL, + CAMERA_OFFSET, + PGAGAIN, + ADCGAIN, + CAM_REG1, + CAM_VAL1, + CAM_REG2, + CAM_VAL2, + CAM_REG3, + CAM_VAL3, + CAM_REG4, + CAM_VAL4, + CAM_REG5, + CAM_VAL5, + CAM_REG6, + CAM_VAL6, + CAM_REG7, + CAM_VAL7, + CAM_REG8, + CAM_VAL8, + CAM_FREQ_1, + LIMITS_ACTION, + LIMITS_FPGA18CURRENT, + LIMITS_FPGA25CURRENT, + LIMITS_FPGA10CURRENT, + LIMITS_MCUCURRENT, + LIMITS_CMOS21CURRENT, + LIMITS_CMOSPIXCURRENT, + LIMITS_CMOS33CURRENT, + LIMITS_CMOSVRESCURRENT, + LIMITS_CMOSTEMPERATURE, + LIMITS_MCUTEMPERATURE, + BLOB_MODE, + BLOB_MIN_VALUE, + BLOB_MIN_DISTANCE, + BLOB_NEIGHBOUR_DISTANCE, + BLOB_NEIGHBOUR_BRIGHTPIXELS, + BLOB_MIN_TOTAL_VALUE, + BLOB_MAX_TOTAL_VALUE, + BLOB_MIN_BRIGHT_NEIGHBOURS, + BLOB_MAX_BRIGHT_NEIGHBOURS, + BLOB_MAX_PIXELSTOCONSIDER, + BLOB_SIGNAL_THRESHOLD, + BLOB_DARK_THRESHOLD, + BLOB_ENABLE_HISTOGRAM, + BLOB_ENABLE_CONTRAST, + BLOB_BIN_MODE, + LOGLEVEL1, + LOGLEVEL2, + LOGLEVEL3, + LOGLEVEL4, + LOGLEVEL5, + LOGLEVEL6, + LOGLEVEL7, + LOGLEVEL8, + LOGLEVEL9, + LOGLEVEL10, + LOGLEVEL11, + LOGLEVEL12, + LOGLEVEL13, + LOGLEVEL14, + LOGLEVEL15, + LOGLEVEL16, + MOUNTING_QW, + MOUNTING_QX, + MOUNTING_QY, + MOUNTING_QZ, + IMAGE_PROCESSOR_MODE, + IMAGE_PROCESSOR_STORE, + IMAGE_PROCESSOR_SIGNALTHRESHOLD, + IMAGE_PROCESSOR_DARKTHRESHOLD, + IMAGE_PROCESSOR_BACKGROUNDCOMPENSATION, + CENTROIDING_ENABLE_FILTER, + CENTROIDING_MAX_QUALITY, + CENTROIDING_DARK_THRESHOLD, + CENTROIDING_MIN_QUALITY, + CENTROIDING_MAX_INTENSITY, + CENTROIDING_MIN_INTENSITY, + CENTROIDING_MAX_MAGNITUDE, + CENTROIDING_GAUSSIAN_CMAX, + CENTROIDING_GAUSSIAN_CMIN, + CENTROIDING_TRANSMATRIX00, + CENTROIDING_TRANSMATRIX01, + CENTROIDING_TRANSMATRIX10, + CENTROIDING_TRANSMATRIX11, + LISA_MODE, + LISA_PREFILTER_DIST_THRESHOLD, + LISA_PREFILTER_ANGLE_THRESHOLD, + LISA_FOV_WIDTH, + LISA_FOV_HEIGHT, + LISA_FLOAT_STAR_LIMIT, + LISA_CLOSE_STAR_LIMIT, + LISA_RATING_WEIGHT_CLOSE_STAR_COUNT, + LISA_RATING_WEIGHT_FRACTION_CLOSE, + LISA_RATING_WEIGHT_MEAN_SUM, + LISA_RATING_WEIGHT_DB_STAR_COUNT, + LISA_MAX_COMBINATIONS, + LISA_NR_STARS_STOP, + LISA_FRACTION_CLOSE_STOP, + MATCHING_SQUARED_DISTANCE_LIMIT, + MATCHING_SQUARED_SHIFT_LIMIT, + TRACKING_THIN_LIMIT, + TRACKING_OUTLIER_THRESHOLD, + TRACKING_OUTLIER_THRESHOLD_QUEST, + TRACKING_TRACKER_CHOICE, + VALIDATION_STABLE_COUNT, + VALIDATION_MAX_DIFFERENCE, + VALIDATION_MIN_TRACKER_CONFIDENCE, + VALIDATION_MIN_MATCHED_STARS, + ALGO_MODE, + ALGO_I2T_MIN_CONFIDENCE, + ALGO_I2T_MIN_MATCHED, + ALGO_I2L_MIN_CONFIDENCE, + ALGO_I2L_MIN_MATCHED, + SUBSCRIPTION_TM1, + SUBSCRIPTION_TM2, + SUBSCRIPTION_TM3, + SUBSCRIPTION_TM4, + SUBSCRIPTION_TM5, + SUBSCRIPTION_TM6, + SUBSCRIPTION_TM7, + SUBSCRIPTION_TM8, + SUBSCRIPTION_TM9, + SUBSCRIPTION_TM10, + SUBSCRIPTION_TM11, + SUBSCRIPTION_TM12, + SUBSCRIPTION_TM13, + SUBSCRIPTION_TM14, + SUBSCRIPTION_TM15, + SUBSCRIPTION_TM16, + LOG_SUBSCRIPTION_LEVEL1, + LOG_SUBSCRIPTION_MODULE1, + LOG_SUBSCRIPTION_LEVEL2, + LOG_SUBSCRIPTION_MODULE2, + DEBUG_CAMERA_TIMING, + DEBUG_CAMERA_TEST +}; + +static const DeviceCommandId_t PING_REQUEST = 0; +// Boots image (works only in bootloader mode) +static const DeviceCommandId_t BOOT = 1; +static const DeviceCommandId_t REQ_VERSION = 2; +static const DeviceCommandId_t REQ_INTERFACE = 3; +static const DeviceCommandId_t REQ_TIME = 4; +static const DeviceCommandId_t SWITCH_TO_BOOTLOADER_PROGRAM = 7; +static const DeviceCommandId_t DOWNLOAD_IMAGE = 9; +static const DeviceCommandId_t UPLOAD_IMAGE = 10; +static const DeviceCommandId_t REQ_POWER = 11; +static const DeviceCommandId_t TAKE_IMAGE = 15; +static const DeviceCommandId_t SUBSCRIPTION = 18; +static const DeviceCommandId_t IMAGE_PROCESSOR = 19; +static const DeviceCommandId_t REQ_SOLUTION = 24; +static const DeviceCommandId_t REQ_TEMPERATURE = 25; +static const DeviceCommandId_t REQ_HISTOGRAM = 28; +static const DeviceCommandId_t LIMITS = 40; +static const DeviceCommandId_t MOUNTING = 41; +static const DeviceCommandId_t CAMERA = 42; +static const DeviceCommandId_t CENTROIDING = 44; +static const DeviceCommandId_t LISA = 45; +static const DeviceCommandId_t MATCHING = 46; +static const DeviceCommandId_t TRACKING = 47; +static const DeviceCommandId_t VALIDATION = 48; +static const DeviceCommandId_t ALGO = 49; +static const DeviceCommandId_t CHECKSUM = 50; +static const DeviceCommandId_t FLASH_READ = 51; +static const DeviceCommandId_t STOP_IMAGE_LOADER = 55; +static const DeviceCommandId_t CHANGE_IMAGE_DOWNLOAD_FILE = 57; +static const DeviceCommandId_t SET_JSON_FILE_NAME = 58; +static const DeviceCommandId_t SET_FLASH_READ_FILENAME = 59; +static const DeviceCommandId_t REQ_CAMERA = 67; +static const DeviceCommandId_t REQ_LIMITS = 68; +static const DeviceCommandId_t REQ_LOG_LEVEL = 69; +static const DeviceCommandId_t REQ_MOUNTING = 70; +static const DeviceCommandId_t REQ_IMAGE_PROCESSOR = 71; +static const DeviceCommandId_t REQ_CENTROIDING = 72; +static const DeviceCommandId_t REQ_LISA = 73; +static const DeviceCommandId_t REQ_MATCHING = 74; +static const DeviceCommandId_t REQ_TRACKING = 75; +static const DeviceCommandId_t REQ_VALIDATION = 76; +static const DeviceCommandId_t REQ_ALGO = 77; +static const DeviceCommandId_t REQ_SUBSCRIPTION = 78; +static const DeviceCommandId_t REQ_LOG_SUBSCRIPTION = 79; +static const DeviceCommandId_t REQ_DEBUG_CAMERA = 80; +static const DeviceCommandId_t LOGLEVEL = 81; +static const DeviceCommandId_t LOGSUBSCRIPTION = 82; +static const DeviceCommandId_t DEBUG_CAMERA = 83; +static const DeviceCommandId_t FIRMWARE_UPDATE = 84; +static const DeviceCommandId_t DISABLE_TIMESTAMP_GENERATION = 85; +static const DeviceCommandId_t ENABLE_TIMESTAMP_GENERATION = 86; +static const DeviceCommandId_t NONE = 0xFFFFFFFF; + +static const uint32_t VERSION_SET_ID = REQ_VERSION; +static const uint32_t INTERFACE_SET_ID = REQ_INTERFACE; +static const uint32_t POWER_SET_ID = REQ_POWER; +static const uint32_t TEMPERATURE_SET_ID = REQ_TEMPERATURE; +static const uint32_t TIME_SET_ID = REQ_TIME; +static const uint32_t SOLUTION_SET_ID = REQ_SOLUTION; +static const uint32_t HISTOGRAM_SET_ID = REQ_HISTOGRAM; +static const uint32_t CHECKSUM_SET_ID = CHECKSUM; +static const uint32_t CAMERA_SET_ID = REQ_CAMERA; +static const uint32_t LIMITS_SET_ID = REQ_LIMITS; +static const uint32_t LOG_LEVEL_SET_ID = REQ_LOG_LEVEL; +static const uint32_t MOUNTING_SET_ID = REQ_MOUNTING; +static const uint32_t IMAGE_PROCESSOR_SET_ID = REQ_IMAGE_PROCESSOR; +static const uint32_t CENTROIDING_SET_ID = REQ_CENTROIDING; +static const uint32_t LISA_SET_ID = REQ_LISA; +static const uint32_t MATCHING_SET_ID = REQ_MATCHING; +static const uint32_t TRACKING_SET_ID = REQ_TRACKING; +static const uint32_t VALIDATION_SET_ID = REQ_VALIDATION; +static const uint32_t ALGO_SET_ID = REQ_ALGO; +static const uint32_t SUBSCRIPTION_SET_ID = REQ_SUBSCRIPTION; +static const uint32_t LOG_SUBSCRIPTION_SET_ID = REQ_LOG_SUBSCRIPTION; +static const uint32_t DEBUG_CAMERA_SET_ID = REQ_DEBUG_CAMERA; + +/** Max size of unencoded frame */ +static const size_t MAX_FRAME_SIZE = 1200; + +static const uint8_t TEMPERATURE_SET_ENTRIES = 5; +static const uint8_t VERSION_SET_ENTRIES = 5; +static const uint8_t INTERFACE_SET_ENTRIES = 4; +static const uint8_t POWER_SET_ENTRIES = 18; +static const uint8_t TIME_SET_ENTRIES = 4; +static const uint8_t SOLUTION_SET_ENTRIES = 23; +static const uint8_t HISTOGRAM_SET_ENTRIES = 38; +static const uint8_t CHECKSUM_SET_ENTRIES = 1; +static const uint8_t CAMERA_SET_ENTRIES = 24; +static const uint8_t LIMITS_SET_ENTRIES = 11; +static const uint8_t LOG_LEVEL_SET_ENTRIES = 16; +static const uint8_t MOUNTING_SET_ENTRIES = 4; +static const uint8_t IMAGE_PROCESSOR_SET_ENTRIES = 5; +static const uint8_t CENTROIDING_PARAMS_SET_ENTRIES = 13; +static const uint8_t LISA_SET_ENTRIES = 14; +static const uint8_t MATCHING_SET_ENTRIES = 2; +static const uint8_t TRACKING_SET_ENTRIES = 4; +static const uint8_t VALIDATION_SET_ENTRIES = 4; +static const uint8_t ALGO_SET_ENTRIES = 5; +static const uint8_t SUBSCRIPTION_SET_ENTRIES = 16; +static const uint8_t LOG_SUBSCRIPTION_SET_ENTRIES = 4; +static const uint8_t DEBUG_CAMERA_SET_ENTRIES = 2; + +// Action, parameter and telemetry IDs +namespace ID { +static const uint8_t PING = 0; +static const uint8_t BOOT = 1; +static const uint8_t VERSION = 2; +static const uint8_t INTERFACE = 3; +static const uint8_t LIMITS = 5; +static const uint8_t MOUNTING = 6; +static const uint8_t IMAGE_PROCESSOR = 10; +static const uint8_t CAMERA = 9; +static const uint8_t CENTROIDING = 11; +static const uint8_t LISA = 12; +static const uint8_t MATCHING = 13; +static const uint8_t TRACKING = 14; +static const uint8_t VALIDATION = 15; +static const uint8_t ALGO = 16; +static const uint8_t REBOOT = 7; +static const uint8_t UPLOAD_IMAGE = 10; +static const uint8_t POWER = 11; +static const uint8_t SET_TIME = 14; +static const uint8_t SUBSCRIPTION = 18; +static const uint8_t SOLUTION = 24; +static const uint8_t TEMPERATURE = 27; +static const uint8_t HISTOGRAM = 28; +static const uint8_t CONTRAST = 29; +static const uint8_t TIME = 1; +static const uint8_t WRITE = 2; +static const uint8_t READ = 3; +static const uint8_t CHECKSUM = 4; +static const uint8_t TAKE_IMAGE = 15; +static const uint8_t LOG_LEVEL = 3; +static const uint8_t LOG_SUBSCRIPTION = 19; +static const uint8_t DEBUG_CAMERA = 20; +} // namespace ID + +namespace Program { +static const uint8_t BOOTLOADER = 1; +static const uint8_t FIRMWARE = 2; +} // namespace Program + +namespace region_secrets { +static const uint32_t REGION_0_SECRET = 0xd1a220d3; +static const uint32_t REGION_1_SECRET = 0xdc770fa8; +static const uint32_t REGION_2_SECRET = 0xdf9066b0; +static const uint32_t REGION_3_SECRET = 0x5f6a0423; +static const uint32_t REGION_4_SECRET = 0xbbaad5d8; +static const uint32_t REGION_5_SECRET = 0xa81c3678; +static const uint32_t REGION_6_SECRET = 0xe10f76f8; +static const uint32_t REGION_7_SECRET = 0x83220919; +static const uint32_t REGION_8_SECRET = 0xec37289d; +static const uint32_t REGION_9_SECRET = 0x27ac0ef8; +static const uint32_t REGION_10_SECRET = 0xf017e43d; +static const uint32_t REGION_11_SECRET = 0xbc7f7f49; +static const uint32_t REGION_12_SECRET = 0x42fedef6; +static const uint32_t REGION_13_SECRET = 0xe53cf10d; +static const uint32_t REGION_14_SECRET = 0xe862b70b; +static const uint32_t REGION_15_SECRET = 0x79b537ca; +static const uint32_t secret[16]{ + REGION_0_SECRET, REGION_1_SECRET, REGION_2_SECRET, REGION_3_SECRET, + REGION_4_SECRET, REGION_5_SECRET, REGION_6_SECRET, REGION_7_SECRET, + REGION_8_SECRET, REGION_9_SECRET, REGION_10_SECRET, REGION_11_SECRET, + REGION_12_SECRET, REGION_13_SECRET, REGION_14_SECRET, REGION_15_SECRET}; +} // namespace region_secrets + +enum class FlashSections : uint8_t { + BOOTLOADER_SECTION = 0, + MAIN_FIRMWARE_SECTION = 1, + ARC_CONFIG_SECTION = 2 +}; + +// Flash region IDs of firmware partition +enum class FirmwareRegions : uint32_t { FIRST = 1, LAST = 8 }; + +static const uint32_t FLASH_REGION_SIZE = 0x20000; + +/** + * @brief This dataset can be used to store the temperature of a reaction wheel. + */ +class TemperatureSet : public StaticLocalDataSet { + public: + static const size_t SIZE = 24; + + TemperatureSet(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, TEMPERATURE_SET_ID) {} + + TemperatureSet(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, TEMPERATURE_SET_ID)) {} + + // Ticks is time reference generated by internal counter of the star tracker + lp_var_t ticks = lp_var_t(sid.objectId, PoolIds::TICKS_TEMPERATURE_SET, this); + /** Unix time in microseconds */ + lp_var_t time = lp_var_t(sid.objectId, PoolIds::TIME_TEMPERATURE_SET, this); + lp_var_t mcuTemperature = lp_var_t(sid.objectId, PoolIds::MCU_TEMPERATURE, this); + lp_var_t cmosTemperature = lp_var_t(sid.objectId, PoolIds::CMOS_TEMPERATURE, this); + lp_var_t fpgaTemperature = lp_var_t(sid.objectId, PoolIds::FPGA_TEMPERATURE, this); + + void printSet() { + sif::info << "TemperatureSet::printSet: Ticks: " << this->ticks << std::endl; + sif::info << "TemperatureSet::printSet: Time: " << this->time << " us" << std::endl; + sif::info << "TemperatureSet::printSet: MCU Temperature: " << this->mcuTemperature << " °C" + << std::endl; + sif::info << "TemperatureSet::printSet: CMOS Temperature (raw): " << this->cmosTemperature + << std::endl; + sif::info << "TemperatureSet::printSet: FPGA Temperature (random value): " + << this->fpgaTemperature << " °C" << std::endl; + } +}; + +/** + * @brief Package to store version parameters + */ +class VersionSet : public StaticLocalDataSet { + public: + static const size_t SIZE = 15; + + VersionSet(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, VERSION_SET_ID) {} + + VersionSet(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, VERSION_SET_ID)) {} + + lp_var_t ticks = lp_var_t(sid.objectId, PoolIds::TICKS_VERSION_SET, this); + /** Unix time in microseconds */ + lp_var_t time = lp_var_t(sid.objectId, PoolIds::TIME_VERSION_SET, this); + lp_var_t program = lp_var_t(sid.objectId, PoolIds::PROGRAM, this); + lp_var_t major = lp_var_t(sid.objectId, PoolIds::MAJOR, this); + lp_var_t minor = lp_var_t(sid.objectId, PoolIds::MINOR, this); + + void printSet() { + PoolReadGuard rg(this); + sif::info << "VersionSet::printSet: Ticks: " << std::dec << this->ticks << std::endl; + sif::info << "VersionSet::printSet: Unix Time: " << this->time << " us" << std::endl; + sif::info << "VersionSet::printSet: Program: " << static_cast(this->program.value) + << std::endl; + sif::info << "VersionSet::printSet: Major: " << static_cast(this->major.value) + << std::endl; + sif::info << "VersionSet::printSet: Minor: " << static_cast(this->minor.value) + << std::endl; + } +}; + +/** + * @brief Dataset to store the interface telemtry data. + */ +class InterfaceSet : public StaticLocalDataSet { + public: + static const size_t SIZE = 20; + + InterfaceSet(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, REQ_INTERFACE) {} + + InterfaceSet(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, REQ_INTERFACE)) {} + + // Ticks is time reference generated by interanl counter of the star tracker + lp_var_t ticks = lp_var_t(sid.objectId, PoolIds::TICKS_INTERFACE_SET, this); + /** Unix time in microseconds */ + lp_var_t time = lp_var_t(sid.objectId, PoolIds::TIME_INTERFACE_SET, this); + lp_var_t frameCount = lp_var_t(sid.objectId, PoolIds::FRAME_COUNT, this); + lp_var_t checksumerrorCount = + lp_var_t(sid.objectId, PoolIds::CHECKSUM_ERROR_COUNT, this); + + void printSet() { + PoolReadGuard rg(this); + sif::info << "InterfaceSet::printSet: Ticks: " << this->ticks << std::endl; + sif::info << "InterfaceSet::printSet: Time: " << this->time << " us" << std::endl; + sif::info << "InterfaceSet::printSet: Frame Count: " << this->frameCount << std::endl; + sif::info << "InterfaceSet::printSet: Checksum Error Count: " << this->checksumerrorCount + << std::endl; + } +}; + +/** + * @brief Dataset to store the data of the power telemetry reply. + */ +class PowerSet : public StaticLocalDataSet { + public: + static const size_t SIZE = 76; + + PowerSet(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, REQ_INTERFACE) {} + + PowerSet(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, REQ_INTERFACE)) {} + + // Ticks is time reference generated by interanl counter of the star tracker + lp_var_t ticks = lp_var_t(sid.objectId, PoolIds::TICKS_POWER_SET, this); + /** Unix time in microseconds */ + lp_var_t time = lp_var_t(sid.objectId, PoolIds::TIME_POWER_SET, this); + lp_var_t mcuCurrent = lp_var_t(sid.objectId, PoolIds::MCU_CURRENT, this); + lp_var_t mcuVoltage = lp_var_t(sid.objectId, PoolIds::MCU_VOLTAGE, this); + lp_var_t fpgaCoreCurrent = lp_var_t(sid.objectId, PoolIds::FPGA_CORE_CURRENT, this); + lp_var_t fpgaCoreVoltage = lp_var_t(sid.objectId, PoolIds::FPGA_CORE_VOLTAGE, this); + lp_var_t fpga18Current = lp_var_t(sid.objectId, PoolIds::FPGA_18_CURRENT, this); + lp_var_t fpga18Voltage = lp_var_t(sid.objectId, PoolIds::FPGA_18_VOLTAGE, this); + lp_var_t fpga25Current = lp_var_t(sid.objectId, PoolIds::FPGA_25_CURRENT, this); + lp_var_t fpga25Voltage = lp_var_t(sid.objectId, PoolIds::FPGA_25_VOLTAGE, this); + lp_var_t cmv21Current = lp_var_t(sid.objectId, PoolIds::CMV_21_CURRENT, this); + lp_var_t cmv21Voltage = lp_var_t(sid.objectId, PoolIds::CMV_21_VOLTAGE, this); + lp_var_t cmvPixCurrent = lp_var_t(sid.objectId, PoolIds::CMV_PIX_CURRENT, this); + lp_var_t cmvPixVoltage = lp_var_t(sid.objectId, PoolIds::CMV_PIX_VOLTAGE, this); + lp_var_t cmv33Current = lp_var_t(sid.objectId, PoolIds::CMV_33_CURRENT, this); + lp_var_t cmv33Voltage = lp_var_t(sid.objectId, PoolIds::CMV_33_VOLTAGE, this); + lp_var_t cmvResCurrent = lp_var_t(sid.objectId, PoolIds::CMV_RES_CURRENT, this); + lp_var_t cmvResVoltage = lp_var_t(sid.objectId, PoolIds::CMV_RES_VOLTAGE, this); + + void printSet() { + PoolReadGuard rg(this); + sif::info << "PowerSet::printSet: Ticks: " << this->ticks << std::endl; + sif::info << "PowerSet::printSet: Time: " << this->time << " us" << std::endl; + sif::info << "PowerSet::printSet: MCU Current: " << this->mcuCurrent << " A" << std::endl; + sif::info << "PowerSet::printSet: MCU Voltage: " << this->mcuVoltage << " V" << std::endl; + sif::info << "PowerSet::printSet: FPGA Core current: " << this->fpgaCoreCurrent << " A" + << std::endl; + sif::info << "PowerSet::printSet: FPGA Core voltage: " << this->fpgaCoreVoltage << " V" + << std::endl; + sif::info << "PowerSet::printSet: FPGA 18 current: " << this->fpga18Current << " A" + << std::endl; + sif::info << "PowerSet::printSet: FPGA 18 voltage: " << this->fpga18Voltage << " V" + << std::endl; + sif::info << "PowerSet::printSet: FPGA 25 current: " << this->fpga25Current << " A" + << std::endl; + sif::info << "PowerSet::printSet: FPGA 25 voltage: " << this->fpga25Voltage << " V" + << std::endl; + sif::info << "PowerSet::printSet: CMV 21 current: " << this->cmv21Current << " A" << std::endl; + sif::info << "PowerSet::printSet: CMV 21 voltage: " << this->cmv21Voltage << " V" << std::endl; + sif::info << "PowerSet::printSet: CMV Pix current: " << this->cmvPixCurrent << " A" + << std::endl; + sif::info << "PowerSet::printSet: CMV Pix voltage: " << this->cmvPixVoltage << " V" + << std::endl; + sif::info << "PowerSet::printSet: CMV 33 current: " << this->cmv33Current << " A" << std::endl; + sif::info << "PowerSet::printSet: CMV 33 voltage: " << this->cmv33Voltage << " V" << std::endl; + sif::info << "PowerSet::printSet: CMV Res current: " << this->cmvResCurrent << " A" + << std::endl; + sif::info << "PowerSet::printSet: CMV Res voltage: " << this->cmvResVoltage << " V" + << std::endl; + } +}; + +/** + * @brief Data set to store the time telemetry packet. + */ +class TimeSet : public StaticLocalDataSet { + public: + static const size_t SIZE = 24; + + TimeSet(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, TIME_SET_ID) {} + + TimeSet(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, TIME_SET_ID)) {} + + lp_var_t ticks = lp_var_t(sid.objectId, PoolIds::TICKS_TIME_SET, this); + /** Unix time in microseconds */ + lp_var_t time = lp_var_t(sid.objectId, PoolIds::TIME_TIME_SET, this); + // Number of milliseconds since processor start-up + lp_var_t runTime = lp_var_t(sid.objectId, PoolIds::RUN_TIME, this); + // Unix time in seconds?? --> maybe typo in datasheet. Seems to be microseconds + lp_var_t unixTime = lp_var_t(sid.objectId, PoolIds::UNIX_TIME, this); + void printSet() { + PoolReadGuard rg(this); + sif::info << "TimeSet::printSet: Ticks: " << this->ticks << std::endl; + sif::info << "TimeSet::printSet: Time (time stamp): " << this->time << " us" << std::endl; + sif::info << "TimeSet::printSet: Run Time: " << this->runTime << " ms" << std::endl; + sif::info << "TimeSet::printSet: Unix Time: " << this->unixTime << " s" << std::endl; + } +}; + +/** + * @brief The solution dataset is the main dataset of the star tracker and contains the + * attitude information. + */ +class SolutionSet : public StaticLocalDataSet { + public: + static const size_t SIZE = 78; + + SolutionSet(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, SOLUTION_SET_ID) {} + + SolutionSet(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, SOLUTION_SET_ID)) {} + + // Ticks timestamp + lp_var_t ticks = lp_var_t(sid.objectId, PoolIds::TICKS_SOLUTION_SET, this); + /// Unix time stamp + lp_var_t time = lp_var_t(sid.objectId, PoolIds::TIME_SOLUTION_SET, this); + // Calibrated quaternion (takes into account the mounting quaternion), typically same as + // track q values + lp_var_t caliQw = lp_var_t(sid.objectId, PoolIds::CALI_QW, this); + lp_var_t caliQx = lp_var_t(sid.objectId, PoolIds::CALI_QX, this); + lp_var_t caliQy = lp_var_t(sid.objectId, PoolIds::CALI_QY, this); + lp_var_t caliQz = lp_var_t(sid.objectId, PoolIds::CALI_QZ, this); + // The lower this value the more confidence that the star tracker solution is correct + lp_var_t trackConfidence = lp_var_t(sid.objectId, PoolIds::TRACK_CONFIDENCE, this); + // Estimated attitude of spacecraft + lp_var_t trackQw = lp_var_t(sid.objectId, PoolIds::TRACK_QW, this); + lp_var_t trackQx = lp_var_t(sid.objectId, PoolIds::TRACK_QX, this); + lp_var_t trackQy = lp_var_t(sid.objectId, PoolIds::TRACK_QY, this); + lp_var_t trackQz = lp_var_t(sid.objectId, PoolIds::TRACK_QZ, this); + // Number of stars removed from tracking solution + lp_var_t trackRemoved = lp_var_t(sid.objectId, PoolIds::TRACK_REMOVED, this); + // Number of stars for which a valid centroid was found + lp_var_t starsCentroided = + lp_var_t(sid.objectId, PoolIds::STARS_CENTROIDED, this); + // Number of stars that matched to a database star + lp_var_t starsMatchedDatabase = + lp_var_t(sid.objectId, PoolIds::STARS_MATCHED_DATABASE, this); + // Result of LISA (lost in space algorithm), searches for stars without prior knowledge of + // attitude + lp_var_t lisaQw = lp_var_t(sid.objectId, PoolIds::LISA_QW, this); + lp_var_t lisaQx = lp_var_t(sid.objectId, PoolIds::LISA_QX, this); + lp_var_t lisaQy = lp_var_t(sid.objectId, PoolIds::LISA_QY, this); + lp_var_t lisaQz = lp_var_t(sid.objectId, PoolIds::LISA_QZ, this); + // Percentage of close stars in LISA solution + lp_var_t lisaPercentageClose = + lp_var_t(sid.objectId, PoolIds::LISA_PERC_CLOSE, this); + // Number of close stars in LISA solution + lp_var_t lisaNrClose = lp_var_t(sid.objectId, PoolIds::LISA_NR_CLOSE, this); + // Gives a combined overview of the validation parameters (1 for valid solution, otherwise 0) + lp_var_t isTrustWorthy = lp_var_t(sid.objectId, PoolIds::TRUST_WORTHY, this); + // Number of times the validation criteria was met + lp_var_t stableCount = lp_var_t(sid.objectId, PoolIds::STABLE_COUNT, this); + // Shows the autonomous mode used to obtain the star tracker attitude + lp_var_t solutionStrategy = + lp_var_t(sid.objectId, PoolIds::SOLUTION_STRATEGY, this); + + void printSet() { + PoolReadGuard rg(this); + sif::info << "SolutionSet::printSet: Ticks: " << this->ticks << std::endl; + sif::info << "SolutionSet::printSet: Time: " << this->time << std::endl; + sif::info << "SolutionSet::printSet: Calibrated quaternion Qw: " << this->caliQw << std::endl; + sif::info << "SolutionSet::printSet: Calibrated quaternion Qx: " << this->caliQx << std::endl; + sif::info << "SolutionSet::printSet: Calibrated quaternion Qy: " << this->caliQy << std::endl; + sif::info << "SolutionSet::printSet: Calibrated quaternion Qz: " << this->caliQz << std::endl; + sif::info << "SolutionSet::printSet: Track confidence: " << this->trackConfidence << std::endl; + sif::info << "SolutionSet::printSet: Track Qw: " << this->trackQw << std::endl; + sif::info << "SolutionSet::printSet: Track Qx: " << this->trackQx << std::endl; + sif::info << "SolutionSet::printSet: Track Qy: " << this->trackQy << std::endl; + sif::info << "SolutionSet::printSet: Track Qz: " << this->trackQz << std::endl; + sif::info << "SolutionSet::printSet: Track removed: " + << static_cast(this->trackRemoved.value) << std::endl; + sif::info << "SolutionSet::printSet: Number of stars centroided: " + << static_cast(this->starsCentroided.value) << std::endl; + sif::info << "SolutionSet::printSet: Number of stars matched database: " + << static_cast(this->starsMatchedDatabase.value) << std::endl; + sif::info << "SolutionSet::printSet: LISA Qw: " << this->lisaQw << std::endl; + sif::info << "SolutionSet::printSet: LISA Qx: " << this->lisaQx << std::endl; + sif::info << "SolutionSet::printSet: LISA Qy: " << this->lisaQy << std::endl; + sif::info << "SolutionSet::printSet: LISA Qz: " << this->lisaQz << std::endl; + sif::info << "SolutionSet::printSet: LISA Percentage close: " << this->lisaPercentageClose + << std::endl; + sif::info << "SolutionSet::printSet: LISA number of close stars: " + << static_cast(this->lisaNrClose.value) << std::endl; + sif::info << "SolutionSet::printSet: Is trust worthy: " + << static_cast(this->isTrustWorthy.value) << std::endl; + sif::info << "SolutionSet::printSet: Stable count: " << this->stableCount << std::endl; + sif::info << "SolutionSet::printSet: Solution strategy: " + << static_cast(this->solutionStrategy.value) << std::endl; + } +}; + +/** + * @brief Dataset to store the histogram + */ +class HistogramSet : public StaticLocalDataSet { + public: + // Size of dataset + static const size_t SIZE = 156; + + HistogramSet(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, HISTOGRAM_SET_ID) {} + + HistogramSet(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, HISTOGRAM_SET_ID)) {} + + lp_var_t ticks = lp_var_t(sid.objectId, PoolIds::TICKS_HISTOGRAM_SET, this); + lp_var_t time = lp_var_t(sid.objectId, PoolIds::TIME_HISTOGRAM_SET, this); + lp_var_t binA0 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BINA0, this); + lp_var_t binA1 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BINA1, this); + lp_var_t binA2 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BINA2, this); + lp_var_t binA3 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BINA3, this); + lp_var_t binA4 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BINA4, this); + lp_var_t binA5 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BINA5, this); + lp_var_t binA6 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BINA6, this); + lp_var_t binA7 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BINA7, this); + lp_var_t binA8 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BINA8, this); + lp_var_t binB0 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BINB0, this); + lp_var_t binB1 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BINB1, this); + lp_var_t binB2 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BINB2, this); + lp_var_t binB3 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BINB3, this); + lp_var_t binB4 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BINB4, this); + lp_var_t binB5 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BINB5, this); + lp_var_t binB6 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BINB6, this); + lp_var_t binB7 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BINB7, this); + lp_var_t binB8 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BINB8, this); + lp_var_t binC0 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BINC0, this); + lp_var_t binC1 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BINC1, this); + lp_var_t binC2 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BINC2, this); + lp_var_t binC3 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BINC3, this); + lp_var_t binC4 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BINC4, this); + lp_var_t binC5 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BINC5, this); + lp_var_t binC6 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BINC6, this); + lp_var_t binC7 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BINC7, this); + lp_var_t binC8 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BINC8, this); + lp_var_t binD0 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BIND0, this); + lp_var_t binD1 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BIND1, this); + lp_var_t binD2 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BIND2, this); + lp_var_t binD3 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BIND3, this); + lp_var_t binD4 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BIND4, this); + lp_var_t binD5 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BIND5, this); + lp_var_t binD6 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BIND6, this); + lp_var_t binD7 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BIND7, this); + lp_var_t binD8 = lp_var_t(sid.objectId, PoolIds::HISTOGRAM_BIND8, this); + + void printSet() { + PoolReadGuard rg(this); + sif::info << "HistogramSet::printSet: Ticks: " << this->ticks << std::endl; + sif::info << "HistogramSet::printSet: Time (time stamp): " << this->time << " us" << std::endl; + sif::info << "HistogramSet::printSet: BinA0: " << this->binA0 << std::endl; + sif::info << "HistogramSet::printSet: BinA1: " << this->binA1 << std::endl; + sif::info << "HistogramSet::printSet: BinA2: " << this->binA2 << std::endl; + sif::info << "HistogramSet::printSet: BinA3: " << this->binA3 << std::endl; + sif::info << "HistogramSet::printSet: BinA4: " << this->binA4 << std::endl; + sif::info << "HistogramSet::printSet: BinA5: " << this->binA5 << std::endl; + sif::info << "HistogramSet::printSet: BinA6: " << this->binA6 << std::endl; + sif::info << "HistogramSet::printSet: BinA7: " << this->binA7 << std::endl; + sif::info << "HistogramSet::printSet: BinA8: " << this->binA8 << std::endl; + sif::info << "HistogramSet::printSet: BinB0: " << this->binB0 << std::endl; + sif::info << "HistogramSet::printSet: BinB1: " << this->binB1 << std::endl; + sif::info << "HistogramSet::printSet: BinB2: " << this->binB2 << std::endl; + sif::info << "HistogramSet::printSet: BinB3: " << this->binB3 << std::endl; + sif::info << "HistogramSet::printSet: BinB4: " << this->binB4 << std::endl; + sif::info << "HistogramSet::printSet: BinB5: " << this->binB5 << std::endl; + sif::info << "HistogramSet::printSet: BinB6: " << this->binB6 << std::endl; + sif::info << "HistogramSet::printSet: BinB7: " << this->binB7 << std::endl; + sif::info << "HistogramSet::printSet: BinB8: " << this->binB8 << std::endl; + sif::info << "HistogramSet::printSet: BinC0: " << this->binC0 << std::endl; + sif::info << "HistogramSet::printSet: BinC1: " << this->binC1 << std::endl; + sif::info << "HistogramSet::printSet: BinC2: " << this->binC2 << std::endl; + sif::info << "HistogramSet::printSet: BinC3: " << this->binC3 << std::endl; + sif::info << "HistogramSet::printSet: BinC4: " << this->binC4 << std::endl; + sif::info << "HistogramSet::printSet: BinC5: " << this->binC5 << std::endl; + sif::info << "HistogramSet::printSet: BinC6: " << this->binC6 << std::endl; + sif::info << "HistogramSet::printSet: BinC7: " << this->binC7 << std::endl; + sif::info << "HistogramSet::printSet: BinC8: " << this->binC8 << std::endl; + sif::info << "HistogramSet::printSet: BinD0: " << this->binD0 << std::endl; + sif::info << "HistogramSet::printSet: BinD1: " << this->binD1 << std::endl; + sif::info << "HistogramSet::printSet: BinD2: " << this->binD2 << std::endl; + sif::info << "HistogramSet::printSet: BinD3: " << this->binD3 << std::endl; + sif::info << "HistogramSet::printSet: BinD4: " << this->binD4 << std::endl; + sif::info << "HistogramSet::printSet: BinD5: " << this->binD5 << std::endl; + sif::info << "HistogramSet::printSet: BinD6: " << this->binD6 << std::endl; + sif::info << "HistogramSet::printSet: BinD7: " << this->binD7 << std::endl; + sif::info << "HistogramSet::printSet: BinD8: " << this->binD8 << std::endl; + } +}; + +/** + * @brief Helper Class to extract information from bytestream. + */ +class ChecksumReply { + public: + /** + * @brief Constructor + * + * @param datafield Pointer to datafield in reply buffer + * + */ + ChecksumReply(const uint8_t* datafield) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + region = *(datafield); + const uint8_t* addressData = datafield + ADDRESS_OFFSET; + size_t size = sizeof(address); + result = SerializeAdapter::deSerialize(&address, &addressData, &size, + SerializeIF::Endianness::LITTLE); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::debug << "ChecksumReply::ChecksumReply: Failed to deserialize address" << std::endl; + } + const uint8_t* lengthData = datafield + LENGTH_OFFSET; + size = sizeof(length); + result = + SerializeAdapter::deSerialize(&length, &lengthData, &size, SerializeIF::Endianness::LITTLE); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::debug << "ChecksumReply::ChecksumReply: Failed to deserialize length" << std::endl; + } + const uint8_t* checksumData = datafield + CHECKSUM_OFFSET; + size = sizeof(checksum); + result = SerializeAdapter::deSerialize(&checksum, &checksumData, &size, + SerializeIF::Endianness::LITTLE); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::debug << "ChecksumReply::ChecksumReply: Failed to deserialize checksum" << std::endl; + } + } + + uint8_t getRegion() { return region; } + + uint32_t getAddress() { return address; } + + uint32_t getLength() { return length; } + + uint32_t getChecksum() { return checksum; } + + void printChecksum() { + sif::info << "ChecksumReply::printChecksum: 0x" << std::hex << checksum << std::endl; + } + + private: + static const uint8_t ADDRESS_OFFSET = 1; + static const uint8_t LENGTH_OFFSET = 5; + static const uint8_t CHECKSUM_OFFSET = 9; + + uint8_t region = 0; + uint32_t address = 0; + uint32_t length = 0; + uint32_t checksum = 0; +}; + +class ChecksumSet : public StaticLocalDataSet { + public: + // Size of dataset + static const size_t SIZE = 156; + + ChecksumSet(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, CHECKSUM_SET_ID) {} + + ChecksumSet(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, CHECKSUM_SET_ID)) {} + + lp_var_t checksum = lp_var_t(sid.objectId, PoolIds::CHKSUM, this); +}; + +/** + * @brief Will store the camera parameters set in the star tracker which are retrieved with + * a get parameter request. + */ +class CameraSet : public StaticLocalDataSet { + public: + // Size of dataset + static const size_t SIZE = 34; + + CameraSet(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, CAMERA_SET_ID) {} + + CameraSet(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, CAMERA_SET_ID)) {} + + lp_var_t mode = lp_var_t(sid.objectId, PoolIds::CAMERA_MODE, this); + lp_var_t focallength = lp_var_t(sid.objectId, PoolIds::FOCALLENGTH, this); + lp_var_t exposure = lp_var_t(sid.objectId, PoolIds::EXPOSURE, this); + lp_var_t interval = lp_var_t(sid.objectId, PoolIds::INTERVAL, this); + lp_var_t offset = lp_var_t(sid.objectId, PoolIds::CAMERA_OFFSET, this); + lp_var_t pgagain = lp_var_t(sid.objectId, PoolIds::PGAGAIN, this); + lp_var_t adcgain = lp_var_t(sid.objectId, PoolIds::ADCGAIN, this); + lp_var_t reg1 = lp_var_t(sid.objectId, PoolIds::CAM_REG1, this); + lp_var_t val1 = lp_var_t(sid.objectId, PoolIds::CAM_VAL1, this); + lp_var_t reg2 = lp_var_t(sid.objectId, PoolIds::CAM_REG2, this); + lp_var_t val2 = lp_var_t(sid.objectId, PoolIds::CAM_VAL2, this); + lp_var_t reg3 = lp_var_t(sid.objectId, PoolIds::CAM_REG3, this); + lp_var_t val3 = lp_var_t(sid.objectId, PoolIds::CAM_VAL3, this); + lp_var_t reg4 = lp_var_t(sid.objectId, PoolIds::CAM_REG4, this); + lp_var_t val4 = lp_var_t(sid.objectId, PoolIds::CAM_VAL4, this); + lp_var_t reg5 = lp_var_t(sid.objectId, PoolIds::CAM_REG5, this); + lp_var_t val5 = lp_var_t(sid.objectId, PoolIds::CAM_VAL5, this); + lp_var_t reg6 = lp_var_t(sid.objectId, PoolIds::CAM_REG6, this); + lp_var_t val6 = lp_var_t(sid.objectId, PoolIds::CAM_VAL6, this); + lp_var_t reg7 = lp_var_t(sid.objectId, PoolIds::CAM_REG7, this); + lp_var_t val7 = lp_var_t(sid.objectId, PoolIds::CAM_VAL7, this); + lp_var_t reg8 = lp_var_t(sid.objectId, PoolIds::CAM_REG8, this); + lp_var_t val8 = lp_var_t(sid.objectId, PoolIds::CAM_VAL8, this); + lp_var_t freq1 = lp_var_t(sid.objectId, PoolIds::CAM_FREQ_1, this); + + void printSet() { + PoolReadGuard rg(this); + sif::info << "CameraSet::printSet: mode: " << static_cast(this->mode.value) + << std::endl; + sif::info << "CameraSet::printSet: focallength: " << this->focallength << std::endl; + sif::info << "CameraSet::printSet: exposure: " << this->exposure << std::endl; + sif::info << "CameraSet::printSet: interval: " << this->interval << std::endl; + sif::info << "CameraSet::printSet: offset: " << this->offset << std::endl; + sif::info << "CameraSet::printSet: PGA gain: " << static_cast(this->pgagain.value) + << std::endl; + sif::info << "CameraSet::printSet: ADC gain: " << static_cast(this->adcgain.value) + << std::endl; + sif::info << "CameraSet::printSet: Reg 1: " << static_cast(this->reg1.value) + << std::endl; + sif::info << "CameraSet::printSet: Val 1: " << static_cast(this->val1.value) + << std::endl; + sif::info << "CameraSet::printSet: Reg 2: " << static_cast(this->reg2.value) + << std::endl; + sif::info << "CameraSet::printSet: Val 2: " << static_cast(this->val2.value) + << std::endl; + sif::info << "CameraSet::printSet: Reg 3: " << static_cast(this->reg3.value) + << std::endl; + sif::info << "CameraSet::printSet: Val 3: " << static_cast(this->val3.value) + << std::endl; + sif::info << "CameraSet::printSet: Reg 4: " << static_cast(this->reg4.value) + << std::endl; + sif::info << "CameraSet::printSet: Val 4: " << static_cast(this->val4.value) + << std::endl; + sif::info << "CameraSet::printSet: Reg 5: " << static_cast(this->reg5.value) + << std::endl; + sif::info << "CameraSet::printSet: Val 5: " << static_cast(this->val5.value) + << std::endl; + sif::info << "CameraSet::printSet: Reg 6: " << static_cast(this->reg6.value) + << std::endl; + sif::info << "CameraSet::printSet: Val 6: " << static_cast(this->val6.value) + << std::endl; + sif::info << "CameraSet::printSet: Reg 7: " << static_cast(this->reg7.value) + << std::endl; + sif::info << "CameraSet::printSet: Val 7: " << static_cast(this->val7.value) + << std::endl; + sif::info << "CameraSet::printSet: Reg 8: " << static_cast(this->reg8.value) + << std::endl; + sif::info << "CameraSet::printSet: Val 8: " << static_cast(this->val8.value) + << std::endl; + sif::info << "CameraSet::printSet: Freq 1: " << static_cast(this->freq1.value) + << std::endl; + } +}; + +/** + * @brief Will store the requested limits + */ +class LimitsSet : public StaticLocalDataSet { + public: + // Size of dataset + static const size_t SIZE = 41; + + LimitsSet(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, LIMITS_SET_ID) {} + + LimitsSet(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, LIMITS_SET_ID)) {} + + lp_var_t action = lp_var_t(sid.objectId, PoolIds::LIMITS_ACTION, this); + lp_var_t fpga18current = + lp_var_t(sid.objectId, PoolIds::LIMITS_FPGA18CURRENT, this); + lp_var_t fpga25current = + lp_var_t(sid.objectId, PoolIds::LIMITS_FPGA25CURRENT, this); + lp_var_t fpga10current = + lp_var_t(sid.objectId, PoolIds::LIMITS_FPGA10CURRENT, this); + lp_var_t mcuCurrent = lp_var_t(sid.objectId, PoolIds::LIMITS_MCUCURRENT, this); + lp_var_t cmos21current = + lp_var_t(sid.objectId, PoolIds::LIMITS_CMOS21CURRENT, this); + lp_var_t cmosPixCurrent = + lp_var_t(sid.objectId, PoolIds::LIMITS_CMOSPIXCURRENT, this); + lp_var_t cmos33current = + lp_var_t(sid.objectId, PoolIds::LIMITS_CMOS33CURRENT, this); + lp_var_t cmosVresCurrent = + lp_var_t(sid.objectId, PoolIds::LIMITS_CMOSVRESCURRENT, this); + lp_var_t cmosTemperature = + lp_var_t(sid.objectId, PoolIds::LIMITS_CMOSTEMPERATURE, this); + + void printSet() { + PoolReadGuard rg(this); + sif::info << "LimitsSet::printSet: action: " << static_cast(this->action.value) + << std::endl; + sif::info << "LimitsSet::printSet: FPGA18Current: " << this->fpga18current << std::endl; + sif::info << "LimitsSet::printSet: FPGA25Current: " << this->fpga25current << std::endl; + sif::info << "LimitsSet::printSet: FPGA10Current: " << this->fpga10current << std::endl; + sif::info << "LimitsSet::printSet: MCUCurrent: " << this->mcuCurrent << std::endl; + sif::info << "LimitsSet::printSet: CMOS21Current: " << this->cmos21current << std::endl; + sif::info << "LimitsSet::printSet: CMOSPixCurrent: " << this->cmosPixCurrent << std::endl; + sif::info << "LimitsSet::printSet: CMOS33Current: " << this->cmos33current << std::endl; + sif::info << "LimitsSet::printSet: CMOSVResCurrent: " << this->cmosVresCurrent << std::endl; + sif::info << "LimitsSet::printSet: CMOSTemperature: " << this->cmosTemperature << std::endl; + } +}; + +/** + * @brief Will store the requested log level parameters + */ +class LogLevelSet : public StaticLocalDataSet { + public: + // Size of dataset + static const size_t SIZE = 16; + + LogLevelSet(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, LOG_LEVEL_SET_ID) {} + + LogLevelSet(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, LOG_LEVEL_SET_ID)) {} + + lp_var_t loglevel1 = lp_var_t(sid.objectId, PoolIds::LOGLEVEL1, this); + lp_var_t loglevel2 = lp_var_t(sid.objectId, PoolIds::LOGLEVEL2, this); + lp_var_t loglevel3 = lp_var_t(sid.objectId, PoolIds::LOGLEVEL3, this); + lp_var_t loglevel4 = lp_var_t(sid.objectId, PoolIds::LOGLEVEL4, this); + lp_var_t loglevel5 = lp_var_t(sid.objectId, PoolIds::LOGLEVEL5, this); + lp_var_t loglevel6 = lp_var_t(sid.objectId, PoolIds::LOGLEVEL6, this); + lp_var_t loglevel7 = lp_var_t(sid.objectId, PoolIds::LOGLEVEL7, this); + lp_var_t loglevel8 = lp_var_t(sid.objectId, PoolIds::LOGLEVEL8, this); + lp_var_t loglevel9 = lp_var_t(sid.objectId, PoolIds::LOGLEVEL9, this); + lp_var_t loglevel10 = lp_var_t(sid.objectId, PoolIds::LOGLEVEL10, this); + lp_var_t loglevel11 = lp_var_t(sid.objectId, PoolIds::LOGLEVEL11, this); + lp_var_t loglevel12 = lp_var_t(sid.objectId, PoolIds::LOGLEVEL12, this); + lp_var_t loglevel13 = lp_var_t(sid.objectId, PoolIds::LOGLEVEL13, this); + lp_var_t loglevel14 = lp_var_t(sid.objectId, PoolIds::LOGLEVEL14, this); + lp_var_t loglevel15 = lp_var_t(sid.objectId, PoolIds::LOGLEVEL15, this); + lp_var_t loglevel16 = lp_var_t(sid.objectId, PoolIds::LOGLEVEL16, this); + + void printSet() { + PoolReadGuard rg(this); + sif::info << "LogLevelSet::printSet: loglevel1: " + << static_cast(this->loglevel1.value) << std::endl; + sif::info << "LogLevelSet::printSet: loglevel2: " + << static_cast(this->loglevel2.value) << std::endl; + sif::info << "LogLevelSet::printSet: loglevel3: " + << static_cast(this->loglevel3.value) << std::endl; + sif::info << "LogLevelSet::printSet: loglevel4: " + << static_cast(this->loglevel4.value) << std::endl; + sif::info << "LogLevelSet::printSet: loglevel5: " + << static_cast(this->loglevel5.value) << std::endl; + sif::info << "LogLevelSet::printSet: loglevel6: " + << static_cast(this->loglevel1.value) << std::endl; + sif::info << "LogLevelSet::printSet: loglevel7: " + << static_cast(this->loglevel1.value) << std::endl; + sif::info << "LogLevelSet::printSet: loglevel8: " + << static_cast(this->loglevel1.value) << std::endl; + sif::info << "LogLevelSet::printSet: loglevel9: " + << static_cast(this->loglevel1.value) << std::endl; + sif::info << "LogLevelSet::printSet: loglevel10: " + << static_cast(this->loglevel1.value) << std::endl; + sif::info << "LogLevelSet::printSet: loglevel11: " + << static_cast(this->loglevel1.value) << std::endl; + sif::info << "LogLevelSet::printSet: loglevel12: " + << static_cast(this->loglevel1.value) << std::endl; + sif::info << "LogLevelSet::printSet: loglevel13: " + << static_cast(this->loglevel1.value) << std::endl; + sif::info << "LogLevelSet::printSet: loglevel14: " + << static_cast(this->loglevel1.value) << std::endl; + sif::info << "LogLevelSet::printSet: loglevel15: " + << static_cast(this->loglevel1.value) << std::endl; + sif::info << "LogLevelSet::printSet: loglevel16: " + << static_cast(this->loglevel1.value) << std::endl; + } +}; + +/** + * @brief Will store the requested mounting parameters + */ +class MountingSet : public StaticLocalDataSet { + public: + // Size of dataset + static const size_t SIZE = 16; + + MountingSet(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, MOUNTING_SET_ID) {} + + MountingSet(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, MOUNTING_SET_ID)) {} + + lp_var_t qw = lp_var_t(sid.objectId, PoolIds::MOUNTING_QW, this); + lp_var_t qx = lp_var_t(sid.objectId, PoolIds::MOUNTING_QX, this); + lp_var_t qy = lp_var_t(sid.objectId, PoolIds::MOUNTING_QY, this); + lp_var_t qz = lp_var_t(sid.objectId, PoolIds::MOUNTING_QZ, this); + + void printSet() { + sif::info << "MountingSet::printSet: qw: " << this->qw << std::endl; + sif::info << "MountingSet::printSet: qx: " << this->qx << std::endl; + sif::info << "MountingSet::printSet: qy: " << this->qy << std::endl; + sif::info << "MountingSet::printSet: qz: " << this->qz << std::endl; + } +}; + +/** + * @brief Will store the requested image processor parameters + */ +class ImageProcessorSet : public StaticLocalDataSet { + public: + // Size of dataset + static const size_t SIZE = 7; + + ImageProcessorSet(HasLocalDataPoolIF* owner) + : StaticLocalDataSet(owner, IMAGE_PROCESSOR_SET_ID) {} + + ImageProcessorSet(object_id_t objectId) + : StaticLocalDataSet(sid_t(objectId, IMAGE_PROCESSOR_SET_ID)) {} + + lp_var_t mode = lp_var_t(sid.objectId, PoolIds::IMAGE_PROCESSOR_MODE, this); + lp_var_t store = lp_var_t(sid.objectId, PoolIds::IMAGE_PROCESSOR_STORE, this); + lp_var_t signalThreshold = + lp_var_t(sid.objectId, PoolIds::IMAGE_PROCESSOR_SIGNALTHRESHOLD, this); + lp_var_t darkThreshold = + lp_var_t(sid.objectId, PoolIds::IMAGE_PROCESSOR_DARKTHRESHOLD, this); + lp_var_t backgroundCompensation = + lp_var_t(sid.objectId, PoolIds::IMAGE_PROCESSOR_BACKGROUNDCOMPENSATION, this); + + void printSet() { + sif::info << "ImageProcessorSet::printSet: mode: " + << static_cast(this->mode.value) << std::endl; + sif::info << "ImageProcessorSet::printSet: store: " + << static_cast(this->store.value) << std::endl; + sif::info << "ImageProcessorSet::printSet: signal threshold: " << this->signalThreshold + << std::endl; + sif::info << "ImageProcessorSet::printSet: dark threshold: " << this->darkThreshold + << std::endl; + sif::info << "ImageProcessorSet::printSet: background compensation: " + << static_cast(this->backgroundCompensation.value) << std::endl; + } +}; + +/** + * @brief Will store the requested centroiding parameters + */ +class CentroidingSet : public StaticLocalDataSet { + public: + // Size of dataset + static const size_t SIZE = 49; + + CentroidingSet(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, CENTROIDING_SET_ID) {} + + CentroidingSet(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, CENTROIDING_SET_ID)) {} + + lp_var_t enableFilter = + lp_var_t(sid.objectId, PoolIds::CENTROIDING_ENABLE_FILTER, this); + lp_var_t maxQuality = + lp_var_t(sid.objectId, PoolIds::CENTROIDING_MAX_QUALITY, this); + lp_var_t darkThreshold = + lp_var_t(sid.objectId, PoolIds::CENTROIDING_DARK_THRESHOLD, this); + lp_var_t minQuality = + lp_var_t(sid.objectId, PoolIds::CENTROIDING_MIN_QUALITY, this); + lp_var_t maxIntensity = + lp_var_t(sid.objectId, PoolIds::CENTROIDING_MAX_INTENSITY, this); + lp_var_t minIntensity = + lp_var_t(sid.objectId, PoolIds::CENTROIDING_MIN_INTENSITY, this); + lp_var_t maxMagnitude = + lp_var_t(sid.objectId, PoolIds::CENTROIDING_MAX_MAGNITUDE, this); + lp_var_t gaussianCmax = + lp_var_t(sid.objectId, PoolIds::CENTROIDING_GAUSSIAN_CMAX, this); + lp_var_t gaussianCmin = + lp_var_t(sid.objectId, PoolIds::CENTROIDING_GAUSSIAN_CMIN, this); + lp_var_t transmatrix00 = + lp_var_t(sid.objectId, PoolIds::CENTROIDING_TRANSMATRIX00, this); + lp_var_t transmatrix01 = + lp_var_t(sid.objectId, PoolIds::CENTROIDING_TRANSMATRIX01, this); + lp_var_t transmatrix10 = + lp_var_t(sid.objectId, PoolIds::CENTROIDING_TRANSMATRIX10, this); + lp_var_t transmatrix11 = + lp_var_t(sid.objectId, PoolIds::CENTROIDING_TRANSMATRIX11, this); + + void printSet() { + sif::info << "CentroidingSet::printSet: enable filter: " + << static_cast(this->enableFilter.value) << std::endl; + sif::info << "CentroidingSet::printSet: max quality: " << this->maxQuality << std::endl; + sif::info << "CentroidingSet::printSet: dark threshold: " << this->darkThreshold << std::endl; + sif::info << "CentroidingSet::printSet: min quality: " << this->minQuality << std::endl; + sif::info << "CentroidingSet::printSet: max intensity: " << this->maxIntensity << std::endl; + sif::info << "CentroidingSet::printSet: min intensity: " << this->minIntensity << std::endl; + sif::info << "CentroidingSet::printSet: max magnitude: " << this->maxMagnitude << std::endl; + sif::info << "CentroidingSet::printSet: gaussian cmax: " << this->gaussianCmax << std::endl; + sif::info << "CentroidingSet::printSet: gaussian cmin: " << this->gaussianCmin << std::endl; + sif::info << "CentroidingSet::printSet: transmatrix 00 : " << this->transmatrix00 << std::endl; + sif::info << "CentroidingSet::printSet: transmatrix 01 : " << this->transmatrix01 << std::endl; + sif::info << "CentroidingSet::printSet: transmatrix 10 : " << this->transmatrix10 << std::endl; + sif::info << "CentroidingSet::printSet: transmatrix 11 : " << this->transmatrix11 << std::endl; + } +}; + +/** + * @brief Will store the requested centroiding parameters + */ +class LisaSet : public StaticLocalDataSet { + public: + // Size of dataset + static const size_t SIZE = 50; + + LisaSet(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, LISA_SET_ID) {} + + LisaSet(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, LISA_SET_ID)) {} + + lp_var_t mode = lp_var_t(sid.objectId, PoolIds::LISA_MODE, this); + lp_var_t prefilterDistThreshold = + lp_var_t(sid.objectId, PoolIds::LISA_PREFILTER_DIST_THRESHOLD, this); + lp_var_t prefilterAngleThreshold = + lp_var_t(sid.objectId, PoolIds::LISA_PREFILTER_ANGLE_THRESHOLD, this); + lp_var_t fovWidth = lp_var_t(sid.objectId, PoolIds::LISA_FOV_WIDTH, this); + lp_var_t fovHeight = lp_var_t(sid.objectId, PoolIds::LISA_FOV_HEIGHT, this); + lp_var_t floatStarLimit = + lp_var_t(sid.objectId, PoolIds::LISA_FLOAT_STAR_LIMIT, this); + lp_var_t closeStarLimit = + lp_var_t(sid.objectId, PoolIds::LISA_CLOSE_STAR_LIMIT, this); + lp_var_t ratingWeightCloseStarCount = + lp_var_t(sid.objectId, PoolIds::LISA_RATING_WEIGHT_CLOSE_STAR_COUNT, this); + lp_var_t ratingWeightFractionClose = + lp_var_t(sid.objectId, PoolIds::LISA_RATING_WEIGHT_FRACTION_CLOSE, this); + lp_var_t ratingWeightMeanSum = + lp_var_t(sid.objectId, PoolIds::LISA_RATING_WEIGHT_MEAN_SUM, this); + lp_var_t ratingWeightDbStarCount = + lp_var_t(sid.objectId, PoolIds::LISA_RATING_WEIGHT_DB_STAR_COUNT, this); + lp_var_t maxCombinations = + lp_var_t(sid.objectId, PoolIds::LISA_MAX_COMBINATIONS, this); + lp_var_t nrStarsStop = + lp_var_t(sid.objectId, PoolIds::LISA_NR_STARS_STOP, this); + lp_var_t fractionCloseStop = + lp_var_t(sid.objectId, PoolIds::LISA_FRACTION_CLOSE_STOP, this); + + void printSet() { + sif::info << "LisaSet::printSet: mode: " << this->mode << std::endl; + sif::info << "LisaSet::printSet: prefilter dist threshold: " << this->prefilterDistThreshold + << std::endl; + sif::info << "LisaSet::printSet: prefilter angle threshold: " << this->prefilterAngleThreshold + << std::endl; + sif::info << "LisaSet::printSet: fov width: " << this->fovWidth << std::endl; + sif::info << "LisaSet::printSet: fov height: " << this->fovHeight << std::endl; + sif::info << "LisaSet::printSet: float star limit: " << this->floatStarLimit << std::endl; + sif::info << "LisaSet::printSet: close star limit: " << this->closeStarLimit << std::endl; + sif::info << "LisaSet::printSet: rating weight close star count: " + << this->ratingWeightCloseStarCount << std::endl; + sif::info << "LisaSet::printSet: rating weight fraction close: " + << this->ratingWeightFractionClose << std::endl; + sif::info << "LisaSet::printSet: rating weight mean sum: " << this->ratingWeightMeanSum + << std::endl; + sif::info << "LisaSet::printSet: rating weight db star count: " << this->ratingWeightDbStarCount + << std::endl; + sif::info << "LisaSet::printSet: max combinations: " + << static_cast(this->maxCombinations.value) << std::endl; + sif::info << "LisaSet::printSet: nr stars stop: " + << static_cast(this->nrStarsStop.value) << std::endl; + sif::info << "LisaSet::printSet: fraction close stop: " << this->fractionCloseStop << std::endl; + } +}; + +/** + * @brief Will store the requested matching parameters + */ +class MatchingSet : public StaticLocalDataSet { + public: + // Size of dataset + static const size_t SIZE = 8; + + MatchingSet(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, MATCHING_SET_ID) {} + + MatchingSet(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, MATCHING_SET_ID)) {} + + lp_var_t squaredDistanceLimit = + lp_var_t(sid.objectId, PoolIds::MATCHING_SQUARED_DISTANCE_LIMIT, this); + lp_var_t squaredShiftLimit = + lp_var_t(sid.objectId, PoolIds::MATCHING_SQUARED_SHIFT_LIMIT, this); + + void printSet() { + sif::info << "MatchingSet::printSet: squared distance limit: " << this->squaredDistanceLimit + << std::endl; + sif::info << "MatchingSet::printSet: squared distance limit: " << this->squaredShiftLimit + << std::endl; + } +}; + +/** + * @brief Will store the requested tracking parameters + */ +class TrackingSet : public StaticLocalDataSet { + public: + // Size of dataset + static const size_t SIZE = 13; + + TrackingSet(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, TRACKING_SET_ID) {} + + TrackingSet(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, TRACKING_SET_ID)) {} + + lp_var_t thinLimit = lp_var_t(sid.objectId, PoolIds::TRACKING_THIN_LIMIT, this); + lp_var_t outlierThreshold = + lp_var_t(sid.objectId, PoolIds::TRACKING_OUTLIER_THRESHOLD, this); + lp_var_t outlierThresholdQuest = + lp_var_t(sid.objectId, PoolIds::TRACKING_OUTLIER_THRESHOLD_QUEST, this); + lp_var_t trackerChoice = + lp_var_t(sid.objectId, PoolIds::TRACKING_TRACKER_CHOICE, this); + + void printSet() { + sif::info << "TrackingSet::printSet: thin limit: " << this->thinLimit << std::endl; + sif::info << "TrackingSet::printSet: outlier threshold: " << this->outlierThreshold + << std::endl; + sif::info << "TrackingSet::printSet: outlier threshold quest: " << this->outlierThresholdQuest + << std::endl; + sif::info << "TrackingSet::printSet: tracker choice: " + << static_cast(this->trackerChoice.value) << std::endl; + } +}; + +/** + * @brief Will store the requested validation parameters + */ +class ValidationSet : public StaticLocalDataSet { + public: + // Size of dataset + static const size_t SIZE = 10; + + ValidationSet(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, VALIDATION_SET_ID) {} + + ValidationSet(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, VALIDATION_SET_ID)) {} + + lp_var_t stableCount = + lp_var_t(sid.objectId, PoolIds::VALIDATION_STABLE_COUNT, this); + lp_var_t maxDifference = + lp_var_t(sid.objectId, PoolIds::VALIDATION_MAX_DIFFERENCE, this); + lp_var_t minTrackerConfidence = + lp_var_t(sid.objectId, PoolIds::VALIDATION_MIN_TRACKER_CONFIDENCE, this); + lp_var_t minMatchedStars = + lp_var_t(sid.objectId, PoolIds::VALIDATION_MIN_MATCHED_STARS, this); + + void printSet() { + sif::info << "ValidationSet::printSet: stable count: " + << static_cast(this->stableCount.value) << std::endl; + sif::info << "ValidationSet::printSet: max difference: " << this->maxDifference << std::endl; + sif::info << "ValidationSet::printSet: min tracker confidence: " << this->minTrackerConfidence + << std::endl; + sif::info << "ValidationSet::printSet: min matched stars: " + << static_cast(this->minMatchedStars.value) << std::endl; + } +}; + +/** + * @brief Will store the requested algo parameters + */ +class AlgoSet : public StaticLocalDataSet { + public: + // Size of dataset + static const size_t SIZE = 11; + + AlgoSet(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, ALGO_SET_ID) {} + + AlgoSet(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, ALGO_SET_ID)) {} + + lp_var_t mode = lp_var_t(sid.objectId, PoolIds::ALGO_MODE, this); + lp_var_t i2tMinConfidence = + lp_var_t(sid.objectId, PoolIds::ALGO_I2T_MIN_CONFIDENCE, this); + lp_var_t i2tMinMatched = + lp_var_t(sid.objectId, PoolIds::ALGO_I2T_MIN_MATCHED, this); + lp_var_t i2lMinConfidence = + lp_var_t(sid.objectId, PoolIds::ALGO_I2L_MIN_CONFIDENCE, this); + lp_var_t i2lMinMatched = + lp_var_t(sid.objectId, PoolIds::ALGO_I2L_MIN_MATCHED, this); + + void printSet() { + sif::info << "AlgoSet::printSet: mode: " << static_cast(this->mode.value) + << std::endl; + sif::info << "AlgoSet::printSet: i2t min confidence: " << this->i2tMinConfidence << std::endl; + sif::info << "AlgoSet::printSet: i2t min matched: " + << static_cast(this->i2tMinMatched.value) << std::endl; + sif::info << "AlgoSet::printSet: i2l min confidence: " << this->i2lMinConfidence << std::endl; + sif::info << "AlgoSet::printSet: i2l min matched: " + << static_cast(this->i2lMinMatched.value) << std::endl; + } +}; + +/** + * @brief Will store the requested subscription parameters + */ +class SubscriptionSet : public StaticLocalDataSet { + public: + // Size of dataset + static const size_t SIZE = 16; + + SubscriptionSet(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, SUBSCRIPTION_SET_ID) {} + + SubscriptionSet(object_id_t objectId) + : StaticLocalDataSet(sid_t(objectId, SUBSCRIPTION_SET_ID)) {} + + lp_var_t tm1 = lp_var_t(sid.objectId, PoolIds::SUBSCRIPTION_TM1, this); + lp_var_t tm2 = lp_var_t(sid.objectId, PoolIds::SUBSCRIPTION_TM2, this); + lp_var_t tm3 = lp_var_t(sid.objectId, PoolIds::SUBSCRIPTION_TM3, this); + lp_var_t tm4 = lp_var_t(sid.objectId, PoolIds::SUBSCRIPTION_TM4, this); + lp_var_t tm5 = lp_var_t(sid.objectId, PoolIds::SUBSCRIPTION_TM5, this); + lp_var_t tm6 = lp_var_t(sid.objectId, PoolIds::SUBSCRIPTION_TM6, this); + lp_var_t tm7 = lp_var_t(sid.objectId, PoolIds::SUBSCRIPTION_TM7, this); + lp_var_t tm8 = lp_var_t(sid.objectId, PoolIds::SUBSCRIPTION_TM8, this); + lp_var_t tm9 = lp_var_t(sid.objectId, PoolIds::SUBSCRIPTION_TM9, this); + lp_var_t tm10 = lp_var_t(sid.objectId, PoolIds::SUBSCRIPTION_TM10, this); + lp_var_t tm11 = lp_var_t(sid.objectId, PoolIds::SUBSCRIPTION_TM11, this); + lp_var_t tm12 = lp_var_t(sid.objectId, PoolIds::SUBSCRIPTION_TM12, this); + lp_var_t tm13 = lp_var_t(sid.objectId, PoolIds::SUBSCRIPTION_TM13, this); + lp_var_t tm14 = lp_var_t(sid.objectId, PoolIds::SUBSCRIPTION_TM14, this); + lp_var_t tm15 = lp_var_t(sid.objectId, PoolIds::SUBSCRIPTION_TM15, this); + lp_var_t tm16 = lp_var_t(sid.objectId, PoolIds::SUBSCRIPTION_TM16, this); + + void printSet() { + sif::info << "SubscriptionSet::printSet: telemetry 1: " + << static_cast(this->tm1.value) << std::endl; + sif::info << "SubscriptionSet::printSet: telemetry 2: " + << static_cast(this->tm2.value) << std::endl; + sif::info << "SubscriptionSet::printSet: telemetry 3: " + << static_cast(this->tm3.value) << std::endl; + sif::info << "SubscriptionSet::printSet: telemetry 4: " + << static_cast(this->tm4.value) << std::endl; + sif::info << "SubscriptionSet::printSet: telemetry 5: " + << static_cast(this->tm5.value) << std::endl; + sif::info << "SubscriptionSet::printSet: telemetry 6: " + << static_cast(this->tm6.value) << std::endl; + sif::info << "SubscriptionSet::printSet: telemetry 7: " + << static_cast(this->tm7.value) << std::endl; + sif::info << "SubscriptionSet::printSet: telemetry 8: " + << static_cast(this->tm8.value) << std::endl; + sif::info << "SubscriptionSet::printSet: telemetry 9: " + << static_cast(this->tm9.value) << std::endl; + sif::info << "SubscriptionSet::printSet: telemetry 10: " + << static_cast(this->tm10.value) << std::endl; + sif::info << "SubscriptionSet::printSet: telemetry 11: " + << static_cast(this->tm11.value) << std::endl; + sif::info << "SubscriptionSet::printSet: telemetry 12: " + << static_cast(this->tm12.value) << std::endl; + sif::info << "SubscriptionSet::printSet: telemetry 13: " + << static_cast(this->tm13.value) << std::endl; + sif::info << "SubscriptionSet::printSet: telemetry 14: " + << static_cast(this->tm14.value) << std::endl; + sif::info << "SubscriptionSet::printSet: telemetry 15: " + << static_cast(this->tm15.value) << std::endl; + sif::info << "SubscriptionSet::printSet: telemetry 16: " + << static_cast(this->tm16.value) << std::endl; + } +}; + +/** + * @brief Will store the requested log subscription parameters + */ +class LogSubscriptionSet : public StaticLocalDataSet { + public: + // Size of dataset + static const size_t SIZE = 4; + + LogSubscriptionSet(HasLocalDataPoolIF* owner) + : StaticLocalDataSet(owner, LOG_SUBSCRIPTION_SET_ID) {} + + LogSubscriptionSet(object_id_t objectId) + : StaticLocalDataSet(sid_t(objectId, LOG_SUBSCRIPTION_SET_ID)) {} + + lp_var_t level1 = + lp_var_t(sid.objectId, PoolIds::LOG_SUBSCRIPTION_LEVEL1, this); + lp_var_t module1 = + lp_var_t(sid.objectId, PoolIds::LOG_SUBSCRIPTION_MODULE1, this); + lp_var_t level2 = + lp_var_t(sid.objectId, PoolIds::LOG_SUBSCRIPTION_LEVEL2, this); + lp_var_t module2 = + lp_var_t(sid.objectId, PoolIds::LOG_SUBSCRIPTION_MODULE2, this); + + void printSet() { + sif::info << "LogSubscriptionSet::printSet: level 1: " + << static_cast(this->level1.value) << std::endl; + sif::info << "LogSubscriptionSet::printSet: module 1: " + << static_cast(this->module1.value) << std::endl; + sif::info << "LogSubscriptionSet::printSet: level 2: " + << static_cast(this->level2.value) << std::endl; + sif::info << "LogSubscriptionSet::printSet: module 2: " + << static_cast(this->module2.value) << std::endl; + } +}; + +/** + * @brief Will store the requested debug camera parameters + */ +class DebugCameraSet : public StaticLocalDataSet { + public: + // Size of dataset + static const size_t SIZE = 8; + + DebugCameraSet(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, DEBUG_CAMERA_SET_ID) {} + + lp_var_t timing = lp_var_t(sid.objectId, PoolIds::DEBUG_CAMERA_TIMING, this); + lp_var_t test = lp_var_t(sid.objectId, PoolIds::DEBUG_CAMERA_TEST, this); + + DebugCameraSet(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, DEBUG_CAMERA_SET_ID)) {} + + void printSet() { + sif::info << "DebugCameraSet::printSet: timing: " << this->timing << std::endl; + sif::info << "DebugCameraSet::printSet: test: " << this->test << std::endl; + } +}; +} // namespace startracker +#endif /* LINUX_DEVICES_DEVICEDEFINITIONS_STARTRACKER_DEFINITIONS_H_ */ diff --git a/linux/devices/devicedefinitions/SusDefinitions.h b/linux/devices/devicedefinitions/SusDefinitions.h deleted file mode 100644 index ba56ec07..00000000 --- a/linux/devices/devicedefinitions/SusDefinitions.h +++ /dev/null @@ -1,95 +0,0 @@ -#ifndef MISSION_DEVICES_DEVICEDEFINITIONS_SUS_H_ -#define MISSION_DEVICES_DEVICEDEFINITIONS_SUS_H_ - -#include -#include -#include - - -namespace SUS { - - /** - * Some MAX1227 could not be reached with frequencies around 4 MHz. Maybe this is caused by - * the decoder and buffer circuits. Thus frequency is here defined to 1 MHz. - */ - static const uint32_t MAX1227_SPI_FREQ = 1000000; - - static const DeviceCommandId_t NONE = 0x0; // Set when no command is pending - - static const DeviceCommandId_t WRITE_SETUP = 0x1; - /** - * This command initiates the ADC conversion for all channels including the internal - * temperature sensor. - */ - static const DeviceCommandId_t START_CONVERSIONS = 0x2; - /** - * This command reads the internal fifo which holds the temperature and the channel - * conversions. - */ - static const DeviceCommandId_t READ_CONVERSIONS = 0x3; - - /** - * @brief This is the configuration byte which will be written to the setup register after - * power on. - * - * @note Bit1 (DIFFSEL1) - Bit0 (DIFFSEL0): 0b00, No byte is following the setup byte - * Bit3 (REFSEL1) - Bit2 (REFSEL0): 0b10, Internal reference, no wake-up delay - * Bit5 (CLKSEL1) - Bit4 (CLKSEL0): 0b10, Internally clocked - * Bit7 - Bit6: 0b01, Tells MAX1227 that this byte should be - * written to the setup register - * - */ - static const uint8_t SETUP = 0b01101000; - - /** - * @brief This values will always be written to the ADC conversion register to specify the - * conversions to perform. - * @details Bit0: 1 - Enables temperature conversion - * Bit2 (SCAN1) and Bit1 (SCAN0): 0b00, Scans channels 0 through N - * Bit6 - Bit3 defines N: 0b0101 (N = 5) - * Bit7: Always 1. Tells the ADC that this is the conversion register. - */ - static const uint8_t CONVERSION = 0b10101001; - - static const uint8_t SUS_DATA_SET_ID = READ_CONVERSIONS; - - /** Size of data replies. Temperature and 6 channel convesions (AIN0 - AIN5) */ - static const uint8_t SIZE_READ_CONVERSIONS = 14; - - static const uint8_t MAX_CMD_SIZE = SIZE_READ_CONVERSIONS; - - static const uint8_t POOL_ENTRIES = 7; - - enum Max1227PoolIds: lp_id_t { - TEMPERATURE_C, - AIN0, - AIN1, - AIN2, - AIN3, - AIN4, - AIN5, - }; - -class SusDataset: public StaticLocalDataSet { -public: - - SusDataset(HasLocalDataPoolIF* owner) : - StaticLocalDataSet(owner, SUS_DATA_SET_ID) { - } - - SusDataset(object_id_t objectId) : - StaticLocalDataSet(sid_t(objectId, SUS_DATA_SET_ID)) { - } - - lp_var_t temperatureCelcius = lp_var_t(sid.objectId, TEMPERATURE_C, this); - lp_var_t ain0 = lp_var_t(sid.objectId, AIN0, this); - lp_var_t ain1 = lp_var_t(sid.objectId, AIN1, this); - lp_var_t ain2 = lp_var_t(sid.objectId, AIN2, this); - lp_var_t ain3 = lp_var_t(sid.objectId, AIN3, this); - lp_var_t ain4 = lp_var_t(sid.objectId, AIN4, this); - lp_var_t ain5 = lp_var_t(sid.objectId, AIN5, this); -}; -} - - -#endif /* MISSION_DEVICES_DEVICEDEFINITIONS_SUS_H_ */ diff --git a/linux/devices/startracker/ArcsecDatalinkLayer.cpp b/linux/devices/startracker/ArcsecDatalinkLayer.cpp new file mode 100644 index 00000000..24eab940 --- /dev/null +++ b/linux/devices/startracker/ArcsecDatalinkLayer.cpp @@ -0,0 +1,62 @@ +#include "ArcsecDatalinkLayer.h" + +ArcsecDatalinkLayer::ArcsecDatalinkLayer() { slipInit(); } + +ArcsecDatalinkLayer::~ArcsecDatalinkLayer() {} + +void ArcsecDatalinkLayer::slipInit() { + slipInfo.buffer = rxBuffer; + slipInfo.maxlength = startracker::MAX_FRAME_SIZE; + slipInfo.length = 0; + slipInfo.unescape_next = 0; + slipInfo.prev_state = SLIP_COMPLETE; +} + +ReturnValue_t ArcsecDatalinkLayer::decodeFrame(const uint8_t* rawData, size_t rawDataSize, + size_t* bytesLeft) { + size_t bytePos = 0; + for (bytePos = 0; bytePos < rawDataSize; bytePos++) { + enum arc_dec_result decResult = + arc_transport_decode_body(*(rawData + bytePos), &slipInfo, decodedFrame, &decFrameSize); + *bytesLeft = rawDataSize - bytePos - 1; + switch (decResult) { + case ARC_DEC_INPROGRESS: { + if (bytePos == rawDataSize - 1) { + return DEC_IN_PROGRESS; + } + continue; + } + case ARC_DEC_ERROR_FRAME_SHORT: + return REPLY_TOO_SHORT; + case ARC_DEC_ERROR_CHECKSUM: + return CRC_FAILURE; + case ARC_DEC_ASYNC: + case ARC_DEC_SYNC: { + // Reset length of SLIP struct for next frame + slipInfo.length = 0; + return RETURN_OK; + } + default: + sif::debug << "ArcsecDatalinkLayer::decodeFrame: Unknown result code" << std::endl; + break; + return RETURN_FAILED; + } + } + return RETURN_FAILED; +} + +uint8_t ArcsecDatalinkLayer::getReplyFrameType() { return decodedFrame[0]; } + +const uint8_t* ArcsecDatalinkLayer::getReply() { return &decodedFrame[1]; } + +void ArcsecDatalinkLayer::encodeFrame(const uint8_t* data, uint32_t length) { + arc_transport_encode_body(data, length, encBuffer, &encFrameSize); +} + +uint8_t* ArcsecDatalinkLayer::getEncodedFrame() { return encBuffer; } + +uint32_t ArcsecDatalinkLayer::getEncodedLength() { return encFrameSize; } + +uint8_t ArcsecDatalinkLayer::getStatusField() { return *(decodedFrame + STATUS_OFFSET); } + +uint8_t ArcsecDatalinkLayer::getId() { return *(decodedFrame + ID_OFFSET); } diff --git a/linux/devices/startracker/ArcsecDatalinkLayer.h b/linux/devices/startracker/ArcsecDatalinkLayer.h new file mode 100644 index 00000000..e3da9b6a --- /dev/null +++ b/linux/devices/startracker/ArcsecDatalinkLayer.h @@ -0,0 +1,98 @@ +#ifndef BSP_Q7S_DEVICES_ARCSECDATALINKLAYER_H_ +#define BSP_Q7S_DEVICES_ARCSECDATALINKLAYER_H_ + +#include "fsfw/returnvalues/HasReturnvaluesIF.h" +#include "linux/devices/devicedefinitions/StarTrackerDefinitions.h" + +extern "C" { +#include "common/misc.h" +} + +/** + * @brief Helper class to handle the datalinklayer of replies from the star tracker of arcsec. + */ +class ArcsecDatalinkLayer : public HasReturnvaluesIF { + public: + static const uint8_t INTERFACE_ID = CLASS_ID::STR_HANDLER; + + //! [EXPORT] : [COMMENT] More data required to complete frame + static const ReturnValue_t DEC_IN_PROGRESS = MAKE_RETURN_CODE(0xA0); + //! [EXPORT] : [COMMENT] Data too short to represent a valid frame + static const ReturnValue_t REPLY_TOO_SHORT = MAKE_RETURN_CODE(0xA1); + //! [EXPORT] : [COMMENT] Detected CRC failure in received frame + static const ReturnValue_t CRC_FAILURE = MAKE_RETURN_CODE(0xA2); + + static const uint8_t STATUS_OK = 0; + + ArcsecDatalinkLayer(); + virtual ~ArcsecDatalinkLayer(); + + /** + * @brief Applies decoding to data referenced by rawData pointer + * + * @param rawData Pointer to raw data received from star tracker + * @param rawDataSize Size of raw data stream + * @param remainingBytes Number of bytes left + */ + ReturnValue_t decodeFrame(const uint8_t* rawData, size_t rawDataSize, size_t* bytesLeft); + + /** + * @brief SLIP encodes data pointed to by data pointer. + * + * @param data Pointer to data to encode + * @param length Length of buffer to encode + */ + void encodeFrame(const uint8_t* data, uint32_t length); + + /** + * @brief Returns the frame type field of a decoded frame. + */ + uint8_t getReplyFrameType(); + + /** + * @brief Returns pointer to reply packet (first entry normally action ID, telemetry ID etc.) + */ + const uint8_t* getReply(); + + /** + * @brief Returns size of encoded frame + */ + uint32_t getEncodedLength(); + + /** + * @brief Returns pointer to encoded frame + */ + uint8_t* getEncodedFrame(); + + /** + * @brief Returns status of reply + */ + uint8_t getStatusField(); + + /** + * @brief Returns ID of reply + */ + uint8_t getId(); + + private: + static const uint8_t ID_OFFSET = 1; + static const uint8_t STATUS_OFFSET = 2; + + // Used by arcsec slip decoding function process received data + uint8_t rxBuffer[startracker::MAX_FRAME_SIZE]; + // Decoded frame will be copied to this buffer + uint8_t decodedFrame[startracker::MAX_FRAME_SIZE]; + // Buffer where encoded frames will be stored. First byte of encoded frame represents type of + // reply + uint8_t encBuffer[startracker::MAX_FRAME_SIZE * 2 + 2]; + // Size of decoded frame + uint32_t decFrameSize = 0; + // Size of encoded frame + uint32_t encFrameSize = 0; + + slip_decode_state slipInfo; + + void slipInit(); +}; + +#endif /* BSP_Q7S_DEVICES_ARCSECDATALINKLAYER_H_ */ diff --git a/linux/devices/startracker/ArcsecJsonKeys.h b/linux/devices/startracker/ArcsecJsonKeys.h new file mode 100644 index 00000000..34989b1f --- /dev/null +++ b/linux/devices/startracker/ArcsecJsonKeys.h @@ -0,0 +1,181 @@ +#ifndef BSP_Q7S_DEVICES_DEVICEDEFINITIONS_ARCSECJSONKEYS_H_ +#define BSP_Q7S_DEVICES_DEVICEDEFINITIONS_ARCSECJSONKEYS_H_ + +/** + * @brief Keys used in JSON file of ARCSEC. + */ +namespace arcseckeys { +static const char PROPERTIES[] = "properties"; +static const char NAME[] = "name"; +static const char VALUE[] = "value"; + +static const char LIMITS[] = "limits"; +static const char ACTION[] = "action"; +static const char FPGA18CURRENT[] = "FPGA18Current"; +static const char FPGA25CURRENT[] = "FPGA25Current"; +static const char FPGA10CURRENT[] = "FPGA10Current"; +static const char MCUCURRENT[] = "MCUCurrent"; +static const char CMOS21CURRENT[] = "CMOS21Current"; +static const char CMOSPIXCURRENT[] = "CMOSPixCurrent"; +static const char CMOS33CURRENT[] = "CMOS33Current"; +static const char CMOSVRESCURRENT[] = "CMOSVResCurrent"; +static const char CMOS_TEMPERATURE[] = "CMOSTemperature"; +static const char MCU_TEMPERATURE[] = "MCUTemperature"; + +static const char MOUNTING[] = "mounting"; +static const char qw[] = "qw"; +static const char qx[] = "qx"; +static const char qy[] = "qy"; +static const char qz[] = "qz"; + +static const char IMAGE_PROCESSOR[] = "imageprocessor"; +static const char IMAGE_PROCESSOR_MODE[] = "mode"; +static const char STORE[] = "store"; +static const char SIGNAL_THRESHOLD[] = "signalThreshold"; +static const char IMAGE_PROCESSOR_DARK_THRESHOLD[] = "darkThreshold"; +static const char BACKGROUND_COMPENSATION[] = "backgroundcompensation"; + +static const char CAMERA[] = "camera"; +static const char MODE[] = "mode"; +static const char FOCALLENGTH[] = "focallength"; +static const char EXPOSURE[] = "exposure"; +static const char INTERVAL[] = "interval"; +static const char OFFSET[] = "offset"; +static const char PGAGAIN[] = "PGAGain"; +static const char ADCGAIN[] = "ADCGain"; +static const char REG_1[] = "reg1"; +static const char VAL_1[] = "val1"; +static const char REG_2[] = "reg2"; +static const char VAL_2[] = "val2"; +static const char REG_3[] = "reg3"; +static const char VAL_3[] = "val3"; +static const char REG_4[] = "reg4"; +static const char VAL_4[] = "val4"; +static const char REG_5[] = "reg5"; +static const char VAL_5[] = "val5"; +static const char REG_6[] = "reg6"; +static const char VAL_6[] = "val6"; +static const char REG_7[] = "reg7"; +static const char VAL_7[] = "val7"; +static const char REG_8[] = "reg8"; +static const char VAL_8[] = "val8"; +static const char FREQ_1[] = "freq1"; + +static const char BLOB[] = "blob"; +static const char MIN_VALUE[] = "minValue"; +static const char MIN_DISTANCE[] = "minDistance"; +static const char NEIGHBOUR_DISTANCE[] = "neighbourDistance"; +static const char NEIGHBOUR_BRIGHT_PIXELS[] = "neighbourBrightPixels"; +static const char MIN_TOTAL_VALUE[] = "minTotalValue"; +static const char MAX_TOTAL_VALUE[] = "maxTotalValue"; +static const char MIN_BRIGHT_NEIGHBOURS[] = "minBrightNeighbours"; +static const char MAX_BRIGHT_NEIGHBOURS[] = "maxBrightNeighbours"; +static const char MAX_PIXEL_TO_CONSIDER[] = "maxPixelsToConsider"; +// static const char SIGNAL_THRESHOLD[] = "signalThreshold"; +static const char BLOB_DARK_THRESHOLD[] = "darkThreshold"; +static const char ENABLE_HISTOGRAM[] = "enableHistogram"; +static const char ENABLE_CONTRAST[] = "enableContrast"; +static const char BIN_MODE[] = "binMode"; + +static const char CENTROIDING[] = "centroiding"; +static const char ENABLE_FILTER[] = "enableFilter"; +static const char MAX_QUALITY[] = "maxquality"; +static const char DARK_THRESHOLD[] = "darkthreshold"; +static const char MIN_QUALITY[] = "minquality"; +static const char MAX_INTENSITY[] = "maxintensity"; +static const char MIN_INTENSITY[] = "minintensity"; +static const char MAX_MAGNITUDE[] = "maxmagnitude"; +static const char GAUSSIAN_CMAX[] = "gaussianCmax"; +static const char GAUSSIAN_CMIN[] = "gaussianCmin"; +static const char TRANSMATRIX_00[] = "transmatrix00"; +static const char TRANSMATRIX_01[] = "transmatrix01"; +static const char TRANSMATRIX_10[] = "transmatrix10"; +static const char TRANSMATRIX_11[] = "transmatrix11"; + +static const char LISA[] = "lisa"; +static const char LISA_MODE[] = "mode"; +static const char PREFILTER_DIST_THRESHOLD[] = "prefilterDistThreshold"; +static const char PREFILTER_ANGLE_THRESHOLD[] = "prefilterAngleThreshold"; +static const char FOV_WIDTH[] = "fov_width"; +static const char FOV_HEIGHT[] = "fov_height"; +static const char FLOAT_STAR_LIMIT[] = "float_star_limit"; +static const char CLOSE_STAR_LIMIT[] = "close_star_limit"; +static const char RATING_WEIGHT_CLOSE_STAR_COUNT[] = "rating_weight_close_star_count"; +static const char RATING_WEIGHT_FRACTION_CLOSE[] = "rating_weight_fraction_close"; +static const char RATING_WEIGHT_MEAN_SUM[] = "rating_weight_mean_sum"; +static const char RATING_WEIGHT_DB_STAR_COUNT[] = "rating_weight_db_star_count"; +static const char MAX_COMBINATIONS[] = "max_combinations"; +static const char NR_STARS_STOP[] = "nr_stars_stop"; +static const char FRACTION_CLOSE_STOP[] = "fraction_close_stop"; + +static const char MATCHING[] = "matching"; +static const char SQUARED_DISTANCE_LIMIT[] = "squaredDistanceLimit"; +static const char SQUARED_SHIFT_LIMIT[] = "squaredShiftLimit"; + +static const char VALIDATION[] = "validation"; +static const char STABLE_COUNT[] = "stable_count"; +static const char MAX_DIFFERENCE[] = "max_difference"; +static const char MIN_TRACKER_CONFIDENCE[] = "min_trackerConfidence"; +static const char MIN_MATCHED_STARS[] = "min_matchedStars"; + +static const char TRACKING[] = "tracking"; +static const char THIN_LIMIT[] = "thinLimit"; +static const char OUTLIER_THRESHOLD[] = "outlierThreshold"; +static const char OUTLIER_THRESHOLD_QUEST[] = "outlierThresholdQUEST"; +static const char TRACKER_CHOICE[] = "trackerChoice"; + +static const char ALGO[] = "algo"; +static const char L2T_MIN_CONFIDENCE[] = "l2t_minConfidence"; +static const char L2T_MIN_MATCHED[] = "l2t_minMatched"; +static const char T2L_MIN_CONFIDENCE[] = "t2l_minConfidence"; +static const char T2L_MIN_MATCHED[] = "t2l_minMatched"; + +static const char LOGLEVEL[] = "loglevel"; +static const char LOGLEVEL1[] = "loglevel1"; +static const char LOGLEVEL2[] = "loglevel2"; +static const char LOGLEVEL3[] = "loglevel3"; +static const char LOGLEVEL4[] = "loglevel4"; +static const char LOGLEVEL5[] = "loglevel5"; +static const char LOGLEVEL6[] = "loglevel6"; +static const char LOGLEVEL7[] = "loglevel7"; +static const char LOGLEVEL8[] = "loglevel8"; +static const char LOGLEVEL9[] = "loglevel9"; +static const char LOGLEVEL10[] = "loglevel10"; +static const char LOGLEVEL11[] = "loglevel11"; +static const char LOGLEVEL12[] = "loglevel12"; +static const char LOGLEVEL13[] = "loglevel13"; +static const char LOGLEVEL14[] = "loglevel14"; +static const char LOGLEVEL15[] = "loglevel15"; +static const char LOGLEVEL16[] = "loglevel16"; + +static const char SUBSCRIPTION[] = "subscription"; +static const char TELEMETRY_1[] = "telemetry1"; +static const char TELEMETRY_2[] = "telemetry2"; +static const char TELEMETRY_3[] = "telemetry3"; +static const char TELEMETRY_4[] = "telemetry4"; +static const char TELEMETRY_5[] = "telemetry5"; +static const char TELEMETRY_6[] = "telemetry6"; +static const char TELEMETRY_7[] = "telemetry7"; +static const char TELEMETRY_8[] = "telemetry8"; +static const char TELEMETRY_9[] = "telemetry9"; +static const char TELEMETRY_10[] = "telemetry10"; +static const char TELEMETRY_11[] = "telemetry11"; +static const char TELEMETRY_12[] = "telemetry12"; +static const char TELEMETRY_13[] = "telemetry13"; +static const char TELEMETRY_14[] = "telemetry14"; +static const char TELEMETRY_15[] = "telemetry15"; +static const char TELEMETRY_16[] = "telemetry16"; + +static const char LOG_SUBSCRIPTION[] = "logsubscription"; +static const char LEVEL1[] = "level1"; +static const char MODULE1[] = "module1"; +static const char LEVEL2[] = "level2"; +static const char MODULE2[] = "module2"; + +static const char DEBUG_CAMERA[] = "debugcamera"; +static const char TIMING[] = "timing"; +static const char TEST[] = "test"; + +} // namespace arcseckeys + +#endif /* BSP_Q7S_DEVICES_DEVICEDEFINITIONS_ARCSECJSONKEYS_H_ */ diff --git a/linux/devices/startracker/ArcsecJsonParamBase.cpp b/linux/devices/startracker/ArcsecJsonParamBase.cpp new file mode 100644 index 00000000..cc8bbc35 --- /dev/null +++ b/linux/devices/startracker/ArcsecJsonParamBase.cpp @@ -0,0 +1,103 @@ +#include "ArcsecJsonParamBase.h" + +#include "ArcsecJsonKeys.h" + +ArcsecJsonParamBase::ArcsecJsonParamBase(std::string setName) : setName(setName) {} + +ReturnValue_t ArcsecJsonParamBase::create(std::string fullname, uint8_t* buffer) { + ReturnValue_t result = RETURN_OK; + result = init(fullname); + if (result != RETURN_OK) { + sif::warning << "ArcsecJsonParamBase::create: Failed to init parameter command for set " + << setName << std::endl; + return result; + } + result = createCommand(buffer); + if (result != RETURN_OK) { + sif::warning << "ArcsecJsonParamBase::create: Failed to create parameter command for set " + << setName << std::endl; + } + return result; +} + +ReturnValue_t ArcsecJsonParamBase::getParam(const std::string name, std::string& value) { + for (json::iterator it = set.begin(); it != set.end(); ++it) { + if ((*it)[arcseckeys::NAME] == name) { + value = (*it)[arcseckeys::VALUE]; + convertEmpty(value); + return RETURN_OK; + } + } + return PARAM_NOT_EXISTS; +} + +void ArcsecJsonParamBase::convertEmpty(std::string& value) { + if (value == "") { + value = "0"; + } +} + +void ArcsecJsonParamBase::addfloat(const std::string value, uint8_t* buffer) { + float param = std::stof(value); + std::memcpy(buffer, ¶m, sizeof(param)); +} + +void ArcsecJsonParamBase::adduint8(const std::string value, uint8_t* buffer) { + uint8_t param = std::stoi(value); + std::memcpy(buffer, ¶m, sizeof(param)); +} + +void ArcsecJsonParamBase::addint16(const std::string value, uint8_t* buffer) { + int16_t param = std::stoi(value); + std::memcpy(buffer, ¶m, sizeof(param)); +} + +void ArcsecJsonParamBase::adduint16(const std::string value, uint8_t* buffer) { + uint16_t param = std::stoi(value); + std::memcpy(buffer, ¶m, sizeof(param)); +} + +void ArcsecJsonParamBase::adduint32(const std::string value, uint8_t* buffer) { + uint32_t param = std::stoi(value); + std::memcpy(buffer, ¶m, sizeof(param)); +} + +void ArcsecJsonParamBase::addSetParamHeader(uint8_t* buffer, uint8_t setId) { + *buffer = static_cast(TMTC_SETPARAMREQ); + *(buffer + 1) = setId; +} + +ReturnValue_t ArcsecJsonParamBase::init(const std::string filename) { + ReturnValue_t result = RETURN_OK; + if (not std::filesystem::exists(filename)) { + sif::warning << "ArcsecJsonParamBase::init: JSON file " << filename << " does not exist" + << std::endl; + return JSON_FILE_NOT_EXISTS; + } + createJsonObject(filename); + result = initSet(); + if (result != RETURN_OK) { + return result; + } + return RETURN_OK; +} + +void ArcsecJsonParamBase::createJsonObject(const std::string fullname) { + json j; + std::ifstream file(fullname); + file >> j; + file.close(); + properties = j[arcseckeys::PROPERTIES]; +} + +ReturnValue_t ArcsecJsonParamBase::initSet() { + for (json::iterator it = properties.begin(); it != properties.end(); ++it) { + if ((*it)["name"] == setName) { + set = (*it)["fields"]; + return RETURN_OK; + } + } + sif::warning << "ArcsecJsonParamBase::initSet: Set " << setName << "not present in json file" + << std::endl; + return SET_NOT_EXISTS; +} diff --git a/linux/devices/startracker/ArcsecJsonParamBase.h b/linux/devices/startracker/ArcsecJsonParamBase.h new file mode 100644 index 00000000..2d20fcae --- /dev/null +++ b/linux/devices/startracker/ArcsecJsonParamBase.h @@ -0,0 +1,146 @@ +#ifndef BSP_Q7S_DEVICES_STARTRACKER_ARCSECJSONPARAMBASE_H_ +#define BSP_Q7S_DEVICES_STARTRACKER_ARCSECJSONPARAMBASE_H_ + +#include +#include +#include + +#include "fsfw/returnvalues/HasReturnvaluesIF.h" +#include "linux/devices/devicedefinitions/StarTrackerDefinitions.h" + +extern "C" { +#include "thirdparty/arcsec_star_tracker/common/generated/tmtcstructs.h" +#include "thirdparty/arcsec_star_tracker/common/genericstructs.h" +} + +using json = nlohmann::json; + +/** + * @brief Base class for creation of parameter configuration commands. Reads parameter set + * from a json file located on the filesystem and generates the appropriate command + * to apply the parameters to the star tracker software. + * + * @author J. Meier + */ +class ArcsecJsonParamBase : public HasReturnvaluesIF { + public: + static const uint8_t INTERFACE_ID = CLASS_ID::ARCSEC_JSON_BASE; + //! [EXPORT] : [COMMENT] Specified json file does not exist + static const ReturnValue_t JSON_FILE_NOT_EXISTS = MAKE_RETURN_CODE(1); + //! [EXPORT] : [COMMENT] Requested set does not exist in json file + static const ReturnValue_t SET_NOT_EXISTS = MAKE_RETURN_CODE(2); + //! [EXPORT] : [COMMENT] Requested parameter does not exist in json file + static const ReturnValue_t PARAM_NOT_EXISTS = MAKE_RETURN_CODE(3); + + /** + * @brief Constructor + * + * @param fullname Name with absolute path of json file containing the parameters to set. + */ + ArcsecJsonParamBase(std::string setName); + + /** + * @brief Fills a buffer with a parameter set + * + * @param fullname The name including the absolute path of the json file containing the + * parameter set. + * @param buffer Pointer to the buffer the command will be written to + */ + ReturnValue_t create(std::string fullname, uint8_t* buffer); + + /** + * @brief Returns the size of the parameter command. + */ + virtual size_t getSize() = 0; + + protected: + /** + * @brief Reads the value of a parameter from a json set + * + * @param name The name of the parameter + * @param value The string representation of the read value + * + * @return RETURN_OK if successful, otherwise PARAM_NOT_EXISTS + */ + ReturnValue_t getParam(const std::string name, std::string& value); + + /** + * @brief Converts empty string which is equal to define a value as zero. + */ + void convertEmpty(std::string& value); + + /** + * @brief This function adds a float represented as string to a buffer + * + * @param value The float in string representation to add + * @param buffer Pointer to the buffer the float will be written to + */ + void addfloat(const std::string value, uint8_t* buffer); + + /** + * @brief This function adds a uint8_t represented as string to a buffer + * + * @param value The uint8_t in string representation to add + * @param buffer Pointer to the buffer the uint8_t will be written to + */ + void adduint8(const std::string value, uint8_t* buffer); + + /** + * @brief This function adds a int16_t represented as string to a buffer + * + * @param value The int16_t in string representation to add + * @param buffer Pointer to the buffer the int16_t will be written to + */ + void addint16(const std::string value, uint8_t* buffer); + + /** + * @brief This function adds a uint16_t represented as string to a buffer + * + * @param value The uint16_t in string representation to add + * @param buffer Pointer to the buffer the uint16_t will be written to + */ + void adduint16(const std::string value, uint8_t* buffer); + + /** + * @brief This function adds a uint32_t represented as string to a buffer + * + * @param value The uint32_t in string representation to add + * @param buffer Pointer to the buffer the uint32_t will be written to + */ + void adduint32(const std::string value, uint8_t* buffer); + + void addSetParamHeader(uint8_t* buffer, uint8_t setId); + + private: + json properties; + json set; + std::string setName; + + /** + * @brief This function must be implemented by the derived class to define creation of a + * parameter command. + */ + virtual ReturnValue_t createCommand(uint8_t* buffer) = 0; + + /** + * @brief Initializes the properties json object and the set json object + * + * @param fullname Name including absolute path to json file + * @param setName The name of the set to work on + * + * @param return JSON_FILE_NOT_EXISTS if specified file does not exist, otherwise + * RETURN_OK + */ + ReturnValue_t init(const std::string filename); + + void createJsonObject(const std::string fullname); + + /** + * @brief Extracts the json set object form the json file + * + * @param setName The name of the set to create the json object from + */ + ReturnValue_t initSet(); +}; + +#endif /* BSP_Q7S_DEVICES_STARTRACKER_ARCSECJSONPARAMBASE_H_ */ diff --git a/linux/devices/startracker/CMakeLists.txt b/linux/devices/startracker/CMakeLists.txt new file mode 100644 index 00000000..be2bf861 --- /dev/null +++ b/linux/devices/startracker/CMakeLists.txt @@ -0,0 +1,7 @@ +target_sources(${OBSW_NAME} PRIVATE + StarTrackerHandler.cpp + StarTrackerJsonCommands.cpp + ArcsecDatalinkLayer.cpp + ArcsecJsonParamBase.cpp + StrHelper.cpp +) \ No newline at end of file diff --git a/linux/devices/startracker/StarTrackerHandler.cpp b/linux/devices/startracker/StarTrackerHandler.cpp new file mode 100644 index 00000000..d06b73f1 --- /dev/null +++ b/linux/devices/startracker/StarTrackerHandler.cpp @@ -0,0 +1,2074 @@ +#include "StarTrackerHandler.h" + +#include + +#include + +#include "OBSWConfig.h" +#include "StarTrackerJsonCommands.h" +extern "C" { +#include +#include +#include + +#include "common/misc.h" +} + +StarTrackerHandler::StarTrackerHandler(object_id_t objectId, object_id_t comIF, CookieIF* comCookie, + StrHelper* strHelper) + : DeviceHandlerBase(objectId, comIF, comCookie), + temperatureSet(this), + versionSet(this), + powerSet(this), + interfaceSet(this), + timeSet(this), + solutionSet(this), + histogramSet(this), + checksumSet(this), + cameraSet(this), + limitsSet(this), + loglevelSet(this), + mountingSet(this), + imageProcessorSet(this), + centroidingSet(this), + lisaSet(this), + matchingSet(this), + trackingSet(this), + validationSet(this), + algoSet(this), + subscriptionSet(this), + logSubscriptionSet(this), + debugCameraSet(this), + strHelper(strHelper) { + if (comCookie == nullptr) { + sif::error << "StarTrackerHandler: Invalid com cookie" << std::endl; + } + if (strHelper == nullptr) { + sif::error << "StarTrackerHandler: Invalid str image loader" << std::endl; + } + eventQueue = QueueFactory::instance()->createMessageQueue(EventMessage::EVENT_MESSAGE_SIZE * 5); +} + +StarTrackerHandler::~StarTrackerHandler() {} + +ReturnValue_t StarTrackerHandler::initialize() { + ReturnValue_t result = RETURN_OK; + result = DeviceHandlerBase::initialize(); + if (result != RETURN_OK) { + return result; + } + + EventManagerIF* manager = ObjectManager::instance()->get(objects::EVENT_MANAGER); + if (manager == nullptr) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::error << "StarTrackerHandler::initialize: 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(StrHelper::IMAGE_UPLOAD_FAILED), + event::getEventId(StrHelper::FIRMWARE_UPDATE_FAILED)); + if (result != RETURN_OK) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "StarTrackerHandler::initialize: Failed to subscribe to events from " + " str helper" + << std::endl; +#endif + return ObjectManagerIF::CHILD_INIT_FAILED; + } + + result = strHelper->setComIF(communicationInterface); + if (result != RETURN_OK) { + return ObjectManagerIF::CHILD_INIT_FAILED; + } + strHelper->setComCookie(comCookie); + return RETURN_OK; +} + +ReturnValue_t StarTrackerHandler::executeAction(ActionId_t actionId, MessageQueueId_t commandedBy, + const uint8_t* data, size_t size) { + ReturnValue_t result = RETURN_OK; + + switch (actionId) { + case (startracker::STOP_IMAGE_LOADER): { + strHelper->stopProcess(); + return EXECUTION_FINISHED; + } + case (startracker::SET_JSON_FILE_NAME): { + if (size > MAX_PATH_SIZE) { + return FILE_PATH_TOO_LONG; + } + paramJsonFile = std::string(reinterpret_cast(data), size); + return EXECUTION_FINISHED; + } + case (startracker::DISABLE_TIMESTAMP_GENERATION): + strHelper->disableTimestamping(); + return EXECUTION_FINISHED; + case (startracker::ENABLE_TIMESTAMP_GENERATION): + strHelper->enableTimestamping(); + return EXECUTION_FINISHED; + default: + break; + } + + if (strHelperExecuting == true) { + return STR_HELPER_EXECUTING; + } + + result = checkMode(actionId); + if (result != RETURN_OK) { + return result; + } + + result = checkCommand(actionId); + if (result != RETURN_OK) { + return result; + } + + // Intercept image loader commands which do not follow the common DHB communication flow + switch (actionId) { + case (startracker::UPLOAD_IMAGE): { + result = DeviceHandlerBase::acceptExternalDeviceCommands(); + if (result != RETURN_OK) { + return result; + } + if (size > MAX_PATH_SIZE + MAX_FILE_NAME) { + return FILE_PATH_TOO_LONG; + } + result = strHelper->startImageUpload(std::string(reinterpret_cast(data), size)); + if (result != RETURN_OK) { + return result; + } + strHelperExecuting = true; + return EXECUTION_FINISHED; + } + case (startracker::DOWNLOAD_IMAGE): { + result = DeviceHandlerBase::acceptExternalDeviceCommands(); + if (result != RETURN_OK) { + return result; + } + if (size > MAX_PATH_SIZE) { + return FILE_PATH_TOO_LONG; + } + result = + strHelper->startImageDownload(std::string(reinterpret_cast(data), size)); + if (result != RETURN_OK) { + return result; + } + strHelperExecuting = true; + return EXECUTION_FINISHED; + } + case (startracker::FLASH_READ): { + result = DeviceHandlerBase::acceptExternalDeviceCommands(); + if (result != RETURN_OK) { + return result; + } + result = executeFlashReadCommand(data, size); + if (result != RETURN_OK) { + return result; + } + strHelperExecuting = true; + return EXECUTION_FINISHED; + } + case (startracker::CHANGE_IMAGE_DOWNLOAD_FILE): { + if (size > MAX_FILE_NAME) { + return FILENAME_TOO_LONG; + } + strHelper->setDownloadImageName(std::string(reinterpret_cast(data), size)); + return EXECUTION_FINISHED; + } + case (startracker::SET_FLASH_READ_FILENAME): { + if (size > MAX_FILE_NAME) { + return FILENAME_TOO_LONG; + } + strHelper->setFlashReadFilename(std::string(reinterpret_cast(data), size)); + return EXECUTION_FINISHED; + } + case (startracker::FIRMWARE_UPDATE): { + result = DeviceHandlerBase::acceptExternalDeviceCommands(); + if (result != RETURN_OK) { + return result; + } + if (size > MAX_PATH_SIZE + MAX_FILE_NAME) { + return FILE_PATH_TOO_LONG; + } + result = + strHelper->startFirmwareUpdate(std::string(reinterpret_cast(data), size)); + if (result != RETURN_OK) { + return result; + } + strHelperExecuting = true; + return EXECUTION_FINISHED; + } + default: + break; + } + return DeviceHandlerBase::executeAction(actionId, commandedBy, data, size); +} + +void StarTrackerHandler::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 << "CCSDSHandler::checkEvents: Did not subscribe to this event message" + << std::endl; + break; + } + } +} + +Submode_t StarTrackerHandler::getInitialSubmode() { return SUBMODE_BOOTLOADER; } + +void StarTrackerHandler::doStartUp() { + switch (startupState) { + case StartupState::IDLE: + startupState = StartupState::CHECK_PROGRAM; + return; + case StartupState::BOOT_BOOTLOADER: + // This step is required in case the star tracker is already in firmware mode to harmonize + // the device handler's submode to the star tracker's mode + return; + case StartupState::DONE: + submode = SUBMODE_BOOTLOADER; + startupState = StartupState::IDLE; + break; + default: + return; + } + setMode(_MODE_TO_ON); +} + +void StarTrackerHandler::doShutDown() { + // If the star tracker is shutdown also stop all running processes in the image loader task + strHelper->stopProcess(); + setMode(_MODE_POWER_DOWN); +} + +void StarTrackerHandler::doOffActivity() { + startupState = StartupState::IDLE; + internalState = InternalState::IDLE; +} + +ReturnValue_t StarTrackerHandler::buildNormalDeviceCommand(DeviceCommandId_t* id) { + switch (normalState) { + case NormalState::TEMPERATURE_REQUEST: + *id = startracker::REQ_TEMPERATURE; + normalState = NormalState::SOLUTION_REQUEST; + break; + case NormalState::SOLUTION_REQUEST: + *id = startracker::REQ_SOLUTION; + normalState = NormalState::TEMPERATURE_REQUEST; + break; + default: + sif::debug << "StarTrackerHandler::buildNormalDeviceCommand: Invalid normal step" + << std::endl; + return NOTHING_TO_SEND; + } + return buildCommandFromCommand(*id, NULL, 0); +} + +ReturnValue_t StarTrackerHandler::buildTransitionDeviceCommand(DeviceCommandId_t* id) { + switch (internalState) { + case InternalState::BOOT: + *id = startracker::BOOT; + bootCountdown.setTimeout(BOOT_TIMEOUT); + internalState = InternalState::BOOT_DELAY; + return buildCommandFromCommand(*id, nullptr, 0); + case InternalState::REQ_VERSION: + internalState = InternalState::VERIFY_BOOT; + // Again read program to check if firmware boot was successful + *id = startracker::REQ_VERSION; + return buildCommandFromCommand(*id, nullptr, 0); + case InternalState::LOGLEVEL: + internalState = InternalState::WAIT_FOR_EXECUTION; + *id = startracker::LOGLEVEL; + return buildCommandFromCommand(*id, reinterpret_cast(paramJsonFile.c_str()), + paramJsonFile.size()); + case InternalState::LIMITS: + internalState = InternalState::WAIT_FOR_EXECUTION; + *id = startracker::LIMITS; + return buildCommandFromCommand(*id, reinterpret_cast(paramJsonFile.c_str()), + paramJsonFile.size()); + case InternalState::TRACKING: + internalState = InternalState::WAIT_FOR_EXECUTION; + *id = startracker::TRACKING; + return buildCommandFromCommand(*id, reinterpret_cast(paramJsonFile.c_str()), + paramJsonFile.size()); + case InternalState::MOUNTING: + internalState = InternalState::WAIT_FOR_EXECUTION; + *id = startracker::MOUNTING; + return buildCommandFromCommand(*id, reinterpret_cast(paramJsonFile.c_str()), + paramJsonFile.size()); + case InternalState::IMAGE_PROCESSOR: + internalState = InternalState::WAIT_FOR_EXECUTION; + *id = startracker::IMAGE_PROCESSOR; + return buildCommandFromCommand(*id, reinterpret_cast(paramJsonFile.c_str()), + paramJsonFile.size()); + case InternalState::CAMERA: + internalState = InternalState::WAIT_FOR_EXECUTION; + *id = startracker::CAMERA; + return buildCommandFromCommand(*id, reinterpret_cast(paramJsonFile.c_str()), + paramJsonFile.size()); + case InternalState::CENTROIDING: + internalState = InternalState::WAIT_FOR_EXECUTION; + *id = startracker::CENTROIDING; + return buildCommandFromCommand(*id, reinterpret_cast(paramJsonFile.c_str()), + paramJsonFile.size()); + case InternalState::LISA: + internalState = InternalState::WAIT_FOR_EXECUTION; + *id = startracker::LISA; + return buildCommandFromCommand(*id, reinterpret_cast(paramJsonFile.c_str()), + paramJsonFile.size()); + case InternalState::MATCHING: + internalState = InternalState::WAIT_FOR_EXECUTION; + *id = startracker::MATCHING; + return buildCommandFromCommand(*id, reinterpret_cast(paramJsonFile.c_str()), + paramJsonFile.size()); + case InternalState::VALIDATION: + internalState = InternalState::WAIT_FOR_EXECUTION; + *id = startracker::VALIDATION; + return buildCommandFromCommand(*id, reinterpret_cast(paramJsonFile.c_str()), + paramJsonFile.size()); + case InternalState::ALGO: + internalState = InternalState::WAIT_FOR_EXECUTION; + *id = startracker::ALGO; + return buildCommandFromCommand(*id, reinterpret_cast(paramJsonFile.c_str()), + paramJsonFile.size()); + case InternalState::LOG_SUBSCRIPTION: + internalState = InternalState::WAIT_FOR_EXECUTION; + *id = startracker::LOGSUBSCRIPTION; + return buildCommandFromCommand(*id, reinterpret_cast(paramJsonFile.c_str()), + paramJsonFile.size()); + case InternalState::DEBUG_CAMERA: + internalState = InternalState::WAIT_FOR_EXECUTION; + *id = startracker::DEBUG_CAMERA; + return buildCommandFromCommand(*id, reinterpret_cast(paramJsonFile.c_str()), + paramJsonFile.size()); + case InternalState::BOOT_BOOTLOADER: + internalState = InternalState::BOOTLOADER_CHECK; + *id = startracker::SWITCH_TO_BOOTLOADER_PROGRAM; + return buildCommandFromCommand(*id, nullptr, 0); + case InternalState::BOOTLOADER_CHECK: + *id = startracker::REQ_VERSION; + return buildCommandFromCommand(*id, nullptr, 0); + default: + break; + } + switch (startupState) { + case StartupState::CHECK_PROGRAM: + startupState = StartupState::WAIT_CHECK_PROGRAM; + *id = startracker::REQ_VERSION; + return buildCommandFromCommand(*id, nullptr, 0); + break; + case StartupState::BOOT_BOOTLOADER: + startupState = StartupState::CHECK_PROGRAM; + *id = startracker::SWITCH_TO_BOOTLOADER_PROGRAM; + return buildCommandFromCommand(*id, nullptr, 0); + break; + default: + break; + } + return NOTHING_TO_SEND; +} + +ReturnValue_t StarTrackerHandler::buildCommandFromCommand(DeviceCommandId_t deviceCommand, + const uint8_t* commandData, + size_t commandDataLen) { + ReturnValue_t result = RETURN_OK; + switch (deviceCommand) { + case (startracker::PING_REQUEST): { + preparePingRequest(); + return RETURN_OK; + } + case (startracker::REQ_TIME): { + prepareTimeRequest(); + return RETURN_OK; + } + case (startracker::BOOT): { + prepareBootCommand(); + return RETURN_OK; + } + case (startracker::REQ_VERSION): { + prepareVersionRequest(); + return RETURN_OK; + } + case (startracker::REQ_INTERFACE): { + prepareInterfaceRequest(); + return RETURN_OK; + } + case (startracker::REQ_POWER): { + preparePowerRequest(); + return RETURN_OK; + } + case (startracker::SWITCH_TO_BOOTLOADER_PROGRAM): { + prepareSwitchToBootloaderCmd(); + return RETURN_OK; + } + case (startracker::TAKE_IMAGE): { + prepareTakeImageCommand(commandData); + return RETURN_OK; + } + case (startracker::SUBSCRIPTION): { + Subscription subscription; + result = prepareParamCommand(commandData, commandDataLen, subscription); + return RETURN_OK; + } + case (startracker::REQ_SOLUTION): { + prepareSolutionRequest(); + return RETURN_OK; + } + case (startracker::REQ_TEMPERATURE): { + prepareTemperatureRequest(); + return RETURN_OK; + } + case (startracker::REQ_HISTOGRAM): { + prepareHistogramRequest(); + return RETURN_OK; + } + case (startracker::LIMITS): { + Limits limits; + result = prepareParamCommand(commandData, commandDataLen, limits); + return result; + } + case (startracker::MOUNTING): { + Mounting mounting; + result = prepareParamCommand(commandData, commandDataLen, mounting); + return result; + } + case (startracker::IMAGE_PROCESSOR): { + ImageProcessor imageProcessor; + result = prepareParamCommand(commandData, commandDataLen, imageProcessor); + return result; + } + case (startracker::CAMERA): { + Camera camera; + result = prepareParamCommand(commandData, commandDataLen, camera); + return result; + } + case (startracker::CENTROIDING): { + Centroiding centroiding; + result = prepareParamCommand(commandData, commandDataLen, centroiding); + return result; + } + case (startracker::LISA): { + Lisa lisa; + result = prepareParamCommand(commandData, commandDataLen, lisa); + return result; + } + case (startracker::MATCHING): { + Matching matching; + result = prepareParamCommand(commandData, commandDataLen, matching); + return result; + } + case (startracker::VALIDATION): { + Validation validation; + result = prepareParamCommand(commandData, commandDataLen, validation); + return result; + } + case (startracker::ALGO): { + Algo algo; + result = prepareParamCommand(commandData, commandDataLen, algo); + return result; + } + case (startracker::TRACKING): { + Tracking tracking; + result = prepareParamCommand(commandData, commandDataLen, tracking); + return result; + } + case (startracker::LOGLEVEL): { + LogLevel logLevel; + result = prepareParamCommand(commandData, commandDataLen, logLevel); + return result; + } + case (startracker::LOGSUBSCRIPTION): { + LogSubscription logSubscription; + result = prepareParamCommand(commandData, commandDataLen, logSubscription); + return result; + } + case (startracker::DEBUG_CAMERA): { + DebugCamera debugCamera; + result = prepareParamCommand(commandData, commandDataLen, debugCamera); + return result; + } + case (startracker::CHECKSUM): { + result = prepareChecksumCommand(commandData, commandDataLen); + return result; + } + case (startracker::REQ_CAMERA): { + result = prepareRequestCameraParams(); + return result; + } + case (startracker::REQ_LIMITS): { + result = prepareRequestLimitsParams(); + return result; + } + case (startracker::REQ_LOG_LEVEL): { + result = prepareRequestLogLevelParams(); + return result; + } + case (startracker::REQ_MOUNTING): { + result = prepareRequestMountingParams(); + return result; + } + case (startracker::REQ_IMAGE_PROCESSOR): { + result = prepareRequestImageProcessorParams(); + return result; + } + case (startracker::REQ_CENTROIDING): { + result = prepareRequestCentroidingParams(); + return result; + } + case (startracker::REQ_LISA): { + result = prepareRequestLisaParams(); + return result; + } + case (startracker::REQ_MATCHING): { + result = prepareRequestMatchingParams(); + return result; + } + case (startracker::REQ_TRACKING): { + result = prepareRequestTrackingParams(); + return result; + } + case (startracker::REQ_VALIDATION): { + result = prepareRequestValidationParams(); + return result; + } + case (startracker::REQ_ALGO): { + result = prepareRequestAlgoParams(); + return result; + } + case (startracker::REQ_SUBSCRIPTION): { + result = prepareRequestSubscriptionParams(); + return result; + } + case (startracker::REQ_LOG_SUBSCRIPTION): { + result = prepareRequestLogSubscriptionParams(); + return result; + } + case (startracker::REQ_DEBUG_CAMERA): { + result = prepareRequestDebugCameraParams(); + return result; + } + default: + return DeviceHandlerIF::COMMAND_NOT_IMPLEMENTED; + } + return HasReturnvaluesIF::RETURN_FAILED; +} + +void StarTrackerHandler::fillCommandAndReplyMap() { + /** Reply lengths are unknown because of the slip encoding. Thus always maximum reply size + * is specified */ + this->insertInCommandAndReplyMap(startracker::PING_REQUEST, 3, nullptr, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandMap(startracker::BOOT); + this->insertInCommandAndReplyMap(startracker::REQ_VERSION, 3, &versionSet, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::REQ_TIME, 3, &timeSet, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandMap(startracker::UPLOAD_IMAGE); + this->insertInCommandMap(startracker::DOWNLOAD_IMAGE); + this->insertInCommandAndReplyMap(startracker::REQ_POWER, 3, &powerSet, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::REQ_INTERFACE, 3, &interfaceSet, + startracker::MAX_FRAME_SIZE * 2 + 2); + // Reboot has no reply. Star tracker reboots immediately + this->insertInCommandMap(startracker::SWITCH_TO_BOOTLOADER_PROGRAM); + this->insertInCommandAndReplyMap(startracker::SUBSCRIPTION, 3, nullptr, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::REQ_SOLUTION, 3, &solutionSet, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::REQ_TEMPERATURE, 3, &temperatureSet, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::REQ_HISTOGRAM, 3, &histogramSet, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::LOGLEVEL, 3, nullptr, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::LOGSUBSCRIPTION, 3, nullptr, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::DEBUG_CAMERA, 3, nullptr, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::LIMITS, 3, nullptr, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::MOUNTING, 3, nullptr, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::IMAGE_PROCESSOR, 3, nullptr, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::CAMERA, 3, nullptr, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::CENTROIDING, 3, nullptr, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::LISA, 3, nullptr, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::MATCHING, 3, nullptr, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::TRACKING, 3, nullptr, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::VALIDATION, 3, nullptr, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::ALGO, 3, nullptr, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::TAKE_IMAGE, 3, nullptr, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::CHECKSUM, 3, &checksumSet, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::REQ_CAMERA, 3, &cameraSet, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::REQ_LIMITS, 3, &limitsSet, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::REQ_LOG_LEVEL, 3, &loglevelSet, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::REQ_MOUNTING, 3, &mountingSet, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::REQ_IMAGE_PROCESSOR, 3, &imageProcessorSet, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::REQ_CENTROIDING, 3, ¢roidingSet, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::REQ_LISA, 3, &lisaSet, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::REQ_MATCHING, 3, &matchingSet, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::REQ_TRACKING, 3, &trackingSet, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::REQ_VALIDATION, 3, &validationSet, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::REQ_ALGO, 3, &algoSet, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::REQ_SUBSCRIPTION, 3, &subscriptionSet, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::REQ_LOG_SUBSCRIPTION, 3, &logSubscriptionSet, + startracker::MAX_FRAME_SIZE * 2 + 2); + this->insertInCommandAndReplyMap(startracker::REQ_DEBUG_CAMERA, 3, &debugCameraSet, + startracker::MAX_FRAME_SIZE * 2 + 2); +} + +ReturnValue_t StarTrackerHandler::isModeCombinationValid(Mode_t mode, Submode_t submode) { + if (this->mode == MODE_NORMAL && mode == MODE_ON) { + return TRANS_NOT_ALLOWED; + } + switch (mode) { + case MODE_OFF: + case MODE_NORMAL: + case MODE_RAW: + if (submode == SUBMODE_NONE) { + return RETURN_OK; + } else { + return INVALID_SUBMODE; + } + case MODE_ON: + if (submode == SUBMODE_BOOTLOADER || submode == SUBMODE_FIRMWARE) { + return RETURN_OK; + } else { + return INVALID_SUBMODE; + } + default: + return HasModesIF::INVALID_MODE; + } +} + +void StarTrackerHandler::doTransition(Mode_t modeFrom, Submode_t subModeFrom) { + switch (mode) { + case _MODE_TO_ON: + doOnTransition(subModeFrom); + break; + case _MODE_TO_RAW: + setMode(MODE_RAW); + break; + case _MODE_TO_NORMAL: + doNormalTransition(modeFrom, subModeFrom); + break; + case _MODE_POWER_DOWN: + internalState = InternalState::IDLE; + startupState = StartupState::IDLE; + break; + default: + break; + } +} + +void StarTrackerHandler::doOnTransition(Submode_t subModeFrom) { + if (submode == SUBMODE_BOOTLOADER && subModeFrom == SUBMODE_FIRMWARE) { + bootBootloader(); + } else if (submode == SUBMODE_FIRMWARE && subModeFrom == SUBMODE_FIRMWARE) { + setMode(MODE_ON); + } else if (submode == SUBMODE_FIRMWARE && subModeFrom == SUBMODE_BOOTLOADER) { + bootFirmware(MODE_ON); + } else if (submode == SUBMODE_BOOTLOADER && subModeFrom == SUBMODE_BOOTLOADER) { + setMode(MODE_ON); + } else if (submode == SUBMODE_BOOTLOADER && subModeFrom == SUBMODE_NONE) { + setMode(MODE_ON); + } else if (submode == SUBMODE_FIRMWARE && subModeFrom == SUBMODE_NONE) { + setMode(MODE_ON); + } +} + +void StarTrackerHandler::doNormalTransition(Mode_t modeFrom, Submode_t subModeFrom) { + if (subModeFrom == SUBMODE_FIRMWARE) { + setMode(MODE_NORMAL); + } else if (subModeFrom == SUBMODE_BOOTLOADER) { + bootFirmware(MODE_NORMAL); + } else if (modeFrom == MODE_NORMAL && subModeFrom == SUBMODE_NONE) { + // Device handler already in mode normal + setMode(MODE_NORMAL); + } +} + +void StarTrackerHandler::bootFirmware(Mode_t toMode) { + switch (internalState) { + case InternalState::IDLE: + internalState = InternalState::BOOT; + break; + case InternalState::BOOT_DELAY: + if (bootCountdown.hasTimedOut()) { + internalState = InternalState::REQ_VERSION; + } + break; + case InternalState::FAILED_FIRMWARE_BOOT: + internalState = InternalState::IDLE; + break; + case InternalState::DONE: + setMode(toMode); + internalState = InternalState::IDLE; + break; + default: + return; + } +} + +void StarTrackerHandler::bootBootloader() { + if (internalState == InternalState::IDLE) { + internalState = InternalState::BOOT_BOOTLOADER; + } else if (internalState == InternalState::BOOTING_BOOTLOADER_FAILED) { + internalState = InternalState::IDLE; + } else if (internalState == InternalState::DONE) { + internalState = InternalState::IDLE; + setMode(MODE_ON); + } +} + +ReturnValue_t StarTrackerHandler::scanForReply(const uint8_t* start, size_t remainingSize, + DeviceCommandId_t* foundId, size_t* foundLen) { + ReturnValue_t result = RETURN_OK; + size_t bytesLeft = 0; + + result = dataLinkLayer.decodeFrame(start, remainingSize, &bytesLeft); + switch (result) { + case ArcsecDatalinkLayer::DEC_IN_PROGRESS: { + remainingSize = bytesLeft; + // Need a second doSendRead pass to reaa in whole packet + return IGNORE_REPLY_DATA; + } + case RETURN_OK: { + break; + } + default: + remainingSize = bytesLeft; + return result; + } + + switch (dataLinkLayer.getReplyFrameType()) { + case TMTC_ACTIONREPLY: { + *foundLen = remainingSize - bytesLeft; + result = scanForActionReply(foundId); + break; + } + case TMTC_SETPARAMREPLY: { + *foundLen = remainingSize - bytesLeft; + result = scanForSetParameterReply(foundId); + break; + } + case TMTC_PARAMREPLY: { + *foundLen = remainingSize - bytesLeft; + result = scanForGetParameterReply(foundId); + break; + } + case TMTC_TELEMETRYREPLYA: + case TMTC_TELEMETRYREPLY: { + *foundLen = remainingSize - bytesLeft; + result = scanForTmReply(foundId); + break; + } + default: { + sif::debug << "StarTrackerHandler::scanForReply: Reply has invalid type id" << std::endl; + result = RETURN_FAILED; + } + } + + remainingSize = bytesLeft; + + return result; +} + +ReturnValue_t StarTrackerHandler::interpretDeviceReply(DeviceCommandId_t id, + const uint8_t* packet) { + ReturnValue_t result = RETURN_OK; + + switch (id) { + case (startracker::REQ_TIME): { + result = handleTm(timeSet, startracker::TimeSet::SIZE); + break; + } + case (startracker::PING_REQUEST): { + result = handlePingReply(); + break; + } + case (startracker::BOOT): + case (startracker::TAKE_IMAGE): + break; + case (startracker::CHECKSUM): { + result = handleChecksumReply(); + break; + } + case (startracker::REQ_VERSION): { + result = handleTm(versionSet, startracker::VersionSet::SIZE); + if (result != RETURN_OK) { + return result; + } + result = checkProgram(); + if (result != RETURN_OK) { + return result; + } + break; + } + case (startracker::REQ_INTERFACE): { + result = handleTm(interfaceSet, startracker::InterfaceSet::SIZE); + break; + } + case (startracker::REQ_POWER): { + result = handleTm(powerSet, startracker::PowerSet::SIZE); + break; + } + case (startracker::REQ_SOLUTION): { + result = handleTm(solutionSet, startracker::SolutionSet::SIZE); + break; + } + case (startracker::REQ_TEMPERATURE): { + result = handleTm(temperatureSet, startracker::TemperatureSet::SIZE); + break; + } + case (startracker::REQ_HISTOGRAM): { + result = handleTm(histogramSet, startracker::HistogramSet::SIZE); + break; + } + case (startracker::SUBSCRIPTION): + case (startracker::LOGLEVEL): + case (startracker::LOGSUBSCRIPTION): + case (startracker::DEBUG_CAMERA): + case (startracker::LIMITS): + case (startracker::MOUNTING): + case (startracker::CAMERA): + case (startracker::CENTROIDING): + case (startracker::LISA): + case (startracker::MATCHING): + case (startracker::TRACKING): + case (startracker::VALIDATION): + case (startracker::IMAGE_PROCESSOR): + case (startracker::ALGO): { + result = handleSetParamReply(); + break; + } + case (startracker::REQ_CAMERA): { + handleParamRequest(cameraSet, startracker::CameraSet::SIZE); + break; + } + case (startracker::REQ_LIMITS): { + handleParamRequest(limitsSet, startracker::LimitsSet::SIZE); + break; + } + case (startracker::REQ_LOG_LEVEL): { + handleParamRequest(loglevelSet, startracker::LogLevelSet::SIZE); + break; + } + case (startracker::REQ_MOUNTING): { + handleParamRequest(mountingSet, startracker::MountingSet::SIZE); + break; + } + case (startracker::REQ_IMAGE_PROCESSOR): { + handleParamRequest(imageProcessorSet, startracker::ImageProcessorSet::SIZE); + break; + } + case (startracker::REQ_CENTROIDING): { + handleParamRequest(centroidingSet, startracker::CentroidingSet::SIZE); + break; + } + case (startracker::REQ_LISA): { + handleParamRequest(lisaSet, startracker::LisaSet::SIZE); + break; + } + case (startracker::REQ_MATCHING): { + handleParamRequest(matchingSet, startracker::MatchingSet::SIZE); + break; + } + case (startracker::REQ_TRACKING): { + handleParamRequest(trackingSet, startracker::TrackingSet::SIZE); + break; + } + case (startracker::REQ_VALIDATION): { + handleParamRequest(validationSet, startracker::ValidationSet::SIZE); + break; + } + case (startracker::REQ_ALGO): { + handleParamRequest(algoSet, startracker::AlgoSet::SIZE); + break; + } + case (startracker::REQ_SUBSCRIPTION): { + handleParamRequest(subscriptionSet, startracker::SubscriptionSet::SIZE); + break; + } + case (startracker::REQ_LOG_SUBSCRIPTION): { + handleParamRequest(logSubscriptionSet, startracker::LogSubscriptionSet::SIZE); + break; + } + case (startracker::REQ_DEBUG_CAMERA): { + handleParamRequest(debugCameraSet, startracker::DebugCameraSet::SIZE); + break; + } + default: { + sif::debug << "StarTrackerHandler::interpretDeviceReply: Unknown device reply id:" << id + << std::endl; + result = DeviceHandlerIF::UNKNOWN_DEVICE_REPLY; + } + } + return result; +} + +void StarTrackerHandler::setNormalDatapoolEntriesInvalid() {} + +uint32_t StarTrackerHandler::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { + return DEFAULT_TRANSITION_DELAY; +} + +ReturnValue_t StarTrackerHandler::initializeLocalDataPool(localpool::DataPool& localDataPoolMap, + LocalDataPoolManager& poolManager) { + localDataPoolMap.emplace(startracker::TICKS_TIME_SET, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::TIME_TIME_SET, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::RUN_TIME, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::UNIX_TIME, new PoolEntry({0})); + + localDataPoolMap.emplace(startracker::TICKS_VERSION_SET, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::TIME_VERSION_SET, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::PROGRAM, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::MAJOR, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::MINOR, new PoolEntry({0})); + + localDataPoolMap.emplace(startracker::TICKS_INTERFACE_SET, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::TIME_INTERFACE_SET, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::FRAME_COUNT, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CHECKSUM_ERROR_COUNT, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::SET_PARAM_COUNT, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::SET_PARAM_REPLY_COUNT, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::PARAM_REQUEST_COUNT, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::PARAM_REPLY_COUNT, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::REQ_TM_COUNT, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::TM_REPLY_COUNT, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::ACTION_REQ_COUNT, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::ACTION_REPLY_COUNT, new PoolEntry({0})); + + localDataPoolMap.emplace(startracker::TICKS_POWER_SET, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::TIME_POWER_SET, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::MCU_CURRENT, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::MCU_VOLTAGE, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::FPGA_CORE_CURRENT, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::FPGA_CORE_VOLTAGE, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::FPGA_18_CURRENT, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::FPGA_18_VOLTAGE, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::FPGA_25_CURRENT, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::FPGA_25_VOLTAGE, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CMV_21_CURRENT, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CMV_21_VOLTAGE, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CMV_PIX_CURRENT, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CMV_PIX_VOLTAGE, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CMV_33_CURRENT, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CMV_33_VOLTAGE, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CMV_RES_CURRENT, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CMV_RES_VOLTAGE, new PoolEntry({0})); + + localDataPoolMap.emplace(startracker::TICKS_TEMPERATURE_SET, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::TIME_TEMPERATURE_SET, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::MCU_TEMPERATURE, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CMOS_TEMPERATURE, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::FPGA_TEMPERATURE, new PoolEntry({0})); + + localDataPoolMap.emplace(startracker::TICKS_SOLUTION_SET, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::TIME_SOLUTION_SET, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CALI_QW, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CALI_QX, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CALI_QY, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CALI_QZ, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::TRACK_CONFIDENCE, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::TRACK_QW, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::TRACK_QX, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::TRACK_QY, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::TRACK_QZ, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::TRACK_REMOVED, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::STARS_CENTROIDED, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::STARS_MATCHED_DATABASE, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LISA_QW, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LISA_QX, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LISA_QY, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LISA_QZ, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LISA_PERC_CLOSE, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LISA_NR_CLOSE, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::TRUST_WORTHY, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::STABLE_COUNT, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::SOLUTION_STRATEGY, new PoolEntry({0})); + + localDataPoolMap.emplace(startracker::TICKS_HISTOGRAM_SET, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::TIME_HISTOGRAM_SET, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BINA0, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BINA1, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BINA2, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BINA3, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BINA4, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BINA5, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BINA6, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BINA7, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BINA8, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BINB0, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BINB1, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BINB2, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BINB3, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BINB4, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BINB5, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BINB6, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BINB7, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BINB8, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BINC0, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BINC1, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BINC2, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BINC3, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BINC4, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BINC5, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BINC6, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BINC7, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BINC8, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BIND0, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BIND1, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BIND2, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BIND3, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BIND4, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BIND5, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BIND6, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BIND7, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::HISTOGRAM_BIND8, new PoolEntry({0})); + + localDataPoolMap.emplace(startracker::CAMERA_MODE, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::FOCALLENGTH, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::EXPOSURE, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::INTERVAL, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CAMERA_OFFSET, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::PGAGAIN, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::ADCGAIN, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CAM_REG1, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CAM_VAL1, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CAM_REG2, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CAM_VAL2, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CAM_REG3, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CAM_VAL3, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CAM_REG4, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CAM_VAL4, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CAM_REG5, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CAM_VAL5, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CAM_REG6, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CAM_VAL6, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CAM_REG7, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CAM_VAL7, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CAM_REG8, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CAM_VAL8, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CAM_FREQ_1, new PoolEntry({0})); + + localDataPoolMap.emplace(startracker::LIMITS_ACTION, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LIMITS_FPGA18CURRENT, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LIMITS_FPGA25CURRENT, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LIMITS_FPGA10CURRENT, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LIMITS_MCUCURRENT, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LIMITS_CMOS21CURRENT, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LIMITS_CMOSPIXCURRENT, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LIMITS_CMOS33CURRENT, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LIMITS_CMOSVRESCURRENT, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LIMITS_CMOSTEMPERATURE, new PoolEntry({0})); + + localDataPoolMap.emplace(startracker::LOGLEVEL1, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LOGLEVEL2, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LOGLEVEL3, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LOGLEVEL4, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LOGLEVEL5, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LOGLEVEL6, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LOGLEVEL7, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LOGLEVEL8, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LOGLEVEL9, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LOGLEVEL10, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LOGLEVEL11, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LOGLEVEL12, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LOGLEVEL13, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LOGLEVEL14, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LOGLEVEL15, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LOGLEVEL16, new PoolEntry({0})); + + localDataPoolMap.emplace(startracker::MOUNTING_QW, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::MOUNTING_QX, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::MOUNTING_QY, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::MOUNTING_QZ, new PoolEntry({0})); + + localDataPoolMap.emplace(startracker::IMAGE_PROCESSOR_MODE, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::IMAGE_PROCESSOR_STORE, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::IMAGE_PROCESSOR_SIGNALTHRESHOLD, + new PoolEntry({0})); + localDataPoolMap.emplace(startracker::IMAGE_PROCESSOR_DARKTHRESHOLD, + new PoolEntry({0})); + localDataPoolMap.emplace(startracker::IMAGE_PROCESSOR_BACKGROUNDCOMPENSATION, + new PoolEntry({0})); + + localDataPoolMap.emplace(startracker::CENTROIDING_ENABLE_FILTER, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CENTROIDING_MAX_QUALITY, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CENTROIDING_DARK_THRESHOLD, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CENTROIDING_MIN_QUALITY, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CENTROIDING_MAX_INTENSITY, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CENTROIDING_MIN_INTENSITY, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CENTROIDING_MAX_MAGNITUDE, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CENTROIDING_GAUSSIAN_CMAX, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CENTROIDING_GAUSSIAN_CMIN, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CENTROIDING_TRANSMATRIX00, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CENTROIDING_TRANSMATRIX01, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CENTROIDING_TRANSMATRIX10, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CENTROIDING_TRANSMATRIX11, new PoolEntry({0})); + + localDataPoolMap.emplace(startracker::LISA_MODE, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LISA_PREFILTER_DIST_THRESHOLD, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LISA_PREFILTER_ANGLE_THRESHOLD, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LISA_FOV_WIDTH, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LISA_FOV_HEIGHT, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LISA_FLOAT_STAR_LIMIT, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LISA_CLOSE_STAR_LIMIT, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LISA_RATING_WEIGHT_CLOSE_STAR_COUNT, + new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LISA_RATING_WEIGHT_FRACTION_CLOSE, + new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LISA_RATING_WEIGHT_MEAN_SUM, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LISA_RATING_WEIGHT_DB_STAR_COUNT, + new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LISA_MAX_COMBINATIONS, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LISA_NR_STARS_STOP, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LISA_FRACTION_CLOSE_STOP, new PoolEntry({0})); + + localDataPoolMap.emplace(startracker::MATCHING_SQUARED_DISTANCE_LIMIT, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::MATCHING_SQUARED_SHIFT_LIMIT, new PoolEntry({0})); + + localDataPoolMap.emplace(startracker::TRACKING_THIN_LIMIT, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::TRACKING_OUTLIER_THRESHOLD, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::TRACKING_OUTLIER_THRESHOLD_QUEST, + new PoolEntry({0})); + localDataPoolMap.emplace(startracker::TRACKING_TRACKER_CHOICE, new PoolEntry({0})); + + localDataPoolMap.emplace(startracker::VALIDATION_STABLE_COUNT, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::VALIDATION_MAX_DIFFERENCE, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::VALIDATION_MIN_TRACKER_CONFIDENCE, + new PoolEntry({0})); + localDataPoolMap.emplace(startracker::VALIDATION_MIN_MATCHED_STARS, new PoolEntry({0})); + + localDataPoolMap.emplace(startracker::ALGO_MODE, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::ALGO_I2T_MIN_CONFIDENCE, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::ALGO_I2T_MIN_MATCHED, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::ALGO_I2L_MIN_CONFIDENCE, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::ALGO_I2L_MIN_MATCHED, new PoolEntry({0})); + + localDataPoolMap.emplace(startracker::SUBSCRIPTION_TM1, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::SUBSCRIPTION_TM2, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::SUBSCRIPTION_TM3, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::SUBSCRIPTION_TM4, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::SUBSCRIPTION_TM5, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::SUBSCRIPTION_TM6, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::SUBSCRIPTION_TM7, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::SUBSCRIPTION_TM8, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::SUBSCRIPTION_TM9, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::SUBSCRIPTION_TM10, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::SUBSCRIPTION_TM11, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::SUBSCRIPTION_TM12, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::SUBSCRIPTION_TM13, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::SUBSCRIPTION_TM14, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::SUBSCRIPTION_TM15, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::SUBSCRIPTION_TM16, new PoolEntry({0})); + + localDataPoolMap.emplace(startracker::LOG_SUBSCRIPTION_LEVEL1, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LOG_SUBSCRIPTION_MODULE1, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LOG_SUBSCRIPTION_LEVEL2, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LOG_SUBSCRIPTION_MODULE2, new PoolEntry({0})); + + localDataPoolMap.emplace(startracker::DEBUG_CAMERA_TIMING, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::DEBUG_CAMERA_TEST, new PoolEntry({0})); + + localDataPoolMap.emplace(startracker::CHKSUM, new PoolEntry({0})); + return RETURN_OK; +} + +size_t StarTrackerHandler::getNextReplyLength(DeviceCommandId_t commandId) { + return startracker::MAX_FRAME_SIZE; +} + +ReturnValue_t StarTrackerHandler::doSendReadHook() { + // Prevent DHB from polling UART during commands executed by the image loader task + if (strHelperExecuting) { + return RETURN_FAILED; + } + return RETURN_OK; +} + +ReturnValue_t StarTrackerHandler::checkMode(ActionId_t actionId) { + switch (actionId) { + case startracker::UPLOAD_IMAGE: + case startracker::DOWNLOAD_IMAGE: + case startracker::FLASH_READ: + case startracker::FIRMWARE_UPDATE: { + return DeviceHandlerBase::acceptExternalDeviceCommands(); + default: + break; + } + } + return RETURN_OK; +} + +ReturnValue_t StarTrackerHandler::scanForActionReply(DeviceCommandId_t* foundId) { + const uint8_t* reply = dataLinkLayer.getReply(); + switch (*reply) { + case (startracker::ID::PING): { + *foundId = startracker::PING_REQUEST; + break; + } + case (startracker::ID::BOOT): { + *foundId = startracker::BOOT; + break; + } + case (startracker::ID::TAKE_IMAGE): { + *foundId = startracker::TAKE_IMAGE; + break; + } + case (startracker::ID::UPLOAD_IMAGE): { + *foundId = startracker::UPLOAD_IMAGE; + break; + } + case (startracker::ID::CHECKSUM): { + *foundId = startracker::CHECKSUM; + break; + } + default: + sif::warning << "StarTrackerHandler::scanForActionReply: Unknown parameter reply id" + << std::endl; + return RETURN_FAILED; + } + return RETURN_OK; +} + +ReturnValue_t StarTrackerHandler::scanForSetParameterReply(DeviceCommandId_t* foundId) { + const uint8_t* reply = dataLinkLayer.getReply(); + switch (*reply) { + case (startracker::ID::SUBSCRIPTION): { + *foundId = startracker::SUBSCRIPTION; + break; + } + case (startracker::ID::LIMITS): { + *foundId = startracker::LIMITS; + break; + } + case (startracker::ID::MOUNTING): { + *foundId = startracker::MOUNTING; + break; + } + case (startracker::ID::IMAGE_PROCESSOR): { + *foundId = startracker::IMAGE_PROCESSOR; + break; + } + case (startracker::ID::CAMERA): { + *foundId = startracker::CAMERA; + break; + } + case (startracker::ID::CENTROIDING): { + *foundId = startracker::CENTROIDING; + break; + } + case (startracker::ID::LISA): { + *foundId = startracker::LISA; + break; + } + case (startracker::ID::MATCHING): { + *foundId = startracker::MATCHING; + break; + } + case (startracker::ID::TRACKING): { + *foundId = startracker::TRACKING; + break; + } + case (startracker::ID::VALIDATION): { + *foundId = startracker::VALIDATION; + break; + } + case (startracker::ID::ALGO): { + *foundId = startracker::ALGO; + break; + } + case (startracker::ID::LOG_LEVEL): { + *foundId = startracker::LOGLEVEL; + break; + } + case (startracker::ID::DEBUG_CAMERA): { + *foundId = startracker::DEBUG_CAMERA; + break; + } + case (startracker::ID::LOG_SUBSCRIPTION): { + *foundId = startracker::LOGSUBSCRIPTION; + break; + } + default: + sif::debug << "StarTrackerHandler::scanForParameterReply: Unknown parameter reply id" + << std::endl; + return RETURN_FAILED; + } + return RETURN_OK; +} + +ReturnValue_t StarTrackerHandler::scanForGetParameterReply(DeviceCommandId_t* foundId) { + const uint8_t* reply = dataLinkLayer.getReply(); + switch (*reply) { + case (startracker::ID::CAMERA): { + *foundId = startracker::REQ_CAMERA; + break; + } + case (startracker::ID::LIMITS): { + *foundId = startracker::REQ_LIMITS; + break; + } + case (startracker::ID::LOG_LEVEL): { + *foundId = startracker::REQ_LOG_LEVEL; + break; + } + case (startracker::ID::MOUNTING): { + *foundId = startracker::REQ_MOUNTING; + break; + } + case (startracker::ID::IMAGE_PROCESSOR): { + *foundId = startracker::REQ_IMAGE_PROCESSOR; + break; + } + case (startracker::ID::CENTROIDING): { + *foundId = startracker::REQ_CENTROIDING; + break; + } + case (startracker::ID::LISA): { + *foundId = startracker::REQ_LISA; + break; + } + case (startracker::ID::MATCHING): { + *foundId = startracker::REQ_MATCHING; + break; + } + case (startracker::ID::TRACKING): { + *foundId = startracker::REQ_TRACKING; + break; + } + case (startracker::ID::VALIDATION): { + *foundId = startracker::REQ_VALIDATION; + break; + } + case (startracker::ID::ALGO): { + *foundId = startracker::REQ_ALGO; + break; + } + case (startracker::ID::SUBSCRIPTION): { + *foundId = startracker::REQ_SUBSCRIPTION; + break; + } + case (startracker::ID::LOG_SUBSCRIPTION): { + *foundId = startracker::REQ_LOG_SUBSCRIPTION; + break; + } + case (startracker::ID::DEBUG_CAMERA): { + *foundId = startracker::REQ_DEBUG_CAMERA; + break; + } + default: { + sif::warning << "tarTrackerHandler::scanForGetParameterReply: UnkNown ID" << std::endl; + return RETURN_FAILED; + break; + } + } + return RETURN_OK; +} + +ReturnValue_t StarTrackerHandler::scanForTmReply(DeviceCommandId_t* foundId) { + const uint8_t* reply = dataLinkLayer.getReply(); + switch (*reply) { + case (startracker::ID::VERSION): { + *foundId = startracker::REQ_VERSION; + break; + } + case (startracker::ID::INTERFACE): { + *foundId = startracker::REQ_INTERFACE; + break; + } + case (startracker::ID::POWER): { + *foundId = startracker::REQ_POWER; + break; + } + case (startracker::ID::TEMPERATURE): { + *foundId = startracker::REQ_TEMPERATURE; + break; + } + case (startracker::ID::HISTOGRAM): { + *foundId = startracker::REQ_HISTOGRAM; + break; + } + case (startracker::ID::TIME): { + *foundId = startracker::REQ_TIME; + break; + } + case (startracker::ID::SOLUTION): { + *foundId = startracker::REQ_SOLUTION; + break; + } + default: { + sif::debug << "StarTrackerHandler::scanForTmReply: Reply contains invalid reply id: " + << static_cast(*reply) << std::endl; + return RETURN_FAILED; + break; + } + } + return RETURN_OK; +} + +void StarTrackerHandler::handleEvent(EventMessage* eventMessage) { + object_id_t objectId = eventMessage->getReporter(); + switch (objectId) { + case objects::STR_HELPER: { + // All events from image loader signal either that the operation was successful or that it + // failed + strHelperExecuting = false; + break; + } + default: + sif::debug << "StarTrackerHandler::handleEvent: Did not subscribe to this event" << std::endl; + break; + } +} + +ReturnValue_t StarTrackerHandler::executeFlashReadCommand(const uint8_t* commandData, + size_t commandDataLen) { + ReturnValue_t result = RETURN_OK; + if (commandDataLen < FlashReadCmd::MIN_LENGTH) { + sif::warning << "StarTrackerHandler::executeFlashReadCommand: Command too short" << std::endl; + return COMMAND_TOO_SHORT; + } + uint8_t startRegion = *(commandData); + uint32_t length; + size_t size = sizeof(length); + const uint8_t* lengthPtr = commandData + sizeof(startRegion); + result = SerializeAdapter::deSerialize(&length, lengthPtr, &size, SerializeIF::Endianness::BIG); + if (result != RETURN_OK) { + sif::debug << "StarTrackerHandler::executeFlashReadCommand: Deserialization of length failed" + << std::endl; + return result; + } + if (commandDataLen - sizeof(startRegion) - sizeof(length) > MAX_PATH_SIZE) { + sif::warning << "StarTrackerHandler::executeFlashReadCommand: Received command with invalid" + << " path and filename" << std::endl; + return FILE_PATH_TOO_LONG; + } + const uint8_t* filePtr = commandData + sizeof(startRegion) + sizeof(length); + std::string fullname = std::string(reinterpret_cast(filePtr), + commandDataLen - sizeof(startRegion) - sizeof(length)); + result = strHelper->startFlashRead(fullname, startRegion, length); + if (result != RETURN_OK) { + return result; + } + return result; +} + +void StarTrackerHandler::prepareBootCommand() { + uint32_t length = 0; + struct BootActionRequest bootRequest = {BOOT_REGION_ID}; + arc_pack_boot_action_req(&bootRequest, commandBuffer, &length); + dataLinkLayer.encodeFrame(commandBuffer, length); + rawPacket = dataLinkLayer.getEncodedFrame(); + rawPacketLen = dataLinkLayer.getEncodedLength(); +} + +ReturnValue_t StarTrackerHandler::prepareChecksumCommand(const uint8_t* commandData, + size_t commandDataLen) { + struct ChecksumActionRequest req; + ReturnValue_t result = RETURN_OK; + if (commandDataLen != ChecksumCmd::LENGTH) { + sif::warning << "StarTrackerHandler::prepareChecksumCommand: Invalid length" << std::endl; + return INVALID_LENGTH; + } + req.region = *(commandData); + size_t size = sizeof(req.address); + const uint8_t* addressPtr = commandData + ChecksumCmd::ADDRESS_OFFSET; + result = + SerializeAdapter::deSerialize(&req.address, addressPtr, &size, SerializeIF::Endianness::BIG); + if (result != RETURN_OK) { + sif::debug << "StarTrackerHandler::prepareChecksumCommand: Deserialization of address " + << "failed" << std::endl; + return result; + } + size = sizeof(req.length); + const uint8_t* lengthPtr = commandData + ChecksumCmd::LENGTH_OFFSET; + result = + SerializeAdapter::deSerialize(&req.length, lengthPtr, &size, SerializeIF::Endianness::BIG); + if (result != RETURN_OK) { + sif::debug << "StarTrackerHandler::prepareChecksumCommand: Deserialization of length failed" + << std::endl; + return result; + } + uint32_t rawCmdLength = 0; + arc_pack_checksum_action_req(&req, commandBuffer, &rawCmdLength); + dataLinkLayer.encodeFrame(commandBuffer, rawCmdLength); + rawPacket = dataLinkLayer.getEncodedFrame(); + rawPacketLen = dataLinkLayer.getEncodedLength(); + checksumCmd.rememberRegion = req.region; + checksumCmd.rememberAddress = req.address; + checksumCmd.rememberLength = req.length; + return result; +} + +void StarTrackerHandler::prepareTimeRequest() { + uint32_t length = 0; + arc_tm_pack_time_req(commandBuffer, &length); + dataLinkLayer.encodeFrame(commandBuffer, length); + rawPacket = dataLinkLayer.getEncodedFrame(); + rawPacketLen = dataLinkLayer.getEncodedLength(); +} + +void StarTrackerHandler::preparePingRequest() { + uint32_t length = 0; + struct PingActionRequest pingRequest = {PING_ID}; + arc_pack_ping_action_req(&pingRequest, commandBuffer, &length); + dataLinkLayer.encodeFrame(commandBuffer, length); + rawPacket = dataLinkLayer.getEncodedFrame(); + rawPacketLen = dataLinkLayer.getEncodedLength(); +} + +void StarTrackerHandler::prepareVersionRequest() { + uint32_t length = 0; + arc_tm_pack_version_req(commandBuffer, &length); + dataLinkLayer.encodeFrame(commandBuffer, length); + rawPacket = dataLinkLayer.getEncodedFrame(); + rawPacketLen = dataLinkLayer.getEncodedLength(); +} + +void StarTrackerHandler::prepareInterfaceRequest() { + uint32_t length = 0; + arc_tm_pack_interface_req(commandBuffer, &length); + dataLinkLayer.encodeFrame(commandBuffer, length); + rawPacket = dataLinkLayer.getEncodedFrame(); + rawPacketLen = dataLinkLayer.getEncodedLength(); +} + +void StarTrackerHandler::preparePowerRequest() { + uint32_t length = 0; + arc_tm_pack_power_req(commandBuffer, &length); + dataLinkLayer.encodeFrame(commandBuffer, length); + rawPacket = dataLinkLayer.getEncodedFrame(); + rawPacketLen = dataLinkLayer.getEncodedLength(); +} + +void StarTrackerHandler::prepareSwitchToBootloaderCmd() { + uint32_t length = 0; + struct RebootActionRequest rebootReq; + arc_pack_reboot_action_req(&rebootReq, commandBuffer, &length); + dataLinkLayer.encodeFrame(commandBuffer, length); + rawPacket = dataLinkLayer.getEncodedFrame(); + rawPacketLen = dataLinkLayer.getEncodedLength(); +} + +void StarTrackerHandler::prepareTakeImageCommand(const uint8_t* commandData) { + uint32_t length = 0; + struct CameraActionRequest camReq; + camReq.actionid = *commandData; + arc_pack_camera_action_req(&camReq, commandBuffer, &length); + dataLinkLayer.encodeFrame(commandBuffer, length); + rawPacket = dataLinkLayer.getEncodedFrame(); + rawPacketLen = dataLinkLayer.getEncodedLength(); +} + +void StarTrackerHandler::prepareSolutionRequest() { + uint32_t length = 0; + arc_tm_pack_solution_req(commandBuffer, &length); + dataLinkLayer.encodeFrame(commandBuffer, length); + rawPacket = dataLinkLayer.getEncodedFrame(); + rawPacketLen = dataLinkLayer.getEncodedLength(); +} + +void StarTrackerHandler::prepareTemperatureRequest() { + uint32_t length = 0; + arc_tm_pack_temperature_req(commandBuffer, &length); + dataLinkLayer.encodeFrame(commandBuffer, length); + rawPacket = dataLinkLayer.getEncodedFrame(); + rawPacketLen = dataLinkLayer.getEncodedLength(); +} + +void StarTrackerHandler::prepareHistogramRequest() { + uint32_t length = 0; + arc_tm_pack_histogram_req(commandBuffer, &length); + dataLinkLayer.encodeFrame(commandBuffer, length); + rawPacket = dataLinkLayer.getEncodedFrame(); + rawPacketLen = dataLinkLayer.getEncodedLength(); +} + +ReturnValue_t StarTrackerHandler::prepareParamCommand(const uint8_t* commandData, + size_t commandDataLen, + ArcsecJsonParamBase& paramSet) { + ReturnValue_t result = RETURN_OK; + if (commandDataLen > MAX_PATH_SIZE) { + return FILE_PATH_TOO_LONG; + } + std::string fullName(reinterpret_cast(commandData), commandDataLen); + + result = paramSet.create(fullName, commandBuffer); + if (result != RETURN_OK) { + return result; + } + dataLinkLayer.encodeFrame(commandBuffer, paramSet.getSize()); + rawPacket = dataLinkLayer.getEncodedFrame(); + rawPacketLen = dataLinkLayer.getEncodedLength(); + return RETURN_OK; +} + +ReturnValue_t StarTrackerHandler::prepareRequestCameraParams() { + uint32_t length = 0; + arc_pack_camera_parameter_req(commandBuffer, &length); + dataLinkLayer.encodeFrame(commandBuffer, length); + rawPacket = dataLinkLayer.getEncodedFrame(); + rawPacketLen = dataLinkLayer.getEncodedLength(); + return RETURN_OK; +} + +ReturnValue_t StarTrackerHandler::prepareRequestLimitsParams() { + uint32_t length = 0; + arc_pack_limits_parameter_req(commandBuffer, &length); + dataLinkLayer.encodeFrame(commandBuffer, length); + rawPacket = dataLinkLayer.getEncodedFrame(); + rawPacketLen = dataLinkLayer.getEncodedLength(); + return RETURN_OK; +} + +ReturnValue_t StarTrackerHandler::prepareRequestLogLevelParams() { + uint32_t length = 0; + arc_pack_loglevel_parameter_req(commandBuffer, &length); + dataLinkLayer.encodeFrame(commandBuffer, length); + rawPacket = dataLinkLayer.getEncodedFrame(); + rawPacketLen = dataLinkLayer.getEncodedLength(); + return RETURN_OK; +} + +ReturnValue_t StarTrackerHandler::prepareRequestMountingParams() { + uint32_t length = 0; + arc_pack_mounting_parameter_req(commandBuffer, &length); + dataLinkLayer.encodeFrame(commandBuffer, length); + rawPacket = dataLinkLayer.getEncodedFrame(); + rawPacketLen = dataLinkLayer.getEncodedLength(); + return RETURN_OK; +} + +ReturnValue_t StarTrackerHandler::prepareRequestImageProcessorParams() { + uint32_t length = 0; + arc_pack_imageprocessor_parameter_req(commandBuffer, &length); + dataLinkLayer.encodeFrame(commandBuffer, length); + rawPacket = dataLinkLayer.getEncodedFrame(); + rawPacketLen = dataLinkLayer.getEncodedLength(); + return RETURN_OK; +} + +ReturnValue_t StarTrackerHandler::prepareRequestCentroidingParams() { + uint32_t length = 0; + arc_pack_centroiding_parameter_req(commandBuffer, &length); + dataLinkLayer.encodeFrame(commandBuffer, length); + rawPacket = dataLinkLayer.getEncodedFrame(); + rawPacketLen = dataLinkLayer.getEncodedLength(); + return RETURN_OK; +} + +ReturnValue_t StarTrackerHandler::prepareRequestLisaParams() { + uint32_t length = 0; + arc_pack_lisa_parameter_req(commandBuffer, &length); + dataLinkLayer.encodeFrame(commandBuffer, length); + rawPacket = dataLinkLayer.getEncodedFrame(); + rawPacketLen = dataLinkLayer.getEncodedLength(); + return RETURN_OK; +} + +ReturnValue_t StarTrackerHandler::prepareRequestMatchingParams() { + uint32_t length = 0; + arc_pack_matching_parameter_req(commandBuffer, &length); + dataLinkLayer.encodeFrame(commandBuffer, length); + rawPacket = dataLinkLayer.getEncodedFrame(); + rawPacketLen = dataLinkLayer.getEncodedLength(); + return RETURN_OK; +} + +ReturnValue_t StarTrackerHandler::prepareRequestTrackingParams() { + uint32_t length = 0; + arc_pack_tracking_parameter_req(commandBuffer, &length); + dataLinkLayer.encodeFrame(commandBuffer, length); + rawPacket = dataLinkLayer.getEncodedFrame(); + rawPacketLen = dataLinkLayer.getEncodedLength(); + return RETURN_OK; +} + +ReturnValue_t StarTrackerHandler::prepareRequestValidationParams() { + uint32_t length = 0; + arc_pack_validation_parameter_req(commandBuffer, &length); + dataLinkLayer.encodeFrame(commandBuffer, length); + rawPacket = dataLinkLayer.getEncodedFrame(); + rawPacketLen = dataLinkLayer.getEncodedLength(); + return RETURN_OK; +} + +ReturnValue_t StarTrackerHandler::prepareRequestAlgoParams() { + uint32_t length = 0; + arc_pack_algo_parameter_req(commandBuffer, &length); + dataLinkLayer.encodeFrame(commandBuffer, length); + rawPacket = dataLinkLayer.getEncodedFrame(); + rawPacketLen = dataLinkLayer.getEncodedLength(); + return RETURN_OK; +} + +ReturnValue_t StarTrackerHandler::prepareRequestSubscriptionParams() { + uint32_t length = 0; + arc_pack_subscription_parameter_req(commandBuffer, &length); + dataLinkLayer.encodeFrame(commandBuffer, length); + rawPacket = dataLinkLayer.getEncodedFrame(); + rawPacketLen = dataLinkLayer.getEncodedLength(); + return RETURN_OK; +} + +ReturnValue_t StarTrackerHandler::prepareRequestLogSubscriptionParams() { + uint32_t length = 0; + arc_pack_logsubscription_parameter_req(commandBuffer, &length); + dataLinkLayer.encodeFrame(commandBuffer, length); + rawPacket = dataLinkLayer.getEncodedFrame(); + rawPacketLen = dataLinkLayer.getEncodedLength(); + return RETURN_OK; +} + +ReturnValue_t StarTrackerHandler::prepareRequestDebugCameraParams() { + uint32_t length = 0; + arc_pack_debugcamera_parameter_req(commandBuffer, &length); + dataLinkLayer.encodeFrame(commandBuffer, length); + rawPacket = dataLinkLayer.getEncodedFrame(); + rawPacketLen = dataLinkLayer.getEncodedLength(); + return RETURN_OK; +} + +ReturnValue_t StarTrackerHandler::handleSetParamReply() { + const uint8_t* reply = dataLinkLayer.getReply(); + uint8_t status = *(reply + STATUS_OFFSET); + if (status != startracker::STATUS_OK) { + sif::warning << "StarTrackerHandler::handleSetParamReply: Failed to execute parameter set " + " command with parameter ID" + << static_cast(*(reply + PARAMETER_ID_OFFSET)) << std::endl; + if (internalState != InternalState::IDLE) { + internalState = InternalState::IDLE; + } + return SET_PARAM_FAILED; + } + if (internalState != InternalState::IDLE) { + handleStartup(reply + PARAMETER_ID_OFFSET); + } + return RETURN_OK; +} + +ReturnValue_t StarTrackerHandler::handleActionReply() { + const uint8_t* reply = dataLinkLayer.getReply(); + uint8_t status = *(reply + STATUS_OFFSET); + if (status != startracker::STATUS_OK) { + sif::warning << "StarTrackerHandler::handleActionReply: Failed to execute action " + << "command with action ID " + << static_cast(*(reply + ACTION_ID_OFFSET)) << " and status " + << static_cast(status) << std::endl; + return ACTION_FAILED; + } + return RETURN_OK; +} + +ReturnValue_t StarTrackerHandler::handleChecksumReply() { + ReturnValue_t result = RETURN_OK; + result = handleActionReply(); + if (result != RETURN_OK) { + return result; + } + const uint8_t* replyData = dataLinkLayer.getReply() + ACTION_DATA_OFFSET; + startracker::ChecksumReply checksumReply(replyData); + if (checksumReply.getRegion() != checksumCmd.rememberRegion) { + sif::warning << "StarTrackerHandler::handleChecksumReply: Region mismatch" << std::endl; + return REGION_MISMATCH; + } + if (checksumReply.getAddress() != checksumCmd.rememberAddress) { + sif::warning << "StarTrackerHandler::handleChecksumReply: Address mismatch" << std::endl; + return ADDRESS_MISMATCH; + } + if (checksumReply.getLength() != checksumCmd.rememberLength) { + sif::warning << "StarTrackerHandler::handleChecksumReply: Length mismatch" << std::endl; + return LENGTH_MISSMATCH; + } + PoolReadGuard rg(&checksumSet); + checksumSet.checksum = checksumReply.getChecksum(); + handleDeviceTM(&checksumSet, startracker::CHECKSUM); +#if OBSW_VERBOSE_LEVEL >= 1 && OBSW_DEBUG_STARTRACKER == 1 + checksumReply.printChecksum(); +#endif /* OBSW_VERBOSE_LEVEL >= 1 && OBSW_DEBUG_STARTRACKER == 1 */ + return RETURN_OK; +} + +ReturnValue_t StarTrackerHandler::handleParamRequest(LocalPoolDataSetBase& dataset, size_t size) { + ReturnValue_t result = RETURN_OK; + result = dataset.read(TIMEOUT_TYPE, MUTEX_TIMEOUT); + if (result != RETURN_OK) { + return result; + } + const uint8_t* reply = dataLinkLayer.getReply() + PARAMS_OFFSET; + dataset.setValidityBufferGeneration(false); + result = dataset.deSerialize(&reply, &size, SerializeIF::Endianness::LITTLE); + if (result != RETURN_OK) { + sif::warning << "StarTrackerHandler::handleParamRequest Deserialization failed" << std::endl; + } + dataset.setValidityBufferGeneration(true); + dataset.setValidity(true, true); + result = dataset.commit(TIMEOUT_TYPE, MUTEX_TIMEOUT); + if (result != RETURN_OK) { + return result; + } +#if OBSW_VERBOSE_LEVEL >= 1 && OBSW_DEBUG_STARTRACKER == 1 + dataset.printSet(); +#endif + return result; +} + +ReturnValue_t StarTrackerHandler::handlePingReply() { + ReturnValue_t result = RETURN_OK; + uint32_t pingId = 0; + const uint8_t* reply = dataLinkLayer.getReply(); + uint8_t status = dataLinkLayer.getStatusField(); + const uint8_t* buffer = reply + ACTION_DATA_OFFSET; + size_t size = sizeof(pingId); + SerializeAdapter::deSerialize(&pingId, &buffer, &size, SerializeIF::Endianness::LITTLE); +#if OBSW_VERBOSE_LEVEL >= 1 && OBSW_DEBUG_STARTRACKER == 1 + sif::info << "StarTracker: Ping status: " << static_cast(status) << std::endl; + sif::info << "Ping id: 0x" << std::hex << pingId << std::endl; +#endif /* OBSW_VERBOSE_LEVEL >= 1 && OBSW_DEBUG_STARTRACKER == 1 */ + if (status != startracker::STATUS_OK || pingId != PING_ID) { + sif::warning << "StarTrackerHandler::handlePingReply: Ping failed" << std::endl; + result = PING_FAILED; + } else { +#if OBSW_VERBOSE_LEVEL >= 1 && OBSW_DEBUG_STARTRACKER == 1 + sif::info << "StarTracker: Ping successful" << std::endl; +#endif + } + return result; +} + +ReturnValue_t StarTrackerHandler::checkProgram() { + PoolReadGuard pg(&versionSet); + switch (versionSet.program.value) { + case startracker::Program::BOOTLOADER: + if (startupState == StartupState::WAIT_CHECK_PROGRAM) { + startupState = StartupState::DONE; + } + if (internalState == InternalState::VERIFY_BOOT) { + sif::warning << "StarTrackerHandler::checkProgram: Failed to boot firmware" << std::endl; + // Device handler will run into timeout and fall back to transition source mode + triggerEvent(BOOTING_FIRMWARE_FAILED); + internalState = InternalState::FAILED_FIRMWARE_BOOT; + } else if (internalState == InternalState::BOOTLOADER_CHECK) { + internalState = InternalState::DONE; + } + break; + case startracker::Program::FIRMWARE: + if (startupState == StartupState::WAIT_CHECK_PROGRAM) { + startupState = StartupState::BOOT_BOOTLOADER; + } + if (internalState == InternalState::VERIFY_BOOT) { + internalState = InternalState::LOGLEVEL; + } else if (internalState == InternalState::BOOTLOADER_CHECK) { + triggerEvent(BOOTING_BOOTLOADER_FAILED); + internalState = InternalState::BOOTING_BOOTLOADER_FAILED; + } + break; + default: + sif::warning << "StarTrackerHandler::checkProgram: Version set has invalid program ID" + << std::endl; + return INVALID_PROGRAM; + } + return RETURN_OK; +} + +ReturnValue_t StarTrackerHandler::handleTm(LocalPoolDataSetBase& dataset, size_t size) { + ReturnValue_t result = RETURN_OK; + uint8_t status = *(dataLinkLayer.getReply() + STATUS_OFFSET); + if (status != startracker::STATUS_OK) { + sif::warning << "StarTrackerHandler::handleTm: Reply error: " + << static_cast(status) << std::endl; + return REPLY_ERROR; + } + result = dataset.read(TIMEOUT_TYPE, MUTEX_TIMEOUT); + if (result != RETURN_OK) { + return result; + } + const uint8_t* reply = dataLinkLayer.getReply() + TICKS_OFFSET; + dataset.setValidityBufferGeneration(false); + result = dataset.deSerialize(&reply, &size, SerializeIF::Endianness::LITTLE); + if (result != RETURN_OK) { + sif::warning << "StarTrackerHandler::handleTm: Deserialization failed" << std::endl; + } + dataset.setValidityBufferGeneration(true); + dataset.setValidity(true, true); + result = dataset.commit(TIMEOUT_TYPE, MUTEX_TIMEOUT); + if (result != RETURN_OK) { + return result; + } +#if OBSW_VERBOSE_LEVEL >= 1 && OBSW_DEBUG_STARTRACKER == 1 + dataset.printSet(); +#endif + return result; +} + +ReturnValue_t StarTrackerHandler::handleActionReplySet(LocalPoolDataSetBase& dataset, size_t size) { + ReturnValue_t result = RETURN_OK; + uint8_t status = *(dataLinkLayer.getReply() + STATUS_OFFSET); + if (status != startracker::STATUS_OK) { + sif::warning << "StarTrackerHandler::handleActionReplySet: Reply error: " + << static_cast(status) << std::endl; + return REPLY_ERROR; + } + result = dataset.read(TIMEOUT_TYPE, MUTEX_TIMEOUT); + if (result != RETURN_OK) { + return result; + } + const uint8_t* reply = dataLinkLayer.getReply() + ACTION_DATA_OFFSET; + dataset.setValidityBufferGeneration(false); + result = dataset.deSerialize(&reply, &size, SerializeIF::Endianness::LITTLE); + if (result != RETURN_OK) { + sif::warning << "StarTrackerHandler::handleActionReplySet Deserialization failed" << std::endl; + } + dataset.setValidityBufferGeneration(true); + dataset.setValidity(true, true); + result = dataset.commit(TIMEOUT_TYPE, MUTEX_TIMEOUT); + if (result != RETURN_OK) { + return result; + } +#if OBSW_VERBOSE_LEVEL >= 1 && OBSW_DEBUG_STARTRACKER == 1 + dataset.printSet(); +#endif + return result; +} + +void StarTrackerHandler::handleStartup(const uint8_t* parameterId) { + switch (*parameterId) { + case (startracker::ID::LOG_LEVEL): { + internalState = InternalState::LIMITS; + break; + } + case (startracker::ID::LIMITS): { + internalState = InternalState::TRACKING; + break; + } + case (startracker::ID::TRACKING): { + internalState = InternalState::MOUNTING; + break; + } + case (startracker::ID::MOUNTING): { + internalState = InternalState::IMAGE_PROCESSOR; + break; + } + case (startracker::ID::IMAGE_PROCESSOR): { + internalState = InternalState::CAMERA; + break; + } + case (startracker::ID::CAMERA): { + internalState = InternalState::CENTROIDING; + break; + } + case (startracker::ID::CENTROIDING): { + internalState = InternalState::LISA; + break; + } + case (startracker::ID::LISA): { + internalState = InternalState::MATCHING; + break; + } + case (startracker::ID::MATCHING): { + internalState = InternalState::VALIDATION; + break; + } + case (startracker::ID::VALIDATION): { + internalState = InternalState::ALGO; + break; + } + case (startracker::ID::ALGO): { + internalState = InternalState::LOG_SUBSCRIPTION; + break; + } + case (startracker::ID::LOG_SUBSCRIPTION): { + internalState = InternalState::DEBUG_CAMERA; + break; + } + case (startracker::ID::DEBUG_CAMERA): { + internalState = InternalState::DONE; + break; + } + default: { + sif::debug << "StarTrackerHandler::handleStartup: Received parameter reply with unexpected" + << " parameter ID" << std::endl; + break; + } + } +} + +ReturnValue_t StarTrackerHandler::checkCommand(ActionId_t actionId) { + switch (actionId) { + case startracker::REQ_INTERFACE: + case startracker::REQ_TIME: + case startracker::SWITCH_TO_BOOTLOADER_PROGRAM: + case startracker::DOWNLOAD_IMAGE: + case startracker::UPLOAD_IMAGE: + case startracker::REQ_POWER: + case startracker::TAKE_IMAGE: + case startracker::REQ_SOLUTION: + case startracker::REQ_TEMPERATURE: + case startracker::REQ_HISTOGRAM: + case startracker::REQ_CAMERA: + case startracker::REQ_LIMITS: + case startracker::REQ_LOG_LEVEL: + case startracker::REQ_MOUNTING: + case startracker::REQ_IMAGE_PROCESSOR: + case startracker::REQ_CENTROIDING: + case startracker::REQ_LISA: + case startracker::REQ_MATCHING: + case startracker::REQ_TRACKING: + case startracker::REQ_VALIDATION: + case startracker::REQ_ALGO: + case startracker::REQ_SUBSCRIPTION: + case startracker::REQ_LOG_SUBSCRIPTION: + case startracker::REQ_DEBUG_CAMERA: + if (not(mode == MODE_ON && submode == startracker::Program::FIRMWARE)) { + return STARTRACKER_RUNNING_BOOTLOADER; + } + break; + case startracker::FIRMWARE_UPDATE: + case startracker::FLASH_READ: + if (not(mode == MODE_ON && submode == startracker::Program::BOOTLOADER)) { + return STARTRACKER_RUNNING_FIRMWARE; + } + break; + default: + break; + } + return RETURN_OK; +} diff --git a/linux/devices/startracker/StarTrackerHandler.h b/linux/devices/startracker/StarTrackerHandler.h new file mode 100644 index 00000000..4bc0f5a5 --- /dev/null +++ b/linux/devices/startracker/StarTrackerHandler.h @@ -0,0 +1,474 @@ +#ifndef MISSION_DEVICES_STARTRACKERHANDLER_H_ +#define MISSION_DEVICES_STARTRACKERHANDLER_H_ + +#include + +#include "ArcsecDatalinkLayer.h" +#include "ArcsecJsonParamBase.h" +#include "OBSWConfig.h" +#include "StrHelper.h" +#include "fsfw/devicehandlers/DeviceHandlerBase.h" +#include "fsfw/src/fsfw/serialize/SerializeAdapter.h" +#include "fsfw/timemanager/Countdown.h" +#include "linux/devices/devicedefinitions/StarTrackerDefinitions.h" +#include "thirdparty/arcsec_star_tracker/common/SLIP.h" + +/** + * @brief This is the device handler for the star tracker from arcsec. + * + * @details Datasheet: https://eive-cloud.irs.uni-stuttgart.de/index.php/apps/files/?dir=/EIVE_IRS/ + * Arbeitsdaten/08_Used%20Components/ArcSec_KULeuven_Startracker/ + * Sagitta%201.0%20Datapack&fileid=659181 + * @author J. Meier + */ +class StarTrackerHandler : public DeviceHandlerBase { + public: + /** + * @brief Constructor + * + * @param objectId + * @param comIF + * @param comCookie + * @param gpioComIF Pointer to gpio communication interface + * @param enablePin GPIO connected to the enable pin of the reaction wheels. Must be pulled + * to high to enable the device. + */ + StarTrackerHandler(object_id_t objectId, object_id_t comIF, CookieIF* comCookie, + StrHelper* strHelper); + virtual ~StarTrackerHandler(); + + ReturnValue_t initialize() override; + + /** + * @brief Overwrite this function from DHB to handle commands executed by the str image + * loader task. + */ + ReturnValue_t executeAction(ActionId_t actionId, MessageQueueId_t commandedBy, + const uint8_t* data, size_t size) override; + + void performOperationHook() override; + + Submode_t getInitialSubmode() override; + + static const Submode_t SUBMODE_BOOTLOADER = 1; + static const Submode_t SUBMODE_FIRMWARE = 2; + + protected: + void doStartUp() override; + void doShutDown() override; + void doOffActivity() override; + ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t* id) override; + ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t* id) override; + void fillCommandAndReplyMap() override; + ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t* commandData, + size_t commandDataLen) override; + ReturnValue_t isModeCombinationValid(Mode_t mode, Submode_t submode) override; + ReturnValue_t scanForReply(const uint8_t* start, size_t remainingSize, DeviceCommandId_t* foundId, + size_t* foundLen) override; + ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t* packet) override; + void setNormalDatapoolEntriesInvalid() override; + uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override; + ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, + LocalDataPoolManager& poolManager) override; + /** + * @brief Overwritten here to always read all available data from the UartComIF. + */ + virtual size_t getNextReplyLength(DeviceCommandId_t deviceCommand) override; + virtual ReturnValue_t doSendReadHook() override; + virtual void doTransition(Mode_t modeFrom, Submode_t subModeFrom) override; + + private: + static const uint8_t INTERFACE_ID = CLASS_ID::STR_HANDLER; + + //! [EXPORT] : [COMMENT] Status in temperature reply signals error + static const ReturnValue_t TEMPERATURE_REQ_FAILED = MAKE_RETURN_CODE(0xA0); + //! [EXPORT] : [COMMENT] Ping command failed + static const ReturnValue_t PING_FAILED = MAKE_RETURN_CODE(0xA1); + //! [EXPORT] : [COMMENT] Status in version reply signals error + static const ReturnValue_t VERSION_REQ_FAILED = MAKE_RETURN_CODE(0xA2); + //! [EXPORT] : [COMMENT] Status in interface reply signals error + static const ReturnValue_t INTERFACE_REQ_FAILED = MAKE_RETURN_CODE(0xA3); + //! [EXPORT] : [COMMENT] Status in power reply signals error + static const ReturnValue_t POWER_REQ_FAILED = MAKE_RETURN_CODE(0xA4); + //! [EXPORT] : [COMMENT] Status of reply to parameter set command signals error + static const ReturnValue_t SET_PARAM_FAILED = MAKE_RETURN_CODE(0xA5); + //! [EXPORT] : [COMMENT] Status of reply to action command signals error + static const ReturnValue_t ACTION_FAILED = MAKE_RETURN_CODE(0xA6); + //! [EXPORT] : [COMMENT] Received invalid path string. Exceeds allowed length + static const ReturnValue_t FILE_PATH_TOO_LONG = MAKE_RETURN_CODE(0xA7); + //! [EXPORT] : [COMMENT] Name of file received with command is too long + static const ReturnValue_t FILENAME_TOO_LONG = MAKE_RETURN_CODE(0xA8); + //! [EXPORT] : [COMMENT] Received version reply with invalid program ID + static const ReturnValue_t INVALID_PROGRAM = MAKE_RETURN_CODE(0xA9); + //! [EXPORT] : [COMMENT] Status field reply signals error + static const ReturnValue_t REPLY_ERROR = MAKE_RETURN_CODE(0xAA); + //! [EXPORT] : [COMMENT] Received command which is too short (some data is missing for proper + //! execution) + static const ReturnValue_t COMMAND_TOO_SHORT = MAKE_RETURN_CODE(0xAB); + //! [EXPORT] : [COMMENT] Received command with invalid length (too few or too many parameters) + static const ReturnValue_t INVALID_LENGTH = MAKE_RETURN_CODE(0xAC); + //! [EXPORT] : [COMMENT] Region mismatch between send and received data + static const ReturnValue_t REGION_MISMATCH = MAKE_RETURN_CODE(0xAD); + //! [EXPORT] : [COMMENT] Address mismatch between send and received data + static const ReturnValue_t ADDRESS_MISMATCH = MAKE_RETURN_CODE(0xAE); + //! [EXPORT] : [COMMENT] Length field mismatch between send and received data + static const ReturnValue_t lENGTH_MISMATCH = MAKE_RETURN_CODE(0xAF); + //! [EXPORT] : [COMMENT] Specified file does not exist + static const ReturnValue_t FILE_NOT_EXISTS = MAKE_RETURN_CODE(0xB0); + //! [EXPORT] : [COMMENT] Download blob pixel command has invalid type field + static const ReturnValue_t INVALID_TYPE = MAKE_RETURN_CODE(0xB1); + //! [EXPORT] : [COMMENT] Received FPGA action command with invalid ID + static const ReturnValue_t INVALID_ID = MAKE_RETURN_CODE(0xB2); + //! [EXPORT] : [COMMENT] Received reply is too short + static const ReturnValue_t REPLY_TOO_SHORT = MAKE_RETURN_CODE(0xB3); + //! [EXPORT] : [COMMENT] Received reply with invalid CRC + static const ReturnValue_t CRC_FAILURE = MAKE_RETURN_CODE(0xB4); + //! [EXPORT] : [COMMENT] Star tracker handler currently executing a command and using the + //! communication interface + static const ReturnValue_t STR_HELPER_EXECUTING = MAKE_RETURN_CODE(0xB5); + //! [EXPORT] : [COMMENT] Star tracker is already in firmware mode + static const ReturnValue_t STARTRACKER_ALREADY_BOOTED = MAKE_RETURN_CODE(0xB6); + //! [EXPORT] : [COMMENT] Star tracker is in firmware mode but must be in bootloader mode to + //! execute this command + static const ReturnValue_t STARTRACKER_RUNNING_FIRMWARE = MAKE_RETURN_CODE(0xB7); + //! [EXPORT] : [COMMENT] Star tracker is in bootloader mode but must be in firmware mode to + //! execute this command + static const ReturnValue_t STARTRACKER_RUNNING_BOOTLOADER = MAKE_RETURN_CODE(0xB8); + + static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::STR_HANDLER; + + //! [EXPORT] : [COMMENT] Failed to boot firmware + static const Event BOOTING_FIRMWARE_FAILED = MAKE_EVENT(1, severity::LOW); + //! [EXPORT] : [COMMENT] Failed to boot star tracker into bootloader mode + static const Event BOOTING_BOOTLOADER_FAILED = MAKE_EVENT(2, severity::LOW); + + static const size_t MAX_PATH_SIZE = 50; + static const size_t MAX_FILE_NAME = 30; + + static const uint8_t STATUS_OFFSET = 1; + static const uint8_t PARAMS_OFFSET = 1; + static const uint8_t TICKS_OFFSET = 2; + static const uint8_t TIME_OFFSET = 6; + static const uint8_t TM_DATA_FIELD_OFFSET = 14; + static const uint8_t PARAMETER_ID_OFFSET = 0; + static const uint8_t ACTION_ID_OFFSET = 0; + static const uint8_t ACTION_DATA_OFFSET = 2; + // Ping request will reply ping with this ID (data field) + static const uint32_t PING_ID = 0x55; + static const uint32_t BOOT_REGION_ID = 1; + static const MutexIF::TimeoutType TIMEOUT_TYPE = MutexIF::TimeoutType::WAITING; + static const uint32_t MUTEX_TIMEOUT = 20; + static const uint32_t BOOT_TIMEOUT = 1000; + static const uint32_t DEFAULT_TRANSITION_DELAY = 15000; + + class FlashReadCmd { + public: + // Minimum length of a read command (region, length and filename) + static const size_t MIN_LENGTH = 7; + }; + + class ChecksumCmd { + public: + static const uint8_t ADDRESS_OFFSET = 1; + static const uint8_t LENGTH_OFFSET = 5; + // Length of checksum command + static const size_t LENGTH = 9; + uint8_t rememberRegion = 0; + uint32_t rememberAddress = 0; + uint32_t rememberLength = 0; + }; + + ChecksumCmd checksumCmd; + + MessageQueueIF* eventQueue = nullptr; + + ArcsecDatalinkLayer dataLinkLayer; + + startracker::TemperatureSet temperatureSet; + startracker::VersionSet versionSet; + startracker::PowerSet powerSet; + startracker::InterfaceSet interfaceSet; + startracker::TimeSet timeSet; + startracker::SolutionSet solutionSet; + startracker::HistogramSet histogramSet; + startracker::ChecksumSet checksumSet; + startracker::CameraSet cameraSet; + startracker::LimitsSet limitsSet; + startracker::LogLevelSet loglevelSet; + startracker::MountingSet mountingSet; + startracker::ImageProcessorSet imageProcessorSet; + startracker::CentroidingSet centroidingSet; + startracker::LisaSet lisaSet; + startracker::MatchingSet matchingSet; + startracker::TrackingSet trackingSet; + startracker::ValidationSet validationSet; + startracker::AlgoSet algoSet; + startracker::SubscriptionSet subscriptionSet; + startracker::LogSubscriptionSet logSubscriptionSet; + startracker::DebugCameraSet debugCameraSet; + + // Pointer to object responsible for uploading and downloading images to/from the star tracker + StrHelper* strHelper = nullptr; + + uint8_t commandBuffer[startracker::MAX_FRAME_SIZE]; + + // Countdown to insert delay for star tracker to switch from bootloader to firmware program + // Loading firmware requires some time and the command will not trigger a reply when executed + Countdown bootCountdown; + +#ifdef EGSE + std::string paramJsonFile = "/home/pi/arcsec/json/flight-config.json"; +#else +#if OBSW_STAR_TRACKER_GROUND_CONFIG == 1 + std::string paramJsonFile = "/mnt/sd0/startracker/ground-config.json"; +#else + std::string paramJsonFile = "/mnt/sd0/startracker/flight-config.json"; +#endif +#endif + + enum class NormalState { TEMPERATURE_REQUEST, SOLUTION_REQUEST }; + + NormalState normalState = NormalState::TEMPERATURE_REQUEST; + + enum class InternalState { + IDLE, + BOOT, + REQ_VERSION, + VERIFY_BOOT, + STARTUP_CHECK, + BOOT_DELAY, + FIRMWARE_CHECK, + LOGLEVEL, + LIMITS, + TRACKING, + MOUNTING, + IMAGE_PROCESSOR, + CAMERA, + BLOB, + CENTROIDING, + LISA, + MATCHING, + VALIDATION, + ALGO, + LOG_SUBSCRIPTION, + DEBUG_CAMERA, + WAIT_FOR_EXECUTION, + DONE, + FAILED_FIRMWARE_BOOT, + BOOT_BOOTLOADER, + BOOTLOADER_CHECK, + BOOTING_BOOTLOADER_FAILED + }; + + InternalState internalState = InternalState::IDLE; + + enum class StartupState { IDLE, CHECK_PROGRAM, WAIT_CHECK_PROGRAM, BOOT_BOOTLOADER, DONE }; + + StartupState startupState = StartupState::IDLE; + + bool strHelperExecuting = false; + + /** + * @brief Handles internal state + */ + void handleInternalState(); + + /** + * @brief Checks mode for commands requiring MODE_ON of MODE_NORMAL for execution. + * + * @param actionId Action id of command to execute + */ + ReturnValue_t checkMode(ActionId_t actionId); + + /** + * @brief This function initializes the serial link ip protocol struct slipInfo. + */ + void slipInit(); + + ReturnValue_t scanForActionReply(DeviceCommandId_t* foundId); + ReturnValue_t scanForSetParameterReply(DeviceCommandId_t* foundId); + ReturnValue_t scanForGetParameterReply(DeviceCommandId_t* foundId); + ReturnValue_t scanForTmReply(DeviceCommandId_t* foundId); + + /** + * @brief Fills command buffer with data to ping the star tracker + */ + void preparePingRequest(); + + /** + * @brief Fills command buffer with data to request the time telemetry. + */ + void prepareTimeRequest(); + + /** + * @brief Handles all received event messages + */ + void handleEvent(EventMessage* eventMessage); + + /** + * @brief Extracts information for flash-read-command from TC data and starts execution of + * flash-read-procedure + * + * @param commandData Pointer to received command data + * @param commandDataLen Size of received command data + * + * @return RETURN_OK if start of execution was successful, otherwise error return value + */ + ReturnValue_t executeFlashReadCommand(const uint8_t* commandData, size_t commandDataLen); + + /** + * @brief Fills command buffer with data to boot image (works only when star tracker is + * in bootloader mode). + */ + void prepareBootCommand(); + + /** + * @brief Fills command buffer with command to get the checksum of a flash part + */ + ReturnValue_t prepareChecksumCommand(const uint8_t* commandData, size_t commandDataLen); + + /** + * @brief Fills the command buffer with the command to take an image. + */ + void prepareTakeImageCommand(const uint8_t* commandData); + + /** + * @brief Fills command buffer with data to request the version telemetry packet + */ + void prepareVersionRequest(); + + /** + * @brief Fills the command buffer with data to request the interface telemetry packet. + */ + void prepareInterfaceRequest(); + + /** + * @brief Fills the command buffer with data to request the power telemetry packet. + */ + void preparePowerRequest(); + + /** + * @brief Fills command buffer with data to reboot star tracker. + */ + void prepareSwitchToBootloaderCmd(); + + /** + * @brief Fills command buffer with data to subscribe to a telemetry packet. + * + * @param tmId The ID of the telemetry packet to subscribe to + */ + void prepareSubscriptionCommand(const uint8_t* tmId); + + /** + * @brief Fills command buffer with data to request solution telemtry packet (contains + * attitude information) + */ + void prepareSolutionRequest(); + + /** + * @brief Fills command buffer with data to request temperature from star tracker + */ + void prepareTemperatureRequest(); + + /** + * @brief Fills command buffer with data to request histogram + */ + void prepareHistogramRequest(); + + /** + * @brief Reads parameters from json file specified by string in commandData and + * prepares the command to apply the parameter set to the star tracker + * + * @param commandData Contains string with file name + * @param commandDataLen Length of command + * @param paramSet The object defining the command generation + * + * @return RETURN_OK if successful, otherwise error return Value + */ + ReturnValue_t prepareParamCommand(const uint8_t* commandData, size_t commandDataLen, + ArcsecJsonParamBase& paramSet); + + /** + * @brief The following function will fill the command buffer with the command to request + * a parameter set. + */ + ReturnValue_t prepareRequestCameraParams(); + ReturnValue_t prepareRequestLimitsParams(); + ReturnValue_t prepareRequestLogLevelParams(); + ReturnValue_t prepareRequestMountingParams(); + ReturnValue_t prepareRequestImageProcessorParams(); + ReturnValue_t prepareRequestCentroidingParams(); + ReturnValue_t prepareRequestLisaParams(); + ReturnValue_t prepareRequestMatchingParams(); + ReturnValue_t prepareRequestTrackingParams(); + ReturnValue_t prepareRequestValidationParams(); + ReturnValue_t prepareRequestAlgoParams(); + ReturnValue_t prepareRequestSubscriptionParams(); + ReturnValue_t prepareRequestLogSubscriptionParams(); + ReturnValue_t prepareRequestDebugCameraParams(); + + /** + * @brief Handles action replies with datasets. + */ + ReturnValue_t handleActionReplySet(LocalPoolDataSetBase& dataset, size_t size); + + /** + * @brief Default function to handle action replies + */ + ReturnValue_t handleActionReply(); + + /** + * @brief Handles reply to upload centroid command + */ + ReturnValue_t handleUploadCentroidReply(); + + /** + * @brief Handles reply to checksum command + */ + ReturnValue_t handleChecksumReply(); + + /** + * @brief Handles all set parameter replies + */ + ReturnValue_t handleSetParamReply(); + + ReturnValue_t handlePingReply(); + + ReturnValue_t handleParamRequest(LocalPoolDataSetBase& dataset, size_t size); + + /** + * @brief Checks the loaded program by means of the version set + */ + ReturnValue_t checkProgram(); + + /** + * @brief Handles the startup state machine + */ + void handleStartup(const uint8_t* parameterId); + + /** + * @brief Handles telemtry replies and fills the appropriate dataset + * + * @param dataset Dataset where reply data will be written to + * @param size Size of the dataset + * + * @return RETURN_OK if successful, otherwise error return value + */ + ReturnValue_t handleTm(LocalPoolDataSetBase& dataset, size_t size); + + /** + * @brief Checks if star tracker is in valid mode for executing the received command. + * + * @param actioId Id of received command + * + * @return RETURN_OK if star tracker is in valid mode, otherwise error return value + */ + ReturnValue_t checkCommand(ActionId_t actionId); + + void doOnTransition(Submode_t subModeFrom); + void doNormalTransition(Mode_t modeFrom, Submode_t subModeFrom); + void bootFirmware(Mode_t toMode); + void bootBootloader(); +}; + +#endif /* MISSION_DEVICES_STARTRACKERHANDLER_H_ */ diff --git a/linux/devices/startracker/StarTrackerJsonCommands.cpp b/linux/devices/startracker/StarTrackerJsonCommands.cpp new file mode 100644 index 00000000..c481c72a --- /dev/null +++ b/linux/devices/startracker/StarTrackerJsonCommands.cpp @@ -0,0 +1,917 @@ +#include "StarTrackerJsonCommands.h" + +#include "ArcsecJsonKeys.h" + +Limits::Limits() : ArcsecJsonParamBase(arcseckeys::LIMITS) {} + +size_t Limits::getSize() { return COMMAND_SIZE; } + +ReturnValue_t Limits::createCommand(uint8_t* buffer) { + ReturnValue_t result = RETURN_OK; + uint8_t offset = 0; + std::string param; + addSetParamHeader(buffer, startracker::ID::LIMITS); + offset = 2; + result = getParam(arcseckeys::ACTION, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::FPGA18CURRENT, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::FPGA25CURRENT, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::FPGA10CURRENT, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::MCUCURRENT, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::CMOS21CURRENT, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::CMOSPIXCURRENT, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::CMOS33CURRENT, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::CMOSVRESCURRENT, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::CMOS_TEMPERATURE, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::MCU_TEMPERATURE, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + return RETURN_OK; +} + +Tracking::Tracking() : ArcsecJsonParamBase(arcseckeys::TRACKING) {} + +size_t Tracking::getSize() { return COMMAND_SIZE; } + +ReturnValue_t Tracking::createCommand(uint8_t* buffer) { + ReturnValue_t result = RETURN_OK; + uint8_t offset = 0; + std::string param; + addSetParamHeader(buffer, startracker::ID::TRACKING); + offset = 2; + result = getParam(arcseckeys::THIN_LIMIT, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::OUTLIER_THRESHOLD, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::OUTLIER_THRESHOLD_QUEST, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::TRACKER_CHOICE, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + return RETURN_OK; +} + +Mounting::Mounting() : ArcsecJsonParamBase(arcseckeys::MOUNTING) {} + +size_t Mounting::getSize() { return COMMAND_SIZE; } + +ReturnValue_t Mounting::createCommand(uint8_t* buffer) { + ReturnValue_t result = RETURN_OK; + uint8_t offset = 0; + std::string param; + addSetParamHeader(buffer, startracker::ID::MOUNTING); + offset = 2; + result = getParam(arcseckeys::qw, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::qx, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::qy, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::qz, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + return RETURN_OK; +} + +ImageProcessor::ImageProcessor() : ArcsecJsonParamBase(arcseckeys::IMAGE_PROCESSOR) {} + +size_t ImageProcessor::getSize() { return COMMAND_SIZE; } + +ReturnValue_t ImageProcessor::createCommand(uint8_t* buffer) { + ReturnValue_t result = RETURN_OK; + uint8_t offset = 0; + std::string param; + addSetParamHeader(buffer, startracker::ID::IMAGE_PROCESSOR); + offset = 2; + result = getParam(arcseckeys::IMAGE_PROCESSOR_MODE, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::STORE, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::SIGNAL_THRESHOLD, param); + if (result != RETURN_OK) { + return result; + } + adduint16(param, buffer + offset); + offset += sizeof(uint16_t); + result = getParam(arcseckeys::IMAGE_PROCESSOR_DARK_THRESHOLD, param); + if (result != RETURN_OK) { + return result; + } + adduint16(param, buffer + offset); + offset += sizeof(uint16_t); + result = getParam(arcseckeys::BACKGROUND_COMPENSATION, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + return RETURN_OK; +} + +Camera::Camera() : ArcsecJsonParamBase(arcseckeys::CAMERA) {} + +size_t Camera::getSize() { return COMMAND_SIZE; } + +ReturnValue_t Camera::createCommand(uint8_t* buffer) { + ReturnValue_t result = RETURN_OK; + uint8_t offset = 0; + std::string param; + addSetParamHeader(buffer, startracker::ID::CAMERA); + offset = 2; + result = getParam(arcseckeys::MODE, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::FOCALLENGTH, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::EXPOSURE, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::INTERVAL, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::OFFSET, param); + if (result != RETURN_OK) { + return result; + } + addint16(param, buffer + offset); + offset += sizeof(int16_t); + result = getParam(arcseckeys::PGAGAIN, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::ADCGAIN, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::REG_1, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::VAL_1, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::REG_2, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::VAL_2, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::REG_3, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::VAL_3, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::REG_4, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::VAL_4, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::REG_5, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::VAL_5, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::REG_6, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::VAL_6, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::REG_7, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::VAL_7, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::REG_8, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::VAL_8, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::FREQ_1, param); + if (result != RETURN_OK) { + return result; + } + adduint32(param, buffer + offset); + return RETURN_OK; +} + +Centroiding::Centroiding() : ArcsecJsonParamBase(arcseckeys::CENTROIDING) {} + +size_t Centroiding::getSize() { return COMMAND_SIZE; } + +ReturnValue_t Centroiding::createCommand(uint8_t* buffer) { + ReturnValue_t result = RETURN_OK; + uint8_t offset = 0; + std::string param; + addSetParamHeader(buffer, startracker::ID::CENTROIDING); + offset = 2; + result = getParam(arcseckeys::ENABLE_FILTER, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::MAX_QUALITY, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::DARK_THRESHOLD, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::MIN_QUALITY, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::MAX_INTENSITY, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::MIN_INTENSITY, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::MAX_MAGNITUDE, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::GAUSSIAN_CMAX, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::GAUSSIAN_CMIN, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::TRANSMATRIX_00, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::TRANSMATRIX_01, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::TRANSMATRIX_10, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::TRANSMATRIX_11, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + return RETURN_OK; +} + +Lisa::Lisa() : ArcsecJsonParamBase(arcseckeys::LISA) {} + +size_t Lisa::getSize() { return COMMAND_SIZE; } + +ReturnValue_t Lisa::createCommand(uint8_t* buffer) { + ReturnValue_t result = RETURN_OK; + uint8_t offset = 0; + std::string param; + addSetParamHeader(buffer, startracker::ID::LISA); + offset = 2; + result = getParam(arcseckeys::LISA_MODE, param); + if (result != RETURN_OK) { + return result; + } + adduint32(param, buffer + offset); + offset += sizeof(uint32_t); + result = getParam(arcseckeys::PREFILTER_DIST_THRESHOLD, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::PREFILTER_ANGLE_THRESHOLD, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::FOV_WIDTH, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::FOV_HEIGHT, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::FLOAT_STAR_LIMIT, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::CLOSE_STAR_LIMIT, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::RATING_WEIGHT_CLOSE_STAR_COUNT, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::RATING_WEIGHT_FRACTION_CLOSE, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::RATING_WEIGHT_MEAN_SUM, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::RATING_WEIGHT_DB_STAR_COUNT, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::MAX_COMBINATIONS, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::NR_STARS_STOP, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::FRACTION_CLOSE_STOP, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + return RETURN_OK; +} + +Matching::Matching() : ArcsecJsonParamBase(arcseckeys::MATCHING) {} + +size_t Matching::getSize() { return COMMAND_SIZE; } + +ReturnValue_t Matching::createCommand(uint8_t* buffer) { + ReturnValue_t result = RETURN_OK; + uint8_t offset = 0; + std::string param; + addSetParamHeader(buffer, startracker::ID::MATCHING); + offset = 2; + result = getParam(arcseckeys::SQUARED_DISTANCE_LIMIT, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::SQUARED_SHIFT_LIMIT, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + return RETURN_OK; +} + +Validation::Validation() : ArcsecJsonParamBase(arcseckeys::VALIDATION) {} + +size_t Validation::getSize() { return COMMAND_SIZE; } + +ReturnValue_t Validation::createCommand(uint8_t* buffer) { + ReturnValue_t result = RETURN_OK; + uint8_t offset = 0; + std::string param; + addSetParamHeader(buffer, startracker::ID::VALIDATION); + offset = 2; + result = getParam(arcseckeys::STABLE_COUNT, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::MAX_DIFFERENCE, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::MIN_TRACKER_CONFIDENCE, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::MIN_MATCHED_STARS, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + return RETURN_OK; +} + +Algo::Algo() : ArcsecJsonParamBase(arcseckeys::ALGO) {} + +size_t Algo::getSize() { return COMMAND_SIZE; } + +ReturnValue_t Algo::createCommand(uint8_t* buffer) { + ReturnValue_t result = RETURN_OK; + uint8_t offset = 0; + std::string param; + addSetParamHeader(buffer, startracker::ID::ALGO); + offset = 2; + result = getParam(arcseckeys::MODE, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::L2T_MIN_CONFIDENCE, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::L2T_MIN_MATCHED, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::T2L_MIN_CONFIDENCE, param); + if (result != RETURN_OK) { + return result; + } + addfloat(param, buffer + offset); + offset += sizeof(float); + result = getParam(arcseckeys::T2L_MIN_MATCHED, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + return RETURN_OK; +} + +LogLevel::LogLevel() : ArcsecJsonParamBase(arcseckeys::LOGLEVEL) {} + +size_t LogLevel::getSize() { return COMMAND_SIZE; } + +ReturnValue_t LogLevel::createCommand(uint8_t* buffer) { + ReturnValue_t result = RETURN_OK; + uint8_t offset = 0; + std::string param; + addSetParamHeader(buffer, startracker::ID::LOG_LEVEL); + offset = 2; + result = getParam(arcseckeys::LOGLEVEL1, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::LOGLEVEL2, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::LOGLEVEL3, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::LOGLEVEL4, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::LOGLEVEL5, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::LOGLEVEL6, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::LOGLEVEL7, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::LOGLEVEL8, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::LOGLEVEL9, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::LOGLEVEL10, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::LOGLEVEL11, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::LOGLEVEL12, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::LOGLEVEL13, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::LOGLEVEL14, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::LOGLEVEL15, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::LOGLEVEL16, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + + return RETURN_OK; +} + +Subscription::Subscription() : ArcsecJsonParamBase(arcseckeys::SUBSCRIPTION) {} + +size_t Subscription::getSize() { return COMMAND_SIZE; } + +ReturnValue_t Subscription::createCommand(uint8_t* buffer) { + ReturnValue_t result = RETURN_OK; + uint8_t offset = 0; + std::string param; + addSetParamHeader(buffer, startracker::ID::SUBSCRIPTION); + offset = 2; + result = getParam(arcseckeys::TELEMETRY_1, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::TELEMETRY_2, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::TELEMETRY_3, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::TELEMETRY_4, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::TELEMETRY_5, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::TELEMETRY_6, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::TELEMETRY_7, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::TELEMETRY_8, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::TELEMETRY_9, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::TELEMETRY_10, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::TELEMETRY_11, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::TELEMETRY_12, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::TELEMETRY_13, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::TELEMETRY_14, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::TELEMETRY_15, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::TELEMETRY_16, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + return RETURN_OK; +} + +LogSubscription::LogSubscription() : ArcsecJsonParamBase(arcseckeys::LOG_SUBSCRIPTION) {} + +size_t LogSubscription::getSize() { return COMMAND_SIZE; } + +ReturnValue_t LogSubscription::createCommand(uint8_t* buffer) { + ReturnValue_t result = RETURN_OK; + uint8_t offset = 0; + std::string param; + addSetParamHeader(buffer, startracker::ID::LOG_SUBSCRIPTION); + offset = 2; + result = getParam(arcseckeys::LEVEL1, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::MODULE1, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::LEVEL2, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + offset += sizeof(uint8_t); + result = getParam(arcseckeys::MODULE2, param); + if (result != RETURN_OK) { + return result; + } + adduint8(param, buffer + offset); + return RETURN_OK; +} + +DebugCamera::DebugCamera() : ArcsecJsonParamBase(arcseckeys::DEBUG_CAMERA) {} + +size_t DebugCamera::getSize() { return COMMAND_SIZE; } + +ReturnValue_t DebugCamera::createCommand(uint8_t* buffer) { + ReturnValue_t result = RETURN_OK; + uint8_t offset = 0; + std::string param; + addSetParamHeader(buffer, startracker::ID::DEBUG_CAMERA); + offset = 2; + result = getParam(arcseckeys::TIMING, param); + if (result != RETURN_OK) { + return result; + } + adduint32(param, buffer + offset); + offset += sizeof(uint32_t); + result = getParam(arcseckeys::TEST, param); + if (result != RETURN_OK) { + return result; + } + adduint32(param, buffer + offset); + return RETURN_OK; +} diff --git a/linux/devices/startracker/StarTrackerJsonCommands.h b/linux/devices/startracker/StarTrackerJsonCommands.h new file mode 100644 index 00000000..381246a6 --- /dev/null +++ b/linux/devices/startracker/StarTrackerJsonCommands.h @@ -0,0 +1,240 @@ +#ifndef BSP_Q7S_DEVICES_DEVICEDEFINITIONS_STARTRACKERJSONCOMMANDS_H_ +#define BSP_Q7S_DEVICES_DEVICEDEFINITIONS_STARTRACKERJSONCOMMANDS_H_ + +/** + * @brief This file defines a few helper classes to generate commands by means of the parameters + * defined in the arcsec json files. + * @author J. Meier + */ + +#include + +#include "ArcsecJsonParamBase.h" +#include "fsfw/serviceinterface/ServiceInterface.h" + +/** + * @brief Generates command to set the limit parameters + * + */ +class Limits : public ArcsecJsonParamBase { + public: + Limits(); + + size_t getSize(); + + private: + static const size_t COMMAND_SIZE = 43; + + virtual ReturnValue_t createCommand(uint8_t* buffer) override; +}; + +/** + * @brief Generates the command to configure the tracking algorithm. + * + */ +class Tracking : public ArcsecJsonParamBase { + public: + Tracking(); + + size_t getSize(); + + private: + static const size_t COMMAND_SIZE = 15; + + ReturnValue_t createCommand(uint8_t* buffer) override; +}; + +/** + * @brief Generates the command to set the mounting quaternion + * + */ +class Mounting : public ArcsecJsonParamBase { + public: + Mounting(); + + size_t getSize(); + + private: + static const size_t COMMAND_SIZE = 18; + + ReturnValue_t createCommand(uint8_t* buffer) override; +}; + +/** + * @brief Generates the command to configure the image processor + * + */ +class ImageProcessor : public ArcsecJsonParamBase { + public: + ImageProcessor(); + + size_t getSize(); + + private: + static const size_t COMMAND_SIZE = 9; + + ReturnValue_t createCommand(uint8_t* buffer) override; +}; + +/** + * @brief Generates the command to set the mounting quaternion + * + */ +class Camera : public ArcsecJsonParamBase { + public: + Camera(); + + size_t getSize(); + + private: + static const size_t COMMAND_SIZE = 39; + + ReturnValue_t createCommand(uint8_t* buffer) override; +}; + +/** + * @brief Generates the command to configure the centroiding algorithm + * + */ +class Centroiding : public ArcsecJsonParamBase { + public: + Centroiding(); + + size_t getSize(); + + private: + static const size_t COMMAND_SIZE = 51; + + ReturnValue_t createCommand(uint8_t* buffer) override; +}; + +/** + * @brief Generates the command to configure the LISA (lost in space algorithm) + * + */ +class Lisa : public ArcsecJsonParamBase { + public: + Lisa(); + + size_t getSize(); + + private: + static const size_t COMMAND_SIZE = 52; + + ReturnValue_t createCommand(uint8_t* buffer) override; +}; + +/** + * @brief Generates the command to configure the matching algorithm + * + */ +class Matching : public ArcsecJsonParamBase { + public: + Matching(); + + size_t getSize(); + + private: + static const size_t COMMAND_SIZE = 10; + + ReturnValue_t createCommand(uint8_t* buffer) override; +}; + +/** + * @brief Generates the command to configure the validation parameters + * + */ +class Validation : public ArcsecJsonParamBase { + public: + Validation(); + + size_t getSize(); + + private: + static const size_t COMMAND_SIZE = 12; + + ReturnValue_t createCommand(uint8_t* buffer) override; +}; + +/** + * @brief Generates command to configure the mechanism of automatically switching between the + * LISA and other algorithms. + * + */ +class Algo : public ArcsecJsonParamBase { + public: + Algo(); + + size_t getSize(); + + private: + static const size_t COMMAND_SIZE = 13; + + ReturnValue_t createCommand(uint8_t* buffer) override; +}; + +/** + * @brief Generates command to configure the log level parameters. + * + */ +class LogLevel : public ArcsecJsonParamBase { + public: + LogLevel(); + + size_t getSize(); + + private: + static const size_t COMMAND_SIZE = 18; + + ReturnValue_t createCommand(uint8_t* buffer) override; +}; + +/** + * @brief Generates command to set subscription parameters. + * + */ +class Subscription : public ArcsecJsonParamBase { + public: + Subscription(); + + size_t getSize(); + + private: + static const size_t COMMAND_SIZE = 18; + + ReturnValue_t createCommand(uint8_t* buffer) override; +}; + +/** + * @brief Generates command to set log subscription parameters. + * + */ +class LogSubscription : public ArcsecJsonParamBase { + public: + LogSubscription(); + + size_t getSize(); + + private: + static const size_t COMMAND_SIZE = 6; + + ReturnValue_t createCommand(uint8_t* buffer) override; +}; + +/** + * @brief Generates command to set debug camera parameters + * + */ +class DebugCamera : public ArcsecJsonParamBase { + public: + DebugCamera(); + + size_t getSize(); + + private: + static const size_t COMMAND_SIZE = 10; + + ReturnValue_t createCommand(uint8_t* buffer) override; +}; + +#endif /* BSP_Q7S_DEVICES_DEVICEDEFINITIONS_STARTRACKERJSONCOMMANDS_H_ */ diff --git a/linux/devices/startracker/StrHelper.cpp b/linux/devices/startracker/StrHelper.cpp new file mode 100644 index 00000000..599b706f --- /dev/null +++ b/linux/devices/startracker/StrHelper.cpp @@ -0,0 +1,601 @@ +#include "StrHelper.h" + +#include +#include + +#include "OBSWConfig.h" +#include "fsfw/timemanager/Countdown.h" +#include "linux/devices/devicedefinitions/StarTrackerDefinitions.h" +#include "mission/utility/ProgressPrinter.h" +#include "mission/utility/Timestamp.h" + +StrHelper::StrHelper(object_id_t objectId) : SystemObject(objectId) {} + +StrHelper::~StrHelper() {} + +ReturnValue_t StrHelper::initialize() { +#ifdef XIPHOS_Q7S + sdcMan = SdCardManager::instance(); + if (sdcMan == nullptr) { + sif::warning << "StrHelper::initialize: Invalid SD Card Manager" << std::endl; + return RETURN_FAILED; + } +#endif + return RETURN_OK; +} + +ReturnValue_t StrHelper::performOperation(uint8_t operationCode) { + ReturnValue_t result = RETURN_OK; + semaphore.acquire(); + while (true) { + switch (internalState) { + case InternalState::IDLE: { + semaphore.acquire(); + break; + } + case InternalState::UPLOAD_IMAGE: { + result = performImageUpload(); + if (result == RETURN_OK) { + triggerEvent(IMAGE_UPLOAD_SUCCESSFUL); + } else { + triggerEvent(IMAGE_UPLOAD_FAILED); + } + internalState = InternalState::IDLE; + break; + } + case InternalState::DOWNLOAD_IMAGE: { + result = performImageDownload(); + if (result == RETURN_OK) { + triggerEvent(IMAGE_DOWNLOAD_SUCCESSFUL); + } else { + triggerEvent(IMAGE_DOWNLOAD_FAILED); + } + internalState = InternalState::IDLE; + break; + } + case InternalState::FLASH_READ: { + result = performFlashRead(); + if (result == RETURN_OK) { + triggerEvent(FLASH_READ_SUCCESSFUL); + } else { + triggerEvent(FLASH_READ_FAILED); + } + internalState = InternalState::IDLE; + break; + } + case InternalState::FIRMWARE_UPDATE: { + result = performFirmwareUpdate(); + if (result == RETURN_OK) { + triggerEvent(FIRMWARE_UPDATE_SUCCESSFUL); + } else { + triggerEvent(FIRMWARE_UPDATE_FAILED); + } + internalState = InternalState::IDLE; + break; + } + default: + sif::debug << "StrHelper::performOperation: Invalid state" << std::endl; + break; + } + } +} + +ReturnValue_t StrHelper::setComIF(DeviceCommunicationIF* communicationInterface_) { + uartComIF = dynamic_cast(communicationInterface_); + if (uartComIF == nullptr) { + sif::warning << "StrHelper::initialize: Invalid uart com if" << std::endl; + return RETURN_FAILED; + } + return RETURN_OK; +} + +void StrHelper::setComCookie(CookieIF* comCookie_) { comCookie = comCookie_; } + +ReturnValue_t StrHelper::startImageUpload(std::string fullname) { +#ifdef XIPHOS_Q7S + ReturnValue_t result = checkPath(fullname); + if (result != RETURN_OK) { + return result; + } +#endif + uploadImage.uploadFile = fullname; + if (not std::filesystem::exists(fullname)) { + return FILE_NOT_EXISTS; + } + internalState = InternalState::UPLOAD_IMAGE; + semaphore.release(); + terminate = false; + return RETURN_OK; +} + +ReturnValue_t StrHelper::startImageDownload(std::string path) { +#ifdef XIPHOS_Q7S + ReturnValue_t result = checkPath(path); + if (result != RETURN_OK) { + return result; + } +#endif + if (not std::filesystem::exists(path)) { + return PATH_NOT_EXISTS; + } + downloadImage.path = path; + internalState = InternalState::DOWNLOAD_IMAGE; + terminate = false; + semaphore.release(); + return RETURN_OK; +} + +void StrHelper::stopProcess() { terminate = true; } + +void StrHelper::setDownloadImageName(std::string filename) { downloadImage.filename = filename; } + +void StrHelper::setFlashReadFilename(std::string filename) { flashRead.filename = filename; } + +ReturnValue_t StrHelper::startFirmwareUpdate(std::string fullname) { +#ifdef XIPHOS_Q7S + ReturnValue_t result = checkPath(fullname); + if (result != RETURN_OK) { + return result; + } +#endif + flashWrite.fullname = fullname; + if (not std::filesystem::exists(flashWrite.fullname)) { + return FILE_NOT_EXISTS; + } + flashWrite.firstRegion = static_cast(startracker::FirmwareRegions::FIRST); + flashWrite.lastRegion = static_cast(startracker::FirmwareRegions::LAST); + internalState = InternalState::FIRMWARE_UPDATE; + semaphore.release(); + terminate = false; + return RETURN_OK; +} + +ReturnValue_t StrHelper::startFlashRead(std::string path, uint8_t startRegion, uint32_t length) { +#ifdef XIPHOS_Q7S + ReturnValue_t result = checkPath(path); + if (result != RETURN_OK) { + return result; + } +#endif + flashRead.path = path; + if (not std::filesystem::exists(flashRead.path)) { + return FILE_NOT_EXISTS; + } + flashRead.startRegion = startRegion; + flashRead.size = length; + internalState = InternalState::FLASH_READ; + semaphore.release(); + terminate = false; + return RETURN_OK; +} + +void StrHelper::disableTimestamping() { timestamping = false; } + +void StrHelper::enableTimestamping() { timestamping = true; } + +ReturnValue_t StrHelper::performImageDownload() { + ReturnValue_t result; +#if OBSW_DEBUG_STARTRACKER == 1 + ProgressPrinter progressPrinter("Image download", ImageDownload::LAST_POSITION); +#endif /* OBSW_DEBUG_STARTRACKER == 1 */ + struct DownloadActionRequest downloadReq; + uint32_t size = 0; + uint32_t retries = 0; + std::string image = makeFullFilename(downloadImage.path, downloadImage.filename); + std::ofstream file(image, std::ios_base::out); + if (not std::filesystem::exists(image)) { + return FILE_CREATION_FAILED; + } + downloadReq.position = 0; + while (downloadReq.position < ImageDownload::LAST_POSITION) { + if (terminate) { + file.close(); + return RETURN_OK; + } + arc_pack_download_action_req(&downloadReq, commandBuffer, &size); + result = sendAndRead(size, downloadReq.position); + if (result != RETURN_OK) { + if (retries < CONFIG_MAX_DOWNLOAD_RETRIES) { + uartComIF->flushUartRxBuffer(comCookie); + retries++; + continue; + } + file.close(); + return result; + } + result = checkActionReply(); + if (result != RETURN_OK) { + if (retries < CONFIG_MAX_DOWNLOAD_RETRIES) { + uartComIF->flushUartRxBuffer(comCookie); + retries++; + continue; + } + file.close(); + return result; + } + result = checkReplyPosition(downloadReq.position); + if (result != RETURN_OK) { + if (retries < CONFIG_MAX_DOWNLOAD_RETRIES) { + uartComIF->flushUartRxBuffer(comCookie); + retries++; + continue; + } + file.close(); + return result; + } + file.write(reinterpret_cast(datalinkLayer.getReply() + IMAGE_DATA_OFFSET), + CHUNK_SIZE); +#if OBSW_DEBUG_STARTRACKER == 1 + progressPrinter.print(downloadReq.position); +#endif /* OBSW_DEBUG_STARTRACKER == 1 */ + downloadReq.position++; + retries = 0; + } + file.close(); + return RETURN_OK; +} + +ReturnValue_t StrHelper::performImageUpload() { + ReturnValue_t result = RETURN_OK; + uint32_t size = 0; + uint32_t imageSize = 0; + struct UploadActionRequest uploadReq; + uploadReq.position = 0; + std::memset(&uploadReq.data, 0, sizeof(uploadReq.data)); + if (not std::filesystem::exists(uploadImage.uploadFile)) { + triggerEvent(STR_HELPER_FILE_NOT_EXISTS, static_cast(internalState)); + internalState = InternalState::IDLE; + return RETURN_FAILED; + } + std::ifstream file(uploadImage.uploadFile, std::ifstream::binary); + // Set position of next character to end of file input stream + file.seekg(0, file.end); + // tellg returns position of character in input stream + imageSize = file.tellg(); +#if OBSW_DEBUG_STARTRACKER == 1 + ProgressPrinter progressPrinter("Image upload", imageSize); +#endif /* OBSW_DEBUG_STARTRACKER == 1 */ + while ((uploadReq.position + 1) * SIZE_IMAGE_PART < imageSize) { + if (terminate) { + file.close(); + return RETURN_OK; + } + file.seekg(uploadReq.position * SIZE_IMAGE_PART, file.beg); + file.read(reinterpret_cast(uploadReq.data), SIZE_IMAGE_PART); + arc_pack_upload_action_req(&uploadReq, commandBuffer, &size); + result = sendAndRead(size, uploadReq.position); + if (result != RETURN_OK) { + file.close(); + return RETURN_FAILED; + } + result = checkActionReply(); + if (result != RETURN_OK) { + file.close(); + return result; + } +#if OBSW_DEBUG_STARTRACKER == 1 + progressPrinter.print((uploadReq.position + 1) * SIZE_IMAGE_PART); +#endif /* OBSW_DEBUG_STARTRACKER == 1 */ + uploadReq.position++; + } + std::memset(uploadReq.data, 0, sizeof(uploadReq.data)); + uint32_t remainder = imageSize - uploadReq.position * SIZE_IMAGE_PART; + file.seekg(uploadReq.position * SIZE_IMAGE_PART, file.beg); + file.read(reinterpret_cast(uploadReq.data), remainder); + file.close(); + uploadReq.position++; + arc_pack_upload_action_req(&uploadReq, commandBuffer, &size); + result = sendAndRead(size, uploadReq.position); + if (result != RETURN_OK) { + return RETURN_FAILED; + } + result = checkActionReply(); + if (result != RETURN_OK) { + return result; + } +#if OBSW_DEBUG_STARTRACKER == 1 + progressPrinter.print((uploadReq.position + 1) * SIZE_IMAGE_PART); +#endif /* OBSW_DEBUG_STARTRACKER == 1 */ + return RETURN_OK; +} + +ReturnValue_t StrHelper::performFirmwareUpdate() { + using namespace startracker; + ReturnValue_t result = RETURN_OK; + result = unlockAndEraseRegions(static_cast(startracker::FirmwareRegions::FIRST), + static_cast(startracker::FirmwareRegions::LAST)); + if (result != RETURN_OK) { + return result; + } + result = performFlashWrite(); + return result; +} + +ReturnValue_t StrHelper::performFlashWrite() { + ReturnValue_t result = RETURN_OK; + uint32_t size = 0; + uint32_t bytesWritten = 0; + uint32_t fileSize = 0; + struct WriteActionRequest req; + if (not std::filesystem::exists(flashWrite.fullname)) { + triggerEvent(STR_HELPER_FILE_NOT_EXISTS, static_cast(internalState)); + internalState = InternalState::IDLE; + return RETURN_FAILED; + } + std::ifstream file(flashWrite.fullname, std::ifstream::binary); + file.seekg(0, file.end); + fileSize = file.tellg(); + if (fileSize > FLASH_REGION_SIZE * (flashWrite.lastRegion - flashWrite.firstRegion)) { + sif::warning << "StrHelper::performFlashWrite: Invalid file" << std::endl; + return RETURN_FAILED; + } +#if OBSW_DEBUG_STARTRACKER == 1 + ProgressPrinter progressPrinter("Flash write", fileSize); +#endif /* OBSW_DEBUG_STARTRACKER == 1 */ + uint32_t fileChunks = fileSize / CHUNK_SIZE; + bytesWritten = 0; + req.region = flashWrite.firstRegion; + req.length = CHUNK_SIZE; + for (uint32_t idx = 0; idx < fileChunks; idx++) { + if (terminate) { + file.close(); + return RETURN_OK; + } + file.seekg(idx * CHUNK_SIZE, file.beg); + file.read(reinterpret_cast(req.data), CHUNK_SIZE); + if (bytesWritten + CHUNK_SIZE > FLASH_REGION_SIZE) { + req.region++; + bytesWritten = 0; + } + req.address = bytesWritten; + arc_pack_write_action_req(&req, commandBuffer, &size); + result = sendAndRead(size, req.address); + if (result != RETURN_OK) { + file.close(); + return result; + } + result = checkActionReply(); + if (result != RETURN_OK) { + file.close(); + return result; + } + bytesWritten += CHUNK_SIZE; +#if OBSW_DEBUG_STARTRACKER == 1 + progressPrinter.print(idx * CHUNK_SIZE); +#endif /* OBSW_DEBUG_STARTRACKER == 1 */ + } + uint32_t remainingBytes = fileSize - fileChunks * CHUNK_SIZE; + file.seekg((fileChunks - 1) * CHUNK_SIZE, file.beg); + file.read(reinterpret_cast(req.data), remainingBytes); + file.close(); + if (bytesWritten + CHUNK_SIZE > FLASH_REGION_SIZE) { + req.region++; + bytesWritten = 0; + } + req.address = bytesWritten; + req.length = remainingBytes; + bytesWritten += remainingBytes; + arc_pack_write_action_req(&req, commandBuffer, &size); + result = sendAndRead(size, req.address); + if (result != RETURN_OK) { + return result; + } + result = checkActionReply(); + if (result != RETURN_OK) { + return result; + } +#if OBSW_DEBUG_STARTRACKER == 1 + progressPrinter.print(fileSize); +#endif /* OBSW_DEBUG_STARTRACKER == 1 */ + return RETURN_OK; +} + +ReturnValue_t StrHelper::performFlashRead() { + ReturnValue_t result; +#if OBSW_DEBUG_STARTRACKER == 1 + ProgressPrinter progressPrinter("Flash read", flashRead.size); +#endif /* OBSW_DEBUG_STARTRACKER == 1 */ + struct ReadActionRequest req; + uint32_t bytesRead = 0; + uint32_t size = 0; + uint32_t retries = 0; + Timestamp timestamp; + std::string fullname = makeFullFilename(flashRead.path, flashRead.filename); + std::ofstream file(fullname, std::ios_base::app | std::ios_base::out); + if (not std::filesystem::exists(fullname)) { + return FILE_CREATION_FAILED; + } + req.region = flashRead.startRegion; + req.address = 0; + while (bytesRead < flashRead.size) { + if (terminate) { + return RETURN_OK; + } + if ((flashRead.size - bytesRead) < CHUNK_SIZE) { + req.length = flashRead.size - bytesRead; + } else { + req.length = CHUNK_SIZE; + } + arc_pack_read_action_req(&req, commandBuffer, &size); + result = sendAndRead(size, req.address); + if (result != RETURN_OK) { + if (retries < CONFIG_MAX_DOWNLOAD_RETRIES) { + uartComIF->flushUartRxBuffer(comCookie); + retries++; + continue; + } + file.close(); + return result; + } + result = checkActionReply(); + if (result != RETURN_OK) { + if (retries < CONFIG_MAX_DOWNLOAD_RETRIES) { + uartComIF->flushUartRxBuffer(comCookie); + retries++; + continue; + } + file.close(); + return result; + } + file.write(reinterpret_cast(datalinkLayer.getReply() + FLASH_READ_DATA_OFFSET), + req.length); + bytesRead += req.length; + req.address += req.length; + if (req.address >= FLASH_REGION_SIZE) { + req.address = 0; + req.region++; + } + retries = 0; +#if OBSW_DEBUG_STARTRACKER == 1 + progressPrinter.print(bytesRead); +#endif /* OBSW_DEBUG_STARTRACKER == 1 */ + } + file.close(); + return RETURN_OK; +} + +ReturnValue_t StrHelper::sendAndRead(size_t size, uint32_t parameter, uint32_t delayMs) { + ReturnValue_t result = RETURN_OK; + ReturnValue_t decResult = RETURN_OK; + size_t receivedDataLen = 0; + uint8_t* receivedData = nullptr; + size_t bytesLeft = 0; + uint32_t missedReplies = 0; + datalinkLayer.encodeFrame(commandBuffer, size); + result = uartComIF->sendMessage(comCookie, datalinkLayer.getEncodedFrame(), + datalinkLayer.getEncodedLength()); + if (result != RETURN_OK) { + sif::warning << "StrHelper::sendAndRead: Failed to send packet" << std::endl; + triggerEvent(STR_HELPER_SENDING_PACKET_FAILED, result, parameter); + return RETURN_FAILED; + } + decResult = ArcsecDatalinkLayer::DEC_IN_PROGRESS; + while (decResult == ArcsecDatalinkLayer::DEC_IN_PROGRESS) { + Countdown delay(delayMs); + delay.resetTimer(); + while (delay.isBusy()) { + } + result = uartComIF->requestReceiveMessage(comCookie, startracker::MAX_FRAME_SIZE * 2 + 2); + if (result != RETURN_OK) { + sif::warning << "StrHelper::sendAndRead: Failed to request reply" << std::endl; + triggerEvent(STR_HELPER_REQUESTING_MSG_FAILED, result, parameter); + return RETURN_FAILED; + } + result = uartComIF->readReceivedMessage(comCookie, &receivedData, &receivedDataLen); + if (result != RETURN_OK) { + sif::warning << "StrHelper::sendAndRead: Failed to read received message" << std::endl; + triggerEvent(STR_HELPER_READING_REPLY_FAILED, result, parameter); + return RETURN_FAILED; + } + if (receivedDataLen == 0 && missedReplies < MAX_POLLS) { + missedReplies++; + continue; + } else if ((receivedDataLen == 0) && (missedReplies >= MAX_POLLS)) { + triggerEvent(STR_HELPER_NO_REPLY, parameter); + return RETURN_FAILED; + } else { + missedReplies = 0; + } + decResult = datalinkLayer.decodeFrame(receivedData, receivedDataLen, &bytesLeft); + if (bytesLeft != 0) { + // This should never happen + sif::warning << "StrHelper::sendAndRead: Bytes left after decoding" << std::endl; + triggerEvent(STR_HELPER_COM_ERROR, result, parameter); + return RETURN_FAILED; + } + } + if (decResult != RETURN_OK) { + triggerEvent(STR_HELPER_DEC_ERROR, decResult, parameter); + return RETURN_FAILED; + } + return RETURN_OK; +} + +ReturnValue_t StrHelper::checkActionReply() { + uint8_t type = datalinkLayer.getReplyFrameType(); + if (type != TMTC_ACTIONREPLY) { + sif::warning << "StrHelper::checkActionReply: Received reply with invalid type ID" << std::endl; + return INVALID_TYPE_ID; + } + uint8_t status = datalinkLayer.getStatusField(); + if (status != ArcsecDatalinkLayer::STATUS_OK) { + sif::warning << "StrHelper::checkActionReply: Status failure: " + << static_cast(status) << std::endl; + return STATUS_ERROR; + } + return RETURN_OK; +} + +ReturnValue_t StrHelper::checkReplyPosition(uint32_t expectedPosition) { + uint32_t receivedPosition = 0; + std::memcpy(&receivedPosition, datalinkLayer.getReply() + POS_OFFSET, sizeof(receivedPosition)); + if (receivedPosition != expectedPosition) { + triggerEvent(POSITION_MISMATCH, receivedPosition); + return RETURN_FAILED; + } + return RETURN_OK; +} + +#ifdef XIPHOS_Q7S +ReturnValue_t StrHelper::checkPath(std::string name) { + if (name.substr(0, sizeof(SdCardManager::SD_0_MOUNT_POINT)) == + std::string(SdCardManager::SD_0_MOUNT_POINT)) { + if (!sdcMan->isSdCardMounted(sd::SLOT_0)) { + sif::warning << "StrHelper::checkPath: SD card 0 not mounted" << std::endl; + return SD_NOT_MOUNTED; + } + } else if (name.substr(0, sizeof(SdCardManager::SD_1_MOUNT_POINT)) == + std::string(SdCardManager::SD_1_MOUNT_POINT)) { + if (!sdcMan->isSdCardMounted(sd::SLOT_0)) { + sif::warning << "StrHelper::checkPath: SD card 1 not mounted" << std::endl; + return SD_NOT_MOUNTED; + } + } + return RETURN_OK; +} +#endif + +ReturnValue_t StrHelper::unlockAndEraseRegions(uint32_t from, uint32_t to) { + ReturnValue_t result = RETURN_OK; +#if OBSW_DEBUG_STARTRACKER == 1 + ProgressPrinter progressPrinter("Unlock and erase", to - from); +#endif /* OBSW_DEBUG_STARTRACKER == 1 */ + struct UnlockActionRequest unlockReq; + struct EraseActionRequest eraseReq; + uint32_t size = 0; + for (uint32_t idx = from; idx <= to; idx++) { + unlockReq.region = idx; + unlockReq.code = startracker::region_secrets::secret[idx]; + arc_pack_unlock_action_req(&unlockReq, commandBuffer, &size); + sendAndRead(size, unlockReq.region); + result = checkActionReply(); + if (result != RETURN_OK) { + sif::warning << "StrHelper::unlockAndEraseRegions: Failed to unlock region with id " + << static_cast(unlockReq.region) << std::endl; + return result; + } + eraseReq.region = idx; + arc_pack_erase_action_req(&eraseReq, commandBuffer, &size); + result = sendAndRead(size, eraseReq.region, FLASH_ERASE_DELAY); + if (result != RETURN_OK) { + sif::warning << "StrHelper::unlockAndEraseRegions: Failed to erase region with id " + << static_cast(eraseReq.region) << std::endl; + return result; + } +#if OBSW_DEBUG_STARTRACKER == 1 + progressPrinter.print(idx - from); +#endif /* OBSW_DEBUG_STARTRACKER == 1 */ + } + 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 new file mode 100644 index 00000000..f34e96ce --- /dev/null +++ b/linux/devices/startracker/StrHelper.h @@ -0,0 +1,364 @@ +#ifndef BSP_Q7S_DEVICES_STRHELPER_H_ +#define BSP_Q7S_DEVICES_STRHELPER_H_ + +#include + +#include "ArcsecDatalinkLayer.h" +#include "OBSWConfig.h" + +#ifdef XIPHOS_Q7S +#include "bsp_q7s/memory/SdCardManager.h" +#endif + +#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" + +extern "C" { +#include "thirdparty/arcsec_star_tracker/client/generated/actionreq.h" +#include "thirdparty/arcsec_star_tracker/common/generated/tmtcstructs.h" +} + +/** + * @brief Helper class for the star tracker handler to accelerate large data transfers. + * + * @author J. Meier + */ +class StrHelper : public SystemObject, public ExecutableObjectIF, public HasReturnvaluesIF { + public: + static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::STR_HELPER; + + //! [EXPORT] : [COMMENT] Image upload failed + static const Event IMAGE_UPLOAD_FAILED = MAKE_EVENT(0, severity::LOW); + //! [EXPORT] : [COMMENT] Image download failed + static const Event IMAGE_DOWNLOAD_FAILED = MAKE_EVENT(1, severity::LOW); + //! [EXPORT] : [COMMENT] Uploading image to star tracker was successfulop + static const Event IMAGE_UPLOAD_SUCCESSFUL = MAKE_EVENT(2, severity::LOW); + //! [EXPORT] : [COMMENT] Image download was successful + static const Event IMAGE_DOWNLOAD_SUCCESSFUL = MAKE_EVENT(3, severity::LOW); + //! [EXPORT] : [COMMENT] Finished flash write procedure successfully + static const Event FLASH_WRITE_SUCCESSFUL = MAKE_EVENT(4, severity::LOW); + //! [EXPORT] : [COMMENT] Finished flash read procedure successfully + static const Event FLASH_READ_SUCCESSFUL = MAKE_EVENT(5, severity::LOW); + //! [EXPORT] : [COMMENT] Flash read procedure failed + static const Event FLASH_READ_FAILED = MAKE_EVENT(6, severity::LOW); + //! [EXPORT] : [COMMENT] Firmware update was successful + static const Event FIRMWARE_UPDATE_SUCCESSFUL = MAKE_EVENT(7, severity::LOW); + //! [EXPORT] : [COMMENT] Firmware update failed + static const Event FIRMWARE_UPDATE_FAILED = MAKE_EVENT(8, severity::LOW); + //! [EXPORT] : [COMMENT] Failed to read communication interface reply data + //! P1: Return code of failed communication interface read call + //! P1: Upload/download position for which the read call failed + static const Event STR_HELPER_READING_REPLY_FAILED = MAKE_EVENT(9, severity::LOW); + //! [EXPORT] : [COMMENT] Unexpected stop of decoding sequence + //! P1: Return code of failed communication interface read call + //! P1: Upload/download position for which the read call failed + static const Event STR_HELPER_COM_ERROR = MAKE_EVENT(10, severity::LOW); + //! [EXPORT] : [COMMENT] Star tracker did not send replies (maybe device is powered off) + //! P1: Position of upload or download packet for which no reply was sent + static const Event STR_HELPER_NO_REPLY = MAKE_EVENT(11, severity::LOW); + //! [EXPORT] : [COMMENT] Error during decoding of received reply occurred + // P1: Return value of decoding function + // P2: Position of upload/download packet, or address of flash write/read request + static const Event STR_HELPER_DEC_ERROR = MAKE_EVENT(12, severity::LOW); + //! [EXPORT] : [COMMENT] Position mismatch + //! P1: The expected position and thus the position for which the image upload/download failed + static const Event POSITION_MISMATCH = MAKE_EVENT(13, severity::LOW); + //! [EXPORT] : [COMMENT] Specified file does not exist + //! P1: Internal state of str helper + static const Event STR_HELPER_FILE_NOT_EXISTS = MAKE_EVENT(14, severity::LOW); + //! [EXPORT] : [COMMENT] Sending packet to star tracker failed + //! P1: Return code of communication interface sendMessage function + //! P2: Position of upload/download packet, or address of flash write/read request for which + //! sending failed + static const Event STR_HELPER_SENDING_PACKET_FAILED = MAKE_EVENT(15, severity::LOW); + //! [EXPORT] : [COMMENT] Communication interface requesting reply failed + //! P1: Return code of failed request + //! P1: Upload/download position, or address of flash write/read request for which transmission + //! failed + static const Event STR_HELPER_REQUESTING_MSG_FAILED = MAKE_EVENT(16, severity::LOW); + + StrHelper(object_id_t objectId); + virtual ~StrHelper(); + + ReturnValue_t initialize() override; + ReturnValue_t performOperation(uint8_t operationCode = 0) override; + + ReturnValue_t setComIF(DeviceCommunicationIF* communicationInterface_); + void setComCookie(CookieIF* comCookie_); + + /** + * @brief Starts sequence to upload image to star tracker + * + * @param uploadImage_ Name including absolute path of the image to upload. Must be previously + * transferred to the OBC with the CFDP protocol. + */ + ReturnValue_t startImageUpload(std::string uploadImage_); + + /** + * @brief Calling this function initiates the download of an image from the star tracker. + * + * @param path Path where downloaded image will be stored + */ + ReturnValue_t startImageDownload(std::string path); + + /** + * @brief Will start the firmware update + * + * @param fullname Full name including absolute path of file containing firmware + * update. + */ + ReturnValue_t startFirmwareUpdate(std::string fullname); + + /** + * @brief Starts the flash read procedure + * + * @param path Path where file with read flash data will be created + * @param startRegion Region form where to start reading + * @param length Number of bytes to read from flash + */ + ReturnValue_t startFlashRead(std::string path, uint8_t startRegion, uint32_t length); + + /** + * @brief Can be used to interrupt a running data transfer. + */ + void stopProcess(); + + /** + * @brief Changes the dafault name of downloaded images + */ + void setDownloadImageName(std::string filename); + + /** + * @brief Sets the name of the file which will be created to store the data read from flash + */ + void setFlashReadFilename(std::string filename); + + /** + * @brief Disables timestamp generation when new file is created + */ + void disableTimestamping(); + + /** + * @brief Enables timestamp generation when new file is created + */ + void enableTimestamping(); + + private: + static const uint8_t INTERFACE_ID = CLASS_ID::STR_HELPER; + + //! [EXPORT] : [COMMENT] SD card specified in path string not mounted + static const ReturnValue_t SD_NOT_MOUNTED = MAKE_RETURN_CODE(0xA0); + //! [EXPORT] : [COMMENT] Specified file does not exist on filesystem + static const ReturnValue_t FILE_NOT_EXISTS = MAKE_RETURN_CODE(0xA1); + //! [EXPORT] : [COMMENT] Specified path does not exist + static const ReturnValue_t PATH_NOT_EXISTS = MAKE_RETURN_CODE(0xA2); + //! [EXPORT] : [COMMENT] Failed to create download image or read flash file + static const ReturnValue_t FILE_CREATION_FAILED = MAKE_RETURN_CODE(0xA3); + //! [EXPORT] : [COMMENT] Region in flash write/read reply does not match expected region + static const ReturnValue_t REGION_MISMATCH = MAKE_RETURN_CODE(0xA4); + //! [EXPORT] : [COMMENT] Address in flash write/read reply does not match expected address + static const ReturnValue_t ADDRESS_MISMATCH = MAKE_RETURN_CODE(0xA5); + //! [EXPORT] : [COMMENT] Length in flash write/read reply does not match expected length + static const ReturnValue_t LENGTH_MISMATCH = MAKE_RETURN_CODE(0xA6); + //! [EXPORT] : [COMMENT] Status field in reply signals error + static const ReturnValue_t STATUS_ERROR = MAKE_RETURN_CODE(0xA7); + //! [EXPORT] : [COMMENT] Reply has invalid type ID (should be of action reply type) + static const ReturnValue_t INVALID_TYPE_ID = MAKE_RETURN_CODE(0xA8); + + // Size of one image part which can be sent per action request + static const size_t SIZE_IMAGE_PART = 1024; + static const uint32_t FLASH_REGION_SIZE = 0x20000; + + class ImageDownload { + public: + static const uint32_t LAST_POSITION = 4095; + }; + + static const uint32_t MAX_POLLS = 10000; + + static const uint8_t ACTION_DATA_OFFSET = 2; + static const uint8_t POS_OFFSET = 2; + static const uint8_t IMAGE_DATA_OFFSET = 5; + static const uint8_t FLASH_READ_DATA_OFFSET = 8; + static const uint8_t REGION_OFFSET = 2; + static const uint8_t ADDRESS_OFFSET = 3; + static const uint8_t LENGTH_OFFSET = 7; + static const size_t CHUNK_SIZE = 1024; + static const size_t CONFIG_MAX_DOWNLOAD_RETRIES = 3; + static const uint32_t FLASH_ERASE_DELAY = 500; + + enum class InternalState { IDLE, UPLOAD_IMAGE, DOWNLOAD_IMAGE, FLASH_READ, FIRMWARE_UPDATE }; + + InternalState internalState = InternalState::IDLE; + + ArcsecDatalinkLayer datalinkLayer; + + BinarySemaphore semaphore; + + class UploadImage { + public: + // Name including absolute path of image to upload + std::string uploadFile; + }; + UploadImage uploadImage; + + class DownloadImage { + public: + // Path where the downloaded image will be stored + std::string path; + // Default name of downloaded image, can be changed via command + std::string filename = "image.bin"; + }; + DownloadImage downloadImage; + + class FlashWrite { + public: + // File which contains data to write when executing the flash write command + std::string fullname; + // The first region to write to + uint8_t firstRegion = 0; + // Maximum region the flash write command is allowed to write to + uint8_t lastRegion = 0; + // Will be set with the flash write command and specifies the start address where to write the + // flash data to + uint32_t address = 0; + }; + FlashWrite flashWrite; + + class FlashRead { + public: + // 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 + std::string filename = "flashread.bin"; + // Will be set with the flash read command + uint8_t startRegion = 0; + // Number of bytes to read from flash + uint32_t size = 0; + }; + FlashRead flashRead; + +#ifdef XIPHOS_Q7S + SdCardManager* sdcMan = nullptr; +#endif + + uint8_t commandBuffer[startracker::MAX_FRAME_SIZE]; + + bool terminate = false; + +#ifdef EGSE + bool timestamping = false; +#else + bool timestamping = true; +#endif + + /** + * UART communication object responsible for low level access of star tracker + * Must be set by star tracker handler + */ + UartComIF* uartComIF = nullptr; + // Communication cookie. Must be set by the star tracker handler + CookieIF* comCookie = nullptr; + + // Queue id of raw data receiver + MessageQueueId_t rawDataReceiver = MessageQueueIF::NO_QUEUE; + + /** + * @brief Performs image uploading + */ + ReturnValue_t performImageUpload(); + + /** + * @brief Performs firmware update + * + * @return RETURN_OK if successful, otherwise error return value + */ + ReturnValue_t performFirmwareUpdate(); + + /** + * @brief Performs download of last taken image from the star tracker. + * + * @details Download is split over multiple packets transporting each a maximum of 1024 bytes. + * In case the download of one position fails, the same packet will be again + * requested. If the download of the packet fails CONFIG_MAX_DOWNLOAD_RETRIES times, + * the download will be stopped. + */ + ReturnValue_t performImageDownload(); + + /** + * @brief Handles flash write procedure + * + * @param ID of first region to write to + * + * @return RETURN_OK if successful, otherwise RETURN_FAILED + */ + ReturnValue_t performFlashWrite(); + + /** + * @brief Sends a sequence of commands to the star tracker to read larger parts from the + * flash memory. + */ + ReturnValue_t performFlashRead(); + + /** + * @brief Sends packet to the star tracker and reads reply by using the communication + * interface + * + * @param size Size of data beforehand written to the commandBuffer + * @param parameter Parameter 2 of trigger event function + * @param delayMs Delay in milliseconds between send and receive call + * + * @return RETURN_OK if successful, otherwise RETURN_FAILED + */ + ReturnValue_t sendAndRead(size_t size, uint32_t parameter, uint32_t delayMs = 0); + + /** + * @brief Checks the header (type id and status fields) of the action reply + * + * @return RETURN_OK if reply confirms success of packet transfer, otherwise REUTRN_FAILED + */ + ReturnValue_t checkActionReply(); + + /** + * @brief Checks the position field in a star tracker upload/download reply. + * + * @param expectedPosition Value of expected position + * + * @return RETURN_OK if received position matches expected position, otherwise RETURN_FAILED + */ + ReturnValue_t checkReplyPosition(uint32_t expectedPosition); + +#ifdef XIPHOS_Q7S + /** + * @brief Checks if a path points to an sd card and whether the SD card is monuted. + * + * @return SD_NOT_MOUNTED id SD card is not mounted, otherwise RETURN_OK + */ + ReturnValue_t checkPath(std::string name); +#endif + + /** + * @brief Unlocks a range of flash regions + * + * @param from First region in range to unlock + * @param to Last region in range to unlock + * + */ + 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 277b89db..8d13e67b 100644 --- a/linux/fsfwconfig/CMakeLists.txt +++ b/linux/fsfwconfig/CMakeLists.txt @@ -1,22 +1,28 @@ -target_sources(${TARGET_NAME} PRIVATE +target_sources(${OBSW_NAME} PRIVATE ipc/MissionMessageTypes.cpp pollingsequence/pollingSequenceFactory.cpp ) -target_include_directories(${TARGET_NAME} PUBLIC +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(${TARGET_NAME} PRIVATE + 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(${TARGET_NAME} PRIVATE + target_sources(${OBSW_NAME} PRIVATE + events/translateEvents.cpp + ) + target_sources(${UNITTEST_NAME} PRIVATE events/translateEvents.cpp ) endif() diff --git a/linux/fsfwconfig/FSFWConfig.h.in b/linux/fsfwconfig/FSFWConfig.h.in index 1b8251da..9db84254 100644 --- a/linux/fsfwconfig/FSFWConfig.h.in +++ b/linux/fsfwconfig/FSFWConfig.h.in @@ -72,12 +72,13 @@ static constexpr size_t FSFW_MAX_TM_PACKET_SIZE = 2048; } -#define FSFW_HAL_LINUX_SPI_WIRETAPPING 0 +#define FSFW_HAL_SPI_WIRETAPPING 0 +#define FSFW_HAL_I2C_WIRETAPPING 0 #define FSFW_DEV_HYPERION_GPS_CREATE_NMEA_CSV 0 #define FSFW_HAL_L3GD20_GYRO_DEBUG 0 #define FSFW_HAL_RM3100_MGM_DEBUG 0 #define FSFW_HAL_LIS3MDL_MGM_DEBUG 0 -#define FSFW_HAL_ADIS16507_GYRO_DEBUG 0 +#define FSFW_HAL_ADIS1650X_GYRO_DEBUG 0 #endif /* CONFIG_FSFWCONFIG_H_ */ diff --git a/linux/fsfwconfig/OBSWConfig.h.in b/linux/fsfwconfig/OBSWConfig.h.in index bf5c1405..cc90cd78 100644 --- a/linux/fsfwconfig/OBSWConfig.h.in +++ b/linux/fsfwconfig/OBSWConfig.h.in @@ -9,6 +9,7 @@ #cmakedefine RASPBERRY_PI #cmakedefine XIPHOS_Q7S #cmakedefine BEAGLEBONEBLACK +#cmakedefine EGSE #ifdef RASPBERRY_PI #include "rpiConfig.h" @@ -33,21 +34,94 @@ debugging. */ //! All of this should be enabled for mission code! #if defined XIPHOS_Q7S +#define OBSW_USE_CCSDS_IP_CORE 1 +// Set to 1 if all telemetry should be sent to the PTME IP Core +#define OBSW_TM_TO_PTME 0 +// Set to 1 if telecommands are received via the PDEC IP Core +#define OBSW_TC_FROM_PDEC 0 + #define OBSW_ENABLE_TIMERS 1 +#define OBSW_ADD_MGT 1 +#define OBSW_ADD_BPX_BATTERY_HANDLER 1 #define OBSW_ADD_STAR_TRACKER 0 #define OBSW_ADD_PLOC_SUPERVISOR 0 #define OBSW_ADD_PLOC_MPSOC 0 #define OBSW_ADD_SUN_SENSORS 0 -#define OBSW_ADD_ACS_BOARD 0 -#define OBSW_ADD_GPS_0 0 -#define OBSW_ADD_GPS_1 0 +#define OBSW_ADD_ACS_BOARD 1 +#define OBSW_ADD_ACS_HANDLERS 0 #define OBSW_ADD_RW 0 #define OBSW_ADD_RTD_DEVICES 0 #define OBSW_ADD_TMP_DEVICES 0 #define OBSW_ADD_RAD_SENSORS 0 +#define OBSW_ADD_PL_PCDU 0 #define OBSW_ADD_SYRLINKS 0 +#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 -#elif defined RASPBERRY_PI +#endif + +#ifdef EGSE +#define OBSW_ADD_STAR_TRACKER 1 +#endif + +/*******************************************************************/ +/** All of the following flags should be disabled for mission code */ +/*******************************************************************/ + +// Can be used to switch device to NORMAL mode immediately +#define OBSW_SWITCH_TO_NORMAL_MODE_AFTER_STARTUP 1 +#define OBSW_PRINT_MISSED_DEADLINES 1 + +#define OBSW_SYRLINKS_SIMULATED 1 +#define OBSW_ADD_TEST_CODE 0 +#define OBSW_ADD_TEST_TASK 0 +#define OBSW_ADD_TEST_PST 0 +// If this is enabled, all other SPI code should be disabled +#define OBSW_ADD_SPI_TEST_CODE 0 +// If this is enabled, all other I2C code should be disabled +#define OBSW_ADD_I2C_TEST_CODE 0 +#define OBSW_ADD_UART_TEST_CODE 0 + +#define OBSW_TEST_ACS 0 +#define OBSW_DEBUG_ACS 0 +#define OBSW_TEST_SUS 0 +#define OBSW_DEBUG_SUS 0 +#define OBSW_TEST_RTD 0 +#define OBSW_DEBUG_RTD 0 +#define OBSW_TEST_RAD_SENSOR 0 +#define OBSW_DEBUG_RAD_SENSOR 0 +#define OBSW_TEST_PL_PCDU 0 +#define OBSW_DEBUG_PL_PCDU 0 +#define OBSW_TEST_LIBGPIOD 0 +#define OBSW_TEST_PLOC_HANDLER 0 +#define OBSW_TEST_BPX_BATT 0 +#define OBSW_TEST_CCSDS_BRIDGE 0 +#define OBSW_TEST_CCSDS_PTME 0 +#define OBSW_TEST_TE7020_HEATER 0 +#define OBSW_TEST_GPIO_OPEN_BY_LABEL 0 +#define OBSW_TEST_GPIO_OPEN_BY_LINE_NAME 0 +#define OBSW_DEBUG_P60DOCK 0 +#define OBSW_DEBUG_BPX_BATT 0 +#define OBSW_DEBUG_PDU1 0 +#define OBSW_DEBUG_PDU2 0 +#define OBSW_DEBUG_GPS 0 +#define OBSW_DEBUG_ACU 0 +#define OBSW_DEBUG_SYRLINKS 0 +#define OBSW_DEBUG_IMTQ 0 +#define OBSW_DEBUG_RW 0 +#define OBSW_DEBUG_PLOC_MPSOC 0 +#define OBSW_DEBUG_PLOC_SUPERVISOR 0 +#define OBSW_DEBUG_PDEC_HANDLER 0 + +#ifdef EGSE +#define OBSW_DEBUG_STARTRACKER 1 +#else +#define OBSW_DEBUG_STARTRACKER 0 +#endif + +#ifdef RASPBERRY_PI #define OBSW_ENABLE_TIMERS 1 #define OBSW_ADD_STAR_TRACKER 0 @@ -66,47 +140,9 @@ debugging. */ #endif /*******************************************************************/ -/** All of the following flags should be disabled for mission code */ +/** CMake Defines */ /*******************************************************************/ - -//! /* Can be used to switch device to NORMAL mode immediately */ -#define OBSW_SWITCH_TO_NORMAL_MODE_AFTER_STARTUP 1 -#define OBSW_PRINT_MISSED_DEADLINES 1 -// If this is enabled, all other SPI code should be disabled -#define OBSW_ADD_TEST_CODE 0 -#define OBSW_ADD_SPI_TEST_CODE 0 -#define OBSW_ADD_TEST_PST 0 -#define OBSW_ADD_TEST_TASK 0 -#define OBSW_TEST_LIBGPIOD 0 -#define OBSW_TEST_RADIATION_SENSOR_HANDLER 0 -#define OBSW_TEST_SUS_HANDLER 0 -#define OBSW_TEST_PLOC_HANDLER 0 -#define OBSW_TEST_CCSDS_BRIDGE 0 -#define OBSW_TEST_CCSDS_PTME 0 -#define OBSW_TEST_TE7020_HEATER 0 -#define OBSW_TEST_GPIO_LABEL 0 - -#define OBSW_DEBUG_P60DOCK 0 -#define OBSW_DEBUG_PDU1 0 -#define OBSW_DEBUG_PDU2 0 -#define OBSW_DEBUG_GPS 0 -#define OBSW_DEBUG_ACU 0 -#define OBSW_DEBUG_SYRLINKS 0 -#define OBSW_DEBUG_IMQT 0 -#define OBSW_DEBUG_ADIS16507 0 -#define OBSW_DEBUG_RAD_SENSOR 0 -#define OBSW_DEBUG_SUS 0 -#define OBSW_DEBUG_RTD 0 -#define OBSW_DEBUG_RW 0 -#define OBSW_DEBUG_STARTRACKER 0 -#define OBSW_DEBUG_PLOC_MPSOC 0 -#define OBSW_DEBUG_PLOC_SUPERVISOR 0 - -/*******************************************************************/ -/** Hardcoded */ -/*******************************************************************/ -// Leave at one as the BSP is linux. Used by the ADIS16507 device handler -#define OBSW_ADIS16507_LINUX_COM_IF 1 +#cmakedefine EIVE_BUILD_GPSD_GPS_HANDLER #include "OBSWVersion.h" @@ -122,6 +158,9 @@ namespace config { /* Add mission configuration flags here */ static constexpr uint32_t OBSW_FILESYSTEM_HANDLER_QUEUE_SIZE = 50; static constexpr uint32_t PLOC_UPDATER_QUEUE_SIZE = 50; +static constexpr uint32_t STR_IMG_HELPER_QUEUE_SIZE = 50; + +static constexpr uint8_t LIVE_TM = 0; #ifdef __cplusplus } diff --git a/linux/fsfwconfig/devices/addresses.cpp b/linux/fsfwconfig/devices/addresses.cpp index 38877737..580818e0 100644 --- a/linux/fsfwconfig/devices/addresses.cpp +++ b/linux/fsfwconfig/devices/addresses.cpp @@ -1,11 +1 @@ -/** - * \file logicalAddresses.cpp - * - * \date 06.11.2019 - */ - #include "addresses.h" - - - - diff --git a/linux/fsfwconfig/devices/addresses.h b/linux/fsfwconfig/devices/addresses.h index 9d620475..0016c6a4 100644 --- a/linux/fsfwconfig/devices/addresses.h +++ b/linux/fsfwconfig/devices/addresses.h @@ -2,84 +2,86 @@ #define FSFWCONFIG_DEVICES_ADDRESSES_H_ #include -#include "objects/systemObjectList.h" + #include +#include "objects/systemObjectList.h" + namespace addresses { - /* Logical addresses have uint32_t datatype */ - enum logicalAddresses: address_t { - PCDU, +/* Logical addresses have uint32_t datatype */ +enum logicalAddresses : address_t { + PCDU, - MGM_0_LIS3 = objects::MGM_0_LIS3_HANDLER, - MGM_1_RM3100 = objects::MGM_1_RM3100_HANDLER, - MGM_2_LIS3 = objects::MGM_2_LIS3_HANDLER, - MGM_3_RM3100 = objects::MGM_3_RM3100_HANDLER, + MGM_0_LIS3 = objects::MGM_0_LIS3_HANDLER, + MGM_1_RM3100 = objects::MGM_1_RM3100_HANDLER, + MGM_2_LIS3 = objects::MGM_2_LIS3_HANDLER, + MGM_3_RM3100 = objects::MGM_3_RM3100_HANDLER, - GYRO_0_ADIS = objects::GYRO_0_ADIS_HANDLER, - GYRO_1_L3G = objects::GYRO_1_L3G_HANDLER, - GYRO_2_ADIS = objects::GYRO_2_ADIS_HANDLER, - GYRO_3_L3G = objects::GYRO_3_L3G_HANDLER, + GYRO_0_ADIS = objects::GYRO_0_ADIS_HANDLER, + GYRO_1_L3G = objects::GYRO_1_L3G_HANDLER, + GYRO_2_ADIS = objects::GYRO_2_ADIS_HANDLER, + GYRO_3_L3G = objects::GYRO_3_L3G_HANDLER, - RAD_SENSOR = objects::RAD_SENSOR, + RAD_SENSOR = objects::RAD_SENSOR, - 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_12 = objects::SUS_12, - SUS_13 = objects::SUS_13, + 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, - /* Dummy and Test Addresses */ - DUMMY_ECHO = 129, - DUMMY_GPS0 = 130, - DUMMY_GPS1 = 131, - }; + /* Dummy and Test Addresses */ + DUMMY_ECHO = 129, + DUMMY_GPS0 = 130, + DUMMY_GPS1 = 131, +}; - enum i2cAddresses: address_t { - IMTQ = 16, - TMP1075_TCS_1 = 72, - TMP1075_TCS_2 = 73, - }; +enum i2cAddresses : address_t { + BPX_BATTERY = 0x07, + IMTQ = 0x10, + TMP1075_TCS_1 = 0x48, + TMP1075_TCS_2 = 0x49, +}; - enum spiAddresses: address_t { - RTD_IC3, - RTD_IC4, - RTD_IC5, - RTD_IC6, - RTD_IC7, - RTD_IC8, - RTD_IC9, - RTD_IC10, - RTD_IC11, - RTD_IC12, - RTD_IC13, - RTD_IC14, - RTD_IC15, - RTD_IC16, - RTD_IC17, - RTD_IC18, - RW1, - RW2, - RW3, - RW4 - }; - - /* Addresses of devices supporting the CSP protocol */ - enum cspAddresses: uint8_t { - P60DOCK = 4, - ACU = 2, - PDU1 = 3, - /* PDU2 occupies X4 slot of P60Dock */ - PDU2 = 6 - }; -} +enum spiAddresses : address_t { + RTD_IC_3, + RTD_IC_4, + RTD_IC_5, + RTD_IC_6, + RTD_IC_7, + RTD_IC_8, + RTD_IC_9, + RTD_IC_10, + RTD_IC_11, + RTD_IC_12, + RTD_IC_13, + RTD_IC_14, + RTD_IC_15, + RTD_IC_16, + RTD_IC_17, + RTD_IC_18, + RW1, + RW2, + RW3, + RW4, + PLPCDU_ADC +}; +/* Addresses of devices supporting the CSP protocol */ +enum cspAddresses : uint8_t { + P60DOCK = 4, + ACU = 2, + PDU1 = 3, + /* PDU2 occupies X4 slot of P60Dock */ + PDU2 = 6 +}; +} // namespace addresses #endif /* FSFWCONFIG_DEVICES_ADDRESSES_H_ */ diff --git a/linux/fsfwconfig/devices/gpioIds.h b/linux/fsfwconfig/devices/gpioIds.h deleted file mode 100644 index b450bf8b..00000000 --- a/linux/fsfwconfig/devices/gpioIds.h +++ /dev/null @@ -1,99 +0,0 @@ -#ifndef FSFWCONFIG_DEVICES_GPIOIDS_H_ -#define FSFWCONFIG_DEVICES_GPIOIDS_H_ - -#include - -namespace gpioIds { -enum gpioId_t { - HEATER_0, - HEATER_1, - HEATER_2, - HEATER_3, - HEATER_4, - HEATER_5, - HEATER_6, - HEATER_7, - DEPLSA1, - DEPLSA2, - - MGM_0_LIS3_CS, - MGM_1_RM3100_CS, - GYRO_0_ADIS_CS, - GYRO_1_L3G_CS, - GYRO_2_ADIS_CS, - GYRO_3_L3G_CS, - MGM_2_LIS3_CS, - MGM_3_RM3100_CS, - - GNSS_0_NRESET, - GNSS_1_NRESET, - - GYRO_0_ENABLE, - GYRO_2_ENABLE, - - TEST_ID_0, - TEST_ID_1, - - RTD_IC3, - RTD_IC4, - RTD_IC5, - RTD_IC6, - RTD_IC7, - RTD_IC8, - RTD_IC9, - RTD_IC10, - RTD_IC11, - RTD_IC12, - RTD_IC13, - RTD_IC14, - RTD_IC15, - RTD_IC16, - RTD_IC17, - RTD_IC18, - - CS_SUS_1, - CS_SUS_2, - CS_SUS_3, - CS_SUS_4, - CS_SUS_5, - CS_SUS_6, - CS_SUS_7, - CS_SUS_8, - CS_SUS_9, - CS_SUS_10, - CS_SUS_11, - CS_SUS_12, - CS_SUS_13, - - SPI_MUX_BIT_1, - SPI_MUX_BIT_2, - SPI_MUX_BIT_3, - SPI_MUX_BIT_4, - SPI_MUX_BIT_5, - SPI_MUX_BIT_6, - - CS_RAD_SENSOR, - - PAPB_BUSY_N, - PAPB_EMPTY, - - EN_RW1, - EN_RW2, - EN_RW3, - EN_RW4, - - CS_RW1, - CS_RW2, - CS_RW3, - CS_RW4, - - EN_RW_CS, - - SPI_MUX -}; -} - - - - -#endif /* FSFWCONFIG_DEVICES_GPIOIDS_H_ */ diff --git a/linux/fsfwconfig/devices/powerSwitcherList.h b/linux/fsfwconfig/devices/powerSwitcherList.h index bc5731fd..cc6bc141 100644 --- a/linux/fsfwconfig/devices/powerSwitcherList.h +++ b/linux/fsfwconfig/devices/powerSwitcherList.h @@ -4,55 +4,54 @@ #include "OBSWConfig.h" namespace pcduSwitches { - /* Switches are uint8_t datatype and go from 0 to 255 */ - enum SwitcherList: uint8_t { - Q7S, - PAYLOAD_PCDU_CH1, - RW, - TCS_BOARD_8V_HEATER_IN, - SUS_REDUNDANT, - DEPLOYMENT_MECHANISM, - PAYLOAD_PCDU_CH6, - ACS_BOARD_SIDE_B, - PAYLOAD_CAMERA, - TCS_BOARD_3V3, - SYRLINKS, - STAR_TRACKER, - MGT, - SUS_NOMINAL, - SOLAR_CELL_EXP, - PLOC, - ACS_BOARD_SIDE_A, - NUMBER_OF_SWITCHES - }; +/* Switches are uint8_t datatype and go from 0 to 255 */ +enum SwitcherList : uint8_t { + Q7S, + PAYLOAD_PCDU_CH1, + RW, + TCS_BOARD_8V_HEATER_IN, + SUS_REDUNDANT, + DEPLOYMENT_MECHANISM, + PAYLOAD_PCDU_CH6, + ACS_BOARD_SIDE_B, + PAYLOAD_CAMERA, + TCS_BOARD_3V3, + SYRLINKS, + STAR_TRACKER, + MGT, + SUS_NOMINAL, + SOLAR_CELL_EXP, + PLOC, + ACS_BOARD_SIDE_A, + NUMBER_OF_SWITCHES +}; - static const uint8_t ON = 1; - static const uint8_t OFF = 0; +static const uint8_t ON = 1; +static const uint8_t OFF = 0; - /* Output states after reboot of the PDUs */ - static const uint8_t INIT_STATE_Q7S = ON; - static const uint8_t INIT_STATE_PAYLOAD_PCDU_CH1 = OFF; - static const uint8_t INIT_STATE_RW = OFF; +/* Output states after reboot of the PDUs */ +static const uint8_t INIT_STATE_Q7S = ON; +static const uint8_t INIT_STATE_PAYLOAD_PCDU_CH1 = OFF; +static const uint8_t INIT_STATE_RW = OFF; #if BOARD_TE0720 == 1 - /* Because the TE0720 is not connected to the PCDU, this switch is always on */ - static const uint8_t INIT_STATE_TCS_BOARD_8V_HEATER_IN = ON; +/* Because the TE0720 is not connected to the PCDU, this switch is always on */ +static const uint8_t INIT_STATE_TCS_BOARD_8V_HEATER_IN = ON; #else - static const uint8_t INIT_STATE_TCS_BOARD_8V_HEATER_IN = OFF; +static const uint8_t INIT_STATE_TCS_BOARD_8V_HEATER_IN = OFF; #endif - static const uint8_t INIT_STATE_SUS_REDUNDANT = OFF; - static const uint8_t INIT_STATE_DEPLOYMENT_MECHANISM = OFF; - static const uint8_t INIT_STATE_PAYLOAD_PCDU_CH6 = OFF; - static const uint8_t INIT_STATE_ACS_BOARD_SIDE_B = OFF; - static const uint8_t INIT_STATE_PAYLOAD_CAMERA = OFF; - static const uint8_t INIT_STATE_TCS_BOARD_3V3 = OFF; - static const uint8_t INIT_STATE_SYRLINKS = OFF; - static const uint8_t INIT_STATE_STAR_TRACKER = OFF; - static const uint8_t INIT_STATE_MGT = OFF; - static const uint8_t INIT_STATE_SUS_NOMINAL = OFF; - static const uint8_t INIT_STATE_SOLAR_CELL_EXP = OFF; - static const uint8_t INIT_STATE_PLOC = OFF; - static const uint8_t INIT_STATE_ACS_BOARD_SIDE_A = OFF; -} - +static const uint8_t INIT_STATE_SUS_REDUNDANT = OFF; +static const uint8_t INIT_STATE_DEPLOYMENT_MECHANISM = OFF; +static const uint8_t INIT_STATE_PAYLOAD_PCDU_CH6 = OFF; +static const uint8_t INIT_STATE_ACS_BOARD_SIDE_B = OFF; +static const uint8_t INIT_STATE_PAYLOAD_CAMERA = OFF; +static const uint8_t INIT_STATE_TCS_BOARD_3V3 = OFF; +static const uint8_t INIT_STATE_SYRLINKS = OFF; +static const uint8_t INIT_STATE_STAR_TRACKER = OFF; +static const uint8_t INIT_STATE_MGT = OFF; +static const uint8_t INIT_STATE_SUS_NOMINAL = OFF; +static const uint8_t INIT_STATE_SOLAR_CELL_EXP = OFF; +static const uint8_t INIT_STATE_PLOC = OFF; +static const uint8_t INIT_STATE_ACS_BOARD_SIDE_A = OFF; +} // namespace pcduSwitches #endif /* FSFWCONFIG_DEVICES_POWERSWITCHERLIST_H_ */ diff --git a/linux/fsfwconfig/events/subsystemIdRanges.h b/linux/fsfwconfig/events/subsystemIdRanges.h index 4894be16..33ef1a09 100644 --- a/linux/fsfwconfig/events/subsystemIdRanges.h +++ b/linux/fsfwconfig/events/subsystemIdRanges.h @@ -1,19 +1,19 @@ #ifndef FSFWCONFIG_EVENTS_SUBSYSTEMIDRANGES_H_ #define FSFWCONFIG_EVENTS_SUBSYSTEMIDRANGES_H_ +#include + #include "common/config/commonSubsystemIds.h" #include "fsfw/events/fwSubsystemIdRanges.h" -#include - /** * These IDs are part of the ID for an event thrown by a subsystem. * Numbers 0-80 are reserved for FSFW Subsystem IDs (framework/events/) */ namespace SUBSYSTEM_ID { -enum: uint8_t { - SUBSYSTEM_ID_START = COMMON_SUBSYSTEM_ID_END, - CORE = 116, +enum : uint8_t { + SUBSYSTEM_ID_START = COMMON_SUBSYSTEM_ID_END, + CORE = 116, }; } diff --git a/linux/fsfwconfig/events/translateEvents.cpp b/linux/fsfwconfig/events/translateEvents.cpp index 9d817651..4b46ede3 100644 --- a/linux/fsfwconfig/events/translateEvents.cpp +++ b/linux/fsfwconfig/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** - * @brief Auto-generated event translation file. Contains 106 translations. + * @brief Auto-generated event translation file. Contains 141 translations. * @details - * Generated on: 2021-08-31 10:50:10 + * Generated on: 2022-03-04 15:13:02 */ #include "translateEvents.h" @@ -34,6 +34,7 @@ const char *DEVICE_UNREQUESTED_REPLY_STRING = "DEVICE_UNREQUESTED_REPLY"; const char *INVALID_DEVICE_COMMAND_STRING = "INVALID_DEVICE_COMMAND"; const char *MONITORING_LIMIT_EXCEEDED_STRING = "MONITORING_LIMIT_EXCEEDED"; const char *MONITORING_AMBIGUOUS_STRING = "MONITORING_AMBIGUOUS"; +const char *DEVICE_WANTS_HARD_REBOOT_STRING = "DEVICE_WANTS_HARD_REBOOT"; const char *FUSE_CURRENT_HIGH_STRING = "FUSE_CURRENT_HIGH"; const char *FUSE_WENT_OFF_STRING = "FUSE_WENT_OFF"; const char *POWER_ABOVE_HIGH_LIMIT_STRING = "POWER_ABOVE_HIGH_LIMIT"; @@ -59,7 +60,6 @@ const char *MONITOR_CHANGED_STATE_STRING = "MONITOR_CHANGED_STATE"; const char *VALUE_BELOW_LOW_LIMIT_STRING = "VALUE_BELOW_LOW_LIMIT"; const char *VALUE_ABOVE_HIGH_LIMIT_STRING = "VALUE_ABOVE_HIGH_LIMIT"; const char *VALUE_OUT_OF_RANGE_STRING = "VALUE_OUT_OF_RANGE"; -const char *SWITCHING_TM_FAILED_STRING = "SWITCHING_TM_FAILED"; const char *CHANGING_MODE_STRING = "CHANGING_MODE"; const char *MODE_INFO_STRING = "MODE_INFO"; const char *FALLBACK_FAILED_STRING = "FALLBACK_FAILED"; @@ -84,6 +84,16 @@ const char *CLOCK_SET_STRING = "CLOCK_SET"; const char *CLOCK_SET_FAILURE_STRING = "CLOCK_SET_FAILURE"; const char *TEST_STRING = "TEST"; const char *CHANGE_OF_SETUP_PARAMETER_STRING = "CHANGE_OF_SETUP_PARAMETER"; +const char *GPIO_PULL_HIGH_FAILED_STRING = "GPIO_PULL_HIGH_FAILED"; +const char *GPIO_PULL_LOW_FAILED_STRING = "GPIO_PULL_LOW_FAILED"; +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 *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"; +const char *DEPL_SA1_GPIO_SWTICH_ON_FAILED_STRING = "DEPL_SA1_GPIO_SWTICH_ON_FAILED"; +const char *DEPL_SA2_GPIO_SWTICH_ON_FAILED_STRING = "DEPL_SA2_GPIO_SWTICH_ON_FAILED"; 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"; @@ -97,11 +107,15 @@ 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 *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 *SANITIZATION_FAILED_STRING = "SANITIZATION_FAILED"; +const char *ALLOC_FAILURE_STRING = "ALLOC_FAILURE"; +const char *REBOOT_SW_STRING = "REBOOT_SW"; +const char *REBOOT_HW_STRING = "REBOOT_HW"; 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"; @@ -111,223 +125,314 @@ 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"; +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 *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"; +const char *IMAGE_DOWNLOAD_SUCCESSFUL_STRING = "IMAGE_DOWNLOAD_SUCCESSFUL"; +const char *FLASH_WRITE_SUCCESSFUL_STRING = "FLASH_WRITE_SUCCESSFUL"; +const char *FLASH_READ_SUCCESSFUL_STRING = "FLASH_READ_SUCCESSFUL"; +const char *FLASH_READ_FAILED_STRING = "FLASH_READ_FAILED"; +const char *FIRMWARE_UPDATE_SUCCESSFUL_STRING = "FIRMWARE_UPDATE_SUCCESSFUL"; +const char *FIRMWARE_UPDATE_FAILED_STRING = "FIRMWARE_UPDATE_FAILED"; +const char *STR_HELPER_READING_REPLY_FAILED_STRING = "STR_HELPER_READING_REPLY_FAILED"; +const char *STR_HELPER_COM_ERROR_STRING = "STR_HELPER_COM_ERROR"; +const char *STR_HELPER_NO_REPLY_STRING = "STR_HELPER_NO_REPLY"; +const char *STR_HELPER_DEC_ERROR_STRING = "STR_HELPER_DEC_ERROR"; +const char *POSITION_MISMATCH_STRING = "POSITION_MISMATCH"; +const char *STR_HELPER_FILE_NOT_EXISTS_STRING = "STR_HELPER_FILE_NOT_EXISTS"; +const char *STR_HELPER_SENDING_PACKET_FAILED_STRING = "STR_HELPER_SENDING_PACKET_FAILED"; +const char *STR_HELPER_REQUESTING_MSG_FAILED_STRING = "STR_HELPER_REQUESTING_MSG_FAILED"; -const char * translateEvents(Event event) { - switch( (event & 0xffff) ) { - case(2200): - return STORE_SEND_WRITE_FAILED_STRING; - case(2201): - return STORE_WRITE_FAILED_STRING; - case(2202): - return STORE_SEND_READ_FAILED_STRING; - case(2203): - return STORE_READ_FAILED_STRING; - case(2204): - return UNEXPECTED_MSG_STRING; - case(2205): - return STORING_FAILED_STRING; - case(2206): - return TM_DUMP_FAILED_STRING; - case(2207): - return STORE_INIT_FAILED_STRING; - case(2208): - return STORE_INIT_EMPTY_STRING; - case(2209): - return STORE_CONTENT_CORRUPTED_STRING; - case(2210): - return STORE_INITIALIZE_STRING; - case(2211): - return INIT_DONE_STRING; - case(2212): - return DUMP_FINISHED_STRING; - case(2213): - return DELETION_FINISHED_STRING; - case(2214): - return DELETION_FAILED_STRING; - case(2215): - return AUTO_CATALOGS_SENDING_FAILED_STRING; - case(2600): - return GET_DATA_FAILED_STRING; - case(2601): - return STORE_DATA_FAILED_STRING; - case(2800): - return DEVICE_BUILDING_COMMAND_FAILED_STRING; - case(2801): - return DEVICE_SENDING_COMMAND_FAILED_STRING; - case(2802): - return DEVICE_REQUESTING_REPLY_FAILED_STRING; - case(2803): - return DEVICE_READING_REPLY_FAILED_STRING; - case(2804): - return DEVICE_INTERPRETING_REPLY_FAILED_STRING; - case(2805): - return DEVICE_MISSED_REPLY_STRING; - case(2806): - return DEVICE_UNKNOWN_REPLY_STRING; - case(2807): - return DEVICE_UNREQUESTED_REPLY_STRING; - case(2808): - return INVALID_DEVICE_COMMAND_STRING; - case(2809): - return MONITORING_LIMIT_EXCEEDED_STRING; - case(2810): - return MONITORING_AMBIGUOUS_STRING; - case(4201): - return FUSE_CURRENT_HIGH_STRING; - case(4202): - return FUSE_WENT_OFF_STRING; - case(4204): - return POWER_ABOVE_HIGH_LIMIT_STRING; - case(4205): - return POWER_BELOW_LOW_LIMIT_STRING; - case(4300): - return SWITCH_WENT_OFF_STRING; - case(5000): - return HEATER_ON_STRING; - case(5001): - return HEATER_OFF_STRING; - case(5002): - return HEATER_TIMEOUT_STRING; - case(5003): - return HEATER_STAYED_ON_STRING; - case(5004): - return HEATER_STAYED_OFF_STRING; - case(5200): - return TEMP_SENSOR_HIGH_STRING; - case(5201): - return TEMP_SENSOR_LOW_STRING; - case(5202): - return TEMP_SENSOR_GRADIENT_STRING; - case(5901): - return COMPONENT_TEMP_LOW_STRING; - case(5902): - return COMPONENT_TEMP_HIGH_STRING; - case(5903): - return COMPONENT_TEMP_OOL_LOW_STRING; - case(5904): - return COMPONENT_TEMP_OOL_HIGH_STRING; - case(5905): - return TEMP_NOT_IN_OP_RANGE_STRING; - case(7101): - return FDIR_CHANGED_STATE_STRING; - case(7102): - return FDIR_STARTS_RECOVERY_STRING; - case(7103): - return FDIR_TURNS_OFF_DEVICE_STRING; - case(7201): - return MONITOR_CHANGED_STATE_STRING; - case(7202): - return VALUE_BELOW_LOW_LIMIT_STRING; - case(7203): - return VALUE_ABOVE_HIGH_LIMIT_STRING; - case(7204): - return VALUE_OUT_OF_RANGE_STRING; - case(7301): - return SWITCHING_TM_FAILED_STRING; - case(7400): - return CHANGING_MODE_STRING; - case(7401): - return MODE_INFO_STRING; - case(7402): - return FALLBACK_FAILED_STRING; - case(7403): - return MODE_TRANSITION_FAILED_STRING; - case(7404): - return CANT_KEEP_MODE_STRING; - case(7405): - return OBJECT_IN_INVALID_MODE_STRING; - case(7406): - return FORCING_MODE_STRING; - case(7407): - return MODE_CMD_REJECTED_STRING; - case(7506): - return HEALTH_INFO_STRING; - case(7507): - return CHILD_CHANGED_HEALTH_STRING; - case(7508): - return CHILD_PROBLEMS_STRING; - case(7509): - return OVERWRITING_HEALTH_STRING; - case(7510): - return TRYING_RECOVERY_STRING; - case(7511): - return RECOVERY_STEP_STRING; - case(7512): - return RECOVERY_DONE_STRING; - case(7900): - return RF_AVAILABLE_STRING; - case(7901): - return RF_LOST_STRING; - case(7902): - return BIT_LOCK_STRING; - case(7903): - return BIT_LOCK_LOST_STRING; - case(7905): - return FRAME_PROCESSING_FAILED_STRING; - case(8900): - return CLOCK_SET_STRING; - case(8901): - return CLOCK_SET_FAILURE_STRING; - case(9700): - return TEST_STRING; - case(10600): - return CHANGE_OF_SETUP_PARAMETER_STRING; - case(11101): - return MEMORY_READ_RPT_CRC_FAILURE_STRING; - case(11102): - return ACK_FAILURE_STRING; - case(11103): - return EXE_FAILURE_STRING; - case(11104): - return CRC_FAILURE_EVENT_STRING; - case(11201): - return SELF_TEST_I2C_FAILURE_STRING; - case(11202): - return SELF_TEST_SPI_FAILURE_STRING; - case(11203): - return SELF_TEST_ADC_FAILURE_STRING; - case(11204): - return SELF_TEST_PWM_FAILURE_STRING; - case(11205): - return SELF_TEST_TC_FAILURE_STRING; - case(11206): - return SELF_TEST_MTM_RANGE_FAILURE_STRING; - case(11207): - return SELF_TEST_COIL_CURRENT_FAILURE_STRING; - case(11208): - return INVALID_ERROR_BYTE_STRING; - case(11301): - return ERROR_STATE_STRING; - case(11501): - return SUPV_MEMORY_READ_RPT_CRC_FAILURE_STRING; - case(11502): - return SUPV_ACK_FAILURE_STRING; - case(11503): - return SUPV_EXE_FAILURE_STRING; - case(11504): - return SUPV_CRC_FAILURE_EVENT_STRING; - case(11600): - return SANITIZATION_FAILED_STRING; - case(11700): - return UPDATE_FILE_NOT_EXISTS_STRING; - case(11701): - return ACTION_COMMANDING_FAILED_STRING; - case(11702): - return UPDATE_AVAILABLE_FAILED_STRING; - case(11703): - return UPDATE_TRANSFER_FAILED_STRING; - case(11704): - return UPDATE_VERIFY_FAILED_STRING; - case(11705): - return UPDATE_FINISHED_STRING; - case(11800): - return SEND_MRAM_DUMP_FAILED_STRING; - case(11801): - return MRAM_DUMP_FAILED_STRING; - case(11802): - return MRAM_DUMP_FINISHED_STRING; - default: - return "UNKNOWN_EVENT"; - } - return 0; +const char *translateEvents(Event event) { + switch ((event & 0xFFFF)) { + case (2200): + return STORE_SEND_WRITE_FAILED_STRING; + case (2201): + return STORE_WRITE_FAILED_STRING; + case (2202): + return STORE_SEND_READ_FAILED_STRING; + case (2203): + return STORE_READ_FAILED_STRING; + case (2204): + return UNEXPECTED_MSG_STRING; + case (2205): + return STORING_FAILED_STRING; + case (2206): + return TM_DUMP_FAILED_STRING; + case (2207): + return STORE_INIT_FAILED_STRING; + case (2208): + return STORE_INIT_EMPTY_STRING; + case (2209): + return STORE_CONTENT_CORRUPTED_STRING; + case (2210): + return STORE_INITIALIZE_STRING; + case (2211): + return INIT_DONE_STRING; + case (2212): + return DUMP_FINISHED_STRING; + case (2213): + return DELETION_FINISHED_STRING; + case (2214): + return DELETION_FAILED_STRING; + case (2215): + return AUTO_CATALOGS_SENDING_FAILED_STRING; + case (2600): + return GET_DATA_FAILED_STRING; + case (2601): + return STORE_DATA_FAILED_STRING; + case (2800): + return DEVICE_BUILDING_COMMAND_FAILED_STRING; + case (2801): + return DEVICE_SENDING_COMMAND_FAILED_STRING; + case (2802): + return DEVICE_REQUESTING_REPLY_FAILED_STRING; + case (2803): + return DEVICE_READING_REPLY_FAILED_STRING; + case (2804): + return DEVICE_INTERPRETING_REPLY_FAILED_STRING; + case (2805): + return DEVICE_MISSED_REPLY_STRING; + case (2806): + return DEVICE_UNKNOWN_REPLY_STRING; + case (2807): + return DEVICE_UNREQUESTED_REPLY_STRING; + case (2808): + return INVALID_DEVICE_COMMAND_STRING; + case (2809): + return MONITORING_LIMIT_EXCEEDED_STRING; + case (2810): + return MONITORING_AMBIGUOUS_STRING; + case (2811): + return DEVICE_WANTS_HARD_REBOOT_STRING; + case (4201): + return FUSE_CURRENT_HIGH_STRING; + case (4202): + return FUSE_WENT_OFF_STRING; + case (4204): + return POWER_ABOVE_HIGH_LIMIT_STRING; + case (4205): + return POWER_BELOW_LOW_LIMIT_STRING; + case (4300): + return SWITCH_WENT_OFF_STRING; + case (5000): + return HEATER_ON_STRING; + case (5001): + return HEATER_OFF_STRING; + case (5002): + return HEATER_TIMEOUT_STRING; + case (5003): + return HEATER_STAYED_ON_STRING; + case (5004): + return HEATER_STAYED_OFF_STRING; + case (5200): + return TEMP_SENSOR_HIGH_STRING; + case (5201): + return TEMP_SENSOR_LOW_STRING; + case (5202): + return TEMP_SENSOR_GRADIENT_STRING; + case (5901): + return COMPONENT_TEMP_LOW_STRING; + case (5902): + return COMPONENT_TEMP_HIGH_STRING; + case (5903): + return COMPONENT_TEMP_OOL_LOW_STRING; + case (5904): + return COMPONENT_TEMP_OOL_HIGH_STRING; + case (5905): + return TEMP_NOT_IN_OP_RANGE_STRING; + case (7101): + return FDIR_CHANGED_STATE_STRING; + case (7102): + return FDIR_STARTS_RECOVERY_STRING; + case (7103): + return FDIR_TURNS_OFF_DEVICE_STRING; + case (7201): + return MONITOR_CHANGED_STATE_STRING; + case (7202): + return VALUE_BELOW_LOW_LIMIT_STRING; + case (7203): + return VALUE_ABOVE_HIGH_LIMIT_STRING; + case (7204): + return VALUE_OUT_OF_RANGE_STRING; + case (7400): + return CHANGING_MODE_STRING; + case (7401): + return MODE_INFO_STRING; + case (7402): + return FALLBACK_FAILED_STRING; + case (7403): + return MODE_TRANSITION_FAILED_STRING; + case (7404): + return CANT_KEEP_MODE_STRING; + case (7405): + return OBJECT_IN_INVALID_MODE_STRING; + case (7406): + return FORCING_MODE_STRING; + case (7407): + return MODE_CMD_REJECTED_STRING; + case (7506): + return HEALTH_INFO_STRING; + case (7507): + return CHILD_CHANGED_HEALTH_STRING; + case (7508): + return CHILD_PROBLEMS_STRING; + case (7509): + return OVERWRITING_HEALTH_STRING; + case (7510): + return TRYING_RECOVERY_STRING; + case (7511): + return RECOVERY_STEP_STRING; + case (7512): + return RECOVERY_DONE_STRING; + case (7900): + return RF_AVAILABLE_STRING; + case (7901): + return RF_LOST_STRING; + case (7902): + return BIT_LOCK_STRING; + case (7903): + return BIT_LOCK_LOST_STRING; + case (7905): + return FRAME_PROCESSING_FAILED_STRING; + case (8900): + return CLOCK_SET_STRING; + case (8901): + return CLOCK_SET_FAILURE_STRING; + case (9700): + return TEST_STRING; + case (10600): + return CHANGE_OF_SETUP_PARAMETER_STRING; + case (10900): + return GPIO_PULL_HIGH_FAILED_STRING; + case (10901): + return GPIO_PULL_LOW_FAILED_STRING; + case (10902): + return SWITCH_ALREADY_ON_STRING; + case (10903): + return SWITCH_ALREADY_OFF_STRING; + case (10904): + return MAIN_SWITCH_TIMEOUT_STRING; + case (11000): + return MAIN_SWITCH_ON_TIMEOUT_STRING; + case (11001): + return MAIN_SWITCH_OFF_TIMEOUT_STRING; + case (11002): + return DEPLOYMENT_FAILED_STRING; + case (11003): + return DEPL_SA1_GPIO_SWTICH_ON_FAILED_STRING; + case (11004): + return DEPL_SA2_GPIO_SWTICH_ON_FAILED_STRING; + case (11101): + return MEMORY_READ_RPT_CRC_FAILURE_STRING; + case (11102): + return ACK_FAILURE_STRING; + case (11103): + return EXE_FAILURE_STRING; + case (11104): + return CRC_FAILURE_EVENT_STRING; + case (11201): + return SELF_TEST_I2C_FAILURE_STRING; + case (11202): + return SELF_TEST_SPI_FAILURE_STRING; + case (11203): + return SELF_TEST_ADC_FAILURE_STRING; + case (11204): + return SELF_TEST_PWM_FAILURE_STRING; + case (11205): + return SELF_TEST_TC_FAILURE_STRING; + case (11206): + return SELF_TEST_MTM_RANGE_FAILURE_STRING; + case (11207): + return SELF_TEST_COIL_CURRENT_FAILURE_STRING; + case (11208): + return INVALID_ERROR_BYTE_STRING; + case (11301): + return ERROR_STATE_STRING; + case (11401): + return BOOTING_FIRMWARE_FAILED_STRING; + case (11402): + return BOOTING_BOOTLOADER_FAILED_STRING; + case (11501): + return SUPV_MEMORY_READ_RPT_CRC_FAILURE_STRING; + case (11502): + return SUPV_ACK_FAILURE_STRING; + case (11503): + return SUPV_EXE_FAILURE_STRING; + case (11504): + return SUPV_CRC_FAILURE_EVENT_STRING; + case (11600): + return ALLOC_FAILURE_STRING; + case (11601): + return REBOOT_SW_STRING; + case (11603): + return REBOOT_HW_STRING; + case (11700): + return UPDATE_FILE_NOT_EXISTS_STRING; + case (11701): + return ACTION_COMMANDING_FAILED_STRING; + case (11702): + return UPDATE_AVAILABLE_FAILED_STRING; + case (11703): + return UPDATE_TRANSFER_FAILED_STRING; + case (11704): + return UPDATE_VERIFY_FAILED_STRING; + case (11705): + return UPDATE_FINISHED_STRING; + case (11800): + return SEND_MRAM_DUMP_FAILED_STRING; + case (11801): + return MRAM_DUMP_FAILED_STRING; + case (11802): + return MRAM_DUMP_FINISHED_STRING; + case (11901): + return INVALID_TC_FRAME_STRING; + case (11902): + return INVALID_FAR_STRING; + case (11903): + return CARRIER_LOCK_STRING; + case (11904): + return BIT_LOCK_PDEC_STRING; + case (12000): + return IMAGE_UPLOAD_FAILED_STRING; + case (12001): + return IMAGE_DOWNLOAD_FAILED_STRING; + case (12002): + return IMAGE_UPLOAD_SUCCESSFUL_STRING; + case (12003): + return IMAGE_DOWNLOAD_SUCCESSFUL_STRING; + case (12004): + return FLASH_WRITE_SUCCESSFUL_STRING; + case (12005): + return FLASH_READ_SUCCESSFUL_STRING; + case (12006): + return FLASH_READ_FAILED_STRING; + case (12007): + return FIRMWARE_UPDATE_SUCCESSFUL_STRING; + case (12008): + return FIRMWARE_UPDATE_FAILED_STRING; + case (12009): + return STR_HELPER_READING_REPLY_FAILED_STRING; + case (12010): + return STR_HELPER_COM_ERROR_STRING; + case (12011): + return STR_HELPER_NO_REPLY_STRING; + case (12012): + return STR_HELPER_DEC_ERROR_STRING; + case (12013): + return POSITION_MISMATCH_STRING; + case (12014): + return STR_HELPER_FILE_NOT_EXISTS_STRING; + case (12015): + return STR_HELPER_SENDING_PACKET_FAILED_STRING; + case (12016): + return STR_HELPER_REQUESTING_MSG_FAILED_STRING; + default: + return "UNKNOWN_EVENT"; + } + return 0; } diff --git a/linux/fsfwconfig/events/translateEvents.h b/linux/fsfwconfig/events/translateEvents.h index bdabb21b..99554317 100644 --- a/linux/fsfwconfig/events/translateEvents.h +++ b/linux/fsfwconfig/events/translateEvents.h @@ -3,6 +3,6 @@ #include "fsfw/events/Event.h" -const char * translateEvents(Event event); +const char *translateEvents(Event event); #endif /* FSFWCONFIG_EVENTS_TRANSLATEEVENTS_H_ */ diff --git a/linux/fsfwconfig/ipc/MissionMessageTypes.cpp b/linux/fsfwconfig/ipc/MissionMessageTypes.cpp index 9ac6f0f4..fa1c4877 100644 --- a/linux/fsfwconfig/ipc/MissionMessageTypes.cpp +++ b/linux/fsfwconfig/ipc/MissionMessageTypes.cpp @@ -1,12 +1,10 @@ #include "MissionMessageTypes.h" + #include - void messagetypes::clearMissionMessage(CommandMessage* message) { - switch(message->getMessageType()) { - default: - break; - } + switch (message->getMessageType()) { + default: + break; + } } - - diff --git a/linux/fsfwconfig/ipc/MissionMessageTypes.h b/linux/fsfwconfig/ipc/MissionMessageTypes.h index ab2a84b5..78b0d343 100644 --- a/linux/fsfwconfig/ipc/MissionMessageTypes.h +++ b/linux/fsfwconfig/ipc/MissionMessageTypes.h @@ -11,12 +11,12 @@ class CommandMessage; * * @param message Generic Command Message */ -namespace messagetypes{ +namespace messagetypes { enum MESSAGE_TYPE { - MISSION_MESSAGE_TYPE_START = FW_MESSAGES_COUNT, + MISSION_MESSAGE_TYPE_START = FW_MESSAGES_COUNT, }; void clearMissionMessage(CommandMessage* message); -} +} // namespace messagetypes #endif /* FSFWCONFIG_IPC_MISSIONMESSAGETYPES_H_ */ diff --git a/linux/fsfwconfig/objects/systemObjectList.h b/linux/fsfwconfig/objects/systemObjectList.h index a8929187..a03e4d38 100644 --- a/linux/fsfwconfig/objects/systemObjectList.h +++ b/linux/fsfwconfig/objects/systemObjectList.h @@ -1,10 +1,12 @@ #ifndef HOSTED_CONFIG_OBJECTS_SYSTEMOBJECTLIST_H_ #define HOSTED_CONFIG_OBJECTS_SYSTEMOBJECTLIST_H_ -#include "commonObjects.h" #include + #include +#include "commonObjects.h" + // The objects will be instantiated in the ID order // For naming scheme see flight manual /* @@ -31,38 +33,39 @@ Fourth byte is a unique counter. */ namespace objects { -enum sourceObjects: uint32_t { - /* 0x53 reserved for FSFW */ - FW_ADDRESS_START = PUS_SERVICE_1_VERIFICATION, - FW_ADDRESS_END = TIME_STAMPER, - PUS_SERVICE_6 = 0x51000500, +enum sourceObjects : uint32_t { + /* 0x53 reserved for FSFW */ + FW_ADDRESS_START = PUS_SERVICE_1_VERIFICATION, + FW_ADDRESS_END = TIME_STAMPER, + PUS_SERVICE_6 = 0x51000500, - CCSDS_IP_CORE_BRIDGE = 0x73500000, - TM_FUNNEL = 0x73000100, + CCSDS_IP_CORE_BRIDGE = 0x73500000, + TM_FUNNEL = 0x73000100, - /* 0x49 ('I') for Communication Interfaces **/ - ARDUINO_COM_IF = 0x49000000, - CSP_COM_IF = 0x49050001, - I2C_COM_IF = 0x49040002, - UART_COM_IF = 0x49030003, - SPI_COM_IF = 0x49020004, - GPIO_IF = 0x49010005, + /* 0x49 ('I') for Communication Interfaces **/ + ARDUINO_COM_IF = 0x49000000, + CSP_COM_IF = 0x49050001, + I2C_COM_IF = 0x49040002, + UART_COM_IF = 0x49030003, + SPI_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, + /* Custom device handler */ + PCDU_HANDLER = 0x442000A1, + SOLAR_ARRAY_DEPL_HANDLER = 0x444100A2, + SYRLINKS_HK_HANDLER = 0x445300A3, + HEATER_HANDLER = 0x444100A4, + RAD_SENSOR = 0x443200A5, - /* 0x54 ('T') for test handlers */ - TEST_TASK = 0x54694269, - LIBGPIOD_TEST = 0x54123456, - SPI_TEST = 0x54000010, - UART_TEST = 0x54000020, - DUMMY_INTERFACE = 0x5400CAFE, - DUMMY_HANDLER = 0x5400AFFE, - P60DOCK_TEST_TASK = 0x00005060, + /* 0x54 ('T') for test handlers */ + TEST_TASK = 0x54694269, + LIBGPIOD_TEST = 0x54123456, + SPI_TEST = 0x54000010, + UART_TEST = 0x54000020, + I2C_TEST = 0x54000030, + DUMMY_INTERFACE = 0x5400CAFE, + DUMMY_HANDLER = 0x5400AFFE, + P60DOCK_TEST_TASK = 0x00005060, }; } diff --git a/linux/fsfwconfig/objects/translateObjects.cpp b/linux/fsfwconfig/objects/translateObjects.cpp index 23a232c8..b0b6d55d 100644 --- a/linux/fsfwconfig/objects/translateObjects.cpp +++ b/linux/fsfwconfig/objects/translateObjects.cpp @@ -1,8 +1,8 @@ /** - * @brief Auto-generated object translation file. + * @brief Auto-generated object translation file. * @details - * Contains 105 translations. - * Generated on: 2021-08-31 10:31:24 + * Contains 112 translations. + * Generated on: 2022-03-04 15:13:13 */ #include "translateObjects.h" @@ -12,6 +12,7 @@ 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"; @@ -23,8 +24,6 @@ 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_12_STRING = "SUS_12"; -const char *SUS_13_STRING = "SUS_13"; 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"; @@ -35,40 +34,42 @@ const char *RW3_STRING = "RW3"; const char *MGM_3_RM3100_HANDLER_STRING = "MGM_3_RM3100_HANDLER"; const char *GYRO_3_L3G_HANDLER_STRING = "GYRO_3_L3G_HANDLER"; const char *RW4_STRING = "RW4"; -const char *START_TRACKER_STRING = "START_TRACKER"; -const char *GPS0_HANDLER_STRING = "GPS0_HANDLER"; -const char *GPS1_HANDLER_STRING = "GPS1_HANDLER"; +const char *STAR_TRACKER_STRING = "STAR_TRACKER"; +const char *GPS_CONTROLLER_STRING = "GPS_CONTROLLER"; const char *IMTQ_HANDLER_STRING = "IMTQ_HANDLER"; const char *PCDU_HANDLER_STRING = "PCDU_HANDLER"; const char *P60DOCK_HANDLER_STRING = "P60DOCK_HANDLER"; const char *PDU1_HANDLER_STRING = "PDU1_HANDLER"; const char *PDU2_HANDLER_STRING = "PDU2_HANDLER"; const char *ACU_HANDLER_STRING = "ACU_HANDLER"; +const char *BPX_BATT_HANDLER_STRING = "BPX_BATT_HANDLER"; +const char *PLPCDU_HANDLER_STRING = "PLPCDU_HANDLER"; const char *RAD_SENSOR_STRING = "RAD_SENSOR"; 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_HANDLER_STRING = "PLOC_MPSOC_HANDLER"; const char *PLOC_SUPERVISOR_HANDLER_STRING = "PLOC_SUPERVISOR_HANDLER"; 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_IC3_STRING = "RTD_IC3"; -const char *RTD_IC4_STRING = "RTD_IC4"; -const char *RTD_IC5_STRING = "RTD_IC5"; -const char *RTD_IC6_STRING = "RTD_IC6"; -const char *RTD_IC7_STRING = "RTD_IC7"; -const char *RTD_IC8_STRING = "RTD_IC8"; -const char *RTD_IC9_STRING = "RTD_IC9"; -const char *RTD_IC10_STRING = "RTD_IC10"; -const char *RTD_IC11_STRING = "RTD_IC11"; -const char *RTD_IC12_STRING = "RTD_IC12"; -const char *RTD_IC13_STRING = "RTD_IC13"; -const char *RTD_IC14_STRING = "RTD_IC14"; -const char *RTD_IC15_STRING = "RTD_IC15"; -const char *RTD_IC16_STRING = "RTD_IC16"; -const char *RTD_IC17_STRING = "RTD_IC17"; -const char *RTD_IC18_STRING = "RTD_IC18"; +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 *SYRLINKS_HK_HANDLER_STRING = "SYRLINKS_HK_HANDLER"; const char *ARDUINO_COM_IF_STRING = "ARDUINO_COM_IF"; const char *GPIO_IF_STRING = "GPIO_IF"; @@ -81,6 +82,10 @@ const char *PUS_PACKET_DISTRIBUTOR_STRING = "PUS_PACKET_DISTRIBUTOR"; const char *TMTC_BRIDGE_STRING = "TMTC_BRIDGE"; const char *TMTC_POLLING_TASK_STRING = "TMTC_POLLING_TASK"; const char *FILE_SYSTEM_HANDLER_STRING = "FILE_SYSTEM_HANDLER"; +const char *SDC_MANAGER_STRING = "SDC_MANAGER"; +const char *PTME_STRING = "PTME"; +const char *PDEC_HANDLER_STRING = "PDEC_HANDLER"; +const char *CCSDS_HANDLER_STRING = "CCSDS_HANDLER"; const char *PUS_SERVICE_6_STRING = "PUS_SERVICE_6"; const char *FSFW_OBJECTS_START_STRING = "FSFW_OBJECTS_START"; const char *PUS_SERVICE_1_VERIFICATION_STRING = "PUS_SERVICE_1_VERIFICATION"; @@ -93,6 +98,7 @@ 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"; const char *PUS_SERVICE_201_HEALTH_STRING = "PUS_SERVICE_201_HEALTH"; +const char *CFDP_PACKET_DISTRIBUTOR_STRING = "CFDP_PACKET_DISTRIBUTOR"; const char *HEALTH_TABLE_STRING = "HEALTH_TABLE"; const char *MODE_STORE_STRING = "MODE_STORE"; const char *EVENT_MANAGER_STRING = "EVENT_MANAGER"; @@ -104,6 +110,7 @@ const char *TIME_STAMPER_STRING = "TIME_STAMPER"; 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_HANDLER_STRING = "DUMMY_HANDLER"; const char *DUMMY_INTERFACE_STRING = "DUMMY_INTERFACE"; const char *LIBGPIOD_TEST_STRING = "LIBGPIOD_TEST"; @@ -112,220 +119,234 @@ 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"; -const char* translateObject(object_id_t object) { - switch( (object & 0xFFFFFFFF) ) { - case 0x00005060: - return P60DOCK_TEST_TASK_STRING; - case 0x43000003: - return CORE_CONTROLLER_STRING; - case 0x43100002: - return ACS_CONTROLLER_STRING; - case 0x43400001: - return THERMAL_CONTROLLER_STRING; - case 0x44120006: - return MGM_0_LIS3_HANDLER_STRING; - case 0x44120010: - return GYRO_0_ADIS_HANDLER_STRING; - case 0x44120032: - return SUS_1_STRING; - case 0x44120033: - return SUS_2_STRING; - case 0x44120034: - return SUS_3_STRING; - case 0x44120035: - return SUS_4_STRING; - case 0x44120036: - return SUS_5_STRING; - case 0x44120037: - return SUS_6_STRING; - case 0x44120038: - return SUS_7_STRING; - case 0x44120039: - return SUS_8_STRING; - case 0x44120040: - return SUS_9_STRING; - case 0x44120041: - return SUS_10_STRING; - case 0x44120042: - return SUS_11_STRING; - case 0x44120043: - return SUS_12_STRING; - case 0x44120044: - return SUS_13_STRING; - case 0x44120047: - return RW1_STRING; - case 0x44120107: - return MGM_1_RM3100_HANDLER_STRING; - case 0x44120111: - return GYRO_1_L3G_HANDLER_STRING; - case 0x44120148: - return RW2_STRING; - case 0x44120208: - return MGM_2_LIS3_HANDLER_STRING; - case 0x44120212: - return GYRO_2_ADIS_HANDLER_STRING; - case 0x44120249: - return RW3_STRING; - case 0x44120309: - return MGM_3_RM3100_HANDLER_STRING; - case 0x44120313: - return GYRO_3_L3G_HANDLER_STRING; - case 0x44120350: - return RW4_STRING; - case 0x44130001: - return START_TRACKER_STRING; - case 0x44130045: - return GPS0_HANDLER_STRING; - case 0x44130146: - return GPS1_HANDLER_STRING; - case 0x44140014: - return IMTQ_HANDLER_STRING; - case 0x442000A1: - return PCDU_HANDLER_STRING; - case 0x44250000: - return P60DOCK_HANDLER_STRING; - case 0x44250001: - return PDU1_HANDLER_STRING; - case 0x44250002: - return PDU2_HANDLER_STRING; - case 0x44250003: - return ACU_HANDLER_STRING; - case 0x443200A5: - return RAD_SENSOR_STRING; - case 0x44330000: - return PLOC_UPDATER_STRING; - case 0x44330001: - return PLOC_MEMORY_DUMPER_STRING; - case 0x44330015: - return PLOC_MPSOC_HANDLER_STRING; - case 0x44330016: - return PLOC_SUPERVISOR_HANDLER_STRING; - case 0x444100A2: - return SOLAR_ARRAY_DEPL_HANDLER_STRING; - case 0x444100A4: - return HEATER_HANDLER_STRING; - case 0x44420004: - return TMP1075_HANDLER_1_STRING; - case 0x44420005: - return TMP1075_HANDLER_2_STRING; - case 0x44420016: - return RTD_IC3_STRING; - case 0x44420017: - return RTD_IC4_STRING; - case 0x44420018: - return RTD_IC5_STRING; - case 0x44420019: - return RTD_IC6_STRING; - case 0x44420020: - return RTD_IC7_STRING; - case 0x44420021: - return RTD_IC8_STRING; - case 0x44420022: - return RTD_IC9_STRING; - case 0x44420023: - return RTD_IC10_STRING; - case 0x44420024: - return RTD_IC11_STRING; - case 0x44420025: - return RTD_IC12_STRING; - case 0x44420026: - return RTD_IC13_STRING; - case 0x44420027: - return RTD_IC14_STRING; - case 0x44420028: - return RTD_IC15_STRING; - case 0x44420029: - return RTD_IC16_STRING; - case 0x44420030: - return RTD_IC17_STRING; - case 0x44420031: - return RTD_IC18_STRING; - case 0x445300A3: - return SYRLINKS_HK_HANDLER_STRING; - case 0x49000000: - return ARDUINO_COM_IF_STRING; - case 0x49010005: - return GPIO_IF_STRING; - case 0x49020004: - return SPI_COM_IF_STRING; - case 0x49030003: - return UART_COM_IF_STRING; - case 0x49040002: - return I2C_COM_IF_STRING; - case 0x49050001: - return CSP_COM_IF_STRING; - case 0x50000100: - return CCSDS_PACKET_DISTRIBUTOR_STRING; - case 0x50000200: - return PUS_PACKET_DISTRIBUTOR_STRING; - case 0x50000300: - return TMTC_BRIDGE_STRING; - case 0x50000400: - return TMTC_POLLING_TASK_STRING; - case 0x50000500: - return FILE_SYSTEM_HANDLER_STRING; - case 0x51000500: - return PUS_SERVICE_6_STRING; - case 0x53000000: - return FSFW_OBJECTS_START_STRING; - case 0x53000001: - return PUS_SERVICE_1_VERIFICATION_STRING; - case 0x53000002: - return PUS_SERVICE_2_DEVICE_ACCESS_STRING; - case 0x53000003: - return PUS_SERVICE_3_HOUSEKEEPING_STRING; - case 0x53000005: - return PUS_SERVICE_5_EVENT_REPORTING_STRING; - case 0x53000008: - return PUS_SERVICE_8_FUNCTION_MGMT_STRING; - case 0x53000009: - return PUS_SERVICE_9_TIME_MGMT_STRING; - case 0x53000017: - return PUS_SERVICE_17_TEST_STRING; - case 0x53000020: - return PUS_SERVICE_20_PARAMETERS_STRING; - case 0x53000200: - return PUS_SERVICE_200_MODE_MGMT_STRING; - case 0x53000201: - return PUS_SERVICE_201_HEALTH_STRING; - case 0x53010000: - return HEALTH_TABLE_STRING; - case 0x53010100: - return MODE_STORE_STRING; - case 0x53030000: - return EVENT_MANAGER_STRING; - case 0x53040000: - return INTERNAL_ERROR_REPORTER_STRING; - case 0x534f0100: - return TC_STORE_STRING; - case 0x534f0200: - return TM_STORE_STRING; - case 0x534f0300: - return IPC_STORE_STRING; - case 0x53500010: - return TIME_STAMPER_STRING; - case 0x53ffffff: - return FSFW_OBJECTS_END_STRING; - case 0x54000010: - return SPI_TEST_STRING; - case 0x54000020: - return UART_TEST_STRING; - case 0x5400AFFE: - return DUMMY_HANDLER_STRING; - case 0x5400CAFE: - return DUMMY_INTERFACE_STRING; - case 0x54123456: - return LIBGPIOD_TEST_STRING; - case 0x54694269: - return TEST_TASK_STRING; - case 0x73000100: - return TM_FUNNEL_STRING; - case 0x73500000: - return CCSDS_IP_CORE_BRIDGE_STRING; - case 0xFFFFFFFF: - return NO_OBJECT_STRING; - default: - return "UNKNOWN_OBJECT"; - } - return 0; +const char *translateObject(object_id_t object) { + switch ((object & 0xFFFFFFFF)) { + case 0x00005060: + return P60DOCK_TEST_TASK_STRING; + case 0x43000003: + return CORE_CONTROLLER_STRING; + case 0x43100002: + return ACS_CONTROLLER_STRING; + case 0x43400001: + return THERMAL_CONTROLLER_STRING; + case 0x44120006: + return MGM_0_LIS3_HANDLER_STRING; + case 0x44120010: + return GYRO_0_ADIS_HANDLER_STRING; + case 0x44120032: + return SUS_0_STRING; + case 0x44120033: + return SUS_1_STRING; + case 0x44120034: + return SUS_2_STRING; + case 0x44120035: + return SUS_3_STRING; + case 0x44120036: + return SUS_4_STRING; + case 0x44120037: + return SUS_5_STRING; + case 0x44120038: + return SUS_6_STRING; + case 0x44120039: + return SUS_7_STRING; + case 0x44120040: + return SUS_8_STRING; + case 0x44120041: + return SUS_9_STRING; + case 0x44120042: + return SUS_10_STRING; + case 0x44120043: + return SUS_11_STRING; + case 0x44120047: + return RW1_STRING; + case 0x44120107: + return MGM_1_RM3100_HANDLER_STRING; + case 0x44120111: + return GYRO_1_L3G_HANDLER_STRING; + case 0x44120148: + return RW2_STRING; + case 0x44120208: + return MGM_2_LIS3_HANDLER_STRING; + case 0x44120212: + return GYRO_2_ADIS_HANDLER_STRING; + case 0x44120249: + return RW3_STRING; + case 0x44120309: + return MGM_3_RM3100_HANDLER_STRING; + case 0x44120313: + return GYRO_3_L3G_HANDLER_STRING; + case 0x44120350: + return RW4_STRING; + case 0x44130001: + return STAR_TRACKER_STRING; + case 0x44130045: + return GPS_CONTROLLER_STRING; + case 0x44140014: + return IMTQ_HANDLER_STRING; + case 0x442000A1: + return PCDU_HANDLER_STRING; + case 0x44250000: + return P60DOCK_HANDLER_STRING; + case 0x44250001: + return PDU1_HANDLER_STRING; + case 0x44250002: + return PDU2_HANDLER_STRING; + case 0x44250003: + return ACU_HANDLER_STRING; + case 0x44260000: + return BPX_BATT_HANDLER_STRING; + case 0x44300000: + return PLPCDU_HANDLER_STRING; + case 0x443200A5: + return RAD_SENSOR_STRING; + case 0x44330000: + return PLOC_UPDATER_STRING; + case 0x44330001: + return PLOC_MEMORY_DUMPER_STRING; + case 0x44330002: + return STR_HELPER_STRING; + case 0x44330015: + return PLOC_MPSOC_HANDLER_STRING; + case 0x44330016: + return PLOC_SUPERVISOR_HANDLER_STRING; + case 0x444100A2: + return SOLAR_ARRAY_DEPL_HANDLER_STRING; + case 0x444100A4: + return HEATER_HANDLER_STRING; + case 0x44420004: + return TMP1075_HANDLER_1_STRING; + case 0x44420005: + return TMP1075_HANDLER_2_STRING; + case 0x44420016: + return RTD_IC_3_STRING; + case 0x44420017: + return RTD_IC_4_STRING; + case 0x44420018: + return RTD_IC_5_STRING; + case 0x44420019: + return RTD_IC_6_STRING; + case 0x44420020: + return RTD_IC_7_STRING; + case 0x44420021: + return RTD_IC_8_STRING; + case 0x44420022: + return RTD_IC_9_STRING; + case 0x44420023: + return RTD_IC_10_STRING; + case 0x44420024: + return RTD_IC_11_STRING; + case 0x44420025: + return RTD_IC_12_STRING; + case 0x44420026: + return RTD_IC_13_STRING; + case 0x44420027: + return RTD_IC_14_STRING; + case 0x44420028: + return RTD_IC_15_STRING; + case 0x44420029: + return RTD_IC_16_STRING; + case 0x44420030: + return RTD_IC_17_STRING; + case 0x44420031: + return RTD_IC_18_STRING; + case 0x445300A3: + return SYRLINKS_HK_HANDLER_STRING; + case 0x49000000: + return ARDUINO_COM_IF_STRING; + case 0x49010005: + return GPIO_IF_STRING; + case 0x49020004: + return SPI_COM_IF_STRING; + case 0x49030003: + return UART_COM_IF_STRING; + case 0x49040002: + return I2C_COM_IF_STRING; + case 0x49050001: + return CSP_COM_IF_STRING; + case 0x50000100: + return CCSDS_PACKET_DISTRIBUTOR_STRING; + case 0x50000200: + return PUS_PACKET_DISTRIBUTOR_STRING; + case 0x50000300: + return TMTC_BRIDGE_STRING; + case 0x50000400: + return TMTC_POLLING_TASK_STRING; + case 0x50000500: + return FILE_SYSTEM_HANDLER_STRING; + case 0x50000550: + return SDC_MANAGER_STRING; + case 0x50000600: + return PTME_STRING; + case 0x50000700: + return PDEC_HANDLER_STRING; + case 0x50000800: + return CCSDS_HANDLER_STRING; + case 0x51000500: + return PUS_SERVICE_6_STRING; + case 0x53000000: + return FSFW_OBJECTS_START_STRING; + case 0x53000001: + return PUS_SERVICE_1_VERIFICATION_STRING; + case 0x53000002: + return PUS_SERVICE_2_DEVICE_ACCESS_STRING; + case 0x53000003: + return PUS_SERVICE_3_HOUSEKEEPING_STRING; + case 0x53000005: + return PUS_SERVICE_5_EVENT_REPORTING_STRING; + case 0x53000008: + return PUS_SERVICE_8_FUNCTION_MGMT_STRING; + case 0x53000009: + return PUS_SERVICE_9_TIME_MGMT_STRING; + case 0x53000017: + return PUS_SERVICE_17_TEST_STRING; + case 0x53000020: + return PUS_SERVICE_20_PARAMETERS_STRING; + case 0x53000200: + return PUS_SERVICE_200_MODE_MGMT_STRING; + case 0x53000201: + return PUS_SERVICE_201_HEALTH_STRING; + case 0x53001000: + return CFDP_PACKET_DISTRIBUTOR_STRING; + case 0x53010000: + return HEALTH_TABLE_STRING; + case 0x53010100: + return MODE_STORE_STRING; + case 0x53030000: + return EVENT_MANAGER_STRING; + case 0x53040000: + return INTERNAL_ERROR_REPORTER_STRING; + case 0x534f0100: + return TC_STORE_STRING; + case 0x534f0200: + return TM_STORE_STRING; + case 0x534f0300: + return IPC_STORE_STRING; + case 0x53500010: + return TIME_STAMPER_STRING; + case 0x53ffffff: + return FSFW_OBJECTS_END_STRING; + case 0x54000010: + return SPI_TEST_STRING; + case 0x54000020: + return UART_TEST_STRING; + case 0x54000030: + return I2C_TEST_STRING; + case 0x5400AFFE: + return DUMMY_HANDLER_STRING; + case 0x5400CAFE: + return DUMMY_INTERFACE_STRING; + case 0x54123456: + return LIBGPIOD_TEST_STRING; + case 0x54694269: + return TEST_TASK_STRING; + case 0x73000100: + return TM_FUNNEL_STRING; + case 0x73500000: + return CCSDS_IP_CORE_BRIDGE_STRING; + case 0xFFFFFFFF: + return NO_OBJECT_STRING; + default: + return "UNKNOWN_OBJECT"; + } + return 0; } diff --git a/linux/fsfwconfig/objects/translateObjects.h b/linux/fsfwconfig/objects/translateObjects.h index dbf5b468..257912f4 100644 --- a/linux/fsfwconfig/objects/translateObjects.h +++ b/linux/fsfwconfig/objects/translateObjects.h @@ -3,6 +3,6 @@ #include -const char* translateObject(object_id_t object); +const char *translateObject(object_id_t object); #endif /* FSFWCONFIG_OBJECTS_TRANSLATEOBJECTS_H_ */ diff --git a/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp b/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp index 3b826119..7bf5a607 100644 --- a/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp +++ b/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp @@ -1,818 +1,664 @@ #include "pollingSequenceFactory.h" -#include "linux/devices/SusHandler.h" -#include "OBSWConfig.h" +#include #include #include -#include #include -#include "objects/systemObjectList.h" +#ifndef RPI_TEST_ADIS16507 +#define RPI_TEST_ADIS16507 0 +#endif -ReturnValue_t pst::pstGpio(FixedTimeslotTaskIF *thisSequence) -{ - // Length of a communication cycle - uint32_t length = thisSequence->getPeriodMs(); +#ifndef RPI_TEST_GPS_HANDLER +#define RPI_TEST_GPS_HANDLER 0 +#endif - thisSequence->addSlot(objects::HEATER_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SOLAR_ARRAY_DEPL_HANDLER, length * 0, - DeviceHandlerIF::PERFORM_OPERATION); +ReturnValue_t pst::pstGpio(FixedTimeslotTaskIF *thisSequence) { + // Length of a communication cycle + uint32_t length = thisSequence->getPeriodMs(); - if (thisSequence->checkSequence() == HasReturnvaluesIF::RETURN_OK) { - return HasReturnvaluesIF::RETURN_OK; - } + thisSequence->addSlot(objects::HEATER_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::SOLAR_ARRAY_DEPL_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); - sif::error << "PollingSequence::initialize has errors!" << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; + if (thisSequence->checkSequence() == HasReturnvaluesIF::RETURN_OK) { + return HasReturnvaluesIF::RETURN_OK; + } + + sif::error << "PollingSequence::initialize has errors!" << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; } ReturnValue_t pst::pstSpi(FixedTimeslotTaskIF *thisSequence) { - uint32_t length = thisSequence->getPeriodMs(); - static_cast(length); + uint32_t length = thisSequence->getPeriodMs(); + static_cast(length); #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); + 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_IC3, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RTD_IC4, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RTD_IC5, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RTD_IC6, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RTD_IC7, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RTD_IC8, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RTD_IC9, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RTD_IC10, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RTD_IC11, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RTD_IC12, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RTD_IC13, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RTD_IC14, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RTD_IC15, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RTD_IC16, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RTD_IC17, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::RTD_IC18, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + 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); + 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_IC3, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RTD_IC4, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RTD_IC5, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RTD_IC6, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RTD_IC7, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RTD_IC8, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RTD_IC9, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RTD_IC10, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RTD_IC11, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RTD_IC12, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RTD_IC13, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RTD_IC14, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RTD_IC15, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RTD_IC16, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RTD_IC17, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::RTD_IC18, length * 0.2, DeviceHandlerIF::SEND_WRITE); + 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.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.4, DeviceHandlerIF::GET_WRITE); #endif #if OBSW_ADD_RTD_DEVICES == 1 - thisSequence->addSlot(objects::RTD_IC3, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RTD_IC4, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RTD_IC5, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RTD_IC6, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RTD_IC7, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RTD_IC8, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RTD_IC9, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RTD_IC10, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RTD_IC11, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RTD_IC12, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RTD_IC13, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RTD_IC14, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RTD_IC15, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RTD_IC16, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RTD_IC17, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RTD_IC18, length * 0.4, DeviceHandlerIF::GET_WRITE); + 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.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.6, DeviceHandlerIF::SEND_READ); #endif #if OBSW_ADD_RTD_DEVICES == 1 - thisSequence->addSlot(objects::RTD_IC3, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RTD_IC4, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RTD_IC5, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RTD_IC6, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RTD_IC7, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RTD_IC8, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RTD_IC9, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RTD_IC10, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RTD_IC11, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RTD_IC12, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RTD_IC13, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RTD_IC14, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RTD_IC15, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RTD_IC16, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RTD_IC17, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RTD_IC18, length * 0.6, DeviceHandlerIF::SEND_READ); + 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); + 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_IC3, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::RTD_IC4, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::RTD_IC5, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::RTD_IC6, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::RTD_IC7, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::RTD_IC8, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::RTD_IC9, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::RTD_IC10, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::RTD_IC11, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::RTD_IC12, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::RTD_IC13, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::RTD_IC14, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::RTD_IC15, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::RTD_IC16, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::RTD_IC17, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::RTD_IC18, length * 0.8, DeviceHandlerIF::GET_READ); + 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); + /* 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_SUN_SENSORS == 1 - /** - * The sun sensor will be shutdown as soon as the chip select is pulled high. Thus all - * requests to a sun sensor must be performed consecutively. Another reason for calling multiple - * device handler cycles is that the ADC conversions take some time. Thus first the ADC - * conversions are initiated and in a next step the results can be read from the internal FIFO. - * One sun sensor communication sequence also blocks the SPI bus. So other devices can not be - * inserted between the device handler cycles of one SUS. - */ - /* Write setup */ - thisSequence->addSlot(objects::SUS_1, length * 0.9, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_1, length * 0.9, SusHandler::FIRST_WRITE); - thisSequence->addSlot(objects::SUS_1, length * 0.9, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_1, length * 0.9, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_1, length * 0.9, DeviceHandlerIF::GET_READ); - /* Write setup */ - thisSequence->addSlot(objects::SUS_1, length * 0.901, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_1, length * 0.901, SusHandler::FIRST_WRITE); - thisSequence->addSlot(objects::SUS_1, length * 0.901, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_1, length * 0.901, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_1, length * 0.901, DeviceHandlerIF::GET_READ); - /* Write setup */ - thisSequence->addSlot(objects::SUS_1, length * 0.902, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_1, length * 0.902, SusHandler::FIRST_WRITE); - thisSequence->addSlot(objects::SUS_1, length * 0.902, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_1, length * 0.902, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_1, length * 0.902, DeviceHandlerIF::GET_READ); + bool addSus0 = true; + bool addSus1 = true; + bool addSus2 = true; + bool addSus3 = true; + bool addSus4 = true; + bool addSus5 = true; + bool addSus6 = true; + bool addSus7 = true; + bool addSus8 = true; + bool addSus9 = true; + bool addSus10 = true; + bool addSus11 = true; + /** + * The sun sensor will be shutdown as soon as the chip select is pulled high. Thus all + * requests to a sun sensor must be performed consecutively. Another reason for calling multiple + * device handler cycles is that the ADC conversions take some time. Thus first the ADC + * conversions are initiated and in a next step the results can be read from the internal FIFO. + * One sun sensor communication sequence also blocks the SPI bus. So other devices can not be + * inserted between the device handler cycles of one SUS. + */ + if (addSus0) { /* Write setup */ - thisSequence->addSlot(objects::SUS_2, length * 0.903, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_2, length * 0.903, SusHandler::FIRST_WRITE); - thisSequence->addSlot(objects::SUS_2, length * 0.903, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_2, length * 0.903, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_2, length * 0.903, DeviceHandlerIF::GET_READ); - /* Write setup */ - thisSequence->addSlot(objects::SUS_2, length * 0.904, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_2, length * 0.904, SusHandler::SEND_WRITE); - thisSequence->addSlot(objects::SUS_2, length * 0.904, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_2, length * 0.904, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_2, length * 0.904, DeviceHandlerIF::GET_READ); - /* Write setup */ - thisSequence->addSlot(objects::SUS_2, length * 0.905, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_2, length * 0.905, SusHandler::SEND_WRITE); - thisSequence->addSlot(objects::SUS_2, length * 0.905, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_2, length * 0.905, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_2, length * 0.905, DeviceHandlerIF::GET_READ); + 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); - /* Write setup */ - thisSequence->addSlot(objects::SUS_3, length * 0.8, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_3, length * 0.8, SusHandler::FIRST_WRITE); - thisSequence->addSlot(objects::SUS_3, length * 0.8, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_3, length * 0.8, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_3, length * 0.8, DeviceHandlerIF::GET_READ); - /* Write setup */ - thisSequence->addSlot(objects::SUS_3, length * 0.91, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_3, length * 0.91, SusHandler::SEND_WRITE); - thisSequence->addSlot(objects::SUS_3, length * 0.91, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_3, length * 0.91, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_3, length * 0.91, DeviceHandlerIF::GET_READ); - /* Write setup */ - thisSequence->addSlot(objects::SUS_3, length * 0.93, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_3, length * 0.93, SusHandler::SEND_WRITE); - thisSequence->addSlot(objects::SUS_3, length * 0.93, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_3, length * 0.93, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_3, length * 0.93, 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); + } + 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); - /* Write setup */ - thisSequence->addSlot(objects::SUS_4, length * 0.909, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_4, length * 0.909, SusHandler::FIRST_WRITE); - thisSequence->addSlot(objects::SUS_4, length * 0.909, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_4, length * 0.909, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_4, length * 0.909, DeviceHandlerIF::GET_READ); - /* Write setup */ - thisSequence->addSlot(objects::SUS_4, length * 0.91, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_4, length * 0.91, SusHandler::FIRST_WRITE); - thisSequence->addSlot(objects::SUS_4, length * 0.91, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_4, length * 0.91, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_4, length * 0.91, DeviceHandlerIF::GET_READ); - /* Write setup */ - thisSequence->addSlot(objects::SUS_4, length * 0.911, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_4, length * 0.911, SusHandler::FIRST_WRITE); - thisSequence->addSlot(objects::SUS_4, length * 0.911, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_4, length * 0.911, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_4, length * 0.911, 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); + } + 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); - /* Write setup */ - thisSequence->addSlot(objects::SUS_5, length * 0.912, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_5, length * 0.912, SusHandler::FIRST_WRITE); - thisSequence->addSlot(objects::SUS_5, length * 0.912, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_5, length * 0.912, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_5, length * 0.912, DeviceHandlerIF::GET_READ); - /* Write setup */ - thisSequence->addSlot(objects::SUS_5, length * 0.913, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_5, length * 0.913, SusHandler::FIRST_WRITE); - thisSequence->addSlot(objects::SUS_5, length * 0.913, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_5, length * 0.913, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_5, length * 0.913, DeviceHandlerIF::GET_READ); - /* Write setup */ - thisSequence->addSlot(objects::SUS_5, length * 0.914, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_5, length * 0.914, SusHandler::FIRST_WRITE); - thisSequence->addSlot(objects::SUS_5, length * 0.914, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_5, length * 0.914, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_5, length * 0.914, 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); + } + 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); - /* Write setup */ - thisSequence->addSlot(objects::SUS_6, length * 0.915, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_6, length * 0.915, SusHandler::FIRST_WRITE); - thisSequence->addSlot(objects::SUS_6, length * 0.915, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_6, length * 0.915, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_6, length * 0.915, DeviceHandlerIF::GET_READ); - /* Start ADC conversions */ - thisSequence->addSlot(objects::SUS_6, length * 0.916, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_6, length * 0.916, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_6, length * 0.916, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_6, length * 0.916, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_6, length * 0.916, DeviceHandlerIF::GET_READ); - /* Read ADC conversions from inernal FIFO */ - thisSequence->addSlot(objects::SUS_6, length * 0.917, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_6, length * 0.917, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_6, length * 0.917, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_6, length * 0.917, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_6, length * 0.917, 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); + } + 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); - /* Write setup */ - thisSequence->addSlot(objects::SUS_7, length * 0.918, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_7, length * 0.918, SusHandler::FIRST_WRITE); - thisSequence->addSlot(objects::SUS_7, length * 0.918, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_7, length * 0.918, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_7, length * 0.918, DeviceHandlerIF::GET_READ); - /* Start ADC conversions */ - thisSequence->addSlot(objects::SUS_7, length * 0.919, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_7, length * 0.919, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_7, length * 0.919, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_7, length * 0.919, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_7, length * 0.919, DeviceHandlerIF::GET_READ); - /* Read ADC conversions from inernal FIFO */ - thisSequence->addSlot(objects::SUS_7, length * 0.92, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_7, length * 0.92, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_7, length * 0.92, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_7, length * 0.92, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_7, length * 0.92, 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); + } + 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); - /* Write setup */ - thisSequence->addSlot(objects::SUS_8, length * 0.921, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_8, length * 0.921, SusHandler::FIRST_WRITE); - thisSequence->addSlot(objects::SUS_8, length * 0.921, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_8, length * 0.921, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_8, length * 0.921, DeviceHandlerIF::GET_READ); - /* Start ADC conversions */ - thisSequence->addSlot(objects::SUS_8, length * 0.922, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_8, length * 0.922, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_8, length * 0.922, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_8, length * 0.922, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_8, length * 0.922, DeviceHandlerIF::GET_READ); - /* Read ADC conversions from inernal FIFO */ - thisSequence->addSlot(objects::SUS_8, length * 0.923, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_8, length * 0.923, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_8, length * 0.923, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_8, length * 0.923, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_8, length * 0.923, 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); + } - /* Write setup */ - thisSequence->addSlot(objects::SUS_9, length * 0.924, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_9, length * 0.924, SusHandler::FIRST_WRITE); - thisSequence->addSlot(objects::SUS_9, length * 0.924, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_9, length * 0.924, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_9, length * 0.924, DeviceHandlerIF::GET_READ); - /* Start ADC conversions */ - thisSequence->addSlot(objects::SUS_9, length * 0.925, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_9, length * 0.925, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_9, length * 0.925, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_9, length * 0.925, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_9, length * 0.925, DeviceHandlerIF::GET_READ); - /* Read ADC conversions */ - thisSequence->addSlot(objects::SUS_9, length * 0.926, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_9, length * 0.926, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_9, length * 0.926, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_9, length * 0.926, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_9, length * 0.926, 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); - /* Write setup */ - thisSequence->addSlot(objects::SUS_10, length * 0.927, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_10, length * 0.927, SusHandler::FIRST_WRITE); - thisSequence->addSlot(objects::SUS_10, length * 0.927, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_10, length * 0.927, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_10, length * 0.927, DeviceHandlerIF::GET_READ); - /* Start ADC conversions */ - thisSequence->addSlot(objects::SUS_10, length * 0.928, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_10, length * 0.928, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_10, length * 0.928, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_10, length * 0.928, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_10, length * 0.928, DeviceHandlerIF::GET_READ); - /* Read ADC conversions */ - thisSequence->addSlot(objects::SUS_10, length * 0.929, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_10, length * 0.929, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_10, length * 0.929, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_10, length * 0.929, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_10, length * 0.929, 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); + } - /* Write setup */ - thisSequence->addSlot(objects::SUS_11, length * 0.93, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_11, length * 0.93, SusHandler::FIRST_WRITE); - thisSequence->addSlot(objects::SUS_11, length * 0.93, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_11, length * 0.93, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_11, length * 0.93, DeviceHandlerIF::GET_READ); - /* Start ADC conversions */ - thisSequence->addSlot(objects::SUS_11, length * 0.931, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_11, length * 0.931, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_11, length * 0.931, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_11, length * 0.931, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_11, length * 0.931, DeviceHandlerIF::GET_READ); - /* Read ADC conversions */ - thisSequence->addSlot(objects::SUS_11, length * 0.932, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_11, length * 0.932, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_11, length * 0.932, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_11, length * 0.932, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_11, length * 0.932, 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); - /* Write setup */ - thisSequence->addSlot(objects::SUS_12, length * 0.933, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_12, length * 0.933, SusHandler::FIRST_WRITE); - thisSequence->addSlot(objects::SUS_12, length * 0.933, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_12, length * 0.933, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_12, length * 0.933, DeviceHandlerIF::GET_READ); - /* Start ADC conversions */ - thisSequence->addSlot(objects::SUS_12, length * 0.934, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_12, length * 0.934, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_12, length * 0.934, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_12, length * 0.934, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_12, length * 0.934, DeviceHandlerIF::GET_READ); - /* Read ADC conversions */ - thisSequence->addSlot(objects::SUS_12, length * 0.935, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_12, length * 0.935, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_12, length * 0.935, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_12, length * 0.935, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_12, length * 0.935, 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); + } - /* Write setup */ - thisSequence->addSlot(objects::SUS_13, length * 0.936, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_13, length * 0.936, SusHandler::FIRST_WRITE); - thisSequence->addSlot(objects::SUS_13, length * 0.936, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_13, length * 0.936, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_13, length * 0.936, DeviceHandlerIF::GET_READ); - /* Start ADC conversions */ - thisSequence->addSlot(objects::SUS_13, length * 0.937, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_13, length * 0.937, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_13, length * 0.937, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_13, length * 0.937, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_13, length * 0.937, DeviceHandlerIF::GET_READ); - /* Read ADC conversions */ - thisSequence->addSlot(objects::SUS_13, length * 0.938, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_13, length * 0.938, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_13, length * 0.938, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_13, length * 0.938, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_13, length * 0.938, DeviceHandlerIF::GET_READ); -#endif + 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, 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); + } + + 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); + } + + 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, 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); + } + + 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, 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); + } +#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.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RW1, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RW1, length * 0.8, DeviceHandlerIF::GET_READ); + 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.6, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RW2, length * 0.7, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RW2, length * 0.85, 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.6, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RW3, length * 0.7, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RW3, length * 0.85, 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.6, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::RW4, length * 0.7, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::RW4, length * 0.85, 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); #endif -#if OBSW_ADD_ACS_BOARD == 1 - bool enableAside = true; - bool enableBside = false; - if(enableAside) { - // A side - thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0, - DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.2, - DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.6, - DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.7, - DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.85, - DeviceHandlerIF::GET_READ); +#if OBSW_ADD_ACS_BOARD == 1 && OBSW_ADD_ACS_HANDLERS == 1 + bool enableAside = false; + bool enableBside = true; + if (enableAside) { + // A side + thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.25, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.6, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.7, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.85, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0, - DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.25, - DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.6, - DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.75, - DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.85, - DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.25, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.6, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.7, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.85, DeviceHandlerIF::GET_READ); -// thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0, -// DeviceHandlerIF::PERFORM_OPERATION); -// thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0.3, -// DeviceHandlerIF::SEND_WRITE); -// thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0.6, -// DeviceHandlerIF::GET_WRITE); -// thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0.75, -// DeviceHandlerIF::SEND_READ); -// thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0.85, -// DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0.25, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0.6, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0.7, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0.85, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0, - DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.35, - DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.6, - DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.75, - DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.85, - DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.25, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.6, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.7, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.85, DeviceHandlerIF::GET_READ); + } + + if (enableBside) { + // B side + thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0.25, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0.6, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0.7, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0.85, DeviceHandlerIF::GET_READ); + + thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER, length * 0.25, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER, length * 0.6, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER, length * 0.7, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER, length * 0.85, DeviceHandlerIF::GET_READ); + + thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0.25, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0.6, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0.7, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0.85, DeviceHandlerIF::GET_READ); + + thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0.25, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0.6, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0.7, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0.85, DeviceHandlerIF::GET_READ); + } +#endif /* OBSW_ADD_ACS_BOARD == 1 && OBSW_ADD_ACS_HANDLERS == 1 */ + + ReturnValue_t seqCheck = thisSequence->checkSequence(); + if (seqCheck != HasReturnvaluesIF::RETURN_OK) { + if (seqCheck == FixedTimeslotTaskIF::SLOT_LIST_EMPTY) { + sif::warning << "SPI PST is empty.." << std::endl; + } else { + sif::error << "SPI PST initialization failed" << std::endl; } - if(enableBside) { - // B side - thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0, - DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0.2, - DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0.6, - DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0.7, - DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0.85, - DeviceHandlerIF::GET_READ); - - thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER, length * 0, - DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER, length * 0.25, - DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER, length * 0.6, - DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER, length * 0.75, - DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER, length * 0.85, - DeviceHandlerIF::GET_READ); - -// thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0, -// DeviceHandlerIF::PERFORM_OPERATION); -// thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0.3, -// DeviceHandlerIF::SEND_WRITE); -// thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0.6, -// DeviceHandlerIF::GET_WRITE); -// thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0.75, -// DeviceHandlerIF::SEND_READ); -// thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0.85, -// DeviceHandlerIF::GET_READ); - - thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0, - DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0.35, - DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0.6, - DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0.75, - DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0.85, - DeviceHandlerIF::GET_READ); - } -#endif /* OBSW_ADD_ACS_BOARD == 1 */ - - if (thisSequence->checkSequence() != HasReturnvaluesIF::RETURN_OK) { - sif::error << "SPI PST initialization failed" << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_OK; + return seqCheck; + } + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t pst::pstI2c(FixedTimeslotTaskIF *thisSequence) { - // Length of a communication cycle - uint32_t length = thisSequence->getPeriodMs(); - thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ); - if (thisSequence->checkSequence() != HasReturnvaluesIF::RETURN_OK) { - sif::error << "I2C PST initialization failed" << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_OK; + // Length of a communication cycle + uint32_t length = thisSequence->getPeriodMs(); + static_cast(length); +#if OBSW_ADD_MGT == 1 + thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ); +#endif +#if OBSW_ADD_BPX_BATTERY_HANDLER == 1 + thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ); +#endif + static_cast(length); + if (thisSequence->checkSequence() != HasReturnvaluesIF::RETURN_OK) { + sif::error << "I2C PST initialization failed" << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t pst::pstUart(FixedTimeslotTaskIF *thisSequence) { - // Length of a communication cycle - uint32_t length = thisSequence->getPeriodMs(); - static_cast(length); - bool uartPstEmpty = true; + // Length of a communication cycle + uint32_t length = thisSequence->getPeriodMs(); + bool uartPstEmpty = true; #if OBSW_ADD_PLOC_MPSOC == 1 - uartPstEmpty = false; - thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0, - DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0.2, - DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0.4, - DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0.6, - DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0.8, - DeviceHandlerIF::GET_READ); + uartPstEmpty = false; + thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ); #endif - thisSequence->addSlot(objects::PLOC_UPDATER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::PLOC_MEMORY_DUMPER, length * 0, - DeviceHandlerIF::PERFORM_OPERATION); +#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); - thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0.2, - DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0.4, - DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0.6, - DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0.8, - DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0.2, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ); #endif #if OBSW_ADD_SYRLINKS == 1 - uartPstEmpty = false; - thisSequence->addSlot(objects::SYRLINKS_HK_HANDLER, length * 0, - DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SYRLINKS_HK_HANDLER, length * 0.2, - DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SYRLINKS_HK_HANDLER, length * 0.4, - DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SYRLINKS_HK_HANDLER, length * 0.6, - DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SYRLINKS_HK_HANDLER, length * 0.8, - DeviceHandlerIF::GET_READ); + uartPstEmpty = false; + thisSequence->addSlot(objects::SYRLINKS_HK_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::SYRLINKS_HK_HANDLER, length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::SYRLINKS_HK_HANDLER, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::SYRLINKS_HK_HANDLER, length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::SYRLINKS_HK_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ); #endif -#if OBSW_ADD_ACS_BOARD == 1 - -#if OBSW_ADD_GPS_0 == 1 - uartPstEmpty = false; - thisSequence->addSlot(objects::GPS0_HANDLER, length * 0, - DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::GPS0_HANDLER, length * 0.2, - DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::GPS0_HANDLER, length * 0.4, - DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::GPS0_HANDLER, length * 0.6, - DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::GPS0_HANDLER, length * 0.8, - DeviceHandlerIF::GET_READ); -#endif /* OBSW_ADD_GPS_0 == 1 */ - -#if OBSW_ADD_GPS_1 == 1 - uartPstEmpty = false; - thisSequence->addSlot(objects::GPS1_HANDLER, length * 0, - DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::GPS1_HANDLER, length * 0.2, - DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::GPS1_HANDLER, length * 0.4, - DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::GPS1_HANDLER, length * 0.6, - DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::GPS1_HANDLER, length * 0.8, - DeviceHandlerIF::GET_READ); -#endif /* OBSW_ADD_GPS_1 == 1 */ - -#endif /* OBSW_ADD_ACS_BOARD == 1 */ - #if OBSW_ADD_STAR_TRACKER == 1 - uartPstEmpty = false; - thisSequence->addSlot(objects::START_TRACKER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::START_TRACKER, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::START_TRACKER, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::START_TRACKER, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::START_TRACKER, length * 0.8, DeviceHandlerIF::GET_READ); + uartPstEmpty = false; + thisSequence->addSlot(objects::STAR_TRACKER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::STAR_TRACKER, length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::STAR_TRACKER, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::STAR_TRACKER, length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::STAR_TRACKER, length * 0.8, DeviceHandlerIF::GET_READ); #endif - - if(uartPstEmpty) { - return HasReturnvaluesIF::RETURN_OK; - } - if (thisSequence->checkSequence() != HasReturnvaluesIF::RETURN_OK) { - sif::error << "UART PST initialization failed" << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; - } + static_cast(length); + if (uartPstEmpty) { return HasReturnvaluesIF::RETURN_OK; + } + if (thisSequence->checkSequence() != HasReturnvaluesIF::RETURN_OK) { + sif::error << "UART PST initialization failed" << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t pst::pstGompaceCan(FixedTimeslotTaskIF *thisSequence){ - uint32_t length = thisSequence->getPeriodMs(); +ReturnValue_t pst::pstGompaceCan(FixedTimeslotTaskIF *thisSequence) { + uint32_t length = thisSequence->getPeriodMs(); - // PCDU handlers receives two messages and both must be handled - thisSequence->addSlot(objects::PCDU_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::PCDU_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + // PCDU handlers receives two messages and both must be handled + thisSequence->addSlot(objects::PCDU_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::PCDU_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::P60DOCK_HANDLER, - length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::PDU1_HANDLER, - length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::PDU2_HANDLER, - length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::ACU_HANDLER, - length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::P60DOCK_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::PDU1_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::PDU2_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::ACU_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::P60DOCK_HANDLER, - length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::PDU1_HANDLER, - length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::PDU2_HANDLER, - length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::ACU_HANDLER, - length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::P60DOCK_HANDLER, length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::PDU1_HANDLER, length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::PDU2_HANDLER, length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::ACU_HANDLER, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::P60DOCK_HANDLER, - length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::PDU1_HANDLER, - length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::PDU2_HANDLER, - length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::ACU_HANDLER, - length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::P60DOCK_HANDLER, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::PDU1_HANDLER, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::PDU2_HANDLER, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::ACU_HANDLER, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::P60DOCK_HANDLER, - length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::PDU1_HANDLER, - length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::PDU2_HANDLER, - length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::ACU_HANDLER, - length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::P60DOCK_HANDLER, length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::PDU1_HANDLER, length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::PDU2_HANDLER, length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::ACU_HANDLER, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::P60DOCK_HANDLER, - length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::PDU1_HANDLER, - length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::PDU2_HANDLER, - length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::ACU_HANDLER, - length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::P60DOCK_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::PDU1_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::PDU2_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::ACU_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ); - if (thisSequence->checkSequence() != HasReturnvaluesIF::RETURN_OK) { - sif::error << "GomSpace PST initialization failed" << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_OK; + if (thisSequence->checkSequence() != HasReturnvaluesIF::RETURN_OK) { + sif::error << "GomSpace PST initialization failed" << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; } -ReturnValue_t pst::pstTest(FixedTimeslotTaskIF* thisSequence) { - /* Length of a communication cycle */ - uint32_t length = thisSequence->getPeriodMs(); - bool notEmpty = false; +ReturnValue_t pst::pstTest(FixedTimeslotTaskIF *thisSequence) { + /* Length of a communication cycle */ + uint32_t length = thisSequence->getPeriodMs(); + bool notEmpty = false; #if RPI_TEST_ADIS16507 == 1 - notEmpty = true; - thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0, - DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ); + notEmpty = true; + thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ); #endif #if RPI_TEST_GPS_HANDLER == 1 - notEmpty = true; - thisSequence->addSlot(objects::GPS0_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + notEmpty = true; + thisSequence->addSlot(objects::GPS0_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::GPS0_HANDLER, length * 0, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::GPS0_HANDLER, length * 0, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::GPS0_HANDLER, length * 0, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::GPS0_HANDLER, length * 0, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::GPS0_HANDLER, length * 0.5, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::GPS0_HANDLER, length * 0.5, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::GPS0_HANDLER, length * 0.5, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::GPS0_HANDLER, length * 0.5, DeviceHandlerIF::GET_READ); #endif - static_cast(length); - if(not notEmpty) { - return HasReturnvaluesIF::RETURN_FAILED; - } - if (thisSequence->checkSequence() != HasReturnvaluesIF::RETURN_OK) { - sif::error << "Test PST initialization failed" << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_OK; + static_cast(length); + if (not notEmpty) { + return HasReturnvaluesIF::RETURN_FAILED; + } + if (thisSequence->checkSequence() != HasReturnvaluesIF::RETURN_OK) { + sif::error << "Test PST initialization failed" << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; } #if BOARD_TE0720 == 1 ReturnValue_t pst::pollingSequenceTE0720(FixedTimeslotTaskIF *thisSequence) { - uint32_t length = thisSequence->getPeriodMs(); + uint32_t length = thisSequence->getPeriodMs(); #if TEST_PLOC_MPSOC_HANDLER == 1 - thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ); #endif -#if OBSW_TEST_RADIATION_SENSOR_HANDLER == 1 - 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); +#if OBSW_TEST_RAD_SENSOR == 1 + 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_TEST_SUS_HANDLER == 1 - /* Write setup */ - thisSequence->addSlot(objects::SUS_1, length * 0.901, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_1, length * 0.902, SusHandler::FIRST_WRITE); - thisSequence->addSlot(objects::SUS_1, length * 0.903, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_1, length * 0.904, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_1, length * 0.905, DeviceHandlerIF::GET_READ); +#if OBSW_TEST_SUS == 1 + /* Write setup */ + thisSequence->addSlot(objects::SUS_1, length * 0.901, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::SUS_1, length * 0.902, SusHandler::FIRST_WRITE); + thisSequence->addSlot(objects::SUS_1, length * 0.903, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::SUS_1, length * 0.904, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::SUS_1, length * 0.905, DeviceHandlerIF::GET_READ); - /* Start conversion*/ - thisSequence->addSlot(objects::SUS_1, length * 0.906, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_1, length * 0.907, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_1, length * 0.908, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_1, length * 0.909, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_1, length * 0.91, DeviceHandlerIF::GET_READ); + /* Start conversion*/ + thisSequence->addSlot(objects::SUS_1, length * 0.906, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::SUS_1, length * 0.907, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::SUS_1, length * 0.908, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::SUS_1, length * 0.909, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::SUS_1, length * 0.91, DeviceHandlerIF::GET_READ); - /* Read conversions */ - thisSequence->addSlot(objects::SUS_1, length * 0.911, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::SUS_1, length * 0.912, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::SUS_1, length * 0.913, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::SUS_1, length * 0.914, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::SUS_1, length * 0.915, DeviceHandlerIF::GET_READ); + /* Read conversions */ + thisSequence->addSlot(objects::SUS_1, length * 0.911, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::SUS_1, length * 0.912, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::SUS_1, length * 0.913, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::SUS_1, length * 0.914, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::SUS_1, length * 0.915, DeviceHandlerIF::GET_READ); #endif #if OBSW_ADD_PLOC_SUPERVISOR == 1 - thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0.7, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0.2, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0.7, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ); #endif - thisSequence->addSlot(objects::PLOC_UPDATER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::PLOC_MEMORY_DUMPER, length * 0, - DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::PLOC_UPDATER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::PLOC_MEMORY_DUMPER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); - if (thisSequence->checkSequence() != HasReturnvaluesIF::RETURN_OK) { - sif::error << "Initialization of TE0720 PST failed" << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_OK; + if (thisSequence->checkSequence() != HasReturnvaluesIF::RETURN_OK) { + sif::error << "Initialization of TE0720 PST failed" << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; } #endif /* BOARD_TE0720 == 1 */ diff --git a/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.h b/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.h index 5bb5ff2a..36b86ba8 100644 --- a/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.h +++ b/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.h @@ -32,7 +32,7 @@ class FixedTimeslotTaskIF; namespace pst { /* 0.4 second period init*/ -ReturnValue_t pstGpio(FixedTimeslotTaskIF *thisSequence); +ReturnValue_t pstGpio(FixedTimeslotTaskIF* thisSequence); /** * @brief This function creates the PST for all gomspace devices. @@ -40,7 +40,7 @@ ReturnValue_t pstGpio(FixedTimeslotTaskIF *thisSequence); * Scheduled in a separate PST because the gomspace library uses blocking calls when requesting * data from devices. */ -ReturnValue_t pstGompaceCan(FixedTimeslotTaskIF *thisSequence); +ReturnValue_t pstGompaceCan(FixedTimeslotTaskIF* thisSequence); ReturnValue_t pstUart(FixedTimeslotTaskIF* thisSequence); @@ -62,7 +62,6 @@ ReturnValue_t pstTest(FixedTimeslotTaskIF* thisSequence); ReturnValue_t pollingSequenceTE0720(FixedTimeslotTaskIF* thisSequence); #endif -} - +} // namespace pst #endif /* POLLINGSEQUENCEINIT_H_ */ diff --git a/linux/fsfwconfig/returnvalues/classIds.h b/linux/fsfwconfig/returnvalues/classIds.h index b98801e2..ecfc8ca9 100644 --- a/linux/fsfwconfig/returnvalues/classIds.h +++ b/linux/fsfwconfig/returnvalues/classIds.h @@ -1,8 +1,8 @@ #ifndef FSFWCONFIG_RETURNVALUES_CLASSIDS_H_ #define FSFWCONFIG_RETURNVALUES_CLASSIDS_H_ -#include #include +#include /** * Source IDs starts at 73 for now @@ -11,13 +11,11 @@ */ namespace CLASS_ID { enum { - CLASS_ID_START = COMMON_CLASS_ID_END, - SA_DEPL_HANDLER, //SADPL - SD_CARD_MANAGER, //SDMA - SCRATCH_BUFFER, //SCBU - CLASS_ID_END // [EXPORT] : [END] + CLASS_ID_START = COMMON_CLASS_ID_END, + SD_CARD_MANAGER, // SDMA + SCRATCH_BUFFER, // SCBU + CLASS_ID_END // [EXPORT] : [END] }; } - #endif /* FSFWCONFIG_RETURNVALUES_CLASSIDS_H_ */ diff --git a/linux/fsfwconfig/tmtc/pusIds.h b/linux/fsfwconfig/tmtc/pusIds.h index a2dd7575..37503786 100644 --- a/linux/fsfwconfig/tmtc/pusIds.h +++ b/linux/fsfwconfig/tmtc/pusIds.h @@ -2,21 +2,21 @@ #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, +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, }; }; diff --git a/linux/obc/AxiPtmeConfig.cpp b/linux/obc/AxiPtmeConfig.cpp new file mode 100644 index 00000000..26830d05 --- /dev/null +++ b/linux/obc/AxiPtmeConfig.cpp @@ -0,0 +1,119 @@ +#include "AxiPtmeConfig.h" + +#include "fsfw/serviceinterface/ServiceInterface.h" +#include "fsfw_hal/linux/uio/UioMapper.h" + +AxiPtmeConfig::AxiPtmeConfig(object_id_t objectId, std::string axiUio, int mapNum) + : SystemObject(objectId), axiUio(axiUio), mapNum(mapNum) { + mutex = MutexFactory::instance()->createMutex(); + if (mutex == nullptr) { + sif::warning << "Failed to create mutex" << std::endl; + } +} + +AxiPtmeConfig::~AxiPtmeConfig() {} + +ReturnValue_t AxiPtmeConfig::initialize() { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + UioMapper uioMapper(axiUio, mapNum); + result = uioMapper.getMappedAdress(&baseAddress, UioMapper::Permissions::READ_WRITE); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t AxiPtmeConfig::writeCaduRateReg(uint8_t rateVal) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + result = mutex->lockMutex(timeoutType, mutexTimeout); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "AxiPtmeConfig::writeCaduRateReg: Failed to lock mutex" << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } + *(baseAddress + CADU_BITRATE_REG) = static_cast(rateVal); + result = mutex->unlockMutex(); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "AxiPtmeConfig::writeCaduRateReg: Failed to unlock mutex" << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t AxiPtmeConfig::enableTxclockManipulator() { + ReturnValue_t result = writeBit(COMMON_CONFIG_REG, true, BitPos::EN_TX_CLK_MANIPULATOR); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t AxiPtmeConfig::disableTxclockManipulator() { + ReturnValue_t result = writeBit(COMMON_CONFIG_REG, false, BitPos::EN_TX_CLK_MANIPULATOR); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t AxiPtmeConfig::enableTxclockInversion() { + ReturnValue_t result = writeBit(COMMON_CONFIG_REG, true, BitPos::INVERT_CLOCK); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t AxiPtmeConfig::disableTxclockInversion() { + ReturnValue_t result = writeBit(COMMON_CONFIG_REG, false, BitPos::INVERT_CLOCK); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t AxiPtmeConfig::writeReg(uint32_t regOffset, uint32_t writeVal) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + result = mutex->lockMutex(timeoutType, mutexTimeout); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "AxiPtmeConfig::readReg: Failed to lock mutex" << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } + *(baseAddress + regOffset / ADRESS_DIVIDER) = writeVal; + result = mutex->unlockMutex(); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "AxiPtmeConfig::readReg: Failed to unlock mutex" << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t AxiPtmeConfig::readReg(uint32_t regOffset, uint32_t* readVal) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + result = mutex->lockMutex(timeoutType, mutexTimeout); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "AxiPtmeConfig::readReg: Failed to lock mutex" << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } + *readVal = *(baseAddress + regOffset / ADRESS_DIVIDER); + result = mutex->unlockMutex(); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "AxiPtmeConfig::readReg: Failed to unlock mutex" << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t AxiPtmeConfig::writeBit(uint32_t regOffset, bool bitVal, BitPos bitPos) { + uint32_t readVal = 0; + ReturnValue_t result = readReg(regOffset, &readVal); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + uint32_t writeVal = + (readVal & ~(1 << static_cast(bitPos))) | bitVal << static_cast(bitPos); + result = writeReg(regOffset, writeVal); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return HasReturnvaluesIF::RETURN_OK; +} diff --git a/linux/obc/AxiPtmeConfig.h b/linux/obc/AxiPtmeConfig.h new file mode 100644 index 00000000..c86bb429 --- /dev/null +++ b/linux/obc/AxiPtmeConfig.h @@ -0,0 +1,99 @@ +#ifndef LINUX_OBC_AXIPTMECONFIG_H_ +#define LINUX_OBC_AXIPTMECONFIG_H_ + +#include + +#include "fsfw/ipc/MutexIF.h" +#include "fsfw/objectmanager/SystemObject.h" +#include "fsfw/returnvalues/HasReturnvaluesIF.h" + +/** + * @brief Class providing low level access to the configuration interface of the PTME. + * + * @author J. Meier + */ +class AxiPtmeConfig : public SystemObject { + public: + /** + * @brief Constructor + * @param axiUio Device file of UIO belonging to the AXI configuration interface. + * @param mapNum Number of map belonging to axi configuration interface. + */ + AxiPtmeConfig(object_id_t objectId, std::string axiUio, int mapNum); + virtual ~AxiPtmeConfig(); + + virtual ReturnValue_t initialize() override; + /** + * @brief Will write to the bitrate configuration register. Actual generated rate depends on + * frequency of the clock connected to the bit clock input of PTME. + */ + ReturnValue_t writeCaduRateReg(uint8_t rateVal); + + /** + * @brief Next to functions control the tx clock manipulator component + * + * @details If the tx clock manipulator is enabled the output clock of the PTME is manipulated + * in a way that both high and low periods in the clock signal have equal lengths. + * The default implementation of the PTME generates a clock where the high level is + * only one bit clock period long. This might be too short to match the setup and hold + * times of the S-and transceiver. + */ + ReturnValue_t enableTxclockManipulator(); + ReturnValue_t disableTxclockManipulator(); + + /** + * @brief The next to functions control whether data will be updated on the rising or falling edge + * of the tx clock. + * Enable inversion will update data on falling edge (not the configuration required by the + * syrlinks) + * Disable clock inversion. Data updated on rising edge. + */ + ReturnValue_t enableTxclockInversion(); + ReturnValue_t disableTxclockInversion(); + + private: + // Address of register storing the bitrate configuration parameter + static const uint32_t CADU_BITRATE_REG = 0x0; + // Address to register storing common configuration parameters + static const uint32_t COMMON_CONFIG_REG = 0x4; + static const uint32_t ADRESS_DIVIDER = 4; + + enum class BitPos : uint32_t { EN_TX_CLK_MANIPULATOR, INVERT_CLOCK }; + + std::string axiUio; + std::string uioMap; + int mapNum = 0; + MutexIF* mutex = nullptr; + MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING; + uint32_t mutexTimeout = 20; + + uint32_t* baseAddress = nullptr; + + /** + * @brief Function to write to configuration registers + * + * @param writeVal Value to write + */ + ReturnValue_t writeReg(uint32_t regOffset, uint32_t writeVal); + + /** + * @brief Reads value from configuration register + * + * @param regOffset Offset of register from base address to read from + * Qparam readVal Pointer to variable where read value will be written to + */ + ReturnValue_t readReg(uint32_t regOffset, uint32_t* readVal); + + /** + * @brief Sets one bit in a register + * + * @param regOffset Offset of the register where to set the bit + * @param bitVal The value of the bit to set (1 or 0) + * @param bitPos The position of the bit within the register to set + * + * @return RETURN_OK if successful, otherwise RETURN_FAILED + */ + ReturnValue_t writeBit(uint32_t regOffset, bool bitVal, BitPos bitPos); +}; + +#endif /* LINUX_OBC_AXIPTMECONFIG_H_ */ diff --git a/linux/obc/CCSDSIPCoreBridge.cpp b/linux/obc/CCSDSIPCoreBridge.cpp deleted file mode 100644 index fe5a7007..00000000 --- a/linux/obc/CCSDSIPCoreBridge.cpp +++ /dev/null @@ -1,136 +0,0 @@ -#include -#include - -#include - -CCSDSIPCoreBridge::CCSDSIPCoreBridge(object_id_t objectId, object_id_t tcDestination, - object_id_t tmStoreId, object_id_t tcStoreId, LinuxLibgpioIF* gpioComIF, - std::string uioPtme, gpioId_t papbBusyId, gpioId_t papbEmptyId) : - TmTcBridge(objectId, tcDestination, tmStoreId, tcStoreId), gpioComIF(gpioComIF), uioPtme( - uioPtme), papbBusyId(papbBusyId), papbEmptyId(papbEmptyId) { -} - -CCSDSIPCoreBridge::~CCSDSIPCoreBridge() { -} - -ReturnValue_t CCSDSIPCoreBridge::initialize() { - ReturnValue_t result = TmTcBridge::initialize(); - - fd = open("/dev/uio0", O_RDWR); - if (fd < 1) { - sif::debug << "CCSDSIPCoreBridge::initialize: Invalid UIO device file" << std::endl; - return RETURN_FAILED; - } - - /** - * Map uio device in virtual address space - * PROT_WRITE: Map uio device in writable only mode - */ - ptmeBaseAddress = static_cast(mmap(NULL, MAP_SIZE, PROT_READ | PROT_WRITE, - MAP_SHARED, fd, 0)); - - if (ptmeBaseAddress == MAP_FAILED) { - sif::error << "CCSDSIPCoreBridge::initialize: Failed to map uio address" << std::endl; - return RETURN_FAILED; - } - - return result; -} - -ReturnValue_t CCSDSIPCoreBridge::handleTm() { - -#if OBSW_TEST_CCSDS_PTME == 1 - return sendTestFrame(); -#else - return TmTcBridge::handleTm(); -#endif - -} - -ReturnValue_t CCSDSIPCoreBridge::sendTm(const uint8_t * data, size_t dataLen) { - - if(pollPapbBusySignal() == RETURN_OK) { - startPacketTransfer(); - } - - for(size_t idx = 0; idx < dataLen; idx++) { - if(pollPapbBusySignal() == RETURN_OK) { - *(ptmeBaseAddress + PTME_DATA_REG_OFFSET) = static_cast(*(data + idx)); - } - else { - sif::debug << "CCSDSIPCoreBridge::sendTm: Only written " << idx - 1 << " of " << dataLen - << " data" << std::endl; - return RETURN_FAILED; - } - } - - if(pollPapbBusySignal() == RETURN_OK) { - endPacketTransfer(); - } - return RETURN_OK; -} - -void CCSDSIPCoreBridge::startPacketTransfer() { - *ptmeBaseAddress = PTME_CONFIG_START; -} - -void CCSDSIPCoreBridge::endPacketTransfer() { - *ptmeBaseAddress = PTME_CONFIG_END; -} - -ReturnValue_t CCSDSIPCoreBridge::pollPapbBusySignal() { - int papbBusyState = 0; - ReturnValue_t result = RETURN_OK; - - /** Check if PAPB interface is ready to receive data */ - result = gpioComIF->readGpio(papbBusyId, &papbBusyState); - if (result != RETURN_OK) { - sif::debug << "CCSDSIPCoreBridge::pollPapbBusySignal: Failed to read papb busy signal" - << std::endl; - return RETURN_FAILED; - } - if (!papbBusyState) { - sif::debug << "CCSDSIPCoreBridge::pollPapbBusySignal: PAPB busy" << std::endl; - return PAPB_BUSY; - } - - return RETURN_OK; -} - -void CCSDSIPCoreBridge::isPtmeBufferEmpty() { - ReturnValue_t result = RETURN_OK; - int papbEmptyState = 1; - - result = gpioComIF->readGpio(papbEmptyId, &papbEmptyState); - - if (result != RETURN_OK) { - sif::debug << "CCSDSIPCoreBridge::isPtmeBufferEmpty: Failed to read papb empty signal" - << std::endl; - return; - } - - if (papbEmptyState == 1) { - sif::debug << "CCSDSIPCoreBridge::isPtmeBufferEmpty: Buffer is empty" << std::endl; - } - else { - sif::debug << "CCSDSIPCoreBridge::isPtmeBufferEmpty: Buffer is not empty" << std::endl; - } - return; -} - -ReturnValue_t CCSDSIPCoreBridge::sendTestFrame() { - /** Size of one complete transfer frame data field amounts to 1105 bytes */ - uint8_t testPacket[1105]; - - /** Fill one test packet */ - for(int idx = 0; idx < 1105; idx++) { - testPacket[idx] = static_cast(idx & 0xFF); - } - - ReturnValue_t result = sendTm(testPacket, 1105); - if(result != RETURN_OK) { - return result; - } - - return RETURN_OK; -} diff --git a/linux/obc/CCSDSIPCoreBridge.h b/linux/obc/CCSDSIPCoreBridge.h deleted file mode 100644 index 2ba68a3a..00000000 --- a/linux/obc/CCSDSIPCoreBridge.h +++ /dev/null @@ -1,131 +0,0 @@ -#ifndef MISSION_OBC_CCSDSIPCOREBRIDGE_H_ -#define MISSION_OBC_CCSDSIPCOREBRIDGE_H_ - -#include "OBSWConfig.h" -#include -#include -#include - -#include - -/** - * @brief This class handles the interfacing to the telemetry (PTME) and telecommand (PDEC) IP - * cores responsible for the CCSDS encoding and decoding. The IP cores are implemented - * on the programmable logic and are accessible through the linux UIO driver. - */ -class CCSDSIPCoreBridge: public TmTcBridge { -public: - /** - * @brief Constructor - * - * @param objectId - * @param tcDestination - * @param tmStoreId - * @param tcStoreId - * @param uioPtme Name of the uio device file which provides access to the PTME IP Core. - * @param papbBusyId The ID of the GPIO which is connected to the PAPBBusy_N signal of the - * PTME IP Core. A low logic level indicates the PTME is not ready to - * receive more data. - * @param papbEmptyId The ID of the GPIO which is connected to the PAPBEmpty signal of the - * PTME IP Core. The signal is high when there are no packets in the - * external buffer memory (BRAM). - */ - CCSDSIPCoreBridge(object_id_t objectId, object_id_t tcDestination, object_id_t tmStoreId, - object_id_t tcStoreId, LinuxLibgpioIF* gpioComIF, std::string uioPtme, - gpioId_t papbBusyId, gpioId_t papbEmptyId); - virtual ~CCSDSIPCoreBridge(); - - ReturnValue_t initialize() override; - -protected: - - /** - * Overwriting this function to provide the capability of testing the PTME IP Core - * implementation. - */ - virtual ReturnValue_t handleTm() override; - - virtual ReturnValue_t sendTm(const uint8_t * data, size_t dataLen) override; - -private: - - static const uint8_t INTERFACE_ID = CLASS_ID::CCSDS_IP_CORE_BRIDGE; - - static const ReturnValue_t PAPB_BUSY = MAKE_RETURN_CODE(0xA0); - - - /** Size of mapped address space. 4k (minimal size of pl device) */ -// static const int MAP_SIZE = 0xFA0; - static const int MAP_SIZE = 0x1000; - - /** - * Configuration bits: - * bit[1:0]: Size of data (1,2,3 or 4 bytes). 1 Byte <=> b00 - * bit[2]: Set this bit to 1 to abort a transfered packet - * bit[3]: Signals to PTME the start of a new telemetry packet - */ - static const uint32_t PTME_CONFIG_START = 0x8; - - /** - * Writing this word to the ptme base address signals to the PTME that a complete tm packet has - * been transferred. - */ - static const uint32_t PTME_CONFIG_END = 0x0; - - /** - * Writing to this offset within the PTME memory space will insert data for encoding to the - * PTME IP core. - * The address offset is 0x400 (= 4 * 256) - */ - static const int PTME_DATA_REG_OFFSET = 256; - - LinuxLibgpioIF* gpioComIF = nullptr; - - /** The uio device file related to the PTME IP Core */ - std::string uioPtme; - - /** Pulled to low when PTME not ready to receive data */ - gpioId_t papbBusyId = gpio::NO_GPIO; - - /** High when externally buffer memory of PTME is empty */ - gpioId_t papbEmptyId = gpio::NO_GPIO; - - /** The file descriptor of the UIO driver */ - int fd; - - uint32_t* ptmeBaseAddress = nullptr; - - /** - * @brief This function sends the config byte to the PTME IP Core to initiate a packet - * transfer. - */ - void startPacketTransfer(); - - /** - * @brief This function sends the config byte to the PTME IP Core to signal the end of a - * packet transfer. - */ - void endPacketTransfer(); - - /** - * @brief This function reads the papb busy signal indicating whether the PAPB interface is - * ready to receive more data or not. PAPB is ready when PAPB_Busy_N == '1'. - * - * @return RETURN_OK when ready to receive data else PAPB_BUSY. - */ - ReturnValue_t pollPapbBusySignal(); - - /** - * @brief This function can be used for debugging to check wheter there are packets in - * the packet buffer of the PTME or not. - */ - void isPtmeBufferEmpty(); - - /** - * @brief This function sends a complete telemetry transfer frame data field (1105 bytes) - * to the input of the PTME IP Core. Can be used to test the implementation. - */ - ReturnValue_t sendTestFrame(); -}; - -#endif /* MISSION_OBC_CCSDSIPCOREBRIDGE_H_ */ diff --git a/linux/obc/CMakeLists.txt b/linux/obc/CMakeLists.txt index 79d9ba9b..6d5c4436 100644 --- a/linux/obc/CMakeLists.txt +++ b/linux/obc/CMakeLists.txt @@ -1,5 +1,10 @@ -target_sources(${TARGET_NAME} PUBLIC - CCSDSIPCoreBridge.cpp +target_sources(${OBSW_NAME} PUBLIC + PapbVcInterface.cpp + Ptme.cpp + PdecHandler.cpp + PdecConfig.cpp + PtmeConfig.cpp + AxiPtmeConfig.cpp ) diff --git a/linux/obc/PapbVcInterface.cpp b/linux/obc/PapbVcInterface.cpp new file mode 100644 index 00000000..5636975a --- /dev/null +++ b/linux/obc/PapbVcInterface.cpp @@ -0,0 +1,98 @@ +#include +#include + +#include "fsfw/serviceinterface/ServiceInterface.h" + +PapbVcInterface::PapbVcInterface(LinuxLibgpioIF* gpioComIF, gpioId_t papbBusyId, + gpioId_t papbEmptyId, std::string uioFile, int mapNum) + : gpioComIF(gpioComIF), + papbBusyId(papbBusyId), + papbEmptyId(papbEmptyId), + uioFile(uioFile), + mapNum(mapNum) {} + +PapbVcInterface::~PapbVcInterface() {} + +ReturnValue_t PapbVcInterface::initialize() { + UioMapper uioMapper(uioFile, mapNum); + return uioMapper.getMappedAdress(&vcBaseReg, UioMapper::Permissions::WRITE_ONLY); +} + +ReturnValue_t PapbVcInterface::write(const uint8_t* data, size_t size) { + if (pollPapbBusySignal() == RETURN_OK) { + startPacketTransfer(); + } + for (size_t idx = 0; idx < size; idx++) { + if (pollPapbBusySignal() == RETURN_OK) { + *(vcBaseReg + DATA_REG_OFFSET) = static_cast(*(data + idx)); + } else { + sif::warning << "PapbVcInterface::write: Only written " << idx << " of " << size << " data" + << std::endl; + return RETURN_FAILED; + } + } + if (pollPapbBusySignal() == RETURN_OK) { + endPacketTransfer(); + } + return RETURN_OK; +} + +void PapbVcInterface::startPacketTransfer() { *vcBaseReg = CONFIG_START; } + +void PapbVcInterface::endPacketTransfer() { *vcBaseReg = CONFIG_END; } + +ReturnValue_t PapbVcInterface::pollPapbBusySignal() { + int papbBusyState = 0; + ReturnValue_t result = RETURN_OK; + + /** Check if PAPB interface is ready to receive data */ + result = gpioComIF->readGpio(papbBusyId, &papbBusyState); + if (result != RETURN_OK) { + sif::warning << "PapbVcInterface::pollPapbBusySignal: Failed to read papb busy signal" + << std::endl; + return RETURN_FAILED; + } + if (!papbBusyState) { + sif::warning << "PapbVcInterface::pollPapbBusySignal: PAPB busy" << std::endl; + return PAPB_BUSY; + } + + return RETURN_OK; +} + +void PapbVcInterface::isVcInterfaceBufferEmpty() { + ReturnValue_t result = RETURN_OK; + int papbEmptyState = 1; + + result = gpioComIF->readGpio(papbEmptyId, &papbEmptyState); + + if (result != RETURN_OK) { + sif::warning << "PapbVcInterface::isVcInterfaceBufferEmpty: Failed to read papb empty signal" + << std::endl; + return; + } + + if (papbEmptyState == 1) { + sif::debug << "PapbVcInterface::isVcInterfaceBufferEmpty: Buffer is empty" << std::endl; + } else { + sif::debug << "PapbVcInterface::isVcInterfaceBufferEmpty: Buffer is not empty" << std::endl; + } + return; +} + +ReturnValue_t PapbVcInterface::sendTestFrame() { + /** Size of one complete transfer frame data field amounts to 1105 bytes */ + uint8_t testPacket[1105]; + + /** Fill one test packet */ + for (int idx = 0; idx < 1105; idx++) { + testPacket[idx] = static_cast(idx & 0xFF); + } + + ReturnValue_t result = write(testPacket, 1105); + if (result != RETURN_OK) { + return result; + } + + return RETURN_OK; +} diff --git a/linux/obc/PapbVcInterface.h b/linux/obc/PapbVcInterface.h new file mode 100644 index 00000000..0d6382e3 --- /dev/null +++ b/linux/obc/PapbVcInterface.h @@ -0,0 +1,113 @@ +#ifndef LINUX_OBC_PAPBVCINTERFACE_H_ +#define LINUX_OBC_PAPBVCINTERFACE_H_ + +#include +#include + +#include "OBSWConfig.h" +#include "fsfw/returnvalues/HasReturnvaluesIF.h" +#include "linux/obc/VcInterfaceIF.h" + +/** + * @brief This class handles the transmission of data to a virtual channel of the PTME IP Core + * via the PAPB interface. + * + * @author J. Meier + */ +class PapbVcInterface : public VcInterfaceIF, public HasReturnvaluesIF { + public: + /** + * @brief Constructor + * + * @param papbBusyId The ID of the GPIO which is connected to the PAPBBusy_N signal of the + * VcInterface IP Core. A low logic level indicates the VcInterface is not + * ready to receive more data. + * @param papbEmptyId The ID of the GPIO which is connected to the PAPBEmpty signal of the + * VcInterface IP Core. The signal is high when there are no packets in the + * external buffer memory (BRAM). + * @param uioFile UIO file providing access to the PAPB bus + * @param mapNum Map number of UIO map associated with this virtual channel + */ + PapbVcInterface(LinuxLibgpioIF* gpioComIF, gpioId_t papbBusyId, gpioId_t papbEmptyId, + std::string uioFile, int mapNum); + virtual ~PapbVcInterface(); + + ReturnValue_t write(const uint8_t* data, size_t size) override; + + ReturnValue_t initialize() override; + + private: + static const uint8_t INTERFACE_ID = CLASS_ID::CCSDS_IP_CORE_BRIDGE; + + static const ReturnValue_t PAPB_BUSY = MAKE_RETURN_CODE(0xA0); + + /** + * Configuration bits: + * bit[1:0]: Size of data (1,2,3 or 4 bytes). 1 Byte <=> b00 + * bit[2]: Set this bit to 1 to abort a transfered packet + * bit[3]: Signals to VcInterface the start of a new telemetry packet + */ + static const uint32_t CONFIG_START = 0x8; + + /** + * Writing this word to the VcInterface base address signals to the virtual channel interface + * that a complete tm packet has been transferred. + */ + static const uint32_t CONFIG_END = 0x0; + + /** + * Writing to this offset within the memory space of a virtual channel will insert data for + * encoding to the external buffer memory of the PTME IP Core. + * The address offset is 0x400 (= 4 * 256) + */ + static const int DATA_REG_OFFSET = 256; + + LinuxLibgpioIF* gpioComIF = nullptr; + + /** Pulled to low when virtual channel not ready to receive data */ + gpioId_t papbBusyId = gpio::NO_GPIO; + /** High when external buffer memory of virtual channel is empty */ + gpioId_t papbEmptyId = gpio::NO_GPIO; + + std::string uioFile; + int mapNum = 0; + + uint32_t* vcBaseReg = nullptr; + + uint32_t vcOffset = 0; + + /** + * @brief This function sends the config byte to the virtual channel of the PTME IP Core + * to initiate a packet transfer. + */ + void startPacketTransfer(); + + /** + * @brief This function sends the config byte to the virtual channel interface of the PTME + * IP Core to signal the end of a packet transfer. + */ + void endPacketTransfer(); + + /** + * @brief This function reads the papb busy signal indicating whether the virtual channel + * interface is ready to receive more data or not. PAPB is ready when + * PAPB_Busy_N == '1'. + * + * @return RETURN_OK when ready to receive data else PAPB_BUSY. + */ + ReturnValue_t pollPapbBusySignal(); + + /** + * @brief This function can be used for debugging to check whether there are packets in + * the packet buffer of the virtual channel or not. + */ + void isVcInterfaceBufferEmpty(); + + /** + * @brief This function sends a complete telemetry transfer frame data field (1105 bytes) + * to the papb interface of the PTME IP Core. Can be used to test the implementation. + */ + ReturnValue_t sendTestFrame(); +}; + +#endif /* LINUX_OBC_PAPBVCINTERFACE_H_ */ diff --git a/linux/obc/PdecConfig.cpp b/linux/obc/PdecConfig.cpp new file mode 100644 index 00000000..ac762a6c --- /dev/null +++ b/linux/obc/PdecConfig.cpp @@ -0,0 +1,33 @@ +#include "PdecConfig.h" + +#include "fsfw/serviceinterface/ServiceInterface.h" + +PdecConfig::PdecConfig() { initialize(); } + +PdecConfig::~PdecConfig() {} + +void PdecConfig::initialize() { + uint32_t word = 0; + word |= (VERSION_ID << 30); + word |= (BYPASS_FLAG << 29); + word |= (CONTROL_COMMAND_FLAG << 28); + word |= (RESERVED_FIELD_A << 26); + word |= (SPACECRAFT_ID << 16); + word |= (VIRTUAL_CHANNEL << 10); + word |= (DUMMY_BITS << 8); + word |= POSITIVE_WINDOW; + configWords[0] = word; + word = 0; + word |= (NEGATIVE_WINDOW << 24); + word |= (HIGH_AU_MAP_ID << 16); + word |= (ENABLE_DERANDOMIZER << 8); + configWords[1] = word; +} + +uint32_t PdecConfig::getConfigWord(uint8_t wordNo) { + if (wordNo >= CONFIG_WORDS_NUM) { + sif::error << "PdecConfig::getConfigWord: Invalid word number" << std::endl; + return 0; + } + return configWords[wordNo]; +} diff --git a/linux/obc/PdecConfig.h b/linux/obc/PdecConfig.h new file mode 100644 index 00000000..37dab151 --- /dev/null +++ b/linux/obc/PdecConfig.h @@ -0,0 +1,52 @@ +#ifndef LINUX_OBC_PDECCONFIG_H_ +#define LINUX_OBC_PDECCONFIG_H_ + +#include + +#include "fsfw/returnvalues/HasReturnvaluesIF.h" + +/** + * @brief This class generates the configuration words for the configuration memory of the PDEC + * IP Cores. + * + * @details Fields are initialized according to pecification in PDEC datasheet section 6.11.3.1 + * PROM usage. + * + * @author J. Meier + */ +class PdecConfig { + public: + PdecConfig(); + virtual ~PdecConfig(); + + /** + * @brief Returns the configuration word by specifying the position. + */ + uint32_t getConfigWord(uint8_t wordNo); + + private: + // TC transfer frame configuration parameters + static const uint8_t VERSION_ID = 0; + // BD Frames + static const uint8_t BYPASS_FLAG = 1; + static const uint8_t CONTROL_COMMAND_FLAG = 0; + + static const uint8_t VIRTUAL_CHANNEL = 0; + static const uint8_t RESERVED_FIELD_A = 0; + static const uint16_t SPACECRAFT_ID = 0x274; + static const uint16_t DUMMY_BITS = 0; + // Parameters to control the FARM for AD frames + // Set here for future use + static const uint8_t POSITIVE_WINDOW = 10; + static const uint8_t NEGATIVE_WINDOW = 151; + static const uint8_t HIGH_AU_MAP_ID = 0xF; + static const uint8_t ENABLE_DERANDOMIZER = 1; + + static const uint8_t CONFIG_WORDS_NUM = 2; + + uint32_t configWords[CONFIG_WORDS_NUM]; + + void initialize(); +}; + +#endif /* LINUX_OBC_PDECCONFIG_H_ */ diff --git a/linux/obc/PdecHandler.cpp b/linux/obc/PdecHandler.cpp new file mode 100644 index 00000000..f97c3965 --- /dev/null +++ b/linux/obc/PdecHandler.cpp @@ -0,0 +1,521 @@ +#include "PdecHandler.h" + +#include +#include + +#include +#include + +#include "OBSWConfig.h" +#include "fsfw/ipc/QueueFactory.h" +#include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/serviceinterface/ServiceInterface.h" +#include "fsfw/tmtcservices/TmTcMessage.h" +#include "fsfw_hal/linux/uio/UioMapper.h" + +PdecHandler::PdecHandler(object_id_t objectId, object_id_t tcDestinationId, + LinuxLibgpioIF* gpioComIF, gpioId_t pdecReset, std::string uioConfigMemory, + std::string uioRamMemory, std::string uioRegisters) + : SystemObject(objectId), + tcDestinationId(tcDestinationId), + gpioComIF(gpioComIF), + pdecReset(pdecReset), + uioConfigMemory(uioConfigMemory), + uioRamMemory(uioRamMemory), + uioRegisters(uioRegisters), + actionHelper(this, nullptr) { + commandQueue = QueueFactory::instance()->createMessageQueue(QUEUE_SIZE); +} + +PdecHandler::~PdecHandler() {} + +ReturnValue_t PdecHandler::initialize() { + tcStore = ObjectManager::instance()->get(objects::TC_STORE); + if (tcStore == nullptr) { + sif::error << "PdecHandler::initialize: Invalid TC store" << std::endl; + return ObjectManagerIF::CHILD_INIT_FAILED; + } + + tcDestination = ObjectManager::instance()->get(tcDestinationId); + + if (tcDestination == nullptr) { + sif::error << "PdecHandler::initialize: Invalid tc destination specified" << std::endl; + return ObjectManagerIF::CHILD_INIT_FAILED; + } + + ReturnValue_t result = RETURN_OK; + + UioMapper regMapper(uioRegisters); + result = regMapper.getMappedAdress(®isterBaseAddress, UioMapper::Permissions::READ_WRITE); + if (result != RETURN_OK) { + return ObjectManagerIF::CHILD_INIT_FAILED; + } + UioMapper configMemMapper(uioConfigMemory); + result = configMemMapper.getMappedAdress(&memoryBaseAddress, UioMapper::Permissions::READ_WRITE); + if (result != RETURN_OK) { + return ObjectManagerIF::CHILD_INIT_FAILED; + } + UioMapper ramMapper(uioRamMemory); + result = ramMapper.getMappedAdress(&ramBaseAddress, UioMapper::Permissions::READ_WRITE); + if (result != RETURN_OK) { + return ObjectManagerIF::CHILD_INIT_FAILED; + } + + writePdecConfig(); + + result = releasePdec(); + if (result != RETURN_OK) { + return ObjectManagerIF::CHILD_INIT_FAILED; + } + + result = actionHelper.initialize(commandQueue); + if (result != RETURN_OK) { + return result; + } + + return RETURN_OK; +} + +MessageQueueId_t PdecHandler::getCommandQueue() const { return commandQueue->getId(); } + +void PdecHandler::writePdecConfig() { + PdecConfig pdecConfig; + + *(memoryBaseAddress + FRAME_HEADER_OFFSET) = pdecConfig.getConfigWord(0); + *(memoryBaseAddress + FRAME_HEADER_OFFSET + 1) = pdecConfig.getConfigWord(1); + + // Configure all MAP IDs as invalid + for (int idx = 0; idx <= MAX_MAP_ADDR; idx += 4) { + *(memoryBaseAddress + MAP_ADDR_LUT_OFFSET + idx + 1 / 4) = + NO_DESTINATION << 24 | NO_DESTINATION << 16 | NO_DESTINATION << 8 | NO_DESTINATION; + } + + // All TCs with MAP ID 7 will be routed to the PM module (can then be read from memory) + uint8_t routeToPm = calcMapAddrEntry(PM_BUFFER); + *(memoryBaseAddress + MAP_ADDR_LUT_OFFSET + 1) = + (NO_DESTINATION << 24) | (NO_DESTINATION << 16) | (NO_DESTINATION << 8) | routeToPm; + + // Write map id clock frequencies + for (int idx = 0; idx <= MAX_MAP_ADDR; idx += 4) { + *(memoryBaseAddress + MAP_CLK_FREQ_OFFSET + idx / 4) = + MAP_CLK_FREQ << 24 | MAP_CLK_FREQ << 16 | MAP_CLK_FREQ << 8 | MAP_CLK_FREQ; + } +} + +ReturnValue_t PdecHandler::resetFarStatFlag() { + uint32_t pdecFar = *(registerBaseAddress + PDEC_FAR_OFFSET); + if (pdecFar != FAR_RESET) { + sif::warning << "PdecHandler::resetFarStatFlag: FAR register did not match expected value." + << " Read value: 0x" << std::hex << static_cast(pdecFar) + << std::endl; + return RETURN_FAILED; + } +#if OBSW_DEBUG_PDEC_HANDLER == 1 + sif::debug << "PdecHandler::resetFarStatFlag: read FAR with value: 0x" << std::hex << pdecFar + << std::endl; +#endif /* OBSW_DEBUG_PDEC_HANDLER == 1 */ + return RETURN_OK; +} + +ReturnValue_t PdecHandler::releasePdec() { + ReturnValue_t result = RETURN_OK; + result = gpioComIF->pullHigh(pdecReset); + if (result != RETURN_OK) { + sif::error << "PdecHandler::releasePdec: Failed to release PDEC reset signal" << std::endl; + } + return result; +} + +ReturnValue_t PdecHandler::performOperation(uint8_t operationCode) { + ReturnValue_t result = RETURN_OK; + + readCommandQueue(); + + switch (state) { + case State::INIT: + resetFarStatFlag(); + if (result != RETURN_OK) { + // Requires reconfiguration and reinitialization of PDEC + triggerEvent(INVALID_FAR); + state = State::WAIT_FOR_RECOVERY; + return result; + } + state = State::RUNNING; + break; + case State::RUNNING: + if (newTcReceived()) { + handleNewTc(); + } + checkLocks(); + break; + case State::WAIT_FOR_RECOVERY: + break; + default: + sif::debug << "PdecHandler::performOperation: Invalid state" << std::endl; + break; + } + + return RETURN_OK; +} + +void PdecHandler::readCommandQueue(void) { + CommandMessage commandMessage; + ReturnValue_t result = RETURN_FAILED; + + result = commandQueue->receiveMessage(&commandMessage); + if (result == RETURN_OK) { + result = actionHelper.handleActionMessage(&commandMessage); + if (result == RETURN_OK) { + return; + } + CommandMessage reply; + reply.setReplyRejected(CommandMessage::UNKNOWN_COMMAND, commandMessage.getCommand()); + commandQueue->reply(&reply); + return; + } +} + +bool PdecHandler::newTcReceived() { + uint32_t pdecFar = *(registerBaseAddress + PDEC_FAR_OFFSET); + + if (pdecFar >> STAT_POSITION != NEW_FAR_RECEIVED) { + return false; + } + if (!checkFrameAna(pdecFar)) { + return false; + } + return true; +} + +void PdecHandler::checkLocks() { + uint32_t clcw = getClcw(); + if (!(clcw & NO_RF_MASK) && (lastClcw & NO_RF_MASK)) { + // Rf available changed from 0 to 1 + triggerEvent(CARRIER_LOCK); + } + if (!(clcw & NO_BITLOCK_MASK) && (lastClcw & NO_BITLOCK_MASK)) { + // Bit lock changed from 0 to 1 + triggerEvent(BIT_LOCK_PDEC); + } + lastClcw = clcw; +} + +bool PdecHandler::checkFrameAna(uint32_t pdecFar) { + bool frameValid = false; + FrameAna_t frameAna = static_cast((pdecFar & FRAME_ANA_MASK) >> FRAME_ANA_POSITION); + switch (frameAna) { + case (FrameAna_t::ABANDONED_CLTU): { + triggerEvent(INVALID_TC_FRAME, ABANDONED_CLTU); + sif::warning << "PdecHandler::checkFrameAna: Abondoned CLTU" << std::endl; + break; + } + case (FrameAna_t::FRAME_DIRTY): { + triggerEvent(INVALID_TC_FRAME, FRAME_DIRTY); + sif::warning << "PdecHandler::checkFrameAna: Frame dirty" << std::endl; + break; + } + case (FrameAna_t::FRAME_ILLEGAL): { + sif::warning << "PdecHandler::checkFrameAna: Frame illegal for one reason" << std::endl; + handleIReason(pdecFar, FRAME_ILLEGAL_ONE_REASON); + break; + } + case (FrameAna_t::FRAME_ILLEGAL_MULTI_REASON): { + sif::warning << "PdecHandler::checkFrameAna: Frame illegal for multiple reasons" << std::endl; + handleIReason(pdecFar, FRAME_ILLEGAL_MULTIPLE_REASONS); + break; + } + case (FrameAna_t::AD_DISCARDED_LOCKOUT): { + triggerEvent(INVALID_TC_FRAME, AD_DISCARDED_LOCKOUT); + sif::warning << "PdecHandler::checkFrameAna: AD frame discarded because of lockout" + << std::endl; + break; + } + case (FrameAna_t::AD_DISCARDED_WAIT): { + triggerEvent(INVALID_TC_FRAME, AD_DISCARDED_LOCKOUT); + sif::warning << "PdecHandler::checkFrameAna: AD frame discarded because of wait" << std::endl; + break; + } + case (FrameAna_t::AD_DISCARDED_NS_VR): { + triggerEvent(INVALID_TC_FRAME, AD_DISCARDED_NS_VS); + sif::warning << "PdecHandler::checkFrameAna: AD frame discarded because N(S) or V(R)" + << std::endl; + break; + } + case (FrameAna_t::FRAME_ACCEPTED): { +#if OBSW_DEBUG_PDEC_HANDLER == 1 + sif::info << "PdecHandler::checkFrameAna: Accepted TC frame" << std::endl; +#endif + frameValid = true; + break; + } + default: { + sif::debug << "PdecHandler::checkFrameAna: Invalid frame analysis report" << std::endl; + break; + } + } + return frameValid; +} + +void PdecHandler::handleIReason(uint32_t pdecFar, ReturnValue_t parameter1) { + IReason_t ireason = static_cast((pdecFar & IREASON_MASK) >> IREASON_POSITION); + switch (ireason) { + case (IReason_t::NO_REPORT): { + triggerEvent(INVALID_TC_FRAME, parameter1, NO_REPORT); + sif::info << "PdecHandler::handleIReason: No illegal report" << std::endl; + break; + } + case (IReason_t::ERROR_VERSION_NUMBER): { + triggerEvent(INVALID_TC_FRAME, parameter1, ERROR_VERSION_NUMBER); + sif::info << "PdecHandler::handleIReason: Error in version number and reserved A and B " + << "fields" << std::endl; + break; + } + case (IReason_t::ILLEGAL_COMBINATION): { + triggerEvent(INVALID_TC_FRAME, parameter1, ILLEGAL_COMBINATION); + sif::info << "PdecHandler::handleIReason: Illegal combination (AC) of bypass and control " + << "command flags" << std::endl; + break; + } + case (IReason_t::INVALID_SC_ID): { + triggerEvent(INVALID_TC_FRAME, parameter1, INVALID_SC_ID); + sif::info << "PdecHandler::handleIReason: Invalid spacecraft identifier " << std::endl; + break; + } + case (IReason_t::INVALID_VC_ID_MSB): { + triggerEvent(INVALID_TC_FRAME, parameter1, INVALID_VC_ID_MSB); + sif::info << "PdecHandler::handleIReason: VC identifier bit 0 to 4 did not match " + << std::endl; + break; + } + case (IReason_t::INVALID_VC_ID_LSB): { + triggerEvent(INVALID_TC_FRAME, parameter1, INVALID_VC_ID_LSB); + sif::info << "PdecHandler::handleIReason: VC identifier bit 5 did not match " << std::endl; + break; + } + case (IReason_t::NS_NOT_ZERO): { + triggerEvent(INVALID_TC_FRAME, parameter1, NS_NOT_ZERO); + sif::info << "PdecHandler::handleIReason: N(S) of BC or BD frame not set to all zeros" + << std::endl; + break; + } + case (IReason_t::INCORRECT_BC_CC): { + triggerEvent(INVALID_TC_FRAME, parameter1, INVALID_BC_CC); + sif::info << "PdecHandler::handleIReason: Invalid BC control command format" << std::endl; + break; + } + default: { + sif::info << "PdecHandler::handleIReason: Invalid reason id" << std::endl; + break; + } + } +} + +void PdecHandler::handleNewTc() { + ReturnValue_t result = RETURN_OK; + + uint32_t tcLength = 0; + result = readTc(tcLength); + if (result != RETURN_OK) { + return; + } +#if OBSW_DEBUG_PDEC_HANDLER == 1 + unsigned int mapId = tcSegment[0] & MAP_ID_MASK; + sif::info << "PdecHandler::handleNewTc: Received TC segment with map ID " << mapId << std::endl; + printTC(tcLength); +#endif /* OBSW_DEBUG_PDEC_HANDLER */ + + store_address_t storeId; + result = tcStore->addData(&storeId, tcSegment + 1, tcLength - 1); + if (result != RETURN_OK) { + sif::warning << "PdecHandler::handleNewTc: Failed to add received space packet to store" + << std::endl; + return; + } + + TmTcMessage message(storeId); + + result = MessageQueueSenderIF::sendMessage(tcDestination->getRequestQueue(), &message); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "PdecHandler::handleNewTc: Failed to send message to TC destination" + << std::endl; + tcStore->deleteData(storeId); + return; + } + + return; +} + +ReturnValue_t PdecHandler::readTc(uint32_t& tcLength) { + uint32_t tcOffset = (*(registerBaseAddress + PDEC_BPTR_OFFSET) - PHYSICAL_RAM_BASE_ADDRESS) / 4; + +#if OBSW_DEBUG_PDEC_HANDLER == 1 + sif::debug << "PdecHandler::readTc: TC offset: 0x" << std::hex << tcOffset << std::endl; +#endif /* OBSW_DEBUG_PDEC_HANDLER */ + + tcLength = *(registerBaseAddress + PDEC_SLEN_OFFSET); + +#if OBSW_DEBUG_PDEC_HANDLER == 1 + sif::debug << "PdecHandler::readTc: TC segment length: " << std::dec << tcLength << std::endl; +#endif /* OBSW_DEBUG_PDEC_HANDLER */ + + if (tcLength > MAX_TC_SEGMENT_SIZE) { + sif::warning << "PdecHandler::handleNewTc: Read invalid TC length from PDEC register" + << std::endl; + return RETURN_FAILED; + } + + uint32_t idx = 0; + uint32_t tcData = 0; + for (idx = 0; idx <= tcLength; idx = idx + 4) { + tcData = *(ramBaseAddress + tcOffset + idx / 4); + if (idx == 0) { + tcSegment[idx] = static_cast((tcData >> 16) & 0xFF); + tcSegment[idx + 1] = static_cast((tcData >> 8) & 0xFF); + tcSegment[idx + 2] = static_cast(tcData & 0xFF); + } else if (tcLength - idx + 1 == 3) { + tcSegment[idx - 1] = static_cast((tcData >> 24) & 0xFF); + tcSegment[idx] = static_cast((tcData >> 16) & 0xFF); + tcSegment[idx + 1] = static_cast((tcData >> 8) & 0xFF); + } else if (tcLength - idx + 1 == 2) { + tcSegment[idx - 1] = static_cast((tcData >> 24) & 0xFF); + tcSegment[idx] = static_cast((tcData >> 16) & 0xFF); + } else if (tcLength - idx + 1 == 1) { + tcSegment[idx - 1] = static_cast((tcData >> 24) & 0xFF); + } else { + tcSegment[idx - 1] = static_cast((tcData >> 24) & 0xFF); + tcSegment[idx] = static_cast((tcData >> 16) & 0xFF); + tcSegment[idx + 1] = static_cast((tcData >> 8) & 0xFF); + tcSegment[idx + 2] = static_cast(tcData & 0xFF); + } + } + + // Backend buffer is handled back to PDEC3 + *(registerBaseAddress + PDEC_BFREE_OFFSET) = 0; + + return RETURN_OK; +} + +void PdecHandler::printTC(uint32_t tcLength) { + std::stringstream tcSegmentStream; + tcSegmentStream << "TC segment data: 0x"; + for (uint32_t idx = 0; idx < tcLength; idx++) { + tcSegmentStream << std::setfill('0') << std::setw(2) << std::hex + << static_cast(tcSegment[idx]); + } + sif::info << tcSegmentStream.str() << std::endl; +} + +uint8_t PdecHandler::calcMapAddrEntry(uint8_t moduleId) { + uint8_t lutEntry = 0; + uint8_t parity = getOddParity(moduleId | (1 << VALID_POSITION)); + lutEntry = (parity << PARITY_POSITION) | (1 << VALID_POSITION) | moduleId; + return lutEntry; +} + +uint8_t PdecHandler::getOddParity(uint8_t number) { + uint8_t parityBit = 0; + uint8_t countBits = 0; + for (unsigned int idx = 0; idx < sizeof(number) * 8; idx++) { + countBits += (number >> idx) & 0x1; + } + parityBit = ~(countBits & 0x1) & 0x1; + return parityBit; +} + +uint32_t PdecHandler::getClcw() { return *(registerBaseAddress + PDEC_CLCW_OFFSET); } + +uint32_t PdecHandler::getPdecMon() { return *(registerBaseAddress + PDEC_MON_OFFSET); } + +void PdecHandler::printClcw() { + uint32_t clcw = getClcw(); + uint8_t type = static_cast((clcw >> 31) & 0x1); + uint8_t versionNo = static_cast((clcw >> 29) & 0x3); + uint8_t status = static_cast((clcw >> 26) & 0x7); + uint8_t cop = static_cast((clcw >> 24) & 0x3); + uint8_t vcId = static_cast((clcw >> 18) & 0x3F); + uint8_t noRf = static_cast((clcw >> 15) & 0x1); + uint8_t noBitLock = static_cast((clcw >> 14) & 0x1); + uint8_t lockoutFlag = static_cast((clcw >> 13) & 0x1); + uint8_t waitFlag = static_cast((clcw >> 12) & 0x1); + uint8_t retransmitFlag = static_cast((clcw >> 11) & 0x1); + uint8_t farmBcnt = static_cast((clcw >> 9) & 0x3); + // Expected frame sequence number in te next AD frame + uint8_t repValue = static_cast(clcw & 0xFF); + sif::info << std::setw(30) << std::left << "CLCW type: " << std::hex << "0x" + << static_cast(type) << std::endl; + sif::info << std::setw(30) << std::left << "CLCW version no: " << std::hex << "0x" + << static_cast(versionNo) << std::endl; + sif::info << std::setw(30) << std::left << "CLCW status: " << std::hex << "0x" + << static_cast(status) << std::endl; + sif::info << std::setw(30) << std::left << "CLCW COP: " << std::hex << "0x" + << static_cast(cop) << std::endl; + sif::info << std::setw(30) << std::left << "CLCW virtual channel ID: " << std::hex << "0x" + << static_cast(vcId) << std::endl; + sif::info << std::setw(30) << std::left << "CLCW no RF: " << std::hex << "0x" + << static_cast(noRf) << std::endl; + sif::info << std::setw(30) << std::left << "CLCW no bit lock: " << std::hex << "0x" + << static_cast(noBitLock) << std::endl; + sif::info << std::setw(30) << std::left << "CLCW lockout flag: " << std::hex << "0x" + << static_cast(lockoutFlag) << std::endl; + sif::info << std::setw(30) << std::left << "CLCW wait flag: " << std::hex << "0x" + << static_cast(waitFlag) << std::endl; + sif::info << std::setw(30) << std::left << "CLCW retransmit flag: " << std::hex << "0x" + << static_cast(retransmitFlag) << std::endl; + sif::info << std::setw(30) << std::left << "CLCW FARM B count: " << std::hex << "0x" + << static_cast(farmBcnt) << std::endl; + sif::info << std::setw(30) << std::left << "CLCW rep value: " << std::hex << "0x" + << static_cast(repValue) << std::endl; +} + +void PdecHandler::printPdecMon() { + uint32_t pdecMon = getPdecMon(); + uint32_t tc0ChannelStatus = (pdecMon & TC0_STATUS_MASK) >> TC0_STATUS_POS; + uint32_t tc1ChannelStatus = (pdecMon & TC1_STATUS_MASK) >> TC1_STATUS_POS; + uint32_t tc2ChannelStatus = (pdecMon & TC2_STATUS_MASK) >> TC2_STATUS_POS; + uint32_t tc3ChannelStatus = (pdecMon & TC3_STATUS_MASK) >> TC3_STATUS_POS; + uint32_t tc4ChannelStatus = (pdecMon & TC4_STATUS_MASK) >> TC4_STATUS_POS; + uint32_t tc5ChannelStatus = (pdecMon & TC5_STATUS_MASK) >> TC5_STATUS_POS; + uint32_t lock = (pdecMon & LOCK_MASK) >> LOCK_POS; + sif::info << std::setw(30) << std::left << "TC0 status: " << getMonStatusString(tc0ChannelStatus) + << std::endl; + sif::info << std::setw(30) << std::left << "TC1 status: " << getMonStatusString(tc1ChannelStatus) + << std::endl; + sif::info << std::setw(30) << std::left << "TC2 status: " << getMonStatusString(tc2ChannelStatus) + << std::endl; + sif::info << std::setw(30) << std::left << "TC3 status: " << getMonStatusString(tc3ChannelStatus) + << std::endl; + sif::info << std::setw(30) << std::left << "TC4 status: " << getMonStatusString(tc4ChannelStatus) + << std::endl; + sif::info << std::setw(30) << std::left << "TC5 status: " << getMonStatusString(tc5ChannelStatus) + << std::endl; + sif::info << std::setw(30) << std::left << "Start sequence lock: " << lock << std::endl; +} + +std::string PdecHandler::getMonStatusString(uint32_t status) { + switch (status) { + case TC_CHANNEL_INACTIVE: + return std::string("inactive"); + case TC_CHANNEL_ACTIVE: + return std::string("active"); + case TC_CHANNEL_TIMEDOUT: + return std::string("timed out"); + default: + sif::warning << "PdecHandler::getMonStatusString: Invalid status" << std::endl; + return std::string(); + break; + } +} + +ReturnValue_t PdecHandler::executeAction(ActionId_t actionId, MessageQueueId_t commandedBy, + const uint8_t* data, size_t size) { + switch (actionId) { + case PRINT_CLCW: + printClcw(); + return EXECUTION_FINISHED; + case PRINT_PDEC_MON: + printPdecMon(); + return EXECUTION_FINISHED; + default: + return COMMAND_NOT_IMPLEMENTED; + } +} diff --git a/linux/obc/PdecHandler.h b/linux/obc/PdecHandler.h new file mode 100644 index 00000000..16a9abd4 --- /dev/null +++ b/linux/obc/PdecHandler.h @@ -0,0 +1,396 @@ +#ifndef LINUX_OBC_PDECHANDLER_H_ +#define LINUX_OBC_PDECHANDLER_H_ + +#include "OBSWConfig.h" +#include "PdecConfig.h" +#include "fsfw/action/ActionHelper.h" +#include "fsfw/action/HasActionsIF.h" +#include "fsfw/objectmanager/SystemObject.h" +#include "fsfw/returnvalues/HasReturnvaluesIF.h" +#include "fsfw/storagemanager/StorageManagerIF.h" +#include "fsfw/tasks/ExecutableObjectIF.h" +#include "fsfw/tmtcservices/AcceptsTelecommandsIF.h" +#include "fsfw_hal/common/gpio/gpioDefinitions.h" +#include "fsfw_hal/linux/gpio/LinuxLibgpioIF.h" + +/** + * @brief This class controls the PDEC IP Core implemented in the programmable logic of the + * Zynq-7020. All registers and memories of the PDEC IP Core are accessed via UIO + * drivers. + * + * @details The PDEC IP Core is responsible for processing data received in form of CLTUs from the + * S-Band transceiver. This comprises the BCH decoding of the CLTUs and reconstruction of + * telecommand transfer frames. Finally the PDEC stores the TC segment transported with + * the TC transfer frame in a register. As soon as a new TC has been received a new + * frame acceptance report (FAR) will be generated. If the FAR confirms the validity of + * a received TC segment, the data can be read out from the associated register. + * Currently, the ground software only supports transmissions of CLTUs containing one + * space packet. + * Link to datasheet of PDEC IP Core: https://eive-cloud.irs.uni-stuttgart.de/index.php/ + * apps/files/?dir=/EIVE_IRS/Arbeitsdaten/08_Used%20Components/CCSDS_IP_Cores&fileid=1108967 + * + * @author J. Meier + */ +class PdecHandler : public SystemObject, + public ExecutableObjectIF, + public HasReturnvaluesIF, + public HasActionsIF { + public: + /** + * @brief Constructor + * @param objectId Object ID of PDEC handler system object + * @param tcDestinationId Object ID of object responsible for processing TCs. + * @param gpioComIF Pointer to GPIO interace responsible for driving GPIOs. + * @param pdecReset GPIO ID of GPIO connected to the reset signal of the PDEC. + * @param uioConfigMemory String of uio device file same mapped to the PDEC memory space + * @param uioregsiters String of uio device file same mapped to the PDEC register space + */ + PdecHandler(object_id_t objectId, object_id_t tcDestinationId, LinuxLibgpioIF* gpioComIF, + gpioId_t pdecReset, std::string uioConfigMemory, std::string uioRamMemory, + std::string uioRegisters); + + virtual ~PdecHandler(); + + ReturnValue_t performOperation(uint8_t operationCode = 0); + + ReturnValue_t initialize() override; + + MessageQueueId_t getCommandQueue() const; + + ReturnValue_t executeAction(ActionId_t actionId, MessageQueueId_t commandedBy, + const uint8_t* data, size_t size) override; + + static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PDEC_HANDLER; + + //! [EXPORT] : [COMMENT] Frame acceptance report signals an invalid frame + //! P1: The frame analysis information (FrameAna field of PDEC_FAR register) + //! P2: When frame declared illegal this parameter this parameter gives information about the + //! reason (IReason field of the PDEC_FAR register) + static const Event INVALID_TC_FRAME = MAKE_EVENT(1, severity::HIGH); + //! [EXPORT] : [COMMENT] Read invalid FAR from PDEC after startup + static const Event INVALID_FAR = MAKE_EVENT(2, severity::HIGH); + //! [EXPORT] : [COMMENT] Carrier lock detected + 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); + + private: + static const uint8_t INTERFACE_ID = CLASS_ID::PDEC_HANDLER; + + static const ReturnValue_t ABANDONED_CLTU = MAKE_RETURN_CODE(0xA0); + static const ReturnValue_t FRAME_DIRTY = MAKE_RETURN_CODE(0xA1); + static const ReturnValue_t FRAME_ILLEGAL_ONE_REASON = MAKE_RETURN_CODE(0xA2); + static const ReturnValue_t FRAME_ILLEGAL_MULTIPLE_REASONS = MAKE_RETURN_CODE(0xA2); + static const ReturnValue_t AD_DISCARDED_LOCKOUT = MAKE_RETURN_CODE(0xA3); + static const ReturnValue_t AD_DISCARDED_WAIT = MAKE_RETURN_CODE(0xA4); + static const ReturnValue_t AD_DISCARDED_NS_VS = MAKE_RETURN_CODE(0xA5); + + //! [EXPORT] : [COMMENT] Received action message with unknown action id + static const ReturnValue_t COMMAND_NOT_IMPLEMENTED = MAKE_RETURN_CODE(0xB0); + + static const ReturnValue_t NO_REPORT = MAKE_RETURN_CODE(0xA6); + //! Error in version number and reserved A and B fields + static const ReturnValue_t ERROR_VERSION_NUMBER = MAKE_RETURN_CODE(0xA7); + //! Illegal combination of bypass and control command flag + static const ReturnValue_t ILLEGAL_COMBINATION = MAKE_RETURN_CODE(0xA8); + //! Spacecraft identifier did not match + static const ReturnValue_t INVALID_SC_ID = MAKE_RETURN_CODE(0xA9); + //! VC identifier bits 0 to 4 did not match + static const ReturnValue_t INVALID_VC_ID_MSB = MAKE_RETURN_CODE(0xAA); + //! VC identifier bit 5 did not match + static const ReturnValue_t INVALID_VC_ID_LSB = MAKE_RETURN_CODE(0xAB); + //! N(S) of BC or BD frame not set to all zeros + static const ReturnValue_t NS_NOT_ZERO = MAKE_RETURN_CODE(0xAC); + //! Invalid BC control command + static const ReturnValue_t INVALID_BC_CC = MAKE_RETURN_CODE(0xAE); + + static const uint32_t QUEUE_SIZE = common::CCSDS_HANDLER_QUEUE_SIZE; + + // Action IDs + static const ActionId_t PRINT_CLCW = 0; + // Print PDEC monitor register + static const ActionId_t PRINT_PDEC_MON = 1; + + static const uint8_t STAT_POSITION = 31; + static const uint8_t FRAME_ANA_POSITION = 28; + static const uint8_t IREASON_POSITION = 25; + + static const uint8_t NEW_FAR_RECEIVED = 0; + + static const uint32_t FRAME_ANA_MASK = 0x70000000; + static const uint32_t IREASON_MASK = 0x0E000000; + + static const uint32_t TC_CHANNEL_INACTIVE = 0x0; + static const uint32_t TC_CHANNEL_ACTIVE = 0x1; + static const uint32_t TC_CHANNEL_TIMEDOUT = 0x2; + + static const uint32_t TC0_STATUS_MASK = 0x3; + static const uint32_t TC1_STATUS_MASK = 0xC; + static const uint32_t TC2_STATUS_MASK = 0x300; + static const uint32_t TC3_STATUS_MASK = 0xC00; + static const uint32_t TC4_STATUS_MASK = 0x30000; + static const uint32_t TC5_STATUS_MASK = 0xc00000; + // Lock register set to 1 when start sequence has been found (CLTU is beeing processed) + static const uint32_t LOCK_MASK = 0xc00000; + + static const uint32_t TC0_STATUS_POS = 0; + static const uint32_t TC1_STATUS_POS = 2; + static const uint32_t TC2_STATUS_POS = 4; + static const uint32_t TC3_STATUS_POS = 6; + static const uint32_t TC4_STATUS_POS = 8; + static const uint32_t TC5_STATUS_POS = 10; + // Lock register set to 1 when start sequence has been found (CLTU is beeing processed) + static const uint32_t LOCK_POS = 12; + + /** + * UIO is 4 byte aligned. Thus offset is calculated with "true offset" / 4 + * Example: PDEC_FAR = 0x2840 => Offset in virtual address space is 0xA10 + */ + static const uint32_t PDEC_FAR_OFFSET = 0xA10; + static const uint32_t PDEC_CLCW_OFFSET = 0xA12; + static const uint32_t PDEC_BFREE_OFFSET = 0xA24; + static const uint32_t PDEC_BPTR_OFFSET = 0xA25; + static const uint32_t PDEC_SLEN_OFFSET = 0xA26; + static const uint32_t PDEC_MON_OFFSET = 0xA27; + +#if BOARD_TE0720 == 1 + static const int CONFIG_MEMORY_MAP_SIZE = 0x400; + static const int RAM_MAP_SIZE = 0x4000; + static const int REGISTER_MAP_SIZE = 0x10000; +#else + static const int CONFIG_MEMORY_MAP_SIZE = 0x400; + static const int RAM_MAP_SIZE = 0x4000; + static const int REGISTER_MAP_SIZE = 0x4000; +#endif /* BOARD_TE0720 == 1 */ + + // 0x200 / 4 = 0x80 + static const uint32_t FRAME_HEADER_OFFSET = 0x80; + + static const size_t MAX_TC_SEGMENT_SIZE = 1017; + static const uint8_t MAP_ID_MASK = 0x3F; + +#if BOARD_TE0720 == 1 + static const uint32_t PHYSICAL_RAM_BASE_ADDRESS = 0x32000000; +#else + static const uint32_t PHYSICAL_RAM_BASE_ADDRESS = 0x26000000; +#endif + + static const uint32_t MAP_ADDR_LUT_OFFSET = 0xA0; + static const uint32_t MAP_CLK_FREQ_OFFSET = 0x90; + + static const uint8_t MAX_MAP_ADDR = 63; + // Writing this to the map address in the look up table will invalidate a MAP ID. + static const uint8_t NO_DESTINATION = 0; + static const uint8_t VALID_POSITION = 6; + static const uint8_t PARITY_POSITION = 7; + + // Expected value stored in FAR register after reset + static const uint32_t FAR_RESET = 0x7FE0; + + static const uint32_t TC_SEGMENT_LEN = 1017; + + static const uint32_t NO_RF_MASK = 0x8000; + static const uint32_t NO_BITLOCK_MASK = 0x4000; + + /** + * TCs with map addresses (also know as Map IDs) assigned to this channel will be stored in + * the PDEC memory. + */ + static const uint8_t PM_BUFFER = 7; + + // MAP clock frequency. Must be a value between 1 and 13 otherwise the TC segment will be + // discarded + static const uint8_t MAP_CLK_FREQ = 2; + + enum class FrameAna_t : uint8_t { + ABANDONED_CLTU, + FRAME_DIRTY, + FRAME_ILLEGAL, + FRAME_ILLEGAL_MULTI_REASON, + AD_DISCARDED_LOCKOUT, + AD_DISCARDED_WAIT, + AD_DISCARDED_NS_VR, + FRAME_ACCEPTED + }; + + enum class IReason_t : uint8_t { + NO_REPORT, + ERROR_VERSION_NUMBER, + ILLEGAL_COMBINATION, + INVALID_SC_ID, + INVALID_VC_ID_LSB, + INVALID_VC_ID_MSB, + NS_NOT_ZERO, + INCORRECT_BC_CC + }; + + enum class State : uint8_t { INIT, RUNNING, WAIT_FOR_RECOVERY }; + + /** + * @brief Reads and handles messages stored in the commandQueue + */ + void readCommandQueue(void); + + /** + * @brief This functions writes the configuration parameters to the configuration + * section of the PDEC. + */ + void writePdecConfig(); + + /** + * @brief Reading the FAR resets the set stat flag which signals a new TC. Without clearing + * this flag no new TC will be excepted. After start up the flag is set and needs + * to be reset. + * Stat flag 0 - new TC received + * Stat flag 1 - old TC (ready to receive next TC) + */ + ReturnValue_t resetFarStatFlag(); + + /** + * @brief Releases the PDEC from reset state. PDEC will start with loading the written + * configuration parameters. + */ + ReturnValue_t releasePdec(); + + /** + * @brief Reads the FAR register and checks if a new TC has been received. + */ + bool newTcReceived(); + + /** + * @brief Checks if carrier lock or bit lock has been detected and triggers appropriate + * event. + */ + void checkLocks(); + + /** + * @brief Analyzes the FramAna field (frame analysis data) of a FAR report. + * + * @return True if frame valid, otherwise false. + */ + bool checkFrameAna(uint32_t pdecFar); + + /** + * @brief This function handles the IReason field of the frame analysis report. + * + * @details In case frame as been declared illegal for multiple reasons, the reason with the + * lowest value will be shown. + */ + void handleIReason(uint32_t pdecFar, ReturnValue_t parameter1); + + /** + * @brief Handles the reception of new TCs. Reads the pointer to the storage location of the + * new TC segment, extracts the PUS packet and forwards the data to the object + * responsible for processing the TC. + */ + void handleNewTc(); + + /** + * @brief Function reads the last received TC segment from the PDEC memory and copies + * the data to the tcSegement array. + * + * @param tcLength The length of the received TC. + * + */ + ReturnValue_t readTc(uint32_t& tcLength); + + /** + * @brief Prints the tc segment data + */ + void printTC(uint32_t tcLength); + + /** + * @brief This function calculates the entry for the configuration of the MAP ID routing. + * + * @param mapAddr The MAP ID to configure + * @param moduleId The destination module where all TCs with the map id mapAddr will be routed + * to. + * + * @details The PDEC has different modules where the TCs can be routed to. A lookup table is + * used which links the MAP ID field to the destination module. The entry for this + * lookup table is created by this function and must be stored in the configuration + * memory region of the PDEC. The entry has a specific format + */ + uint8_t calcMapAddrEntry(uint8_t moduleId); + + /** + * @brief This functions calculates the odd parity of the bits in number. + * + * @param number The number from which to calculate the odd parity. + */ + uint8_t getOddParity(uint8_t number); + + /** + * brief Returns the 32-bit wide communication link control word (CLCW) + */ + uint32_t getClcw(); + + /** + * @brief Returns the PDEC monitor register content + * + */ + uint32_t getPdecMon(); + + /** + * @brief Reads and prints the CLCW. Can be useful for debugging. + */ + void printClcw(); + + /** + * @brief Prints monitor register information to debug console. + */ + void printPdecMon(); + + std::string getMonStatusString(uint32_t status); + + object_id_t tcDestinationId; + + AcceptsTelecommandsIF* tcDestination = nullptr; + + LinuxLibgpioIF* gpioComIF = nullptr; + + /** + * Reset signal is required to hold PDEC in reset state until the configuration has been + * written to the appropriate memory space. + * Can also be used to reboot PDEC in case of erros. + */ + gpioId_t pdecReset = gpio::NO_GPIO; + + // UIO device file giving access to the PDEC configuration memory section + std::string uioConfigMemory; + + // UIO device file giving access to the PDEC RAM section + std::string uioRamMemory; + + // UIO device file giving access to the PDEC register space + std::string uioRegisters; + + ActionHelper actionHelper; + + StorageManagerIF* tcStore = nullptr; + + MessageQueueIF* commandQueue = nullptr; + + State state = State::INIT; + + /** + * Pointer pointing to base address of the PDEC memory space. + * This address is equivalent with the base address of the section named configuration area in + * the PDEC datasheet. + */ + uint32_t* memoryBaseAddress = nullptr; + + uint32_t* ramBaseAddress = nullptr; + + // Pointer pointing to base address of register space + uint32_t* registerBaseAddress = nullptr; + + uint32_t pdecFar = 0; + + uint8_t tcSegment[TC_SEGMENT_LEN]; + + // Used to check carrier and bit lock changes (default set to no rf and no bitlock) + uint32_t lastClcw = 0xC000; +}; + +#endif /* LINUX_OBC_PDECHANDLER_H_ */ diff --git a/linux/obc/Ptme.cpp b/linux/obc/Ptme.cpp new file mode 100644 index 00000000..68ba3924 --- /dev/null +++ b/linux/obc/Ptme.cpp @@ -0,0 +1,52 @@ +#include +#include +#include +#include + +#include "PtmeConfig.h" +#include "fsfw/serviceinterface/ServiceInterface.h" + +Ptme::Ptme(object_id_t objectId) : SystemObject(objectId) {} + +Ptme::~Ptme() {} + +ReturnValue_t Ptme::initialize() { + VcInterfaceMapIter iter; + for (iter = vcInterfaceMap.begin(); iter != vcInterfaceMap.end(); iter++) { + iter->second->initialize(); + } + return RETURN_OK; +} + +ReturnValue_t Ptme::writeToVc(uint8_t vcId, const uint8_t* data, size_t size) { + ReturnValue_t result = RETURN_OK; + VcInterfaceMapIter vcInterfaceMapIter = vcInterfaceMap.find(vcId); + if (vcInterfaceMapIter == vcInterfaceMap.end()) { + sif::warning << "Ptme::writeToVc: No virtual channel interface found for the virtual " + "channel with id " + << static_cast(vcId) << std::endl; + return UNKNOWN_VC_ID; + } + result = vcInterfaceMapIter->second->write(data, size); + return result; +} + +void Ptme::addVcInterface(VcId_t vcId, VcInterfaceIF* vc) { + if (vcId > common::NUMBER_OF_VIRTUAL_CHANNELS) { + sif::warning << "Ptme::addVcInterface: Invalid virtual channel ID" << std::endl; + return; + } + + if (vc == nullptr) { + sif::warning << "Ptme::addVcInterface: Invalid virtual channel interface" << std::endl; + return; + } + + auto status = vcInterfaceMap.emplace(vcId, vc); + if (status.second == false) { + sif::warning << "Ptme::addVcInterface: Failed to add virtual channel interface to " + "virtual channel map" + << std::endl; + return; + } +} diff --git a/linux/obc/Ptme.h b/linux/obc/Ptme.h new file mode 100644 index 00000000..cdb2d6c6 --- /dev/null +++ b/linux/obc/Ptme.h @@ -0,0 +1,79 @@ +#ifndef LINUX_OBC_PTME_H_ +#define LINUX_OBC_PTME_H_ + +#include +#include + +#include +#include + +#include "OBSWConfig.h" +#include "fsfw/returnvalues/HasReturnvaluesIF.h" +#include "linux/obc/PtmeIF.h" +#include "linux/obc/VcInterfaceIF.h" + +/** + * @brief This class handles the interfacing to the telemetry (PTME) IP core responsible for the + * encoding of telemetry packets according to the CCSDS standards CCSDS 131.0-B-3 (TM + * Synchro- nization and channel coding) and CCSDS 132.0-B-2 (TM Space Data Link Protocoll). The IP + * cores are implemented on the programmable logic and are accessible through the linux UIO driver. + */ +class Ptme : public PtmeIF, public SystemObject, public HasReturnvaluesIF { + public: + using VcId_t = uint8_t; + + /** + * @brief Constructor + * + * @param objectId + */ + Ptme(object_id_t objectId); + virtual ~Ptme(); + + ReturnValue_t initialize() override; + ReturnValue_t writeToVc(uint8_t vcId, const uint8_t* data, size_t size) override; + + /** + * @brief This function adds the reference to a virtual channel interface to the vcInterface + * map. + */ + void addVcInterface(VcId_t vcId, VcInterfaceIF* vc); + + private: + static const uint8_t INTERFACE_ID = CLASS_ID::PTME; + + static const ReturnValue_t UNKNOWN_VC_ID = MAKE_RETURN_CODE(0xA0); + + /** + * Configuration bits: + * bit[1:0]: Size of data (1,2,3 or 4 bytes). 1 Byte <=> b00 + * bit[2]: Set this bit to 1 to abort a transfered packet + * bit[3]: Signals to PTME the start of a new telemetry packet + */ + static const uint32_t PTME_CONFIG_START = 0x8; + + /** + * Writing this word to the ptme base address signals to the PTME that a complete tm packet has + * been transferred. + */ + static const uint32_t PTME_CONFIG_END = 0x0; + + /** + * Writing to this offset within the PTME memory space will insert data for encoding to the + * PTME IP core. + * The address offset is 0x400 (= 4 * 256) + */ + static const int PTME_DATA_REG_OFFSET = 256; + + /** The file descriptor of the UIO driver */ + int fd = 0; + + uint32_t* ptmeBaseAddress = nullptr; + + using VcInterfaceMap = std::unordered_map; + using VcInterfaceMapIter = VcInterfaceMap::iterator; + + VcInterfaceMap vcInterfaceMap; +}; + +#endif /* LINUX_OBC_PTME_H_ */ diff --git a/linux/obc/PtmeConfig.cpp b/linux/obc/PtmeConfig.cpp new file mode 100644 index 00000000..9cbda7a6 --- /dev/null +++ b/linux/obc/PtmeConfig.cpp @@ -0,0 +1,50 @@ +#include "PtmeConfig.h" + +#include "fsfw/serviceinterface/ServiceInterface.h" + +PtmeConfig::PtmeConfig(object_id_t objectId, AxiPtmeConfig* axiPtmeConfig) + : SystemObject(objectId), axiPtmeConfig(axiPtmeConfig) {} + +PtmeConfig::~PtmeConfig() {} + +ReturnValue_t PtmeConfig::initialize() { + if (axiPtmeConfig == nullptr) { + sif::warning << "PtmeConfig::initialize: Invalid AxiPtmeConfig object" << std::endl; + return RETURN_FAILED; + } + return RETURN_OK; +} + +ReturnValue_t PtmeConfig::setRate(uint32_t bitRate) { + if (bitRate == 0) { + return BAD_BIT_RATE; + } + uint32_t rateVal = BIT_CLK_FREQ / bitRate - 1; + if (rateVal > 0xFF) { + return RATE_NOT_SUPPORTED; + } + return axiPtmeConfig->writeCaduRateReg(static_cast(rateVal)); +} + +ReturnValue_t PtmeConfig::invertTxClock(bool invert) { + ReturnValue_t result = RETURN_OK; + if (invert) { + result = axiPtmeConfig->enableTxclockInversion(); + } else { + result = axiPtmeConfig->disableTxclockInversion(); + } + if (result != RETURN_OK) { + return CLK_INVERSION_FAILED; + } + return result; +} + +ReturnValue_t PtmeConfig::configTxManipulator(bool enable) { + ReturnValue_t result = RETURN_OK; + if (enable) { + result = axiPtmeConfig->enableTxclockManipulator(); + } else { + result = axiPtmeConfig->disableTxclockManipulator(); + } + return result; +} diff --git a/linux/obc/PtmeConfig.h b/linux/obc/PtmeConfig.h new file mode 100644 index 00000000..d6e35b57 --- /dev/null +++ b/linux/obc/PtmeConfig.h @@ -0,0 +1,76 @@ +#ifndef LINUX_OBC_PTMECONFIG_H_ +#define LINUX_OBC_PTMECONFIG_H_ + +#include "AxiPtmeConfig.h" +#include "fsfw/objectmanager/SystemObject.h" +#include "fsfw/returnvalues/HasReturnvaluesIF.h" +#include "linux/obc/PtmeConfig.h" + +/** + * @brief Class to configure donwlink specific parameters in the PTME IP core. + * + * @author J. Meier + */ +class PtmeConfig : public SystemObject, public HasReturnvaluesIF { + public: + /** + * @brief Constructor + * + * ptmeAxiConfig Pointer to object providing access to PTME configuration registers. + */ + PtmeConfig(object_id_t opbjectId, AxiPtmeConfig* axiPtmeConfig); + virtual ~PtmeConfig(); + + virtual ReturnValue_t initialize() override; + /** + * @brief Changes the input frequency to the S-Band transceiver and thus the downlink rate + * + * @details This is the bitrate of the CADU clock and not the downlink which has twice the bitrate + * of the CADU clock due to the convolutional code added by the s-Band transceiver. + */ + ReturnValue_t setRate(uint32_t bitRate); + + /** + * @brief Will change the time the tx data signal is updated with respect to the tx clock + * + * @param invert True -> Data signal will be updated on the falling edge (not desired by the + * Syrlinks) + * False -> Data signal updated on rising edge (default configuration and desired + * by the syrlinks) + * + * @return REUTRN_OK if successful, otherwise error return value + */ + ReturnValue_t invertTxClock(bool invert); + + /** + * @brief Controls the tx clock manipulator of the PTME wrapper component + * + * @param enable Manipulator will be enabled (this is also the default configuration) + * @param disable Manipulator will be disabled + * + * @return REUTRN_OK if successful, otherwise error return value + */ + ReturnValue_t configTxManipulator(bool enable); + + private: + static const uint8_t INTERFACE_ID = CLASS_ID::RATE_SETTER; + + //! [EXPORT] : [COMMENT] The commanded rate is not supported by the current FPGA design + static const ReturnValue_t RATE_NOT_SUPPORTED = MAKE_RETURN_CODE(0xA0); + //! [EXPORT] : [COMMENT] Bad bitrate has been commanded (e.g. 0) + static const ReturnValue_t BAD_BIT_RATE = MAKE_RETURN_CODE(0xA1); + //! [EXPORT] : [COMMENT] Failed to invert clock and thus change the time the data is updated with + //! respect to the tx clock + static const ReturnValue_t CLK_INVERSION_FAILED = MAKE_RETURN_CODE(0xA2); + //! [EXPORT] : [COMMENT] Failed to change configuration bit of tx clock manipulator + static const ReturnValue_t TX_MANIPULATOR_CONFIG_FAILED = MAKE_RETURN_CODE(0xA3); + + // Bitrate register field is only 8 bit wide + static const uint32_t MAX_BITRATE = 0xFF; + // Bit clock frequency of PMTE IP core in Hz + static const uint32_t BIT_CLK_FREQ = 20000000; + + AxiPtmeConfig* axiPtmeConfig = nullptr; +}; + +#endif /* LINUX_OBC_PTMECONFIG_H_ */ diff --git a/linux/obc/PtmeIF.h b/linux/obc/PtmeIF.h new file mode 100644 index 00000000..7108df05 --- /dev/null +++ b/linux/obc/PtmeIF.h @@ -0,0 +1,27 @@ +#ifndef LINUX_OBC_PTMEIF_H_ +#define LINUX_OBC_PTMEIF_H_ + +#include "fsfw/returnvalues/HasReturnvaluesIF.h" + +/** + * @brief Interface class for managing the PTME IP Core implemented in the programmable logic. + * + * @details PTME IP Core: https://www.esa.int/Enabling_Support/Space_Engineering_Technology/ + * Microelectronics/PTME + * @author J. Meier + */ +class PtmeIF { + public: + virtual ~PtmeIF(){}; + + /** + * @brief Implements to function to write to a specific virtual channel. + * + * @param vcId Virtual channel to write to + * @param data Pointer to buffer holding the data to write + * @param size Number of bytes to write + */ + virtual ReturnValue_t writeToVc(uint8_t vcId, const uint8_t* data, size_t size) = 0; +}; + +#endif /* LINUX_OBC_PTMEIF_H_ */ diff --git a/linux/obc/VcInterfaceIF.h b/linux/obc/VcInterfaceIF.h new file mode 100644 index 00000000..45226e21 --- /dev/null +++ b/linux/obc/VcInterfaceIF.h @@ -0,0 +1,30 @@ +#ifndef LINUX_OBC_VCINTERFACEIF_H_ +#define LINUX_OBC_VCINTERFACEIF_H_ + +#include + +#include "fsfw/returnvalues/HasReturnvaluesIF.h" + +/** + * @brief Interface class for managing different virtual channels of the PTME IP core implemented + * in the programmable logic. + * + * @author J. Meier + */ +class VcInterfaceIF { + public: + virtual ~VcInterfaceIF(){}; + + /** + * @brief Implememts the functionality to write data in the virtual channel of the PTME IP + * Core. + * + * @param data Pointer to buffer holding the data to write + * @param size Number of bytes to write + */ + virtual ReturnValue_t write(const uint8_t* data, size_t size) = 0; + + virtual ReturnValue_t initialize() = 0; +}; + +#endif /* LINUX_OBC_VCINTERFACEIF_H_ */ diff --git a/linux/utility/CMakeLists.txt b/linux/utility/CMakeLists.txt index a3387531..56937cea 100644 --- a/linux/utility/CMakeLists.txt +++ b/linux/utility/CMakeLists.txt @@ -1,4 +1,4 @@ -target_sources(${TARGET_NAME} PUBLIC +target_sources(${OBSW_NAME} PUBLIC utility.cpp ) diff --git a/linux/utility/utility.cpp b/linux/utility/utility.cpp index 1d6ec5c0..cd0d47ef 100644 --- a/linux/utility/utility.cpp +++ b/linux/utility/utility.cpp @@ -1,13 +1,14 @@ -#include "OBSWConfig.h" -#include "FSFWConfig.h" #include "utility.h" -#include "fsfw/serviceinterface/ServiceInterface.h" #include +#include "FSFWConfig.h" +#include "OBSWConfig.h" +#include "fsfw/serviceinterface/ServiceInterface.h" + void utility::handleSystemError(int retcode, std::string function) { #if OBSW_VERBOSE_LEVEL >= 1 - sif::warning << function << ": System call failed with code " << retcode << ": " << - strerror(retcode) << std::endl; + sif::warning << function << ": System call failed with code " << retcode << ": " + << strerror(retcode) << std::endl; #endif } diff --git a/linux/utility/utility.h b/linux/utility/utility.h index 3eb17a9b..8f7df04f 100644 --- a/linux/utility/utility.h +++ b/linux/utility/utility.h @@ -1,9 +1,10 @@ #ifndef LINUX_UTILITY_UTILITY_H_ #define LINUX_UTILITY_UTILITY_H_ -#include "fsfw/returnvalues/HasReturnvaluesIF.h" #include +#include "fsfw/returnvalues/HasReturnvaluesIF.h" + namespace utility { void handleSystemError(int retcode, std::string function); diff --git a/misc/eclipse/.cproject b/misc/eclipse/.cproject index fe0208b8..15b0195b 100644 --- a/misc/eclipse/.cproject +++ b/misc/eclipse/.cproject @@ -23,6 +23,8 @@ @@ -31,6 +33,8 @@ @@ -38,6 +42,8 @@ @@ -79,6 +85,8 @@ @@ -87,6 +95,8 @@ @@ -94,6 +104,8 @@ @@ -137,6 +149,8 @@