diff --git a/CHANGELOG.md b/CHANGELOG.md new file mode 100644 index 00000000..17d29e7b --- /dev/null +++ b/CHANGELOG.md @@ -0,0 +1,26 @@ +Change Log +======= + +All notable changes to this project will be documented in this file. + +The format is based on [Keep a Changelog](http://keepachangelog.com/) +and this project adheres to [Semantic Versioning](http://semver.org/). + +The [milestone](https://egit.irs.uni-stuttgart.de/eive/eive-obsw/milestones) +list yields a list of all related PRs for each release. + +# [unreleased] + +# [v1.11.0] + +## Changed + +- Update rootfs base of Linux, all related OBSW changes +- Use gpsd version 3.17 now. Includes API changes +- Add `/usr/local/bin` to PATH. All shell scripts are there now +- Rename GPS device to `/dev/gps0` + +# [v1.10.0] + +For all releases equal or prior to v1.10.0, +see [milestones](https://egit.irs.uni-stuttgart.de/eive/eive-obsw/milestones) diff --git a/CMakeLists.txt b/CMakeLists.txt index 03d51ac2..585284ac 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -20,6 +20,9 @@ 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) +set(OBSW_ADD_STAR_TRACKER 0) +set(OBSW_DEBUG_STARTRACKER 0) + if(NOT FSFW_OSAL) set(FSFW_OSAL linux CACHE STRING "OS for the FSFW.") endif() @@ -37,8 +40,12 @@ endif() include(${CMAKE_SCRIPT_PATH}/PreProjectConfig.cmake) pre_project_config() +# Check whether the user has already installed Catch2 first. This has to come before +# the project call. We could also exlcude doing this when the Q7S primary OBSW is built.. +find_package(Catch2 3 CONFIG QUIET) + # Project Name -project(eive-obsw ASM C CXX) +project(eive-obsw) ################################################################################ # Pre-Sources preparation @@ -67,7 +74,7 @@ set(LIB_JSON_NAME nlohmann_json::nlohmann_json) # Set path names set(FSFW_PATH fsfw) -set(TEST_PATH test/testtasks) +set(TEST_PATH test) set(UNITTEST_PATH unittest) set(LINUX_PATH linux) set(COMMON_PATH common) @@ -93,7 +100,8 @@ 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/egse" + OR TGT_BSP MATCHES "arm/beagleboneblack" OR TGT_BSP MATCHES "arm/egse" + OR TGT_BSP MATCHES "arm/te0720-1cfa" ) set(FSFW_CONFIG_PATH "linux/fsfwconfig") if(NOT BUILD_Q7S_SIMPLE_MODE) @@ -113,6 +121,8 @@ if(TGT_BSP) # Used by configure file set(EGSE ON) set(FSFW_HAL_LINUX_ADD_LIBGPIOD OFF) + set(OBSW_ADD_STAR_TRACKER 1) + set(OBSW_DEBUG_STARTRACKER 1) endif() if(TGT_BSP MATCHES "arm/beagleboneblack") @@ -124,6 +134,10 @@ if(TGT_BSP) # Used by configure file set(XIPHOS_Q7S ON) endif() + + if(TGT_BSP MATCHES "arm/te0720-1cfa") + set(TE0720_1CFA ON) + endif() else() # Required by FSFW library set(FSFW_CONFIG_PATH "${BSP_PATH}/fsfwconfig") @@ -150,9 +164,6 @@ 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 ################################################################################ @@ -199,8 +210,10 @@ elseif(CMAKE_CXX_COMPILER_ID STREQUAL "MSVC") set(COMPILER_FLAGS "/permissive-") endif() +if (NOT(TGT_BSP MATCHES "arm/te0720-1cfa") AND NOT(TGT_BSP MATCHES "arm/q7s")) # Not installed, so use FetchContent to download and provide Catch2 if(NOT Catch2_FOUND) + message(STATUS "Did not find a valid Catch2 installation. Using FetchContent to install it") include(FetchContent) FetchContent_Declare( @@ -215,7 +228,7 @@ if(NOT Catch2_FOUND) set_target_properties(Catch2 PROPERTIES EXCLUDE_FROM_ALL "true") set_target_properties(Catch2WithMain PROPERTIES EXCLUDE_FROM_ALL "true") endif() - +endif() add_library(${LIB_EIVE_MISSION}) diff --git a/README.md b/README.md index 0effabb8..4d897980 100644 --- a/README.md +++ b/README.md @@ -385,20 +385,7 @@ more recent disitributions anymore. ## Installing toolchain without Vivado You can download the toolchains for Windows and Linux -[from the EIVE cloud](https://eive-cloud.irs.uni-stuttgart.de/index.php/apps/files?dir=/EIVE_IRS/Software/tools&fileid=831898). - -If `wget` is available (e.g. MinGW64), you can use the following command to download the -toolchain for Windows - -```sh -wget https://eive-cloud.irs.uni-stuttgart.de/index.php/s/rfoaistRd67yBbH/download/gcc-arm-linux-gnueabi-win.zip -``` - -or the following command for Linux (could be useful for CI/CD) - -```sh -wget https://eive-cloud.irs.uni-stuttgart.de/index.php/s/MRaeA2XnMXpZ5Pp/download/gcc-arm-8.3-2019.03-x86_64-arm-linux-gnueabihf.tar.xz -``` +[from the EIVE cloud](https://eive-cloud.irs.uni-stuttgart.de/index.php/apps/files/?dir=/EIVE_IRS/Software/tools). ## Installing CMake and MSYS2 on Windows diff --git a/archive/gpio/gpioDefinitions.h b/archive/gpio/gpioDefinitions.h index 0db4db11..46050d12 100644 --- a/archive/gpio/gpioDefinitions.h +++ b/archive/gpio/gpioDefinitions.h @@ -8,13 +8,13 @@ using gpioId_t = uint16_t; namespace gpio { -enum Levels { LOW = 0, HIGH = 1 }; +enum class Levels : uint8_t { LOW = 0, HIGH = 1 }; -enum Direction { IN = 0, OUT = 1 }; +enum class Direction : uint8_t { IN = 0, OUT = 1 }; -enum GpioOperation { READ, WRITE }; +enum class GpioOperation { READ, WRITE }; -enum GpioTypes { NONE, GPIOD_REGULAR, CALLBACK }; +enum class GpioTypes { NONE, GPIOD_REGULAR, CALLBACK }; static constexpr gpioId_t NO_GPIO = -1; } // namespace gpio diff --git a/automation/Dockerfile b/automation/Dockerfile index 9042cf13..63592c77 100644 --- a/automation/Dockerfile +++ b/automation/Dockerfile @@ -16,5 +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" \ No newline at end of file +ENV ZYNQ_7020_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" diff --git a/automation/Jenkinsfile b/automation/Jenkinsfile index fe79dc73..ee50924a 100644 --- a/automation/Jenkinsfile +++ b/automation/Jenkinsfile @@ -5,7 +5,7 @@ pipeline { } agent { docker { - image 'eive-obsw-ci:d2' + image 'eive-obsw-ci:d3' args '--sysctl fs.mqueue.msg_max=100' } } diff --git a/bsp_egse/ObjectFactory.cpp b/bsp_egse/ObjectFactory.cpp index 10eea471..8d5e3416 100644 --- a/bsp_egse/ObjectFactory.cpp +++ b/bsp_egse/ObjectFactory.cpp @@ -3,7 +3,6 @@ #include #include #include -#include #include "OBSWConfig.h" #include "busConf.h" diff --git a/bsp_egse/main.cpp b/bsp_egse/main.cpp index ce7966ff..75fb4f19 100644 --- a/bsp_egse/main.cpp +++ b/bsp_egse/main.cpp @@ -3,8 +3,8 @@ #include "InitMission.h" #include "OBSWConfig.h" #include "OBSWVersion.h" -#include "fsfw/FSFWVersion.h" #include "fsfw/tasks/TaskFactory.h" +#include "fsfw/version.h" /** * @brief This is the main program entry point for the egse (raspberry pi 4) diff --git a/bsp_hosted/fsfwconfig/devices/powerSwitcherList.h b/bsp_hosted/fsfwconfig/devices/powerSwitcherList.h deleted file mode 100644 index ae259374..00000000 --- a/bsp_hosted/fsfwconfig/devices/powerSwitcherList.h +++ /dev/null @@ -1,57 +0,0 @@ -#ifndef FSFWCONFIG_DEVICES_POWERSWITCHERLIST_H_ -#define FSFWCONFIG_DEVICES_POWERSWITCHERLIST_H_ - -#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 -}; - -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; -} // namespace pcduSwitches - -#endif /* FSFWCONFIG_DEVICES_POWERSWITCHERLIST_H_ */ diff --git a/bsp_linux_board/CMakeLists.txt b/bsp_linux_board/CMakeLists.txt index 0272f476..9884b983 100644 --- a/bsp_linux_board/CMakeLists.txt +++ b/bsp_linux_board/CMakeLists.txt @@ -1,6 +1,7 @@ target_sources(${OBSW_NAME} PUBLIC InitMission.cpp main.cpp + gpioInit.cpp ObjectFactory.cpp ) diff --git a/bsp_linux_board/InitMission.cpp b/bsp_linux_board/InitMission.cpp index 6dfe3af1..0fa7a4f6 100644 --- a/bsp_linux_board/InitMission.cpp +++ b/bsp_linux_board/InitMission.cpp @@ -192,7 +192,7 @@ void initmission::createPstTasks(TaskFactory& factory, 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); + "SPI_PST", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 1.0, missedDeadlineFunc); result = pst::pstSpi(spiPst); if (result != HasReturnvaluesIF::RETURN_OK) { sif::error << "InitMission::initTasks: Creating PST failed!" << std::endl; diff --git a/bsp_linux_board/ObjectFactory.cpp b/bsp_linux_board/ObjectFactory.cpp index 18da8896..b1ae6005 100644 --- a/bsp_linux_board/ObjectFactory.cpp +++ b/bsp_linux_board/ObjectFactory.cpp @@ -5,10 +5,13 @@ #include "devices/addresses.h" #include "devices/gpioIds.h" #include "fsfw/datapoollocal/LocalDataPoolManager.h" +#include "fsfw/power/DummyPowerSwitcher.h" #include "fsfw/tasks/TaskFactory.h" #include "fsfw/tmtcpacket/pus/tm.h" #include "fsfw/tmtcservices/CommandingServiceBase.h" #include "fsfw/tmtcservices/PusServiceBase.h" +#include "gpioInit.h" +#include "linux/ObjectFactory.h" #include "linux/boardtest/LibgpiodTest.h" #include "linux/boardtest/SpiTestClass.h" #include "linux/boardtest/UartTestClass.h" @@ -64,37 +67,55 @@ void ObjectFactory::produce(void* args) { GpioCookie* gpioCookie = nullptr; static_cast(gpioCookie); - new SpiComIF(objects::SPI_COM_IF, gpioIF); + SpiComIF* spiComIF = new SpiComIF(objects::SPI_COM_IF, gpioIF); + static_cast(spiComIF); + auto pwrSwitcher = new DummyPowerSwitcher(objects::PCDU_HANDLER, 18, 0); + static_cast(pwrSwitcher); - std::string spiDev; - SpiCookie* spiCookie = nullptr; - static_cast(spiCookie); +#if OBSW_ADD_ACS_BOARD == 1 && defined(RASPBERRY_PI) + createRpiAcsBoard(gpioIF, spiDev); +#endif -#if OBSW_ADD_ACS_BOARD == 1 - if (gpioCookie == nullptr) { - gpioCookie = new GpioCookie(); - } +#if OBSW_ADD_SUN_SENSORS == 1 || defined(OBSW_ADD_RTD_DEVICES) +#ifdef RASPBERRY_PI + rpi::gpio::initSpiCsDecoder(gpioIF); +#endif +#endif + +#if OBSW_ADD_SUN_SENSORS == 1 + createSunSensorComponents(gpioIF, spiComIF, pwrSwitcher, spi::DEV); +#endif + +#if OBSW_ADD_RTD_DEVICES == 1 + createRtdComponents(spi::DEV, gpioIF, pwrSwitcher); +#endif + +#if OBSW_ADD_TEST_CODE == 1 + createTestTasks(); +#endif /* OBSW_ADD_TEST_CODE == 1 */ +} + +void ObjectFactory::createRpiAcsBoard(GpioIF* gpioIF, std::string spiDev) { + GpioCookie* 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::Direction::OUT, gpio::Levels::HIGH); gpio::createRpiGpioConfig(gpioCookie, gpioIds::MGM_1_RM3100_CS, gpio::MGM_1_BCM_PIN, - "MGM_1_RM3100", gpio::Direction::OUT, 1); + "MGM_1_RM3100", gpio::Direction::OUT, gpio::Levels::HIGH); gpio::createRpiGpioConfig(gpioCookie, gpioIds::MGM_2_LIS3_CS, gpio::MGM_2_BCM_PIN, "MGM_2_LIS3", - gpio::Direction::OUT, 1); + gpio::Direction::OUT, gpio::Levels::HIGH); gpio::createRpiGpioConfig(gpioCookie, gpioIds::MGM_3_RM3100_CS, gpio::MGM_3_BCM_PIN, - "MGM_3_RM3100", gpio::Direction::OUT, 1); + "MGM_3_RM3100", gpio::Direction::OUT, gpio::Levels::HIGH); gpio::createRpiGpioConfig(gpioCookie, gpioIds::GYRO_0_ADIS_CS, gpio::GYRO_0_BCM_PIN, - "GYRO_0_ADIS", gpio::Direction::OUT, 1); + "GYRO_0_ADIS", gpio::Direction::OUT, gpio::Levels::HIGH); gpio::createRpiGpioConfig(gpioCookie, gpioIds::GYRO_1_L3G_CS, gpio::GYRO_1_BCM_PIN, "GYRO_1_L3G", - gpio::Direction::OUT, 1); + gpio::Direction::OUT, gpio::Levels::HIGH); gpio::createRpiGpioConfig(gpioCookie, gpioIds::GYRO_2_ADIS_CS, gpio::GYRO_2_BCM_PIN, - "GYRO_2_ADIS", gpio::Direction::OUT, 1); + "GYRO_2_ADIS", gpio::Direction::OUT, gpio::Levels::HIGH); gpio::createRpiGpioConfig(gpioCookie, gpioIds::GYRO_3_L3G_CS, gpio::GYRO_3_BCM_PIN, "GYRO_3_L3G", - gpio::Direction::OUT, 1); + gpio::Direction::OUT, gpio::Levels::HIGH); gpioIF->addGpios(gpioCookie); - - spiDev = "/dev/spidev0.1"; - spiCookie = + 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 = @@ -136,9 +157,9 @@ void ObjectFactory::produce(void* args) { 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); + ADIS1650X::MAXIMUM_REPLY_SIZE, spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED); + auto adisHandler = new GyroADIS1650XHandler(objects::GYRO_0_ADIS_HANDLER, objects::SPI_COM_IF, + spiCookie, ADIS1650X::Type::ADIS16505); adisHandler->setStartUpImmediately(); spiCookie = new SpiCookie(addresses::GYRO_1_L3G, gpioIds::GYRO_1_L3G_CS, spiDev, L3GD20H::MAX_BUFFER_SIZE, @@ -152,9 +173,9 @@ void ObjectFactory::produce(void* args) { 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); + ADIS1650X::MAXIMUM_REPLY_SIZE, spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED); + adisHandler = new GyroADIS1650XHandler(objects::GYRO_2_ADIS_HANDLER, objects::SPI_COM_IF, + spiCookie, ADIS1650X::Type::ADIS16505); adisHandler->setStartUpImmediately(); spiCookie = @@ -166,12 +187,6 @@ void ObjectFactory::produce(void* args) { #if FSFW_HAL_L3GD20_GYRO_DEBUG == 1 gyroL3gHandler->setToGoToNormalMode(true); #endif - -#endif /* RPI_TEST_ACS_BOARD == 1 */ - -#if OBSW_ADD_TEST_CODE == 1 - createTestTasks(); -#endif /* OBSW_ADD_TEST_CODE == 1 */ } void ObjectFactory::createTestTasks() { diff --git a/bsp_linux_board/ObjectFactory.h b/bsp_linux_board/ObjectFactory.h index 909baf06..7365fb8f 100644 --- a/bsp_linux_board/ObjectFactory.h +++ b/bsp_linux_board/ObjectFactory.h @@ -1,10 +1,15 @@ #ifndef BSP_LINUX_OBJECTFACTORY_H_ #define BSP_LINUX_OBJECTFACTORY_H_ +#include + +class GpioIF; + namespace ObjectFactory { void setStatics(); void produce(void* args); +void createRpiAcsBoard(GpioIF* gpioIF, std::string spiDev); void createTestTasks(); }; // namespace ObjectFactory diff --git a/bsp_linux_board/boardconfig/rpiConfig.h.in b/bsp_linux_board/boardconfig/rpiConfig.h.in index 7341fcca..b58a1037 100644 --- a/bsp_linux_board/boardconfig/rpiConfig.h.in +++ b/bsp_linux_board/boardconfig/rpiConfig.h.in @@ -17,16 +17,4 @@ #define RPI_ADD_UART_TEST 0 -/* Adapt these values accordingly */ -namespace gpio { -static constexpr uint8_t MGM_0_BCM_PIN = 17; -static constexpr uint8_t MGM_1_BCM_PIN = 27; -static constexpr uint8_t MGM_2_BCM_PIN = 22; -static constexpr uint8_t MGM_3_BCM_PIN = 23; -static constexpr uint8_t GYRO_0_BCM_PIN = 5; -static constexpr uint8_t GYRO_1_BCM_PIN = 6; -static constexpr uint8_t GYRO_2_BCM_PIN = 13; -static constexpr uint8_t GYRO_3_BCM_PIN = 19; -} - #endif /* BSP_RPI_BOARDCONFIG_RPI_CONFIG_H_ */ diff --git a/bsp_linux_board/definitions.h b/bsp_linux_board/definitions.h new file mode 100644 index 00000000..1b6814f4 --- /dev/null +++ b/bsp_linux_board/definitions.h @@ -0,0 +1,37 @@ +#ifndef BSP_LINUX_BOARD_DEFINITIONS_H_ +#define BSP_LINUX_BOARD_DEFINITIONS_H_ + +#include + +#include "OBSWConfig.h" + +#ifdef RASPBERRY_PI + +namespace spi { + +static constexpr char DEV[] = "/dev/spidev0.1"; + +} + +/* Adapt these values accordingly */ +namespace gpio { +static constexpr uint8_t MGM_0_BCM_PIN = 17; +static constexpr uint8_t MGM_1_BCM_PIN = 27; +static constexpr uint8_t MGM_2_BCM_PIN = 22; +static constexpr uint8_t MGM_3_BCM_PIN = 23; +static constexpr uint8_t GYRO_0_BCM_PIN = 5; +static constexpr uint8_t GYRO_1_BCM_PIN = 6; +static constexpr uint8_t GYRO_2_BCM_PIN = 13; +static constexpr uint8_t GYRO_3_BCM_PIN = 19; + +static constexpr uint8_t SPI_MUX_0_BCM = 17; +static constexpr uint8_t SPI_MUX_1_BCM = 27; +static constexpr uint8_t SPI_MUX_2_BCM = 22; +static constexpr uint8_t SPI_MUX_3_BCM = 23; +static constexpr uint8_t SPI_MUX_4_BCM = 5; +static constexpr uint8_t SPI_MUX_5_BCM = 6; +} // namespace gpio + +#endif + +#endif /* BSP_LINUX_BOARD_DEFINITIONS_H_ */ diff --git a/bsp_linux_board/gpioInit.cpp b/bsp_linux_board/gpioInit.cpp new file mode 100644 index 00000000..f913db8a --- /dev/null +++ b/bsp_linux_board/gpioInit.cpp @@ -0,0 +1,56 @@ +#include "gpioInit.h" + +#include +#include +#include +#include + +#include "definitions.h" +#include "fsfw_hal/linux/rpi/GpioRPi.h" + +#ifdef RASPBERRY_PI + +struct MuxInfo { + MuxInfo(gpioId_t gpioId, int bcmNum, std::string consumer) + : gpioId(gpioId), bcmNum(bcmNum), consumer(consumer) {} + gpioId_t gpioId; + int bcmNum; + std::string consumer; +}; + +void rpi::gpio::initSpiCsDecoder(GpioIF* gpioComIF) { + using namespace ::gpio; + ReturnValue_t result; + + if (gpioComIF == nullptr) { + sif::debug << "initSpiCsDecoder: Invalid gpioComIF" << std::endl; + return; + } + + std::array<::MuxInfo, 6> muxInfo{ + MuxInfo(gpioIds::SPI_MUX_BIT_0, SPI_MUX_0_BCM, "SPI_MUX_0"), + MuxInfo(gpioIds::SPI_MUX_BIT_1, SPI_MUX_1_BCM, "SPI_MUX_1"), + MuxInfo(gpioIds::SPI_MUX_BIT_2, SPI_MUX_2_BCM, "SPI_MUX_2"), + MuxInfo(gpioIds::SPI_MUX_BIT_3, SPI_MUX_3_BCM, "SPI_MUX_3"), + MuxInfo(gpioIds::SPI_MUX_BIT_4, SPI_MUX_4_BCM, "SPI_MUX_4"), + MuxInfo(gpioIds::SPI_MUX_BIT_5, SPI_MUX_5_BCM, "SPI_MUX_5"), + }; + GpioCookie* spiMuxGpios = new GpioCookie; + + for (const auto& info : muxInfo) { + result = createRpiGpioConfig(spiMuxGpios, info.gpioId, info.bcmNum, info.consumer, + Direction::OUT, Levels::LOW); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "Creating Raspberry Pi SPI Mux GPIO failed with code " << result << std::endl; + return; + } + } + + result = gpioComIF->addGpios(spiMuxGpios); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "initSpiCsDecoder: Failed to add mux bit gpios to gpioComIF" << std::endl; + return; + } +} + +#endif diff --git a/bsp_linux_board/gpioInit.h b/bsp_linux_board/gpioInit.h new file mode 100644 index 00000000..0ca66412 --- /dev/null +++ b/bsp_linux_board/gpioInit.h @@ -0,0 +1,20 @@ +#pragma once + +#include "OBSWConfig.h" + +class GpioIF; + +#ifdef RASPBERRY_PI +namespace rpi { +namespace gpio { + +/** + * @brief This function initializes the GPIOs used to control the SN74LVC138APWR decoders on + * the TCS Board and the interface board. + */ +void initSpiCsDecoder(GpioIF* gpioComIF); + +} // namespace gpio +} // namespace rpi + +#endif diff --git a/bsp_linux_board/main.cpp b/bsp_linux_board/main.cpp index 4e286f5d..98c4d79b 100644 --- a/bsp_linux_board/main.cpp +++ b/bsp_linux_board/main.cpp @@ -3,8 +3,8 @@ #include "InitMission.h" #include "OBSWConfig.h" #include "OBSWVersion.h" -#include "fsfw/FSFWVersion.h" #include "fsfw/tasks/TaskFactory.h" +#include "fsfw/version.h" #ifdef RASPBERRY_PI static const char* const BOARD_NAME = "Raspberry Pi"; @@ -22,8 +22,7 @@ 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; + << SW_REVISION << ", FSFW v" << fsfw::FSFW_VERSION << " --" << std::endl; std::cout << "-- " << __DATE__ << " " << __TIME__ << " --" << std::endl; initmission::initMission(); diff --git a/bsp_q7s/CMakeLists.txt b/bsp_q7s/CMakeLists.txt index 17e4ba2d..459ead8a 100644 --- a/bsp_q7s/CMakeLists.txt +++ b/bsp_q7s/CMakeLists.txt @@ -22,4 +22,4 @@ add_subdirectory(comIF) add_subdirectory(core) add_subdirectory(memory) add_subdirectory(callbacks) -add_subdirectory(devices) +add_subdirectory(xadc) diff --git a/bsp_q7s/boardconfig/busConf.h b/bsp_q7s/boardconfig/busConf.h index eba4fb36..bc6efd7a 100644 --- a/bsp_q7s/boardconfig/busConf.h +++ b/bsp_q7s/boardconfig/busConf.h @@ -84,6 +84,7 @@ 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"; +static constexpr char SYRLINKS_FAULT[] = "syrlinks_fault"; static constexpr char PL_PCDU_ENABLE_VBAT0[] = "enable_plpcdu_vbat0"; static constexpr char PL_PCDU_ENABLE_VBAT1[] = "enable_plpcdu_vbat1"; @@ -94,6 +95,9 @@ 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"; +static constexpr char ENABLE_SUPV_UART[] = "enable_supv_uart"; +static constexpr char ENABLE_MPSOC_UART[] = "enable_mpsoc_uart"; + } // namespace gpioNames } // namespace q7s diff --git a/bsp_q7s/boardtest/Q7STestTask.cpp b/bsp_q7s/boardtest/Q7STestTask.cpp index 1f14d0e1..8b96450f 100644 --- a/bsp_q7s/boardtest/Q7STestTask.cpp +++ b/bsp_q7s/boardtest/Q7STestTask.cpp @@ -2,6 +2,7 @@ #include #include +#include #include #include #include @@ -23,6 +24,7 @@ Q7STestTask::Q7STestTask(object_id_t objectId) : TestTask(objectId) { doTestSdCard = false; doTestScratchApi = false; doTestGps = false; + doTestXadc = true; } ReturnValue_t Q7STestTask::performOneShotAction() { @@ -44,6 +46,9 @@ ReturnValue_t Q7STestTask::performPeriodicAction() { if (doTestGps) { testGpsDaemon(); } + if (doTestXadc) { + xadcTest(); + } return TestTask::performPeriodicAction(); } @@ -395,3 +400,53 @@ void Q7STestTask::testFileSystemHandlerDirect(FsOpCodes opCode) { } } } + +void Q7STestTask::xadcTest() { + ReturnValue_t result = RETURN_OK; + float temperature = 0; + float vccPint = 0; + float vccPaux = 0; + float vccInt = 0; + float vccAux = 0; + float vccBram = 0; + float vccOddr = 0; + float vrefp = 0; + float vrefn = 0; + Xadc xadc; + result = xadc.getTemperature(temperature); + if (result == HasReturnvaluesIF::RETURN_OK) { + sif::info << "Q7STestTask::xadcTest: Chip Temperature: " << temperature << " °C" << std::endl; + } + result = xadc.getVccPint(vccPint); + if (result == HasReturnvaluesIF::RETURN_OK) { + sif::info << "Q7STestTask::xadcTest: VCC PS internal: " << vccPint << " mV" << std::endl; + } + result = xadc.getVccPaux(vccPaux); + if (result == HasReturnvaluesIF::RETURN_OK) { + sif::info << "Q7STestTask::xadcTest: VCC PS auxilliary: " << vccPaux << " mV" << std::endl; + } + result = xadc.getVccInt(vccInt); + if (result == HasReturnvaluesIF::RETURN_OK) { + sif::info << "Q7STestTask::xadcTest: VCC PL internal: " << vccInt << " mV" << std::endl; + } + result = xadc.getVccAux(vccAux); + if (result == HasReturnvaluesIF::RETURN_OK) { + sif::info << "Q7STestTask::xadcTest: VCC PL auxilliary: " << vccAux << " mV" << std::endl; + } + result = xadc.getVccBram(vccBram); + if (result == HasReturnvaluesIF::RETURN_OK) { + sif::info << "Q7STestTask::xadcTest: VCC BRAM: " << vccBram << " mV" << std::endl; + } + result = xadc.getVccOddr(vccOddr); + if (result == HasReturnvaluesIF::RETURN_OK) { + sif::info << "Q7STestTask::xadcTest: VCC PS I/O DDR : " << vccOddr << " mV" << std::endl; + } + result = xadc.getVrefp(vrefp); + if (result == HasReturnvaluesIF::RETURN_OK) { + sif::info << "Q7STestTask::xadcTest: Vrefp : " << vrefp << " mV" << std::endl; + } + result = xadc.getVrefn(vrefn); + if (result == HasReturnvaluesIF::RETURN_OK) { + sif::info << "Q7STestTask::xadcTest: Vrefn : " << vrefn << " mV" << std::endl; + } +} diff --git a/bsp_q7s/boardtest/Q7STestTask.h b/bsp_q7s/boardtest/Q7STestTask.h index b7aa791e..ebef1fad 100644 --- a/bsp_q7s/boardtest/Q7STestTask.h +++ b/bsp_q7s/boardtest/Q7STestTask.h @@ -15,6 +15,7 @@ class Q7STestTask : public TestTask { bool doTestSdCard = false; bool doTestScratchApi = false; bool doTestGps = false; + bool doTestXadc = false; CoreController* coreController = nullptr; ReturnValue_t performOneShotAction() override; @@ -24,6 +25,7 @@ class Q7STestTask : public TestTask { void testSdCard(); void fileTests(); + void xadcTest(); void testScratchApi(); void testJsonLibDirect(); diff --git a/bsp_q7s/callbacks/CMakeLists.txt b/bsp_q7s/callbacks/CMakeLists.txt index a4462937..584e6026 100644 --- a/bsp_q7s/callbacks/CMakeLists.txt +++ b/bsp_q7s/callbacks/CMakeLists.txt @@ -2,5 +2,5 @@ target_sources(${OBSW_NAME} PRIVATE rwSpiCallback.cpp gnssCallback.cpp pcduSwitchCb.cpp - gpioCallbacks.cpp + q7sGpioCallbacks.cpp ) diff --git a/bsp_q7s/callbacks/gpioCallbacks.cpp b/bsp_q7s/callbacks/gpioCallbacks.cpp deleted file mode 100644 index e5fd877a..00000000 --- a/bsp_q7s/callbacks/gpioCallbacks.cpp +++ /dev/null @@ -1,487 +0,0 @@ -#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/pcduSwitchCb.cpp b/bsp_q7s/callbacks/pcduSwitchCb.cpp index ec5f4dc5..f9b6c761 100644 --- a/bsp_q7s/callbacks/pcduSwitchCb.cpp +++ b/bsp_q7s/callbacks/pcduSwitchCb.cpp @@ -10,8 +10,8 @@ void pcdu::switchCallback(GOMSPACE::Pdu pdu, uint8_t channel, bool state, void* return; } if (pdu == GOMSPACE::Pdu::PDU1) { - PDU1::SwitchChannels typedChannel = static_cast(channel); - if (typedChannel == PDU1::SwitchChannels::ACS_A_SIDE) { + PDU1::Channels typedChannel = static_cast(channel); + if (typedChannel == PDU1::Channels::ACS_A_SIDE) { if (state) { gpioComIF->pullHigh(gpioIds::GNSS_0_NRESET); } else { @@ -20,8 +20,8 @@ void pcdu::switchCallback(GOMSPACE::Pdu pdu, uint8_t channel, bool state, void* } } else if (pdu == GOMSPACE::Pdu::PDU2) { - PDU2::SwitchChannels typedChannel = static_cast(channel); - if (typedChannel == PDU2::SwitchChannels::ACS_B_SIDE) { + PDU2::Channels typedChannel = static_cast(channel); + if (typedChannel == PDU2::Channels::ACS_B_SIDE) { if (state) { gpioComIF->pullHigh(gpioIds::GNSS_1_NRESET); } else { diff --git a/bsp_q7s/callbacks/q7sGpioCallbacks.cpp b/bsp_q7s/callbacks/q7sGpioCallbacks.cpp new file mode 100644 index 00000000..6db5aed4 --- /dev/null +++ b/bsp_q7s/callbacks/q7sGpioCallbacks.cpp @@ -0,0 +1,54 @@ +#include "q7sGpioCallbacks.h" + +#include +#include +#include +#include + +#include "busConf.h" + +void q7s::gpioCallbacks::initSpiCsDecoder(GpioIF* gpioComIF) { + using namespace gpio; + ReturnValue_t result; + + if (gpioComIF == nullptr) { + sif::debug << "initSpiCsDecoder: Invalid gpioComIF" << std::endl; + return; + } + + 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 = gpioComIF->addGpios(spiMuxGpios); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "initSpiCsDecoder: Failed to add mux bit gpios to gpioComIF" << std::endl; + return; + } +} diff --git a/bsp_q7s/callbacks/q7sGpioCallbacks.h b/bsp_q7s/callbacks/q7sGpioCallbacks.h new file mode 100644 index 00000000..e3306554 --- /dev/null +++ b/bsp_q7s/callbacks/q7sGpioCallbacks.h @@ -0,0 +1,15 @@ +#pragma once + +class GpioIF; + +namespace q7s { +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); + +} // namespace gpioCallbacks +} // namespace q7s diff --git a/bsp_q7s/core/CoreController.cpp b/bsp_q7s/core/CoreController.cpp index b1783054..73fd49bb 100644 --- a/bsp_q7s/core/CoreController.cpp +++ b/bsp_q7s/core/CoreController.cpp @@ -1,32 +1,35 @@ #include "CoreController.h" #include +#include #include "OBSWConfig.h" #include "OBSWVersion.h" -#include "fsfw/FSFWVersion.h" #include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/timemanager/Stopwatch.h" -#include "watchdogConf.h" +#include "fsfw/version.h" +#include "watchdog/definitions.h" #if OBSW_USE_TMTC_TCP_BRIDGE == 0 #include "fsfw/osal/common/UdpTmTcBridge.h" #else #include "fsfw/osal/common/TcpTmTcServer.h" #endif - #include #include +#include #include #include "bsp_q7s/memory/SdCardManager.h" #include "bsp_q7s/memory/scratchApi.h" +#include "bsp_q7s/xadc/Xadc.h" +#include "linux/utility/utility.h" xsc::Chip CoreController::CURRENT_CHIP = xsc::Chip::NO_CHIP; xsc::Copy CoreController::CURRENT_COPY = xsc::Copy::NO_COPY; CoreController::CoreController(object_id_t objectId) - : ExtendedControllerBase(objectId, objects::NO_OBJECT, 5), opDivider(5) { + : ExtendedControllerBase(objectId, objects::NO_OBJECT, 5), opDivider(5), hkSet(this) { ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; try { result = initWatchdogFifo(); @@ -50,6 +53,7 @@ CoreController::CoreController(object_id_t objectId) } catch (const std::filesystem::filesystem_error &e) { sif::error << "CoreController::CoreController: Failed with exception " << e.what() << std::endl; } + eventQueue = QueueFactory::instance()->createMessageQueue(5, EventMessage::MAX_MESSAGE_SIZE); } ReturnValue_t CoreController::handleCommandMessage(CommandMessage *message) { @@ -57,21 +61,42 @@ ReturnValue_t CoreController::handleCommandMessage(CommandMessage *message) { } void CoreController::performControlOperation() { + EventMessage event; + for (ReturnValue_t result = eventQueue->receiveMessage(&event); result == RETURN_OK; + result = eventQueue->receiveMessage(&event)) { + switch (event.getEvent()) { + case (GpsHyperion::GPS_FIX_CHANGE): { + gpsFix = static_cast(event.getParameter2()); + break; + } + } + } performWatchdogControlOperation(); sdStateMachine(); performMountedSdCardOperations(); + readHkData(); } ReturnValue_t CoreController::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) { + localDataPoolMap.emplace(core::TEMPERATURE, new PoolEntry({0})); + localDataPoolMap.emplace(core::PS_VOLTAGE, new PoolEntry({0})); + localDataPoolMap.emplace(core::PL_VOLTAGE, new PoolEntry({0})); return HasReturnvaluesIF::RETURN_OK; } -LocalPoolDataSetBase *CoreController::getDataSetHandle(sid_t sid) { return nullptr; } +LocalPoolDataSetBase *CoreController::getDataSetHandle(sid_t sid) { + if (sid.ownerSetId == core::HK_SET_ID) { + return &hkSet; + } + return nullptr; +} ReturnValue_t CoreController::initialize() { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - + ReturnValue_t result = ExtendedControllerBase::initialize(); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "CoreController::initialize: Base init failed" << std::endl; + } result = scratch::writeNumber(scratch::ALLOC_FAILURE_COUNT, 0); if (result != HasReturnvaluesIF::RETURN_OK) { sif::warning << "CoreController::initialize: Setting up alloc failure " @@ -82,7 +107,23 @@ ReturnValue_t CoreController::initialize() { sdStateMachine(); triggerEvent(REBOOT_SW, CURRENT_CHIP, CURRENT_COPY); - return ExtendedControllerBase::initialize(); + EventManagerIF *eventManager = + ObjectManager::instance()->get(objects::EVENT_MANAGER); + if (eventManager == nullptr or eventQueue == nullptr) { + sif::warning << "CoreController::initialize: No valid event manager found or " + "queue invalid" + << std::endl; + } + result = eventManager->registerListener(eventQueue->getId()); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "CoreController::initialize: Registering as event listener failed" << std::endl; + } + result = eventManager->subscribeToEvent(eventQueue->getId(), + event::getEventId(GpsHyperion::GPS_FIX_CHANGE)); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "Subscribing for GPS GPS_FIX_CHANGE event failed" << std::endl; + } + return RETURN_OK; } ReturnValue_t CoreController::initializeAfterTaskCreation() { @@ -104,6 +145,7 @@ ReturnValue_t CoreController::initializeAfterTaskCreation() { setenv("PATH", updatedEnvPath.c_str(), true); updateProtInfo(); initPrint(); + ExtendedControllerBase::initializeAfterTaskCreation(); return result; } @@ -608,6 +650,7 @@ ReturnValue_t CoreController::incrementAllocationFailureCount() { } ReturnValue_t CoreController::initVersionFile() { + using namespace fsfw; 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; @@ -624,12 +667,11 @@ ReturnValue_t CoreController::initVersionFile() { 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); + char versionString[16] = {}; + fsfw::FSFW_VERSION.getVersion(versionString, sizeof(versionString)); + std::string fullFsfwVersionString = "FSFW: v" + std::string(versionString); std::string systemString = "System: " + unameLine; - std::string mountPrefix = SdCardManager::instance()->getCurrentMountPrefix(); - std::string versionFilePath = mountPrefix + VERSION_FILE; + std::string versionFilePath = currMntPrefix + VERSION_FILE; std::fstream versionFile; if (not std::filesystem::exists(versionFilePath)) { @@ -1187,24 +1229,27 @@ void CoreController::performWatchdogControlOperation() { } void CoreController::performMountedSdCardOperations() { + currMntPrefix = sdcMan->getCurrentMountPrefix(); if (doPerformMountedSdCardOps) { bool sdCardMounted = false; sdCardMounted = sdcMan->isSdCardMounted(sdInfo.pref); if (sdCardMounted) { - std::string path = sdcMan->getCurrentMountPrefix(sdInfo.pref) + "/" + CONF_FOLDER; + std::string path = currMntPrefix + "/" + CONF_FOLDER; if (not std::filesystem::exists(path)) { std::filesystem::create_directory(path); } initVersionFile(); + initClockFromTimeFile(); performRebootFileHandling(false); doPerformMountedSdCardOps = false; } } + timeFileHandler(); } void CoreController::performRebootFileHandling(bool recreateFile) { using namespace std; - std::string path = sdcMan->getCurrentMountPrefix(sdInfo.pref) + REBOOT_FILE; + std::string path = currMntPrefix + REBOOT_FILE; if (not std::filesystem::exists(path) or recreateFile) { #if OBSW_VERBOSE_LEVEL >= 1 sif::info << "CoreController::performRebootFileHandling: Recreating reboot file" << std::endl; @@ -1583,7 +1628,7 @@ bool CoreController::parseRebootFile(std::string path, RebootFile &rf) { } void CoreController::resetRebootCount(xsc::Chip tgtChip, xsc::Copy tgtCopy) { - std::string path = sdcMan->getCurrentMountPrefix(sdInfo.pref) + REBOOT_FILE; + std::string path = currMntPrefix + REBOOT_FILE; // Disable the reboot file mechanism parseRebootFile(path, rebootFile); if (tgtChip == xsc::ALL_CHIP and tgtCopy == xsc::ALL_COPY) { @@ -1610,7 +1655,7 @@ void CoreController::resetRebootCount(xsc::Chip tgtChip, xsc::Copy tgtCopy) { } void CoreController::rewriteRebootFile(RebootFile file) { - std::string path = sdcMan->getCurrentMountPrefix(sdInfo.pref) + REBOOT_FILE; + std::string path = currMntPrefix + REBOOT_FILE; std::ofstream rebootFile(path); if (rebootFile.is_open()) { // Initiate reboot file first. Reboot handling will be on on initialization @@ -1645,3 +1690,93 @@ void CoreController::setRebootMechanismLock(bool lock, xsc::Chip tgtChip, xsc::C } rewriteRebootFile(rebootFile); } + +ReturnValue_t CoreController::timeFileHandler() { + if (gpsFix == GpsHyperion::FixMode::FIX_2D or gpsFix == GpsHyperion::FixMode::FIX_3D) { + // It is assumed that the system time is set from the GPS time + timeval currentTime = {}; + ReturnValue_t result = Clock::getClock_timeval(¤tTime); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + std::ofstream timeFile(currMntPrefix + TIME_FILE); + timeFile << "UNIX SECONDS: " << currentTime.tv_sec << std::endl; + } + return RETURN_OK; +} + +ReturnValue_t CoreController::initClockFromTimeFile() { + using namespace GpsHyperion; + using namespace std; + std::string fileName = currMntPrefix + TIME_FILE; + if (std::filesystem::exists(fileName) and + ((gpsFix == FixMode::UNKNOWN or gpsFix == FixMode::NOT_SEEN) or + not utility::timeSanityCheck())) { + ifstream timeFile(fileName); + string nextWord; + getline(timeFile, nextWord); + istringstream iss(nextWord); + iss >> nextWord; + if (iss.bad() or nextWord != "UNIX") { + return RETURN_FAILED; + } + iss >> nextWord; + if (iss.bad() or nextWord != "SECONDS:") { + return RETURN_FAILED; + } + iss >> nextWord; + timeval currentTime = {}; + char *checkPtr; + currentTime.tv_sec = strtol(nextWord.c_str(), &checkPtr, 10); + if (iss.bad() or *checkPtr) { + return RETURN_FAILED; + } +#if OBSW_VERBOSE_LEVEL >= 1 + time_t timeRaw = currentTime.tv_sec; + std::tm *time = std::gmtime(&timeRaw); + sif::info << "Setting system time from time files: " << std::put_time(time, "%c %Z") + << std::endl; +#endif + return Clock::setClock(¤tTime); + } + return RETURN_OK; +} + +void CoreController::readHkData() { + ReturnValue_t result = RETURN_OK; + result = hkSet.read(TIMEOUT_TYPE, MUTEX_TIMEOUT); + if (result != RETURN_OK) { + return; + } + Xadc xadc; + result = xadc.getTemperature(hkSet.temperature.value); + if (result != RETURN_OK) { + hkSet.temperature.setValid(false); + } else { + hkSet.temperature.setValid(true); + } + result = xadc.getVccPint(hkSet.psVoltage.value); + if (result != RETURN_OK) { + hkSet.psVoltage.setValid(false); + } else { + hkSet.psVoltage.setValid(true); + } + result = xadc.getVccInt(hkSet.plVoltage.value); + if (result != RETURN_OK) { + hkSet.plVoltage.setValid(false); + } else { + hkSet.plVoltage.setValid(true); + } +#if OBSW_PRINT_CORE_HK == 1 + hkSet.printSet(); +#endif /* OBSW_PRINT_CORE_HK == 1 */ + result = hkSet.commit(TIMEOUT_TYPE, MUTEX_TIMEOUT); + if (result != RETURN_OK) { + return; + } +} + +bool CoreController::isNumber(const std::string &s) { + return !s.empty() && std::find_if(s.begin(), s.end(), + [](unsigned char c) { return !std::isdigit(c); }) == s.end(); +} diff --git a/bsp_q7s/core/CoreController.h b/bsp_q7s/core/CoreController.h index 48bc9b7f..b5e4e511 100644 --- a/bsp_q7s/core/CoreController.h +++ b/bsp_q7s/core/CoreController.h @@ -6,9 +6,11 @@ #include +#include "CoreDefinitions.h" #include "bsp_q7s/memory/SdCardManager.h" #include "events/subsystemIdRanges.h" #include "fsfw/controller/ExtendedControllerBase.h" +#include "mission/devices/devicedefinitions/GPSDefinitions.h" class Timer; class SdCardManager; @@ -52,10 +54,12 @@ class CoreController : public ExtendedControllerBase { static constexpr char CONF_FOLDER[] = "conf"; static constexpr char VERSION_FILE_NAME[] = "version.txt"; static constexpr char REBOOT_FILE_NAME[] = "reboot.txt"; + static constexpr char TIME_FILE_NAME[] = "time.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); + const std::string TIME_FILE = "/" + std::string(CONF_FOLDER) + "/" + std::string(TIME_FILE_NAME); static constexpr ActionId_t LIST_DIRECTORY_INTO_FILE = 0; static constexpr ActionId_t SWITCH_REBOOT_FILE_HANDLING = 5; @@ -120,9 +124,12 @@ class CoreController : public ExtendedControllerBase { bool sdInitFinished() const; private: + static constexpr MutexIF::TimeoutType TIMEOUT_TYPE = MutexIF::TimeoutType::WAITING; + static constexpr uint32_t MUTEX_TIMEOUT = 20; // Designated value for rechecking FIFO open static constexpr int RETRY_FIFO_OPEN = -2; int watchdogFifoFd = 0; + GpsHyperion::FixMode gpsFix = GpsHyperion::FixMode::UNKNOWN; // States for SD state machine, which is used in non-blocking mode enum class SdStates { @@ -148,6 +155,7 @@ class CoreController : public ExtendedControllerBase { static constexpr bool BLOCKING_SD_INIT = false; SdCardManager* sdcMan = nullptr; + MessageQueueIF* eventQueue = nullptr; struct SdInfo { sd::SdCard pref = sd::SdCard::NONE; @@ -170,6 +178,7 @@ class CoreController : public ExtendedControllerBase { sd::SdState commandedState = sd::SdState::OFF; } sdInfo; RebootFile rebootFile = {}; + std::string currMntPrefix; bool doPerformMountedSdCardOps = true; /** @@ -181,12 +190,17 @@ class CoreController : public ExtendedControllerBase { std::array protArray; PeriodicOperationDivider opDivider; + core::HkSet hkSet; + 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 initClockFromTimeFile(); + ReturnValue_t timeFileHandler(); ReturnValue_t initBootCopy(); ReturnValue_t initWatchdogFifo(); ReturnValue_t initSdCardBlocking(); @@ -220,6 +234,8 @@ class CoreController : public ExtendedControllerBase { void setRebootMechanismLock(bool lock, xsc::Chip tgtChip, xsc::Copy tgtCopy); bool parseRebootFile(std::string path, RebootFile& file); void rewriteRebootFile(RebootFile file); + void readHkData(); + bool isNumber(const std::string& s); }; #endif /* BSP_Q7S_CORE_CORECONTROLLER_H_ */ diff --git a/bsp_q7s/core/CoreDefinitions.h b/bsp_q7s/core/CoreDefinitions.h new file mode 100644 index 00000000..91896301 --- /dev/null +++ b/bsp_q7s/core/CoreDefinitions.h @@ -0,0 +1,39 @@ +#ifndef BSP_Q7S_CORE_COREDEFINITIONS_H_ +#define BSP_Q7S_CORE_COREDEFINITIONS_H_ + +#include + +namespace core { + +static const uint8_t HK_SET_ENTRIES = 3; +static const uint32_t HK_SET_ID = 5; + +enum PoolIds { TEMPERATURE, PS_VOLTAGE, PL_VOLTAGE }; + +/** + * @brief Set storing OBC internal housekeeping data + */ +class HkSet : public StaticLocalDataSet { + public: + HkSet(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, HK_SET_ID) {} + + HkSet(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, HK_SET_ID)) {} + + // On-chip temperature + lp_var_t temperature = lp_var_t(sid.objectId, PoolIds::TEMPERATURE, this); + // Processing system VCC + lp_var_t psVoltage = lp_var_t(sid.objectId, PoolIds::PS_VOLTAGE, this); + // Programmable logic VCC + lp_var_t plVoltage = lp_var_t(sid.objectId, PoolIds::PL_VOLTAGE, this); + + void printSet() { + sif::info << "HkSet::printSet: On-chip temperature: " << this->temperature << " °C" + << std::endl; + sif::info << "HkSet::printSet: PS voltage: " << this->psVoltage << " mV" << std::endl; + sif::info << "HkSet::printSet: PL voltage: " << this->plVoltage << " mV" << std::endl; + } +}; + +} // namespace core + +#endif /* BSP_Q7S_CORE_COREDEFINITIONS_H_ */ diff --git a/bsp_q7s/core/InitMission.cpp b/bsp_q7s/core/InitMission.cpp index 9d28e1d3..ced1d12a 100644 --- a/bsp_q7s/core/InitMission.cpp +++ b/bsp_q7s/core/InitMission.cpp @@ -55,14 +55,12 @@ void initmission::initTasks() { 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); } -#endif /* TMTC Distribution */ PeriodicTaskIF* tmTcDistributor = factory->createPeriodicTask( @@ -116,15 +114,32 @@ void initmission::initTasks() { #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); + PeriodicTaskIF* acsTask = factory->createPeriodicTask( + "ACS_CTRL", 45, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, 0.4, missedDeadlineFunc); + result = acsTask->addComponent(objects::GPS_CONTROLLER); if (result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("ACS_CTRL", objects::GPS_CONTROLLER); + initmission::printAddObjectError("GPS_CTRL", objects::GPS_CONTROLLER); } + #endif /* OBSW_ADD_ACS_HANDLERS */ -#if BOARD_TE0720 == 0 + PeriodicTaskIF* sysTask = factory->createPeriodicTask( + "SYS_TASK", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, 0.4, missedDeadlineFunc); + result = sysTask->addComponent(objects::ACS_BOARD_ASS); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("ACS_BOARD_ASS", objects::ACS_BOARD_ASS); + } +#if OBSW_ADD_SUS_BOARD_ASS == 1 + result = sysTask->addComponent(objects::SUS_BOARD_ASS); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("SUS_BOARD_ASS", objects::SUS_BOARD_ASS); + } +#endif + result = sysTask->addComponent(objects::TCS_BOARD_ASS); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("TCS_BOARD_ASS", objects::TCS_BOARD_ASS); + } + // 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( @@ -143,7 +158,14 @@ void initmission::initTasks() { } #endif /* OBSW_ADD_STAR_TRACKER == 1 */ -#endif /* BOARD_TE0720 */ +#if OBSW_ADD_PLOC_MPSOC == 1 + PeriodicTaskIF* mpsocHelperTask = factory->createPeriodicTask( + "PLOC_MPSOC_HELPER", 20, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc); + result = mpsocHelperTask->addComponent(objects::PLOC_MPSOC_HELPER); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PLOC_MPSOC_HELPER", objects::PLOC_MPSOC_HELPER); + } +#endif /* OBSW_ADD_PLOC_MPSOC */ #if OBSW_TEST_CCSDS_BRIDGE == 1 PeriodicTaskIF* ptmeTestTask = factory->createPeriodicTask( @@ -187,9 +209,7 @@ void initmission::initTasks() { pdecHandlerTask->startTask(); #endif /* OBSW_USE_CCSDS_IP_CORE == 1 */ -#if BOARD_TE0720 == 0 coreController->startTask(); -#endif taskStarter(pstTasks, "PST task vector"); taskStarter(pusTasks, "PUS task vector"); @@ -201,16 +221,15 @@ void initmission::initTasks() { ptmeTestTask->startTask(); #endif -#if BOARD_TE0720 == 0 fsTask->startTask(); #if OBSW_ADD_STAR_TRACKER == 1 - strHelperTask > startTask(); + strHelperTask->startTask(); #endif /* OBSW_ADD_STAR_TRACKER == 1 */ -#endif #if OBSW_ADD_ACS_HANDLERS == 1 - acsCtrl->startTask(); + acsTask->startTask(); #endif + sysTask->startTask(); sif::info << "Tasks started.." << std::endl; } @@ -219,15 +238,16 @@ void initmission::createPstTasks(TaskFactory& factory, TaskDeadlineMissedFunction missedDeadlineFunc, std::vector& taskVec) { ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; -#if BOARD_TE0720 == 0 /* Polling Sequence Table Default */ #if OBSW_ADD_SPI_TEST_CODE == 0 FixedTimeslotTaskIF* spiPst = factory.createFixedTimeslotTask( "PST_TASK_DEFAULT", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 0.5, missedDeadlineFunc); result = pst::pstSpi(spiPst); if (result != HasReturnvaluesIF::RETURN_OK) { - if (result != FixedTimeslotTaskIF::SLOT_LIST_EMPTY) { - sif::error << "InitMission::initTasks: Creating PST failed!" << std::endl; + if (result == FixedTimeslotTaskIF::SLOT_LIST_EMPTY) { + sif::warning << "InitMission::initTasks: SPI PST is empty" << std::endl; + } else { + sif::error << "InitMission::initTasks: Creating SPI PST failed!" << std::endl; } } else { taskVec.push_back(spiPst); @@ -238,43 +258,51 @@ void initmission::createPstTasks(TaskFactory& factory, "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; + if (result == FixedTimeslotTaskIF::SLOT_LIST_EMPTY) { + sif::warning << "InitMission::initTasks: UART PST is empty" << std::endl; + } else { + sif::error << "InitMission::initTasks: Creating UART PST failed!" << std::endl; + } + } else { + taskVec.push_back(uartPst); } - 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; + if (result == FixedTimeslotTaskIF::SLOT_LIST_EMPTY) { + sif::warning << "InitMission::initTasks: GPIO PST is empty" << std::endl; + } else { + sif::error << "InitMission::initTasks: Creating GPIO PST failed!" << std::endl; + } + } else { + taskVec.push_back(gpioPst); } - taskVec.push_back(gpioPst); - #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; + if (result == FixedTimeslotTaskIF::SLOT_LIST_EMPTY) { + sif::warning << "InitMission::initTasks: I2C PST is empty" << std::endl; + } else { + sif::error << "InitMission::initTasks: Creating I2C PST failed!" << std::endl; + } + } else { + taskVec.push_back(i2cPst); } - 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; + if (result != FixedTimeslotTaskIF::SLOT_LIST_EMPTY) { + 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, @@ -381,12 +409,6 @@ void initmission::createTestTasks(TaskFactory& factory, } #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); - } -#endif /* BOARD_TE0720 == 1 && OBSW_TEST_LIBGPIOD == 1 */ taskVec.push_back(testTask); #endif // OBSW_ADD_TEST_TASK == 1 && OBSW_ADD_TEST_CODE == 1 diff --git a/bsp_q7s/core/ObjectFactory.cpp b/bsp_q7s/core/ObjectFactory.cpp index 519dec8f..c9c8e0e2 100644 --- a/bsp_q7s/core/ObjectFactory.cpp +++ b/bsp_q7s/core/ObjectFactory.cpp @@ -1,21 +1,12 @@ #include "ObjectFactory.h" -#include -#include -#include -#include -#include - #include "OBSWConfig.h" #include "bsp_q7s/boardtest/Q7STestTask.h" #include "bsp_q7s/callbacks/gnssCallback.h" -#include "bsp_q7s/callbacks/gpioCallbacks.h" #include "bsp_q7s/callbacks/pcduSwitchCb.h" +#include "bsp_q7s/callbacks/q7sGpioCallbacks.h" #include "bsp_q7s/callbacks/rwSpiCallback.h" #include "bsp_q7s/core/CoreController.h" -#include "bsp_q7s/devices/PlocMemoryDumper.h" -#include "bsp_q7s/devices/PlocSupervisorHandler.h" -#include "bsp_q7s/devices/PlocUpdater.h" #include "bsp_q7s/memory/FileSystemHandler.h" #include "busConf.h" #include "ccsdsConfig.h" @@ -23,15 +14,34 @@ #include "devices/addresses.h" #include "devices/gpioIds.h" #include "devices/powerSwitcherList.h" +#include "fsfw/ipc/QueueFactory.h" +#include "linux/ObjectFactory.h" #include "linux/boardtest/I2cTestClass.h" #include "linux/boardtest/SpiTestClass.h" #include "linux/boardtest/UartTestClass.h" +#include "linux/callbacks/gpioCallbacks.h" #include "linux/csp/CspComIF.h" #include "linux/csp/CspCookie.h" #include "linux/devices/GPSHyperionLinuxController.h" +#include "linux/devices/devicedefinitions/PlocMPSoCDefinitions.h" #include "linux/devices/devicedefinitions/StarTrackerDefinitions.h" +#include "linux/devices/ploc/PlocMPSoCHandler.h" +#include "linux/devices/ploc/PlocMPSoCHelper.h" +#include "linux/devices/ploc/PlocMemoryDumper.h" +#include "linux/devices/ploc/PlocSupervisorHandler.h" +#include "linux/devices/ploc/PlocUpdater.h" #include "linux/devices/startracker/StarTrackerHandler.h" #include "linux/devices/startracker/StrHelper.h" +#include "linux/obc/AxiPtmeConfig.h" +#include "linux/obc/PapbVcInterface.h" +#include "linux/obc/PdecHandler.h" +#include "linux/obc/Ptme.h" +#include "linux/obc/PtmeConfig.h" +#include "mission/system/AcsBoardFdir.h" +#include "mission/system/RtdFdir.h" +#include "mission/system/SusAssembly.h" +#include "mission/system/SusFdir.h" +#include "mission/system/TcsBoardAssembly.h" #include "tmtc/apid.h" #include "tmtc/pusIds.h" @@ -46,6 +56,7 @@ #include "fsfw/tmtcservices/CommandingServiceBase.h" #include "fsfw/tmtcservices/PusServiceBase.h" #include "fsfw_hal/common/gpio/GpioCookie.h" +#include "fsfw_hal/common/gpio/gpioDefinitions.h" #include "fsfw_hal/devicehandlers/GyroL3GD20Handler.h" #include "fsfw_hal/devicehandlers/MgmLIS3MDLHandler.h" #include "fsfw_hal/devicehandlers/MgmRM3100Handler.h" @@ -68,7 +79,6 @@ #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" @@ -77,12 +87,12 @@ #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/system/AcsBoardAssembly.h" #include "mission/tmtc/CCSDSHandler.h" #include "mission/tmtc/VirtualChannel.h" #include "mission/utility/TmFunnel.h" @@ -99,8 +109,8 @@ void Factory::setStaticFrameworkObjectIds() { CommandingServiceBase::defaultPacketSource = objects::PUS_PACKET_DISTRIBUTOR; CommandingServiceBase::defaultPacketDestination = objects::TM_FUNNEL; - // DeviceHandlerBase::powerSwitcherId = objects::PCDU_HANDLER; - DeviceHandlerBase::powerSwitcherId = objects::NO_OBJECT; + DeviceHandlerBase::powerSwitcherId = objects::PCDU_HANDLER; + // DeviceHandlerBase::powerSwitcherId = objects::NO_OBJECT; #if OBSW_TM_TO_PTME == 1 TmFunnel::downlinkDestination = objects::CCSDS_HANDLER; @@ -124,36 +134,39 @@ void ObjectFactory::produce(void* args) { UartComIF* uartComIF = nullptr; SpiComIF* spiComIF = nullptr; I2cComIF* i2cComIF = nullptr; + PowerSwitchIF* pwrSwitcher = nullptr; createCommunicationInterfaces(&gpioComIF, &uartComIF, &spiComIF, &i2cComIF); createTmpComponents(); -#if BOARD_TE0720 == 0 new CoreController(objects::CORE_CONTROLLER); - gpioCallbacks::disableAllDecoder(); - createPcduComponents(gpioComIF); + gpioCallbacks::disableAllDecoder(gpioComIF); + createPcduComponents(gpioComIF, &pwrSwitcher); createRadSensorComponent(gpioComIF); - createSunSensorComponents(gpioComIF, spiComIF); + createSunSensorComponents(gpioComIF, spiComIF, pwrSwitcher, q7s::SPI_DEFAULT_DEV); #if OBSW_ADD_ACS_BOARD == 1 - createAcsBoardComponents(gpioComIF, uartComIF); + createAcsBoardComponents(gpioComIF, uartComIF, pwrSwitcher); #endif createHeaterComponents(); createSolarArrayDeploymentComponents(); - createPlPcduComponents(gpioComIF, spiComIF); + createPlPcduComponents(gpioComIF, spiComIF, pwrSwitcher); #if OBSW_ADD_SYRLINKS == 1 createSyrlinksComponents(); #endif /* OBSW_ADD_SYRLINKS == 1 */ - createRtdComponents(gpioComIF); + createRtdComponents(q7s::SPI_DEFAULT_DEV, gpioComIF, pwrSwitcher); + createPayloadComponents(gpioComIF); #if OBSW_ADD_MGT == 1 I2cCookie* imtqI2cCookie = new I2cCookie(addresses::IMTQ, IMTQ::MAX_REPLY_SIZE, q7s::I2C_DEFAULT_DEV); - auto imtqHandler = new IMTQHandler(objects::IMTQ_HANDLER, objects::I2C_COM_IF, imtqI2cCookie); + auto imtqHandler = new IMTQHandler(objects::IMTQ_HANDLER, objects::I2C_COM_IF, imtqI2cCookie, + pcdu::Switches::PDU1_CH3_MGT_5V); + imtqHandler->setPowerSwitcher(pwrSwitcher); static_cast(imtqHandler); #if OBSW_DEBUG_IMTQ == 1 - imtqHandler->setToGoToNormal(true); imtqHandler->setStartUpImmediately(); + imtqHandler->setToGoToNormal(true); #else (void)imtqHandler; #endif @@ -172,39 +185,21 @@ void ObjectFactory::produce(void* args) { #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); -#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(); -#endif /* OBSW_ADD_PLOC_SUPERVISOR == 1 */ - new FileSystemHandler(objects::FILE_SYSTEM_HANDLER); #if OBSW_ADD_STAR_TRACKER == 1 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); + new UartCookie(objects::STAR_TRACKER, q7s::UART_STAR_TRACKER_DEV, uart::STAR_TRACKER_BAUD, + startracker::MAX_FRAME_SIZE * 2 + 2, UartModes::NON_CANONICAL); starTrackerCookie->setNoFixedSizeReply(); StrHelper* strHelper = new StrHelper(objects::STR_HELPER); - StarTrackerHandler* starTrackerHandler = new StarTrackerHandler( - objects::STAR_TRACKER, objects::UART_COM_IF, starTrackerCookie, strHelper); - starTrackerHandler->setStartUpImmediately(); + auto starTracker = + new StarTrackerHandler(objects::STAR_TRACKER, objects::UART_COM_IF, starTrackerCookie, + strHelper, pcdu::PDU1_CH2_STAR_TRACKER_5V); + starTracker->setPowerSwitcher(pwrSwitcher); #endif /* OBSW_ADD_STAR_TRACKER == 1 */ -#endif /* TE7020 == 0 */ - #if OBSW_USE_CCSDS_IP_CORE == 1 createCcsdsComponents(gpioComIF); #endif /* OBSW_USE_CCSDS_IP_CORE == 1 */ @@ -219,17 +214,10 @@ void ObjectFactory::produce(void* args) { } 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")); -#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); -#endif /* Temperature sensors */ Tmp1075Handler* tmp1075Handler_1 = @@ -254,13 +242,11 @@ void ObjectFactory::createCommunicationInterfaces(LinuxLibgpioIF** gpioComIF, Ua *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); -#endif + q7s::gpioCallbacks::initSpiCsDecoder(*gpioComIF); } -void ObjectFactory::createPcduComponents(LinuxLibgpioIF* gpioComIF) { +void ObjectFactory::createPcduComponents(LinuxLibgpioIF* gpioComIF, PowerSwitchIF** pwrSwitcher) { CspCookie* p60DockCspCookie = new CspCookie(P60Dock::MAX_REPLY_LENGTH, addresses::P60DOCK); CspCookie* pdu1CspCookie = new CspCookie(PDU::MAX_REPLY_LENGTH, addresses::PDU1); CspCookie* pdu2CspCookie = new CspCookie(PDU::MAX_REPLY_LENGTH, addresses::PDU2); @@ -270,12 +256,10 @@ void ObjectFactory::createPcduComponents(LinuxLibgpioIF* gpioComIF) { 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); + auto pcduHandler = new PCDUHandler(objects::PCDU_HANDLER, 50); /** * Setting PCDU devices to mode normal immediately after start up because PCDU is always @@ -285,6 +269,9 @@ void ObjectFactory::createPcduComponents(LinuxLibgpioIF* gpioComIF) { pdu1handler->setModeNormal(); pdu2handler->setModeNormal(); acuhandler->setModeNormal(); + if (pwrSwitcher != nullptr) { + *pwrSwitcher = pcduHandler; + } } void ObjectFactory::createRadSensorComponent(LinuxLibgpioIF* gpioComIF) { @@ -306,173 +293,17 @@ void ObjectFactory::createRadSensorComponent(LinuxLibgpioIF* gpioComIF) { auto radSensor = new RadiationSensorHandler(objects::RAD_SENSOR, objects::SPI_COM_IF, spiCookieRadSensor, gpioComIF); static_cast(radSensor); -#if OBSW_TEST_RAD_SENSOR == 1 + // The radiation sensor ADC is powered by the 5V stack connector which should always be on radSensor->setStartUpImmediately(); + // It's a simple sensor, so just to to normal mode immediately radSensor->setToGoToNormalModeImmediately(); +#if OBSW_DEBUG_RAD_SENSOR == 1 + radSensor->enablePeriodicDataPrint(true); #endif } -void ObjectFactory::createSunSensorComponents(LinuxLibgpioIF* gpioComIF, SpiComIF* spiComIF) { - using namespace gpio; - GpioCookie* gpioCookieSus = new GpioCookie(); - GpioCallback* susgpio = nullptr; - - 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); - -#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); - - 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) { +void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, UartComIF* uartComIF, + PowerSwitchIF* pwrSwitcher) { using namespace gpio; GpioCookie* gpioCookieAcsBoard = new GpioCookie(); @@ -571,6 +402,8 @@ void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, UartComI Levels::LOW); gpioCookieAcsBoard->addGpio(gpioIds::GNSS_SELECT, gpio); gpioComIF->addGpios(gpioCookieAcsBoard); + AcsBoardFdir* fdir = nullptr; + static_cast(fdir); #if OBSW_ADD_ACS_HANDLERS == 1 std::string spiDev = q7s::SPI_DEFAULT_DEV; @@ -579,12 +412,15 @@ void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, UartComI MGMLIS3MDL::MAX_BUFFER_SIZE, spi::DEFAULT_LIS3_MODE, spi::DEFAULT_LIS3_SPEED); auto mgmLis3Handler = new MgmLIS3MDLHandler(objects::MGM_0_LIS3_HANDLER, objects::SPI_COM_IF, spiCookie, spi::LIS3_TRANSITION_DELAY); + fdir = new AcsBoardFdir(objects::MGM_0_LIS3_HANDLER); + mgmLis3Handler->setCustomFdir(fdir); + static_cast(mgmLis3Handler); #if OBSW_TEST_ACS == 1 mgmLis3Handler->setStartUpImmediately(); mgmLis3Handler->setToGoToNormalMode(true); +#endif #if OBSW_DEBUG_ACS == 1 mgmLis3Handler->enablePeriodicPrintouts(true, 10); -#endif #endif spiCookie = @@ -592,38 +428,48 @@ void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, UartComI RM3100::MAX_BUFFER_SIZE, spi::DEFAULT_RM3100_MODE, spi::DEFAULT_RM3100_SPEED); auto mgmRm3100Handler = new MgmRM3100Handler(objects::MGM_1_RM3100_HANDLER, objects::SPI_COM_IF, spiCookie, spi::RM3100_TRANSITION_DELAY); + fdir = new AcsBoardFdir(objects::MGM_1_RM3100_HANDLER); + mgmRm3100Handler->setCustomFdir(fdir); + mgmRm3100Handler->setParent(objects::ACS_BOARD_ASS); + static_cast(mgmRm3100Handler); #if OBSW_TEST_ACS == 1 mgmRm3100Handler->setStartUpImmediately(); mgmRm3100Handler->setToGoToNormalMode(true); +#endif #if OBSW_DEBUG_ACS == 1 mgmRm3100Handler->enablePeriodicPrintouts(true, 10); -#endif #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); + mgmLis3Handler = new MgmLIS3MDLHandler(objects::MGM_2_LIS3_HANDLER, objects::SPI_COM_IF, + spiCookie, spi::LIS3_TRANSITION_DELAY); + fdir = new AcsBoardFdir(objects::MGM_2_LIS3_HANDLER); + mgmLis3Handler->setCustomFdir(fdir); + mgmLis3Handler->setParent(objects::ACS_BOARD_ASS); + static_cast(mgmLis3Handler); #if OBSW_TEST_ACS == 1 - mgmLis3Handler2->setStartUpImmediately(); - mgmLis3Handler2->setToGoToNormalMode(true); + mgmLis3Handler->setStartUpImmediately(); + mgmLis3Handler->setToGoToNormalMode(true); +#endif #if OBSW_DEBUG_ACS == 1 - mgmLis3Handler2->enablePeriodicPrintouts(true, 10); + mgmLis3Handler->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); + fdir = new AcsBoardFdir(objects::MGM_3_RM3100_HANDLER); + mgmRm3100Handler->setCustomFdir(fdir); + mgmRm3100Handler->setParent(objects::ACS_BOARD_ASS); #if OBSW_TEST_ACS == 1 mgmRm3100Handler->setStartUpImmediately(); mgmRm3100Handler->setToGoToNormalMode(true); +#endif #if OBSW_DEBUG_ACS == 1 mgmRm3100Handler->enablePeriodicPrintouts(true, 10); -#endif #endif // Commented until ACS board V2 in in clean room again @@ -633,12 +479,16 @@ void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, UartComI spi::DEFAULT_ADIS16507_SPEED); auto adisHandler = new GyroADIS1650XHandler(objects::GYRO_0_ADIS_HANDLER, objects::SPI_COM_IF, spiCookie, ADIS1650X::Type::ADIS16505); + fdir = new AcsBoardFdir(objects::GYRO_0_ADIS_HANDLER); + adisHandler->setCustomFdir(fdir); + adisHandler->setParent(objects::ACS_BOARD_ASS); + static_cast(adisHandler); #if OBSW_TEST_ACS == 1 adisHandler->setStartUpImmediately(); adisHandler->setToGoToNormalModeImmediately(); +#endif #if OBSW_DEBUG_ACS == 1 adisHandler->enablePeriodicPrintouts(true, 10); -#endif #endif // Gyro 1 Side A @@ -647,19 +497,27 @@ void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, UartComI spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED); auto gyroL3gHandler = new GyroHandlerL3GD20H(objects::GYRO_1_L3G_HANDLER, objects::SPI_COM_IF, spiCookie, spi::L3G_TRANSITION_DELAY); + fdir = new AcsBoardFdir(objects::GYRO_1_L3G_HANDLER); + gyroL3gHandler->setCustomFdir(fdir); + gyroL3gHandler->setParent(objects::ACS_BOARD_ASS); + static_cast(gyroL3gHandler); #if OBSW_TEST_ACS == 1 gyroL3gHandler->setStartUpImmediately(); gyroL3gHandler->setToGoToNormalMode(true); +#endif #if OBSW_DEBUG_ACS == 1 gyroL3gHandler->enablePeriodicPrintouts(true, 10); #endif -#endif + // Gyro 2 Side B spiCookie = new SpiCookie(addresses::GYRO_2_ADIS, gpioIds::GYRO_2_ADIS_CS, spiDev, ADIS1650X::MAXIMUM_REPLY_SIZE, spi::DEFAULT_ADIS16507_MODE, spi::DEFAULT_ADIS16507_SPEED); adisHandler = new GyroADIS1650XHandler(objects::GYRO_2_ADIS_HANDLER, objects::SPI_COM_IF, spiCookie, ADIS1650X::Type::ADIS16505); + fdir = new AcsBoardFdir(objects::GYRO_2_ADIS_HANDLER); + adisHandler->setCustomFdir(fdir); + adisHandler->setParent(objects::ACS_BOARD_ASS); #if OBSW_TEST_ACS == 1 adisHandler->setStartUpImmediately(); adisHandler->setToGoToNormalModeImmediately(); @@ -670,12 +528,15 @@ void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, UartComI spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED); gyroL3gHandler = new GyroHandlerL3GD20H(objects::GYRO_3_L3G_HANDLER, objects::SPI_COM_IF, spiCookie, spi::L3G_TRANSITION_DELAY); + fdir = new AcsBoardFdir(objects::GYRO_3_L3G_HANDLER); + gyroL3gHandler->setCustomFdir(fdir); + gyroL3gHandler->setParent(objects::ACS_BOARD_ASS); #if OBSW_TEST_ACS == 1 gyroL3gHandler->setStartUpImmediately(); gyroL3gHandler->setToGoToNormalMode(true); +#endif #if OBSW_DEBUG_ACS == 1 gyroL3gHandler->enablePeriodicPrintouts(true, 10); -#endif #endif bool debugGps = false; @@ -691,6 +552,14 @@ void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, UartComI auto gpsHandler0 = new GPSHyperionLinuxController(objects::GPS_CONTROLLER, objects::NO_OBJECT, debugGps); gpsHandler0->setResetPinTriggerFunction(gps::triggerGpioResetPin, &resetArgsGnss0); + + AcsBoardHelper acsBoardHelper = AcsBoardHelper( + objects::MGM_0_LIS3_HANDLER, objects::MGM_1_RM3100_HANDLER, objects::MGM_2_LIS3_HANDLER, + objects::MGM_3_RM3100_HANDLER, objects::GYRO_0_ADIS_HANDLER, objects::GYRO_1_L3G_HANDLER, + objects::GYRO_2_ADIS_HANDLER, objects::GYRO_3_L3G_HANDLER, objects::GPS_CONTROLLER); + auto acsAss = new AcsBoardAssembly(objects::ACS_BOARD_ASS, objects::NO_OBJECT, pwrSwitcher, + acsBoardHelper, gpioComIF); + static_cast(acsAss); #endif /* OBSW_ADD_ACS_HANDLERS == 1 */ } @@ -736,7 +605,7 @@ void ObjectFactory::createHeaterComponents() { heaterGpiosCookie->addGpio(gpioIds::HEATER_7, gpio); new HeaterHandler(objects::HEATER_HANDLER, objects::GPIO_IF, heaterGpiosCookie, - objects::PCDU_HANDLER, pcduSwitches::TCS_BOARD_8V_HEATER_IN); + objects::PCDU_HANDLER, pcdu::Switches::PDU2_CH3_TCS_BOARD_HEATER_IN_8V); } void ObjectFactory::createSolarArrayDeploymentComponents() { @@ -756,210 +625,57 @@ void ObjectFactory::createSolarArrayDeploymentComponents() { // 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); + pcdu::Switches::PDU2_CH5_DEPLOYMENT_MECHANISM_8V, + gpioIds::DEPLSA1, gpioIds::DEPLSA2, 1000); } -void ObjectFactory::createSyrlinksComponents() { +void ObjectFactory::createSyrlinksComponents(PowerSwitchIF* pwrSwitcher) { UartCookie* syrlinksUartCookie = - new UartCookie(objects::SYRLINKS_HK_HANDLER, q7s::UART_SYRLINKS_DEV, UartModes::NON_CANONICAL, - uart::SYRLINKS_BAUD, SYRLINKS::MAX_REPLY_SIZE); + new UartCookie(objects::SYRLINKS_HK_HANDLER, q7s::UART_SYRLINKS_DEV, uart::SYRLINKS_BAUD, + syrlinks::MAX_REPLY_SIZE, UartModes::NON_CANONICAL); syrlinksUartCookie->setParityEven(); - new SyrlinksHkHandler(objects::SYRLINKS_HK_HANDLER, objects::UART_COM_IF, syrlinksUartCookie); + auto syrlinksHandler = new SyrlinksHkHandler(objects::SYRLINKS_HK_HANDLER, objects::UART_COM_IF, + syrlinksUartCookie, pcdu::PDU1_CH1_SYRLINKS_12V); + syrlinksHandler->setPowerSwitcher(pwrSwitcher); } -void ObjectFactory::createRtdComponents(LinuxLibgpioIF* gpioComIF) { +void ObjectFactory::createPayloadComponents(LinuxLibgpioIF* gpioComIF) { using namespace gpio; - GpioCookie* rtdGpioCookie = new GpioCookie; + std::stringstream consumer; +#if OBSW_ADD_PLOC_MPSOC == 1 + consumer << "0x" << std::hex << objects::PLOC_MPSOC_HANDLER; + auto gpioConfigMPSoC = new GpiodRegularByLineName(q7s::gpioNames::ENABLE_MPSOC_UART, + consumer.str(), Direction::OUT, Levels::HIGH); + auto mpsocGpioCookie = new GpioCookie; + mpsocGpioCookie->addGpio(gpioIds::ENABLE_MPSOC_UART, gpioConfigMPSoC); + gpioComIF->addGpios(mpsocGpioCookie); + auto mpsocCookie = + new UartCookie(objects::PLOC_MPSOC_HANDLER, q7s::UART_PLOC_MPSOC_DEV, uart::PLOC_MPSOC_BAUD, + mpsoc::MAX_REPLY_SIZE, UartModes::NON_CANONICAL); + mpsocCookie->setNoFixedSizeReply(); + auto plocMpsocHelper = new PlocMPSoCHelper(objects::PLOC_MPSOC_HELPER); + new PlocMPSoCHandler(objects::PLOC_MPSOC_HANDLER, objects::UART_COM_IF, mpsocCookie, + plocMpsocHelper, Gpio(gpioIds::ENABLE_MPSOC_UART, gpioComIF), + objects::PLOC_SUPERVISOR_HANDLER); +#endif /* OBSW_ADD_PLOC_MPSOC == 1 */ - 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); - -#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* 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); - -#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 +#if OBSW_ADD_PLOC_SUPERVISOR == 1 + consumer << "0x" << std::hex << objects::PLOC_SUPERVISOR_HANDLER; + auto gpioConfigSupv = new GpiodRegularByLineName(q7s::gpioNames::ENABLE_SUPV_UART, consumer.str(), + Direction::OUT, Levels::HIGH); + auto supvGpioCookie = new GpioCookie; + supvGpioCookie->addGpio(gpioIds::ENABLE_SUPV_UART, gpioConfigSupv); + gpioComIF->addGpios(supvGpioCookie); + auto supervisorCookie = new UartCookie(objects::PLOC_SUPERVISOR_HANDLER, + q7s::UART_PLOC_SUPERVSIOR_DEV, uart::PLOC_SUPERVISOR_BAUD, + supv::MAX_PACKET_SIZE * 20, UartModes::NON_CANONICAL); + supervisorCookie->setNoFixedSizeReply(); + new PlocSupervisorHandler(objects::PLOC_SUPERVISOR_HANDLER, objects::UART_COM_IF, + supervisorCookie, Gpio(gpioIds::ENABLE_SUPV_UART, gpioComIF), + pcdu::PDU1_CH6_PLOC_12V); +#endif /* OBSW_ADD_PLOC_SUPERVISOR == 1 */ + static_cast(consumer); } void ObjectFactory::createReactionWheelComponents(LinuxLibgpioIF* gpioComIF) { @@ -1113,9 +829,15 @@ void ObjectFactory::createCcsdsComponents(LinuxLibgpioIF* gpioComIF) { AxiPtmeConfig* axiPtmeConfig = new AxiPtmeConfig(objects::AXI_PTME_CONFIG, q7s::UIO_PTME, q7s::uiomapids::PTME_CONFIG); PtmeConfig* ptmeConfig = new PtmeConfig(objects::PTME_CONFIG, axiPtmeConfig); +#if OBSW_ENABLE_SYRLINKS_TRANSMIT_TIMEOUT == 1 + // Set to high value when not sending via syrlinks + static const uint32_t TRANSMITTER_TIMEOUT = 86400000; // 1 day +#else + static const uint32_t TRANSMITTER_TIMEOUT = 900000; // 15 minutes +#endif CCSDSHandler* ccsdsHandler = new CCSDSHandler( objects::CCSDS_HANDLER, objects::PTME, objects::CCSDS_PACKET_DISTRIBUTOR, ptmeConfig, - gpioComIF, gpioIds::RS485_EN_TX_CLOCK, gpioIds::RS485_EN_TX_DATA); + gpioComIF, gpioIds::RS485_EN_TX_CLOCK, gpioIds::RS485_EN_TX_DATA, TRANSMITTER_TIMEOUT); VirtualChannel* vc = nullptr; vc = new VirtualChannel(ccsds::VC0, common::VC0_QUEUE_SIZE, objects::CCSDS_HANDLER); @@ -1140,7 +862,6 @@ void ObjectFactory::createCcsdsComponents(LinuxLibgpioIF* gpioComIF) { 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); @@ -1158,10 +879,10 @@ void ObjectFactory::createCcsdsComponents(LinuxLibgpioIF* gpioComIF) { gpioRS485Chip->addGpio(gpioIds::RS485_EN_RX_DATA, gpio); gpioComIF->addGpios(gpioRS485Chip); -#endif /* BOARD_TE0720 == 0 */ } -void ObjectFactory::createPlPcduComponents(LinuxLibgpioIF* gpioComIF, SpiComIF* spiComIF) { +void ObjectFactory::createPlPcduComponents(LinuxLibgpioIF* gpioComIF, SpiComIF* spiComIF, + PowerSwitchIF* pwrSwitcher) { using namespace gpio; // Create all GPIO components first GpioCookie* plPcduGpios = new GpioCookie; @@ -1207,116 +928,24 @@ void ObjectFactory::createPlPcduComponents(LinuxLibgpioIF* gpioComIF, SpiComIF* 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); + auto plPcduHandler = new PayloadPcduHandler( + objects::PLPCDU_HANDLER, objects::SPI_COM_IF, spiCookie, gpioComIF, SdCardManager::instance(), + pwrSwitcher, pcdu::Switches::PDU2_CH1_PL_PCDU_BATT_0_14V8, + pcdu::Switches::PDU2_CH6_PL_PCDU_BATT_1_14V8, false); spiCookie->setCallbackMode(PayloadPcduHandler::extConvAsTwoCallback, plPcduHandler); - static_cast(plPcduHandler); +// plPcduHandler->enablePeriodicPrintout(true, 5); +// static_cast(plPcduHandler); #if OBSW_TEST_PL_PCDU == 1 plPcduHandler->setStartUpImmediately(); +#endif #if OBSW_DEBUG_PL_PCDU == 1 plPcduHandler->setToGoToNormalModeImmediately(true); - plPcduHandler->enablePeriodicPrintout(true, 5); -#endif + plPcduHandler->enablePeriodicPrintout(true, 10); #endif } void ObjectFactory::createTestComponents(LinuxLibgpioIF* gpioComIF) { -#if BOARD_TE0720 == 0 new Q7STestTask(objects::TEST_TASK); -#endif - -#if BOARD_TE0720 == 1 && OBSW_TEST_LIBGPIOD == 1 -#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); -#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); -#endif - -#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_0, std::string("/dev/spidev1.0"), SUS::MAX_CMD_SIZE, - spi::DEFAULT_MAX_1227_MODE, spi::DEFAULT_MAX_1227_SPEED); - - 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_VC0")); - gpioCookieCcsdsIp->addGpio(gpioIds::PAPB_BUSY_N, papbBusyN); - GpiodRegular* papbEmpty = - new GpiodRegular(std::string("gpiochip0"), 1, std::string("PAPBEmpty_VC0")); - gpioCookieCcsdsIp->addGpio(gpioIds::PAPB_EMPTY, papbEmpty); - gpioComIF->addGpios(gpioCookieCcsdsIp); - - new CCSDSIPCoreBridge(objects::CCSDS_IP_CORE_BRIDGE, objects::CCSDS_PACKET_DISTRIBUTOR, - objects::TM_STORE, objects::TC_STORE, gpioComIF, std::string("/dev/uio0"), - gpioIds::PAPB_BUSY_N, gpioIds::PAPB_EMPTY); -#endif - -#if 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); - - 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(); -#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); -#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(); -#endif - #if OBSW_ADD_SPI_TEST_CODE == 1 new SpiTestClass(objects::SPI_TEST, gpioComIF); #endif @@ -1327,3 +956,13 @@ void ObjectFactory::createTestComponents(LinuxLibgpioIF* gpioComIF) { new UartTestClass(objects::UART_TEST); #endif } + +void ObjectFactory::testAcsBrdAss(AcsBoardAssembly* acsAss) { + CommandMessage msg; + ModeMessage::setModeMessage(&msg, ModeMessage::CMD_MODE_COMMAND, DeviceHandlerIF::MODE_NORMAL, + duallane::A_SIDE); + ReturnValue_t result = MessageQueueSenderIF::sendMessage(acsAss->getCommandQueue(), &msg); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "Sending mode command failed" << std::endl; + } +} diff --git a/bsp_q7s/core/ObjectFactory.h b/bsp_q7s/core/ObjectFactory.h index ecc92f01..a812be35 100644 --- a/bsp_q7s/core/ObjectFactory.h +++ b/bsp_q7s/core/ObjectFactory.h @@ -5,6 +5,8 @@ class LinuxLibgpioIF; class UartComIF; class SpiComIF; class I2cComIF; +class PowerSwitchIF; +class AcsBoardAssembly; namespace ObjectFactory { @@ -13,21 +15,23 @@ void produce(void* args); void createCommunicationInterfaces(LinuxLibgpioIF** gpioComIF, UartComIF** uartComIF, SpiComIF** spiComIF, I2cComIF** i2cComIF); - -void createPlPcduComponents(LinuxLibgpioIF* gpioComIF, SpiComIF* spiComIF); +void createPcduComponents(LinuxLibgpioIF* gpioComIF, PowerSwitchIF** pwrSwitcher); +void createPlPcduComponents(LinuxLibgpioIF* gpioComIF, SpiComIF* spiComIF, + PowerSwitchIF* pwrSwitcher); void createTmpComponents(); -void createPcduComponents(LinuxLibgpioIF* gpioComIF); void createRadSensorComponent(LinuxLibgpioIF* gpioComIF); -void createSunSensorComponents(LinuxLibgpioIF* gpioComIF, SpiComIF* spiComIF); -void createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, UartComIF* uartComIF); +void createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, UartComIF* uartComIF, + PowerSwitchIF* pwrSwitcher); void createHeaterComponents(); void createSolarArrayDeploymentComponents(); -void createSyrlinksComponents(); -void createRtdComponents(LinuxLibgpioIF* gpioComIF); +void createSyrlinksComponents(PowerSwitchIF* pwrSwitcher); +void createPayloadComponents(LinuxLibgpioIF* gpioComIF); void createReactionWheelComponents(LinuxLibgpioIF* gpioComIF); void createCcsdsComponents(LinuxLibgpioIF* gpioComIF); void createTestComponents(LinuxLibgpioIF* gpioComIF); +void testAcsBrdAss(AcsBoardAssembly* assAss); + }; // namespace ObjectFactory #endif /* BSP_Q7S_OBJECTFACTORY_H_ */ diff --git a/bsp_q7s/core/obsw.cpp b/bsp_q7s/core/obsw.cpp index 04163a82..359d04c2 100644 --- a/bsp_q7s/core/obsw.cpp +++ b/bsp_q7s/core/obsw.cpp @@ -6,21 +6,18 @@ #include "InitMission.h" #include "OBSWConfig.h" #include "OBSWVersion.h" -#include "fsfw/FSFWVersion.h" #include "fsfw/tasks/TaskFactory.h" -#include "watchdogConf.h" +#include "fsfw/version.h" +#include "watchdog/definitions.h" static int OBSW_ALREADY_RUNNING = -2; int obsw::obsw() { + using namespace fsfw; std::cout << "-- EIVE OBSW --" << std::endl; -#if BOARD_TE0720 == 0 std::cout << "-- Compiled for Linux (Xiphos Q7S) --" << std::endl; -#else - 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; + << FSFW_VERSION << "--" << std::endl; std::cout << "-- " << __DATE__ << " " << __TIME__ << " --" << std::endl; #if Q7S_CHECK_FOR_ALREADY_RUNNING_IMG == 1 diff --git a/bsp_q7s/memory/CMakeLists.txt b/bsp_q7s/memory/CMakeLists.txt index 0658242a..a0d4f66f 100644 --- a/bsp_q7s/memory/CMakeLists.txt +++ b/bsp_q7s/memory/CMakeLists.txt @@ -2,4 +2,5 @@ target_sources(${OBSW_NAME} PRIVATE FileSystemHandler.cpp SdCardManager.cpp scratchApi.cpp + FilesystemHelper.cpp ) \ No newline at end of file diff --git a/bsp_q7s/memory/FileSystemHandler.h b/bsp_q7s/memory/FileSystemHandler.h index 6973c3c8..282cddba 100644 --- a/bsp_q7s/memory/FileSystemHandler.h +++ b/bsp_q7s/memory/FileSystemHandler.h @@ -6,6 +6,7 @@ #include "OBSWConfig.h" #include "SdCardManager.h" +#include "eive/definitions.h" #include "fsfw/ipc/MessageQueueIF.h" #include "fsfw/memory/HasFileSystemIF.h" #include "fsfw/objectmanager/SystemObject.h" diff --git a/bsp_q7s/memory/FilesystemHelper.cpp b/bsp_q7s/memory/FilesystemHelper.cpp new file mode 100644 index 00000000..4b9140f1 --- /dev/null +++ b/bsp_q7s/memory/FilesystemHelper.cpp @@ -0,0 +1,40 @@ +#include "FilesystemHelper.h" + +#include +#include + +#include "bsp_q7s/memory/SdCardManager.h" +#include "fsfw/serviceinterface/ServiceInterfaceStream.h" + +FilesystemHelper::FilesystemHelper() {} + +FilesystemHelper::~FilesystemHelper() {} + +ReturnValue_t FilesystemHelper::checkPath(std::string path) { + SdCardManager* sdcMan = SdCardManager::instance(); + if (sdcMan == nullptr) { + sif::warning << "FilesystemHelper::checkPath: Invalid SD card manager" << std::endl; + return RETURN_FAILED; + } + if (path.substr(0, sizeof(SdCardManager::SD_0_MOUNT_POINT)) == + std::string(SdCardManager::SD_0_MOUNT_POINT)) { + if (!sdcMan->isSdCardMounted(sd::SLOT_0)) { + sif::warning << "FilesystemHelper::checkPath: SD card 0 not mounted" << std::endl; + return SD_NOT_MOUNTED; + } + } else if (path.substr(0, sizeof(SdCardManager::SD_1_MOUNT_POINT)) == + std::string(SdCardManager::SD_1_MOUNT_POINT)) { + if (!sdcMan->isSdCardMounted(sd::SLOT_0)) { + sif::warning << "FilesystemHelper::checkPath: SD card 1 not mounted" << std::endl; + return SD_NOT_MOUNTED; + } + } + return RETURN_OK; +} + +ReturnValue_t FilesystemHelper::fileExists(std::string file) { + if (not std::filesystem::exists(file)) { + return FILE_NOT_EXISTS; + } + return RETURN_OK; +} diff --git a/bsp_q7s/memory/FilesystemHelper.h b/bsp_q7s/memory/FilesystemHelper.h new file mode 100644 index 00000000..cb8e27a8 --- /dev/null +++ b/bsp_q7s/memory/FilesystemHelper.h @@ -0,0 +1,49 @@ +#ifndef BSP_Q7S_MEMORY_FILESYSTEMHELPER_H_ +#define BSP_Q7S_MEMORY_FILESYSTEMHELPER_H_ + +#include + +#include "commonClassIds.h" +#include "fsfw/returnvalues/HasReturnvaluesIF.h" + +/** + * @brief This class implements often used functions concerning the file system management. + * + * @author J. Meier + */ +class FilesystemHelper : public HasReturnvaluesIF { + public: + static const uint8_t INTERFACE_ID = CLASS_ID::FILE_SYSTEM_HELPER; + + //! [EXPORT] : [COMMENT] SD card specified with 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); + + FilesystemHelper(); + virtual ~FilesystemHelper(); + + /** + * @brief In case the path points to a directory on the sd card the function checks if the + * appropriate SD card is mounted. + * + * @param path Path to check + * + * @return RETURN_OK if path points to SD card and the appropriate SD card is mounted or if + * path does not point to SD card. + * Return error code if path points to SD card and the corresponding SD card is not + * mounted. + */ + static ReturnValue_t checkPath(std::string path); + + /** + * @brief Checks if the file exists on the filesystem. + * + * param file File to check + * + * @return RETURN_OK if fiel exists, otherwise return error code. + */ + static ReturnValue_t fileExists(std::string file); +}; + +#endif /* BSP_Q7S_MEMORY_FILESYSTEMHELPER_H_ */ diff --git a/bsp_q7s/memory/SdCardManager.cpp b/bsp_q7s/memory/SdCardManager.cpp index 06072253..4ca11787 100644 --- a/bsp_q7s/memory/SdCardManager.cpp +++ b/bsp_q7s/memory/SdCardManager.cpp @@ -1,6 +1,5 @@ #include "SdCardManager.h" -#include "OBSWConfig.h" #include #include #include @@ -10,6 +9,7 @@ #include #include +#include "OBSWConfig.h" #include "common/config/commonObjects.h" #include "fsfw/ipc/MutexFactory.h" #include "fsfw/serviceinterface/ServiceInterface.h" diff --git a/bsp_q7s/xadc/CMakeLists.txt b/bsp_q7s/xadc/CMakeLists.txt new file mode 100644 index 00000000..0f2ea7df --- /dev/null +++ b/bsp_q7s/xadc/CMakeLists.txt @@ -0,0 +1,3 @@ +target_sources(${OBSW_NAME} PRIVATE + Xadc.cpp +) \ No newline at end of file diff --git a/bsp_q7s/xadc/Xadc.cpp b/bsp_q7s/xadc/Xadc.cpp new file mode 100644 index 00000000..e1f1a505 --- /dev/null +++ b/bsp_q7s/xadc/Xadc.cpp @@ -0,0 +1,144 @@ +#include "Xadc.h" + +#include +#include + +#include + +#include "fsfw/serviceinterface/ServiceInterfaceStream.h" + +Xadc::Xadc() {} + +Xadc::~Xadc() {} + +ReturnValue_t Xadc::getTemperature(float& temperature) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + int raw = 0; + int offset = 0; + float scale = 0; + result = readValFromFile(xadc::file::tempRaw.c_str(), raw); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = readValFromFile(xadc::file::tempOffset.c_str(), offset); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = readValFromFile(xadc::file::tempScale.c_str(), scale); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + temperature = (raw + offset) * scale / 1000; + return result; +} + +ReturnValue_t Xadc::getVccPint(float& vccPint) { + ReturnValue_t result = + readVoltageFromSysfs(xadc::file::vccpintRaw, xadc::file::vccpintScale, vccPint); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t Xadc::getVccPaux(float& vccPaux) { + ReturnValue_t result = + readVoltageFromSysfs(xadc::file::vccpauxRaw, xadc::file::vccpauxScale, vccPaux); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t Xadc::getVccInt(float& vccInt) { + ReturnValue_t result = + readVoltageFromSysfs(xadc::file::vccintRaw, xadc::file::vccintScale, vccInt); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t Xadc::getVccAux(float& vccAux) { + ReturnValue_t result = + readVoltageFromSysfs(xadc::file::vccauxRaw, xadc::file::vccauxScale, vccAux); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t Xadc::getVccBram(float& vccBram) { + ReturnValue_t result = + readVoltageFromSysfs(xadc::file::vccbramRaw, xadc::file::vccbramScale, vccBram); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t Xadc::getVccOddr(float& vccOddr) { + ReturnValue_t result = + readVoltageFromSysfs(xadc::file::vccoddrRaw, xadc::file::vccoddrScale, vccOddr); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t Xadc::getVrefp(float& vrefp) { + ReturnValue_t result = readVoltageFromSysfs(xadc::file::vrefpRaw, xadc::file::vrefpScale, vrefp); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t Xadc::getVrefn(float& vrefn) { + ReturnValue_t result = readVoltageFromSysfs(xadc::file::vrefnRaw, xadc::file::vrefnScale, vrefn); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t Xadc::readVoltageFromSysfs(std::string rawFile, std::string scaleFile, + float& voltage) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + float raw = 0; + float scale = 0; + result = readValFromFile(rawFile.c_str(), raw); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = readValFromFile(scaleFile.c_str(), scale); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + voltage = calculateVoltage(raw, scale); + return result; +} + +float Xadc::calculateVoltage(int raw, float scale) { return static_cast(raw * scale); } + +template +ReturnValue_t Xadc::readValFromFile(const char* filename, T& val) { + FILE* fp; + fp = fopen(filename, "r"); + if (fp == nullptr) { + sif::warning << "Xadc::readValFromFile: Failed to open file " << filename << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } + char valstring[MAX_STR_LENGTH] = ""; + char* returnVal = fgets(valstring, MAX_STR_LENGTH, fp); + if (returnVal == nullptr) { + sif::warning << "Xadc::readValFromFile: Failed to read string from file " << filename + << std::endl; + fclose(fp); + return HasReturnvaluesIF::RETURN_FAILED; + } + std::istringstream valSstream(valstring); + valSstream >> val; + fclose(fp); + return HasReturnvaluesIF::RETURN_OK; +} diff --git a/bsp_q7s/xadc/Xadc.h b/bsp_q7s/xadc/Xadc.h new file mode 100644 index 00000000..92ec2c0c --- /dev/null +++ b/bsp_q7s/xadc/Xadc.h @@ -0,0 +1,108 @@ +#ifndef BSP_Q7S_XADC_XADC_H_ +#define BSP_Q7S_XADC_XADC_H_ + +#include + +#include "fsfw/returnvalues/HasReturnvaluesIF.h" + +namespace xadc { +using namespace std; +static const string iioPath = "/sys/bus/iio/devices/iio:device1"; +namespace file { +static const string tempOffset = iioPath + "/in_temp0_offset"; +static const string tempRaw = iioPath + "/in_temp0_raw"; +static const string tempScale = iioPath + "/in_temp0_scale"; +static const string vccintRaw = iioPath + "/in_voltage0_vccint_raw"; +static const string vccintScale = iioPath + "/in_voltage0_vccint_scale"; +static const string vccauxRaw = iioPath + "/in_voltage1_vccaux_raw"; +static const string vccauxScale = iioPath + "/in_voltage1_vccaux_scale"; +static const string vccbramRaw = iioPath + "/in_voltage2_vccbram_raw"; +static const string vccbramScale = iioPath + "/in_voltage2_vccbram_scale"; +static const string vccpintRaw = iioPath + "/in_voltage3_vccpint_raw"; +static const string vccpintScale = iioPath + "/in_voltage3_vccpint_scale"; +static const string vccpauxRaw = iioPath + "/in_voltage4_vccpaux_raw"; +static const string vccpauxScale = iioPath + "/in_voltage4_vccpaux_scale"; +static const string vccoddrRaw = iioPath + "/in_voltage5_vccoddr_raw"; +static const string vccoddrScale = iioPath + "/in_voltage5_vccoddr_scale"; +static const string vrefpRaw = iioPath + "/in_voltage6_vrefp_raw"; +static const string vrefpScale = iioPath + "/in_voltage6_vrefp_scale"; +static const string vrefnRaw = iioPath + "/in_voltage7_vrefn_raw"; +static const string vrefnScale = iioPath + "/in_voltage7_vrefn_scale"; +} // namespace file +} // namespace xadc + +/** + * @brief Class providing access to the data generated by the analog mixed signal module (XADC). + * + * @details Details about the XADC peripheral of the Zynq-7020 can be found in the UG480 "7-Series + * FPGAs and Zynq-7000 SoC XADC Dual 12-Bit 1 MSPS Analog-to-Digital Converter" user guide + * from Xilinx. + * + * @author J. Meier + */ +class Xadc { + public: + /** + * @brief Constructor + */ + Xadc(); + virtual ~Xadc(); + + /** + * @brief Returns on-chip temperature degree celcius + */ + ReturnValue_t getTemperature(float& temperature); + + /** + * @brief Returns PS internal logic supply voltage in millivolts + */ + ReturnValue_t getVccPint(float& vccPint); + + /** + * @brief Returns PS auxiliary supply voltage in millivolts + */ + ReturnValue_t getVccPaux(float& vccPaux); + + /** + * @brief Returns PL internal supply voltage in millivolts + */ + ReturnValue_t getVccInt(float& vccInt); + + /** + * @brief Returns PL auxiliary supply voltage in millivolts + */ + ReturnValue_t getVccAux(float& vccAux); + + /** + * @brief Returns PL block RAM supply voltage in millivolts + */ + ReturnValue_t getVccBram(float& vccBram); + + /** + * @brief Returns the PS DDR I/O supply voltage + */ + ReturnValue_t getVccOddr(float& vcOddr); + + /** + * @brief Returns XADC reference input voltage relative to GND in millivolts + */ + ReturnValue_t getVrefp(float& vrefp); + + /** + * @brief Returns negative reference input voltage. Should normally be 0 V. + */ + ReturnValue_t getVrefn(float& vrefn); + + private: + // Maximum length of the string representation of a value in a xadc sysfs file + static const uint8_t MAX_STR_LENGTH = 15; + + ReturnValue_t readVoltageFromSysfs(std::string rawFile, std::string scaleFile, float& voltage); + + float calculateVoltage(int raw, float scale); + + template + ReturnValue_t readValFromFile(const char* filename, T& val); +}; + +#endif /* BSP_Q7S_XADC_XADC_H_ */ diff --git a/bsp_te0720_1cfa/CMakeLists.txt b/bsp_te0720_1cfa/CMakeLists.txt new file mode 100644 index 00000000..cb02f937 --- /dev/null +++ b/bsp_te0720_1cfa/CMakeLists.txt @@ -0,0 +1,7 @@ +target_sources(${OBSW_NAME} PUBLIC + InitMission.cpp + main.cpp + ObjectFactory.cpp +) + +add_subdirectory(boardconfig) diff --git a/bsp_te0720_1cfa/InitMission.cpp b/bsp_te0720_1cfa/InitMission.cpp new file mode 100644 index 00000000..f1809bca --- /dev/null +++ b/bsp_te0720_1cfa/InitMission.cpp @@ -0,0 +1,188 @@ +#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 << "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( + "UART_PST", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 1.0, missedDeadlineFunc); + result = pst::pstUart(pst); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "InitMission::initTasks: Creating PST failed!" << std::endl; + } + pstTasks.push_back(pst); + + PeriodicTaskIF* mpsocHelperTask = factory->createPeriodicTask( + "PLOC_MPSOC_HELPER", 20, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc); + result = mpsocHelperTask->addComponent(objects::PLOC_MPSOC_HELPER); + if (result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PLOC_MPSOC_HELPER", objects::PLOC_MPSOC_HELPER); + } + pstTasks.push_back(mpsocHelperTask); + + 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_te0720_1cfa/InitMission.h b/bsp_te0720_1cfa/InitMission.h new file mode 100644 index 00000000..c3ba58ec --- /dev/null +++ b/bsp_te0720_1cfa/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_te0720_1cfa/ObjectFactory.cpp b/bsp_te0720_1cfa/ObjectFactory.cpp new file mode 100644 index 00000000..eb6c4fa4 --- /dev/null +++ b/bsp_te0720_1cfa/ObjectFactory.cpp @@ -0,0 +1,151 @@ +#include "ObjectFactory.h" + +#include +#include "fsfw_hal/linux/uart/UartComIF.h" +#include "fsfw_hal/linux/i2c/I2cComIF.h" +#include "fsfw_hal/linux/uart/UartCookie.h" + +#include "OBSWConfig.h" +#include "busConf.h" +#include "devConf.h" +#include "fsfw/datapoollocal/LocalDataPoolManager.h" +#include "fsfw/tmtcpacket/pus/tm.h" +#include "fsfw/tmtcservices/CommandingServiceBase.h" +#include "fsfw/tmtcservices/PusServiceBase.h" +#include "fsfw_hal/linux/i2c/I2cCookie.h" +#include "linux/devices/ploc/PlocMPSoCHandler.h" +#include "linux/devices/ploc/PlocMPSoCHelper.h" +#include "mission/devices/Tmp1075Handler.h" +#include "mission/core/GenericFactory.h" +#include "mission/utility/TmFunnel.h" +#include "test/gpio/DummyGpioIF.h" +#include "objects/systemObjectList.h" +#include "devices/addresses.h" +#include "devices/gpioIds.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(); + +#if OBSW_ADD_PLOC_MPSOC == 1 + UartCookie* mpsocUartCookie = new UartCookie(objects::PLOC_MPSOC_HANDLER, te0720_1cfa::MPSOC_UART, + uart::PLOC_MPSOC_BAUD, mpsoc::MAX_REPLY_SIZE); + mpsocUartCookie->setNoFixedSizeReply(); + PlocMPSoCHelper* plocMpsocHelper = new PlocMPSoCHelper(objects::PLOC_MPSOC_HELPER); + new UartComIF(objects::UART_COM_IF); + auto dummyGpioIF = new DummyGpioIF(); + PlocMPSoCHandler* plocMPSoCHandler = new PlocMPSoCHandler( + objects::PLOC_MPSOC_HANDLER, objects::UART_COM_IF, mpsocUartCookie, plocMpsocHelper, + Gpio(gpioIds::ENABLE_MPSOC_UART, dummyGpioIF), objects::PLOC_SUPERVISOR_HANDLER); + plocMPSoCHandler->setStartUpImmediately(); +#endif /* OBSW_ADD_PLOC_MPSOC == 1 */ + +#if OBSW_TEST_LIBGPIOD == 1 +#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); +#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); +#endif + +#if 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_0, std::string("/dev/spidev1.0"), SUS::MAX_CMD_SIZE, + spi::DEFAULT_MAX_1227_MODE, spi::DEFAULT_MAX_1227_SPEED); + + new SusHandler(objects::SUS_0, objects::SPI_COM_IF, spiCookieSus, gpioComIF, gpioIds::CS_SUS_0); +#endif + +#if OBSW_TEST_CCSDS_BRIDGE == 1 + GpioCookie* gpioCookieCcsdsIp = new GpioCookie; + GpiodRegular* papbBusyN = + new GpiodRegular(std::string("gpiochip0"), 0, std::string("PAPBBusy_VC0")); + gpioCookieCcsdsIp->addGpio(gpioIds::PAPB_BUSY_N, papbBusyN); + GpiodRegular* papbEmpty = + new GpiodRegular(std::string("gpiochip0"), 1, std::string("PAPBEmpty_VC0")); + gpioCookieCcsdsIp->addGpio(gpioIds::PAPB_EMPTY, papbEmpty); + gpioComIF->addGpios(gpioCookieCcsdsIp); + + new CCSDSIPCoreBridge(objects::CCSDS_IP_CORE_BRIDGE, objects::CCSDS_PACKET_DISTRIBUTOR, + objects::TM_STORE, objects::TC_STORE, gpioComIF, std::string("/dev/uio0"), + gpioIds::PAPB_BUSY_N, gpioIds::PAPB_EMPTY); +#endif + +#if OBSW_TEST_RAD_SENSOR == 1 + GpioCookie* gpioCookieRadSensor = new GpioCookie; + GpiodRegular* chipSelectRadSensor = new GpiodRegular( + 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); + + RadiationSensorHandler* radSensor = + new RadiationSensorHandler(objects::RAD_SENSOR, objects::SPI_COM_IF, spiCookieRadSensor); + radSensor->setStartUpImmediately(); +#endif + +#if 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); +#endif + +#if OBSW_ADD_PLOC_SUPERVISOR == 1 + /* Configuration for MIO0 on TE0720-03-1CFA */ + UartCookie* plocSupervisorCookie = + new UartCookie(objects::PLOC_SUPERVISOR_HANDLER, std::string("/dev/ttyPS1"), + UartModes::NON_CANONICAL, 115200, PLOC_SPV::MAX_PACKET_SIZE * 20); + plocSupervisorCookie->setNoFixedSizeReply(); + PlocSupervisorHandler* plocSupervisor = new PlocSupervisorHandler( + objects::PLOC_SUPERVISOR_HANDLER, objects::UART_COM_IF, plocSupervisorCookie); + plocSupervisor->setStartUpImmediately(); +#endif + +new I2cComIF(objects::I2C_COM_IF); + +I2cCookie* i2cCookieTmp1075tcs1 = + new I2cCookie(addresses::TMP1075_TCS_1, TMP1075::MAX_REPLY_LENGTH, std::string("/dev/i2c-0")); +I2cCookie* i2cCookieTmp1075tcs2 = + new I2cCookie(addresses::TMP1075_TCS_2, TMP1075::MAX_REPLY_LENGTH, std::string("/dev/i2c-0")); + +/* Temperature sensors */ +new Tmp1075Handler(objects::TMP1075_HANDLER_1, objects::I2C_COM_IF, i2cCookieTmp1075tcs1); +new Tmp1075Handler(objects::TMP1075_HANDLER_2, objects::I2C_COM_IF, i2cCookieTmp1075tcs2); +} diff --git a/bsp_te0720_1cfa/ObjectFactory.h b/bsp_te0720_1cfa/ObjectFactory.h new file mode 100644 index 00000000..b24dd321 --- /dev/null +++ b/bsp_te0720_1cfa/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_te0720_1cfa/boardconfig/CMakeLists.txt b/bsp_te0720_1cfa/boardconfig/CMakeLists.txt new file mode 100644 index 00000000..f9136e3e --- /dev/null +++ b/bsp_te0720_1cfa/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_te0720_1cfa/boardconfig/busConf.h b/bsp_te0720_1cfa/boardconfig/busConf.h new file mode 100644 index 00000000..893014c1 --- /dev/null +++ b/bsp_te0720_1cfa/boardconfig/busConf.h @@ -0,0 +1,11 @@ +#ifndef BSP_EGSE_BOARDCONFIG_BUSCONF_H_ +#define BSP_EGSE_BOARDCONFIG_BUSCONF_H_ + +namespace te0720_1cfa { +static constexpr char MPSOC_UART[] = "/dev/ttyPS1"; +namespace baudrate { + +} +} + +#endif /* BSP_EGSE_BOARDCONFIG_BUSCONF_H_ */ diff --git a/bsp_te0720_1cfa/boardconfig/etl_profile.h b/bsp_te0720_1cfa/boardconfig/etl_profile.h new file mode 100644 index 00000000..54aca344 --- /dev/null +++ b/bsp_te0720_1cfa/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_te0720_1cfa/boardconfig/gcov.h b/bsp_te0720_1cfa/boardconfig/gcov.h new file mode 100644 index 00000000..80acdd86 --- /dev/null +++ b/bsp_te0720_1cfa/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_te0720_1cfa/boardconfig/print.c b/bsp_te0720_1cfa/boardconfig/print.c new file mode 100644 index 00000000..1739e90b --- /dev/null +++ b/bsp_te0720_1cfa/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_te0720_1cfa/boardconfig/print.h b/bsp_te0720_1cfa/boardconfig/print.h new file mode 100644 index 00000000..8e7e2e5d --- /dev/null +++ b/bsp_te0720_1cfa/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_te0720_1cfa/main.cpp b/bsp_te0720_1cfa/main.cpp new file mode 100644 index 00000000..cb7d987e --- /dev/null +++ b/bsp_te0720_1cfa/main.cpp @@ -0,0 +1,29 @@ +#include + +#include "InitMission.h" +#include "OBSWConfig.h" +#include "OBSWVersion.h" +#include "fsfw/version.h" +#include "fsfw/tasks/TaskFactory.h" + +/** + * @brief This is the main program entry point for the obsw running on the trenz electronic + * te0720-1cfa. + * @return + */ +int main(void) { + using namespace fsfw; + std::cout << "-- EIVE OBSW --" << std::endl; + std::cout << "-- Compiled for Trenz TE0720-1CFA" + << " --" << std::endl; + std::cout << "-- OBSW v" << SW_VERSION << "." << SW_SUBVERSION << "." << SW_REVISION << ", FSFW v" + << FSFW_VERSION << "--" << std::endl; + std::cout << "-- " << __DATE__ << " " << __TIME__ << " --" << std::endl; + + initmission::initMission(); + + for (;;) { + /* Suspend main thread by sleeping it. */ + TaskFactory::delayTask(5000); + } +} diff --git a/cmake/HardwareOsPreConfig.cmake b/cmake/HardwareOsPreConfig.cmake index 88df808c..7b90eb54 100644 --- a/cmake/HardwareOsPreConfig.cmake +++ b/cmake/HardwareOsPreConfig.cmake @@ -59,6 +59,8 @@ if(TGT_BSP) set(BSP_PATH "bsp_q7s") elseif(TGT_BSP MATCHES "arm/egse") set(BSP_PATH "bsp_egse") + elseif(TGT_BSP MATCHES "arm/te0720-1cfa") + set(BSP_PATH "bsp_te0720_1cfa") 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 fa50baf3..41dd7de4 100644 --- a/cmake/PreProjectConfig.cmake +++ b/cmake/PreProjectConfig.cmake @@ -12,9 +12,9 @@ endif() # Disable compiler checks for cross-compiling. if(FSFW_OSAL MATCHES linux AND TGT_BSP) - if(TGT_BSP MATCHES "arm/q7s") + if(TGT_BSP MATCHES "arm/q7s" OR TGT_BSP MATCHES "arm/te0720-1cfa") set(CMAKE_TOOLCHAIN_FILE - "${CMAKE_SCRIPT_PATH}/Q7SCrossCompileConfig.cmake" + "${CMAKE_SCRIPT_PATH}/Zynq7020CrossCompileConfig.cmake" PARENT_SCOPE ) elseif(TGT_BSP MATCHES "arm/raspberrypi" OR TGT_BSP MATCHES "arm/egse") diff --git a/cmake/Q7SCrossCompileConfig.cmake b/cmake/Zynq7020CrossCompileConfig.cmake similarity index 87% rename from cmake/Q7SCrossCompileConfig.cmake rename to cmake/Zynq7020CrossCompileConfig.cmake index db05c8f0..be6702a1 100644 --- a/cmake/Q7SCrossCompileConfig.cmake +++ b/cmake/Zynq7020CrossCompileConfig.cmake @@ -1,16 +1,16 @@ -if(DEFINED ENV{Q7S_SYSROOT}) - set(ENV{Q7S_ROOTFS} $ENV{Q7S_SYSROOT}) +if(DEFINED ENV{ZYNQ_7020_SYSROOT}) + set(ENV{ZYNQ_7020_ROOTFS} $ENV{ZYNQ_7020_SYSROOT}) endif() # CROSS_COMPILE also needs to be set accordingly or passed to the CMake command -if(NOT DEFINED ENV{Q7S_ROOTFS}) +if(NOT DEFINED ENV{ZYNQ_7020_ROOTFS}) # Sysroot has not been cached yet and was not set in environment either if(NOT DEFINED SYSROOT_PATH) message(FATAL_ERROR - "Define the Q7S_ROOTFS variable to point to the Q7S rootfs." + "Define the ZYNQ_7020_ROOTFS variable to point to the Zynq-7020 rootfs." ) endif() else() - set(SYSROOT_PATH "$ENV{Q7S_ROOTFS}" CACHE PATH "Q7S root filesystem path") + set(SYSROOT_PATH "$ENV{ZYNQ_7020_ROOTFS}" CACHE PATH "Zynq-7020 root filesystem path") endif() if(NOT DEFINED ENV{CROSS_COMPILE}) @@ -87,18 +87,21 @@ set(C_FLAGS -mfloat-abi=hard ${COMMON_FLAGS} -lgpiod - -lxiphos ) +if (TGT_BSP MATCHES "arm/q7s") + set(C_FLAGS ${C_FLAGS} -lxiphos) +endif() + string (REPLACE ";" " " C_FLAGS "${C_FLAGS}") set(CMAKE_C_FLAGS ${C_FLAGS} - CACHE STRING "C flags for Q7S" + CACHE STRING "C flags for Zynq-7020" ) set(CMAKE_CXX_FLAGS "${CMAKE_C_FLAGS}" - CACHE STRING "CPP flags for Q7S" + CACHE STRING "CPP flags for Zynq-7020" ) # search for programs in the build host directories diff --git a/cmake/scripts/Q7S/q7s-env.sh b/cmake/scripts/Q7S/q7s-env.sh index 818ff213..df9dbadc 100755 --- a/cmake/scripts/Q7S/q7s-env.sh +++ b/cmake/scripts/Q7S/q7s-env.sh @@ -2,6 +2,6 @@ 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 ZYNQ_7020_SYSROOT="$HOME/Xilinx/cortexa9hf-neon-xiphos-linux-gnueabi" export CONSOLE_PREFIX="[Q7S ENV]" /bin/bash diff --git a/cmake/scripts/Q7S/win-q7s-env.sh b/cmake/scripts/Q7S/win-q7s-env.sh new file mode 100644 index 00000000..703949e3 --- /dev/null +++ b/cmake/scripts/Q7S/win-q7s-env.sh @@ -0,0 +1,49 @@ +#!/bin/sh +# Run with: source win-q7s-env.sh [OPTIONS] +function help () { + echo "source win-q7s-env.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 ZYNQ_7020_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/cmake-build-cfg.py b/cmake/scripts/cmake-build-cfg.py index 5d1b1048..4c5ee536 100755 --- a/cmake/scripts/cmake-build-cfg.py +++ b/cmake/scripts/cmake-build-cfg.py @@ -12,6 +12,7 @@ import os import sys import argparse import shutil +import stat def main(): @@ -102,7 +103,7 @@ def main(): build_path = source_location + os.path.sep + build_folder remove_old_dir = False if remove_old_dir: - shutil.rmtree(build_path) + rm_build_dir(build_path) os.chdir(source_location) os.mkdir(build_folder) print(f"Navigating into build directory: {build_path}") @@ -117,6 +118,14 @@ def main(): print(f"\" {cmake_command} \"") os.system(cmake_command) print("-- CMake configuration done. --") + + +def rm_build_dir(path: str): + # On windows the permissions of the build directory may have been set to read-only. If this + # is the case the permissions are changed before trying to delete the directory. + if not os.access(path, os.W_OK): + os.chmod(path, stat.S_IWUSR) + shutil.rmtree(path) def determine_source_location() -> str: diff --git a/cmake/scripts/te0720-1cfa/make-debug-cfg.sh b/cmake/scripts/te0720-1cfa/make-debug-cfg.sh new file mode 100644 index 00000000..46008c41 --- /dev/null +++ b/cmake/scripts/te0720-1cfa/make-debug-cfg.sh @@ -0,0 +1,34 @@ +#!/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/te0720-1cfa" +build_generator="make" +build_dir="build-Debug-te0720-1cfa" +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}" \ + -l"${build_dir}" +# set +x diff --git a/cmake/scripts/Q7S/q7s-env-win.sh b/cmake/scripts/te0720-1cfa/win-env-te0720-1cfa.sh similarity index 87% rename from cmake/scripts/Q7S/q7s-env-win.sh rename to cmake/scripts/te0720-1cfa/win-env-te0720-1cfa.sh index 2cbc0bab..e77de4c8 100644 --- a/cmake/scripts/Q7S/q7s-env-win.sh +++ b/cmake/scripts/te0720-1cfa/win-env-te0720-1cfa.sh @@ -5,7 +5,7 @@ function help () { } 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" +SYSROOT="/c/Users/${USER}/eive-software/sysroots-petalinux-2019-2/cortexa9t2hf-neon-xilinx-linux-gnueabi" for i in "$@"; do case $i in @@ -41,7 +41,7 @@ else fi if [ -d "$SYSROOT" ]; then - export Q7S_SYSROOT=$SYSROOT + export ZYNQ_7020_SYSROOT=$SYSROOT echo "Set sysroot path to $SYSROOT" else echo "Sysroot path $SYSROOT does not exist" diff --git a/common/config/commonClassIds.h b/common/config/commonClassIds.h index 01f186a4..03d51888 100644 --- a/common/config/commonClassIds.h +++ b/common/config/commonClassIds.h @@ -13,7 +13,8 @@ enum commonClassIds: uint8_t { IMTQ_HANDLER, //IMTQ RW_HANDLER, //RWHA STR_HANDLER, //STRH - PLOC_MPSOC_HANDLER, //PLMP + DWLPWRON_CMD, //DWLPWRON + MPSOC_TM, //MPTM PLOC_SUPERVISOR_HANDLER, //PLSV SUS_HANDLER, //SUSS CCSDS_IP_CORE_BRIDGE, //IPCI @@ -27,7 +28,10 @@ enum commonClassIds: uint8_t { RATE_SETTER, //RS ARCSEC_JSON_BASE, //JSONBASE NVM_PARAM_BASE, //NVMB + FILE_SYSTEM_HELPER, //FSHLP + PLOC_MPSOC_HELPER, // PLMPHLP SA_DEPL_HANDLER, //SADPL + MPSOC_RETURN_VALUES_IF, //MPSOCRTVIF COMMON_CLASS_ID_END // [EXPORT] : [END] }; diff --git a/common/config/commonObjects.h b/common/config/commonObjects.h index 6cc90be9..a4f3319e 100644 --- a/common/config/commonObjects.h +++ b/common/config/commonObjects.h @@ -42,6 +42,7 @@ enum commonObjects: uint32_t { IMTQ_HANDLER = 0x44140014, PLOC_MPSOC_HANDLER = 0x44330015, PLOC_SUPERVISOR_HANDLER = 0x44330016, + PLOC_SUPERVISOR_HELPER = 0x44330017, /** * Not yet specified which pt1000 will measure which device/location in the satellite. @@ -89,8 +90,14 @@ enum commonObjects: uint32_t { PLOC_UPDATER = 0x44330000, PLOC_MEMORY_DUMPER = 0x44330001, STR_HELPER = 0x44330002, - AXI_PTME_CONFIG = 44330003, - PTME_CONFIG = 44330004, + PLOC_MPSOC_HELPER = 0x44330003, + AXI_PTME_CONFIG = 44330004, + PTME_CONFIG = 44330005, + + // 0x73 ('s') for assemblies and system/subsystem components + ACS_BOARD_ASS = 0x73000001, + SUS_BOARD_ASS = 0x73000002, + TCS_BOARD_ASS = 0x73000003 }; } diff --git a/common/config/commonSubsystemIds.h b/common/config/commonSubsystemIds.h index 9f293ec6..cd692231 100644 --- a/common/config/commonSubsystemIds.h +++ b/common/config/commonSubsystemIds.h @@ -6,20 +6,30 @@ namespace SUBSYSTEM_ID { enum: uint8_t { COMMON_SUBSYSTEM_ID_START = FW_SUBSYSTEM_ID_RANGE, - PCDU_HANDLER = 108, - HEATER_HANDLER = 109, - SA_DEPL_HANDLER = 110, - PLOC_MPSOC_HANDLER = 111, - IMTQ_HANDLER = 112, - RW_HANDLER = 113, - STR_HANDLER = 114, - PLOC_SUPERVISOR_HANDLER = 115, - FILE_SYSTEM = 116, - PLOC_UPDATER = 117, - PLOC_MEMORY_DUMPER = 118, - PDEC_HANDLER = 119, - STR_HELPER = 120, - PL_PCDU_HANDLER = 121, + ACS_SUBSYSTEM = 112, + PCDU_HANDLER = 113, + HEATER_HANDLER = 114, + SA_DEPL_HANDLER = 115, + PLOC_MPSOC_HANDLER = 116, + IMTQ_HANDLER = 117, + RW_HANDLER = 118, + STR_HANDLER = 119, + PLOC_SUPERVISOR_HANDLER = 120, + FILE_SYSTEM = 121, + PLOC_UPDATER = 122, + PLOC_MEMORY_DUMPER = 123, + PDEC_HANDLER = 124, + STR_HELPER = 125, + PLOC_MPSOC_HELPER = 126, + PL_PCDU_HANDLER = 127, + ACS_BOARD_ASS = 128, + SUS_BOARD_ASS = 129, + TCS_BOARD_ASS = 130, + GPS_HANDLER = 131, + P60_DOCK_HANDLER = 132, + PDU1_HANDLER = 133, + PDU2_HANDLER = 134, + ACU_HANDLER = 135, COMMON_SUBSYSTEM_ID_END }; } diff --git a/common/config/devConf.h b/common/config/devConf.h index 8a35a0fa..abb3b3e1 100644 --- a/common/config/devConf.h +++ b/common/config/devConf.h @@ -3,6 +3,7 @@ #include #include +#include /** * SPI configuration will be contained here to let the device handlers remain independent @@ -28,6 +29,7 @@ static constexpr spi::SpiModes DEFAULT_L3G_MODE = spi::SpiModes::MODE_3; * 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 spi::SpiModes SUS_MAX_1227_MODE = spi::SpiModes::MODE_3; static constexpr uint32_t DEFAULT_MAX_1227_SPEED = 976'000; static constexpr spi::SpiModes DEFAULT_MAX_1227_MODE = spi::SpiModes::MODE_3; @@ -48,11 +50,11 @@ static constexpr spi::SpiModes RTD_MODE = spi::SpiModes::MODE_3; 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 = 921600; -static constexpr uint32_t PLOC_SUPERVISOR_BAUD = 115200; -static constexpr uint32_t STAR_TRACKER_BAUD = 921600; +static constexpr UartBaudRate SYRLINKS_BAUD = UartBaudRate::RATE_38400; +static constexpr UartBaudRate GNSS_BAUD = UartBaudRate::RATE_9600; +static constexpr UartBaudRate PLOC_MPSOC_BAUD = UartBaudRate::RATE_115200; +static constexpr UartBaudRate PLOC_SUPERVISOR_BAUD = UartBaudRate::RATE_115200; +static constexpr UartBaudRate STAR_TRACKER_BAUD = UartBaudRate::RATE_921600; } diff --git a/common/config/devices/gpioIds.h b/common/config/devices/gpioIds.h index e6f42eb4..199439cc 100644 --- a/common/config/devices/gpioIds.h +++ b/common/config/devices/gpioIds.h @@ -119,7 +119,11 @@ enum gpioId_t { PLPCDU_ENB_TX, PLPCDU_ENB_HPA, PLPCDU_ENB_MPA, - PLPCDU_ADC_CS + PLPCDU_ADC_CS, + + ENABLE_MPSOC_UART, + ENABLE_SUPV_UART + }; } diff --git a/common/config/devices/powerSwitcherList.h b/common/config/devices/powerSwitcherList.h index 45428a2e..d032428b 100644 --- a/common/config/devices/powerSwitcherList.h +++ b/common/config/devices/powerSwitcherList.h @@ -1,60 +1,6 @@ #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; -} - +#include "mission/devices/devicedefinitions/GomspaceDefinitions.h" #endif /* FSFWCONFIG_DEVICES_POWERSWITCHERLIST_H_ */ diff --git a/common/config/eive/definitions.h b/common/config/eive/definitions.h new file mode 100644 index 00000000..db430540 --- /dev/null +++ b/common/config/eive/definitions.h @@ -0,0 +1,25 @@ +#ifndef COMMON_CONFIG_DEFINITIONS_H_ +#define COMMON_CONFIG_DEFINITIONS_H_ + +#include + +namespace config { + +static constexpr uint32_t PL_PCDU_TRANSITION_TIMEOUT_MS = 20 * 60 * 1000; +static constexpr uint32_t LONGEST_MODE_TIMEOUT_SECONDS = PL_PCDU_TRANSITION_TIMEOUT_MS / 1000; + +/* 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; + +/* Limits for filename and path checks */ +static constexpr uint32_t MAX_PATH_SIZE = 100; +static constexpr uint32_t MAX_FILENAME_SIZE = 50; + +} + + +#endif /* COMMON_CONFIG_DEFINITIONS_H_ */ diff --git a/fsfw b/fsfw index 47d15815..613dbe95 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 47d158156b9efa0edbca9b3a1694f4132b0b30e5 +Subproject commit 613dbe9592c30d9acf4cdb95d81d9f216f07374b diff --git a/generators/.gitignore b/generators/.gitignore index 181d655f..889fd273 100644 --- a/generators/.gitignore +++ b/generators/.gitignore @@ -1 +1,2 @@ .~lock* +/venv diff --git a/generators/.run/events.run.xml b/generators/.run/events.run.xml index 18f71033..6bc73c96 100644 --- a/generators/.run/events.run.xml +++ b/generators/.run/events.run.xml @@ -12,7 +12,7 @@