diff --git a/.vscode/c_cpp_properties.json b/.vscode/c_cpp_properties.json index f271484838c73b30512fd12e39515d079062ba97..8904aa9867061dead40b723fc7546c552407fbe6 100755 --- a/.vscode/c_cpp_properties.json +++ b/.vscode/c_cpp_properties.json @@ -487,6 +487,28 @@ "${workspaceFolder}/skyward-boardcore/src/bsps/stm32f767zi_orion_biscotto" ] }, + { + "name": "stm32f767zi_orion_engine", + "cStandard": "c11", + "cppStandard": "c++14", + "compilerPath": "/opt/arm-miosix-eabi/bin/arm-miosix-eabi-g++", + "defines": [ + "${defaultDefines}", + "_MIOSIX_BOARDNAME=stm32f767zi_orion_engine", + "_BOARD_STM32F767ZI_ORION_ENGINE", + "_ARCH_CORTEXM7_STM32F7", + "HSE_VALUE=25000000", + "SYSCLK_FREQ_216MHz=216000000", + "__ENABLE_XRAM", + "V_DDA_VOLTAGE=3.3f" + ], + "includePath": [ + "${defaultIncludePaths}", + "${workspaceFolder}/skyward-boardcore/libs/miosix-kernel/miosix/arch/cortexM7_stm32f7/common", + "${workspaceFolder}/skyward-boardcore/src/bsps/stm32f767zi_orion_engine/config", + "${workspaceFolder}/skyward-boardcore/src/bsps/stm32f767zi_orion_engine" + ] + }, { "name": "logdecoder", "includePath": [ diff --git a/CMakeLists.txt b/CMakeLists.txt index 1902a11e287e5a8d2e1ebe2c2e0f5b8eae44a0c1..3eb32d9e4343a445fe18f306c9c70ab01351e592 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -64,9 +64,9 @@ target_include_directories(payload-entry-euroc PRIVATE ${OBSW_INCLUDE_DIRS}) target_compile_definitions(payload-entry-euroc PRIVATE EUROC) sbs_target(payload-entry-euroc stm32f767zi_lyra_biscotto) -add_executable(motor-entry src/Motor/motor-entry.cpp ${MOTOR_SOURCES}) -target_include_directories(motor-entry PRIVATE ${OBSW_INCLUDE_DIRS}) -sbs_target(motor-entry stm32f767zi_lyra_motor) +add_executable(engine-entry src/Engine/engine-entry.cpp ${ENGINE_SOURCES}) +target_include_directories(engine-entry PRIVATE ${OBSW_INCLUDE_DIRS}) +sbs_target(engine-entry stm32f767zi_orion_engine) add_executable(rig-v2-entry src/RIGv2/rig-v2-entry.cpp ${RIG_V2_COMPUTER}) target_include_directories(rig-v2-entry PRIVATE ${OBSW_INCLUDE_DIRS}) diff --git a/cmake/dependencies.cmake b/cmake/dependencies.cmake index 31286e428d19780d9c6f8c07aaed992cff7e5c6e..e03e2ad7f380b198169103dd92d0987fcc8d4164 100644 --- a/cmake/dependencies.cmake +++ b/cmake/dependencies.cmake @@ -49,12 +49,12 @@ set(GROUNDSTATION_COMMON src/Groundstation/Common/HubBase.cpp ) -set(MOTOR_SOURCES - src/Motor/PersistentVars/PersistentVars.cpp - src/Motor/HIL/HIL.cpp - src/Motor/Actuators/Actuators.cpp - src/Motor/Sensors/Sensors.cpp - src/Motor/CanHandler/CanHandler.cpp +set(ENGINE_SOURCES + src/Engine/PersistentVars/PersistentVars.cpp + src/Engine/HIL/HIL.cpp + src/Engine/Actuators/Actuators.cpp + src/Engine/Sensors/Sensors.cpp + src/Engine/CanHandler/CanHandler.cpp ) set(RIG_V2_COMPUTER diff --git a/scripts/logdecoder/Motor/Makefile b/scripts/logdecoder/Engine/Makefile similarity index 100% rename from scripts/logdecoder/Motor/Makefile rename to scripts/logdecoder/Engine/Makefile diff --git a/scripts/logdecoder/Motor/logdecoder.cpp b/scripts/logdecoder/Engine/logdecoder.cpp similarity index 93% rename from scripts/logdecoder/Motor/logdecoder.cpp rename to scripts/logdecoder/Engine/logdecoder.cpp index 18396a28d251c26c7914c26fff4d4359cf96ef3d..451f27d63624cc3697d2f622f0add7df7e68b785 100644 --- a/scripts/logdecoder/Motor/logdecoder.cpp +++ b/scripts/logdecoder/Engine/logdecoder.cpp @@ -20,8 +20,8 @@ * THE SOFTWARE. */ -#include <Motor/Actuators/ActuatorsData.h> -#include <Motor/Sensors/SensorsData.h> +#include <Engine/Actuators/ActuatorsData.h> +#include <Engine/Sensors/SensorsData.h> #include <logger/Deserializer.h> #include <logger/LogTypes.h> #include <tscpp/stream.h> @@ -43,7 +43,7 @@ using namespace tscpp; using namespace Boardcore; -using namespace Motor; +using namespace Engine; void registerTypes(Deserializer& ds) { @@ -51,8 +51,9 @@ void registerTypes(Deserializer& ds) LogTypes::registerTypes(ds); // Custom types - ds.registerType<TopTankPressureData>(); - ds.registerType<BottomTankPressureData>(); + ds.registerType<OxTopTankPressureData>(); + ds.registerType<OxBottomTankPressureData>(); + ds.registerType<N2TankPressureData>(); ds.registerType<CCPressureData>(); ds.registerType<ActuatorsData>(); } diff --git a/scripts/logdecoder/General/logdecoder.cpp b/scripts/logdecoder/General/logdecoder.cpp index a237a6efc86fc7c05e94f49c7dc478fe92f2bd63..3e9e5cf83002cd38061b20dfa866055187fbb7e7 100644 --- a/scripts/logdecoder/General/logdecoder.cpp +++ b/scripts/logdecoder/General/logdecoder.cpp @@ -30,8 +30,8 @@ #include <Main/StateMachines/FlightModeManager/FlightModeManagerData.h> #include <Main/StateMachines/MEAController/MEAControllerData.h> #include <Main/StateMachines/NASController/NASControllerData.h> -#include <Motor/Actuators/ActuatorsData.h> -#include <Motor/Sensors/SensorsData.h> +#include <Engine/Actuators/ActuatorsData.h> +#include <Engine/Sensors/SensorsData.h> #include <Payload/PinHandler/PinData.h> #include <Payload/Sensors/SensorData.h> #include <Payload/StateMachines/FlightModeManager/FlightModeManagerData.h> @@ -89,11 +89,12 @@ void registerTypes(Deserializer& ds) ds.registerType<Main::LIS2MDLExternalData>(); ds.registerType<Main::CalibrationData>(); - // Motor - ds.registerType<Motor::TopTankPressureData>(); - ds.registerType<Motor::BottomTankPressureData>(); - ds.registerType<Motor::CCPressureData>(); - ds.registerType<Motor::ActuatorsData>(); + // Engine + ds.registerType<Engine::OxTopTankPressureData>(); + ds.registerType<Engine::OxBottomTankPressureData>(); + ds.registerType<Engine::N2TankPressureData>(); + ds.registerType<Engine::CCPressureData>(); + ds.registerType<Engine::ActuatorsData>(); // Payload ds.registerType<Payload::FlightModeManagerStatus>(); diff --git a/src/Motor/Actuators/Actuators.cpp b/src/Engine/Actuators/Actuators.cpp similarity index 83% rename from src/Motor/Actuators/Actuators.cpp rename to src/Engine/Actuators/Actuators.cpp index 8582d035f283338c4c430993bcfff76c04cfc1a1..446cbffa3420f72960e0413e56dc3473938ea7a7 100644 --- a/src/Motor/Actuators/Actuators.cpp +++ b/src/Engine/Actuators/Actuators.cpp @@ -22,13 +22,13 @@ #include "Actuators.h" -#include <Motor/Actuators/ActuatorsData.h> -#include <Motor/Configs/ActuatorsConfig.h> +#include <Engine/Actuators/ActuatorsData.h> +#include <Engine/Configs/ActuatorsConfig.h> #include <interfaces-impl/hwmapping.h> using namespace miosix; using namespace Boardcore; -using namespace Motor; +using namespace Engine; void Actuators::ServoInfo::openServoWithTime(uint32_t time) { @@ -74,13 +74,21 @@ float Actuators::ServoInfo::getServoPosition() Actuators::Actuators() { infos[0].servo = std::make_unique<Servo>( - MIOSIX_SERVOS_1_TIM, TimerUtils::Channel::MIOSIX_SERVOS_1_CHANNEL, + MIOSIX_SERVOS_0_TIM, TimerUtils::Channel::MIOSIX_SERVOS_0_CHANNEL, Config::Servos::MIN_PULSE, Config::Servos::MAX_PULSE, Config::Servos::FREQUENCY); infos[1].servo = std::make_unique<Servo>( + MIOSIX_SERVOS_1_TIM, TimerUtils::Channel::MIOSIX_SERVOS_1_CHANNEL, + Config::Servos::MIN_PULSE, Config::Servos::MAX_PULSE, + Config::Servos::FREQUENCY); + infos[2].servo = std::make_unique<Servo>( MIOSIX_SERVOS_2_TIM, TimerUtils::Channel::MIOSIX_SERVOS_2_CHANNEL, Config::Servos::MIN_PULSE, Config::Servos::MAX_PULSE, Config::Servos::FREQUENCY); + infos[3].servo = std::make_unique<Servo>( + MIOSIX_SERVOS_3_TIM, TimerUtils::Channel::MIOSIX_SERVOS_3_CHANNEL, + Config::Servos::MIN_PULSE, Config::Servos::MAX_PULSE, + Config::Servos::FREQUENCY); ServoInfo* info; info = getServo(ServosList::MAIN_VALVE); @@ -88,9 +96,19 @@ Actuators::Actuators() info->flipped = Config::Servos::MAIN_FLIPPED; info->unsafeSetServoPosition(0.0f); - info = getServo(ServosList::VENTING_VALVE); - info->limit = Config::Servos::VENTING_LIMIT; - info->flipped = Config::Servos::VENTING_FLIPPED; + info = getServo(ServosList::OX_VENTING_VALVE); + info->limit = Config::Servos::OX_VENTING_LIMIT; + info->flipped = Config::Servos::OX_VENTING_FLIPPED; + info->unsafeSetServoPosition(0.0f); + + info = getServo(ServosList::NITROGEN_VALVE); + info->limit = Config::Servos::NITROGEN_LIMIT; + info->flipped = Config::Servos::NITROGEN_FLIPPED; + info->unsafeSetServoPosition(0.0f); + + info = getServo(ServosList::N2_QUENCHING_VALVE); + info->limit = Config::Servos::N2_QUENCHING_LIMIT; + info->flipped = Config::Servos::N2_QUENCHING_FLIPPED; info->unsafeSetServoPosition(0.0f); } @@ -99,8 +117,8 @@ bool Actuators::start() TaskScheduler& scheduler = getModule<BoardScheduler>()->getActuatorsScheduler(); - infos[0].servo->enable(); - infos[1].servo->enable(); + for (size_t i = 0; i < infos.size(); ++i) + infos[i].servo->enable(); // Reset all actions lastActionTs = getTime(); @@ -165,10 +183,14 @@ Actuators::ServoInfo* Actuators::getServo(ServosList servo) { switch (servo) { - case VENTING_VALVE: + case OX_VENTING_VALVE: return &infos[0]; case MAIN_VALVE: return &infos[1]; + case NITROGEN_VALVE: + return &infos[2]; + case N2_QUENCHING_VALVE: + return &infos[3]; default: // Oh FUCK @@ -251,7 +273,7 @@ void Actuators::updatePositionsTask() if (shouldVent) { // Open for at least timeout time - openServoWithTime(ServosList::VENTING_VALVE, + openServoWithTime(ServosList::OX_VENTING_VALVE, Config::Servos::SERVO_ACTION_TIMEOUT + 1000); } } diff --git a/src/Motor/Actuators/Actuators.h b/src/Engine/Actuators/Actuators.h similarity index 93% rename from src/Motor/Actuators/Actuators.h rename to src/Engine/Actuators/Actuators.h index 15133ade166bccf168662904efbb00b6062f760a..177854541fc2c3108c75fe03445821361171b8a1 100644 --- a/src/Motor/Actuators/Actuators.h +++ b/src/Engine/Actuators/Actuators.h @@ -22,13 +22,13 @@ #pragma once -#include <Motor/BoardScheduler.h> -#include <Motor/CanHandler/CanHandler.h> +#include <Engine/BoardScheduler.h> +#include <Engine/CanHandler/CanHandler.h> #include <actuators/Servo/Servo.h> -#include <common/MavlinkLyra.h> +#include <common/MavlinkOrion.h> #include <utils/DependencyManager/DependencyManager.h> -namespace Motor +namespace Engine { class Actuators @@ -76,7 +76,7 @@ private: miosix::FastMutex infosMutex; // Timestamp of last servo action long long lastActionTs = 0; - ServoInfo infos[2] = {}; + std::array<ServoInfo, 4> infos; }; -} // namespace Motor +} // namespace Engine diff --git a/src/Motor/Actuators/ActuatorsData.h b/src/Engine/Actuators/ActuatorsData.h similarity index 97% rename from src/Motor/Actuators/ActuatorsData.h rename to src/Engine/Actuators/ActuatorsData.h index a623c9a32fdf4059cdf1a9690cb6c41dde219b0a..99f5db7982ddbb0711120adb0b9bc1e079c11502 100644 --- a/src/Motor/Actuators/ActuatorsData.h +++ b/src/Engine/Actuators/ActuatorsData.h @@ -25,7 +25,7 @@ #include <cstdint> #include <ostream> -namespace Motor +namespace Engine { struct ActuatorsData { @@ -53,4 +53,4 @@ struct ActuatorsData } }; -} // namespace Motor +} // namespace Engine diff --git a/src/Motor/BoardScheduler.h b/src/Engine/BoardScheduler.h similarity index 96% rename from src/Motor/BoardScheduler.h rename to src/Engine/BoardScheduler.h index 503908b53dd1f4e39725dcba5f9f2bf1cb6fefe6..fb8dadab16d3737b38b4bd5387a11ba0499cae2f 100644 --- a/src/Motor/BoardScheduler.h +++ b/src/Engine/BoardScheduler.h @@ -22,11 +22,11 @@ #pragma once -#include <Motor/Configs/SchedulerConfig.h> +#include <Engine/Configs/SchedulerConfig.h> #include <scheduler/TaskScheduler.h> #include <utils/DependencyManager/DependencyManager.h> -namespace Motor +namespace Engine { class BoardScheduler : public Boardcore::Injectable @@ -69,4 +69,4 @@ private: Boardcore::TaskScheduler actuators; }; -} // namespace Motor +} // namespace Engine diff --git a/src/Motor/Buses.h b/src/Engine/Buses.h similarity index 94% rename from src/Motor/Buses.h rename to src/Engine/Buses.h index 62a25fde5d8e258c69e59a8467c9da5ea6bc708d..08d2283f59b3f654be38d9de664b6711d44932a6 100644 --- a/src/Motor/Buses.h +++ b/src/Engine/Buses.h @@ -26,7 +26,7 @@ #include <drivers/usart/USART.h> #include <utils/DependencyManager/DependencyManager.h> -namespace Motor +namespace Engine { class Buses : public Boardcore::Injectable @@ -39,6 +39,7 @@ public: Boardcore::SPIBus& getLIS2MDL() { return spi3; } Boardcore::SPIBus& getLSM6DSRX() { return spi3; } Boardcore::SPIBus& getADS131M08() { return spi4; } + Boardcore::SPIBus& getThermocouple() { return spi1; } Boardcore::USART& getHILUart() { return usart4; } @@ -50,4 +51,4 @@ private: Boardcore::USART usart4{UART4, 256000, 1024}; }; -} // namespace Motor +} // namespace Engine diff --git a/src/Motor/CanHandler/CanHandler.cpp b/src/Engine/CanHandler/CanHandler.cpp similarity index 70% rename from src/Motor/CanHandler/CanHandler.cpp rename to src/Engine/CanHandler/CanHandler.cpp index a110d856d9fba927476b02dc9d4f289f422efc22..bcd3b14d00fe2f085633a30b58e9294820d239b7 100644 --- a/src/Motor/CanHandler/CanHandler.cpp +++ b/src/Engine/CanHandler/CanHandler.cpp @@ -22,14 +22,14 @@ #include "CanHandler.h" -#include <Motor/Actuators/Actuators.h> -#include <Motor/Configs/CanHandlerConfig.h> -#include <Motor/Configs/SchedulerConfig.h> +#include <Engine/Actuators/Actuators.h> +#include <Engine/Configs/CanHandlerConfig.h> +#include <Engine/Configs/SchedulerConfig.h> #include <common/CanConfig.h> #include <drivers/timer/TimestampTimer.h> #include <events/EventData.h> -using namespace Motor; +using namespace Engine; using namespace Boardcore; using namespace Canbus; using namespace Common; @@ -63,7 +63,7 @@ bool CanHandler::start() protocol.enqueueData( static_cast<uint8_t>(CanConfig::Priority::MEDIUM), static_cast<uint8_t>(CanConfig::PrimaryType::STATUS), - static_cast<uint8_t>(CanConfig::Board::MOTOR), + static_cast<uint8_t>(CanConfig::Board::ENGINE), static_cast<uint8_t>(CanConfig::Board::BROADCAST), 0x00, DeviceStatus{ TimestampTimer::getTimestamp(), @@ -90,7 +90,7 @@ bool CanHandler::start() protocol.enqueueData( static_cast<uint8_t>(CanConfig::Priority::HIGH), static_cast<uint8_t>(CanConfig::PrimaryType::SENSORS), - static_cast<uint8_t>(CanConfig::Board::MOTOR), + static_cast<uint8_t>(CanConfig::Board::ENGINE), static_cast<uint8_t>(CanConfig::Board::BROADCAST), static_cast<uint8_t>(CanConfig::SensorId::CC_PRESSURE), static_cast<PressureData>(sensors->getCCPressLastSample())); @@ -98,20 +98,39 @@ bool CanHandler::start() protocol.enqueueData( static_cast<uint8_t>(CanConfig::Priority::HIGH), static_cast<uint8_t>(CanConfig::PrimaryType::SENSORS), - static_cast<uint8_t>(CanConfig::Board::MOTOR), + static_cast<uint8_t>(CanConfig::Board::ENGINE), static_cast<uint8_t>(CanConfig::Board::BROADCAST), - static_cast<uint8_t>(CanConfig::SensorId::TOP_TANK_PRESSURE), + static_cast<uint8_t>(CanConfig::SensorId::OX_TOP_TANK_PRESSURE), static_cast<PressureData>( - sensors->getTopTankPressLastSample())); + sensors->getOxTopTankPressLastSample())); protocol.enqueueData( static_cast<uint8_t>(CanConfig::Priority::HIGH), static_cast<uint8_t>(CanConfig::PrimaryType::SENSORS), - static_cast<uint8_t>(CanConfig::Board::MOTOR), + static_cast<uint8_t>(CanConfig::Board::ENGINE), static_cast<uint8_t>(CanConfig::Board::BROADCAST), - static_cast<uint8_t>(CanConfig::SensorId::BOTTOM_TANK_PRESSURE), + static_cast<uint8_t>( + CanConfig::SensorId::OX_BOTTOM_TANK_PRESSURE_0), static_cast<PressureData>( - sensors->getBottomTankPressLastSample())); + sensors->getOxBottomTankPress0LastSample())); + + protocol.enqueueData( + static_cast<uint8_t>(CanConfig::Priority::HIGH), + static_cast<uint8_t>(CanConfig::PrimaryType::SENSORS), + static_cast<uint8_t>(CanConfig::Board::ENGINE), + static_cast<uint8_t>(CanConfig::Board::BROADCAST), + static_cast<uint8_t>( + CanConfig::SensorId::OX_BOTTOM_TANK_PRESSURE_1), + static_cast<PressureData>( + sensors->getOxBottomTankPress1LastSample())); + + protocol.enqueueData( + static_cast<uint8_t>(CanConfig::Priority::HIGH), + static_cast<uint8_t>(CanConfig::PrimaryType::SENSORS), + static_cast<uint8_t>(CanConfig::Board::ENGINE), + static_cast<uint8_t>(CanConfig::Board::BROADCAST), + static_cast<uint8_t>(CanConfig::SensorId::N2_TANK_PRESSURE), + static_cast<PressureData>(sensors->getN2TankPressLastSample())); }, Config::CanHandler::PRESSURE_PERIOD); @@ -129,7 +148,7 @@ bool CanHandler::start() protocol.enqueueData( static_cast<uint8_t>(CanConfig::Priority::MEDIUM), static_cast<uint8_t>(CanConfig::PrimaryType::SENSORS), - static_cast<uint8_t>(CanConfig::Board::MOTOR), + static_cast<uint8_t>(CanConfig::Board::ENGINE), static_cast<uint8_t>(CanConfig::Board::BROADCAST), static_cast<uint8_t>(CanConfig::SensorId::TANK_TEMPERATURE), static_cast<TemperatureData>(sensors->getTankTempLastSample())); @@ -137,9 +156,9 @@ bool CanHandler::start() protocol.enqueueData( static_cast<uint8_t>(CanConfig::Priority::MEDIUM), static_cast<uint8_t>(CanConfig::PrimaryType::SENSORS), - static_cast<uint8_t>(CanConfig::Board::MOTOR), + static_cast<uint8_t>(CanConfig::Board::ENGINE), static_cast<uint8_t>(CanConfig::Board::BROADCAST), - static_cast<uint8_t>(CanConfig::SensorId::MOTOR_BOARD_VOLTAGE), + static_cast<uint8_t>(CanConfig::SensorId::ENGINE_BOARD_VOLTAGE), static_cast<VoltageData>( sensors->getBatteryVoltageLastSample())); }, @@ -159,7 +178,7 @@ bool CanHandler::start() protocol.enqueueData( static_cast<uint8_t>(CanConfig::Priority::HIGH), static_cast<uint8_t>(CanConfig::PrimaryType::ACTUATORS), - static_cast<uint8_t>(CanConfig::Board::MOTOR), + static_cast<uint8_t>(CanConfig::Board::ENGINE), static_cast<uint8_t>(CanConfig::Board::BROADCAST), static_cast<uint8_t>(ServosList::MAIN_VALVE), ServoFeedback{ @@ -170,13 +189,35 @@ bool CanHandler::start() protocol.enqueueData( static_cast<uint8_t>(CanConfig::Priority::HIGH), static_cast<uint8_t>(CanConfig::PrimaryType::ACTUATORS), - static_cast<uint8_t>(CanConfig::Board::MOTOR), + static_cast<uint8_t>(CanConfig::Board::ENGINE), + static_cast<uint8_t>(CanConfig::Board::BROADCAST), + static_cast<uint8_t>(ServosList::OX_VENTING_VALVE), + ServoFeedback{ + TimestampTimer::getTimestamp(), + actuators->getServoPosition(ServosList::OX_VENTING_VALVE), + actuators->isServoOpen(ServosList::OX_VENTING_VALVE)}); + + protocol.enqueueData( + static_cast<uint8_t>(CanConfig::Priority::HIGH), + static_cast<uint8_t>(CanConfig::PrimaryType::ACTUATORS), + static_cast<uint8_t>(CanConfig::Board::ENGINE), + static_cast<uint8_t>(CanConfig::Board::BROADCAST), + static_cast<uint8_t>(ServosList::NITROGEN_VALVE), + ServoFeedback{ + TimestampTimer::getTimestamp(), + actuators->getServoPosition(ServosList::NITROGEN_VALVE), + actuators->isServoOpen(ServosList::NITROGEN_VALVE)}); + + protocol.enqueueData( + static_cast<uint8_t>(CanConfig::Priority::HIGH), + static_cast<uint8_t>(CanConfig::PrimaryType::ACTUATORS), + static_cast<uint8_t>(CanConfig::Board::ENGINE), static_cast<uint8_t>(CanConfig::Board::BROADCAST), - static_cast<uint8_t>(ServosList::VENTING_VALVE), + static_cast<uint8_t>(ServosList::N2_QUENCHING_VALVE), ServoFeedback{ TimestampTimer::getTimestamp(), - actuators->getServoPosition(ServosList::VENTING_VALVE), - actuators->isServoOpen(ServosList::VENTING_VALVE)}); + actuators->getServoPosition(ServosList::N2_QUENCHING_VALVE), + actuators->isServoOpen(ServosList::N2_QUENCHING_VALVE)}); }, Config::CanHandler::ACTUATORS_PERIOD); diff --git a/src/Motor/CanHandler/CanHandler.h b/src/Engine/CanHandler/CanHandler.h similarity index 93% rename from src/Motor/CanHandler/CanHandler.h rename to src/Engine/CanHandler/CanHandler.h index c29da6fd311c3a726858d7aca0e03ab3b0b8cf0f..464cc9b75ad343e2587e450501ab5e44a6628d2f 100644 --- a/src/Motor/CanHandler/CanHandler.h +++ b/src/Engine/CanHandler/CanHandler.h @@ -22,16 +22,16 @@ #pragma once -#include <Motor/BoardScheduler.h> -#include <Motor/PersistentVars/PersistentVars.h> -#include <Motor/Sensors/Sensors.h> +#include <Engine/BoardScheduler.h> +#include <Engine/PersistentVars/PersistentVars.h> +#include <Engine/Sensors/Sensors.h> #include <common/CanConfig.h> #include <drivers/canbus/CanProtocol/CanProtocol.h> #include <utils/DependencyManager/DependencyManager.h> #include <atomic> -namespace Motor +namespace Engine { class Actuators; @@ -67,4 +67,4 @@ private: Boardcore::Canbus::CanProtocol protocol; }; -} // namespace Motor +} // namespace Engine diff --git a/src/Motor/Configs/ActuatorsConfig.h b/src/Engine/Configs/ActuatorsConfig.h similarity index 80% rename from src/Motor/Configs/ActuatorsConfig.h rename to src/Engine/Configs/ActuatorsConfig.h index 36a876cd7fef7e0a3bfd45096f3f3342319a9b0e..108e4ad0e68c4a13e9c8ab701482d845d92b4568 100644 --- a/src/Motor/Configs/ActuatorsConfig.h +++ b/src/Engine/Configs/ActuatorsConfig.h @@ -25,7 +25,7 @@ #include <interfaces-impl/hwmapping.h> #include <units/Frequency.h> -namespace Motor +namespace Engine { namespace Config @@ -49,13 +49,19 @@ constexpr float SERVO_CONFIDENCE = 0.02; // 2% // Timeout is currently set at 2h constexpr long long SERVO_ACTION_TIMEOUT = 2 * 60 * 60 * 1000; -constexpr float VENTING_LIMIT = 0.90f; -constexpr float MAIN_LIMIT = 0.90f; +// TODO: check this values +constexpr float OX_VENTING_LIMIT = 0.90f; +constexpr float MAIN_LIMIT = 0.90f; +constexpr float NITROGEN_LIMIT = 0.90f; +constexpr float N2_QUENCHING_LIMIT = 0.90f; -constexpr bool VENTING_FLIPPED = true; -constexpr bool MAIN_FLIPPED = true; +// TODO: check this values +constexpr bool OX_VENTING_FLIPPED = true; +constexpr bool MAIN_FLIPPED = true; +constexpr bool NITROGEN_FLIPPED = true; +constexpr bool N2_QUENCHING_FLIPPED = true; } // namespace Servos } // namespace Config -} // namespace Motor +} // namespace Engine diff --git a/src/Motor/Configs/CanHandlerConfig.h b/src/Engine/Configs/CanHandlerConfig.h similarity index 97% rename from src/Motor/Configs/CanHandlerConfig.h rename to src/Engine/Configs/CanHandlerConfig.h index dca3dbc199b9bffe0dccd1f4f6870a8b07baebad..b9ce955aab97c072f9c58e4df5394ec6854bce94 100644 --- a/src/Motor/Configs/CanHandlerConfig.h +++ b/src/Engine/Configs/CanHandlerConfig.h @@ -26,7 +26,7 @@ #include <chrono> -namespace Motor +namespace Engine { namespace Config @@ -50,4 +50,4 @@ constexpr Hertz TEMPERATURE_PERIOD = 10_hz; } // namespace Config -} // namespace Motor +} // namespace Engine diff --git a/src/Motor/Configs/HILSimulationConfig.h b/src/Engine/Configs/HILSimulationConfig.h similarity index 97% rename from src/Motor/Configs/HILSimulationConfig.h rename to src/Engine/Configs/HILSimulationConfig.h index 2549746189cbb80b9cdc1ffafc1d34d2daccf193..2fb42e7814d7fce3766ff14b3ba3067f6613c05f 100644 --- a/src/Motor/Configs/HILSimulationConfig.h +++ b/src/Engine/Configs/HILSimulationConfig.h @@ -31,7 +31,7 @@ /* linter off */ using namespace Boardcore::Units::Frequency; -namespace Motor +namespace Engine { namespace Config { @@ -51,4 +51,4 @@ static_assert(N_DATA_BARO_CHAMBER * SIMULATION_RATE >= Sensors::ADS131M08::RATE, } // namespace HIL } // namespace Config -} // namespace Motor +} // namespace Engine diff --git a/src/Motor/Configs/SchedulerConfig.h b/src/Engine/Configs/SchedulerConfig.h similarity index 97% rename from src/Motor/Configs/SchedulerConfig.h rename to src/Engine/Configs/SchedulerConfig.h index ec35d17a496a042a344830cfd485c68f9bc63fbd..2bc58620b2bc184e1ed9e73ba7323730047c5864 100644 --- a/src/Motor/Configs/SchedulerConfig.h +++ b/src/Engine/Configs/SchedulerConfig.h @@ -24,7 +24,7 @@ #include <miosix.h> -namespace Motor +namespace Engine { namespace Config @@ -43,4 +43,4 @@ static const miosix::Priority CAN_PRIORITY = miosix::PRIORITY_MAX - 1; } // namespace Config -} // namespace Motor +} // namespace Engine diff --git a/src/Motor/Configs/SensorsConfig.h b/src/Engine/Configs/SensorsConfig.h similarity index 78% rename from src/Motor/Configs/SensorsConfig.h rename to src/Engine/Configs/SensorsConfig.h index f3d039dcc40e288d1404ea345e621379e73ab35c..19bbf69de2a4b110ffa591148be03341ff144fec 100644 --- a/src/Motor/Configs/SensorsConfig.h +++ b/src/Engine/Configs/SensorsConfig.h @@ -29,7 +29,7 @@ #include <sensors/LSM6DSRX/LSM6DSRX.h> #include <units/Units.h> -namespace Motor +namespace Engine { namespace Config @@ -111,16 +111,26 @@ Channel 4 - 29.65ohm 0.3584V 12.06mA 29.72ohm 0.5911V 20mA 29.55ohm */ + +// TODO: calibrate ch0 and ch1 +constexpr float CH0_SHUNT_RESISTANCE = 29.0; +constexpr float CH1_SHUNT_RESISTANCE = 29.0; + constexpr float CH4_SHUNT_RESISTANCE = 29.79; constexpr float CH5_SHUNT_RESISTANCE = 29.7; constexpr float CH6_SHUNT_RESISTANCE = 29.65; +// TODO: check if the selected channels are fine constexpr Boardcore::ADS131M08Defs::Channel TANK_TC_CHANNEL = Boardcore::ADS131M08Defs::Channel::CHANNEL_3; -constexpr Boardcore::ADS131M08Defs::Channel TANK_TOP_PT_CHANNEL = +constexpr Boardcore::ADS131M08Defs::Channel OX_TANK_TOP_PT_CHANNEL = Boardcore::ADS131M08Defs::Channel::CHANNEL_5; -constexpr Boardcore::ADS131M08Defs::Channel TANK_BOTTOM_PT_CHANNEL = +constexpr Boardcore::ADS131M08Defs::Channel OX_TANK_BOTTOM_0_PT_CHANNEL = Boardcore::ADS131M08Defs::Channel::CHANNEL_6; +constexpr Boardcore::ADS131M08Defs::Channel OX_TANK_BOTTOM_1_PT_CHANNEL = + Boardcore::ADS131M08Defs::Channel::CHANNEL_0; +constexpr Boardcore::ADS131M08Defs::Channel N2_TANK_PT_CHANNEL = + Boardcore::ADS131M08Defs::Channel::CHANNEL_1; constexpr Boardcore::ADS131M08Defs::Channel ENGINE_PT_CHANNEL = Boardcore::ADS131M08Defs::Channel::CHANNEL_4; @@ -130,16 +140,23 @@ constexpr bool ENABLED = true; namespace Trafag { -constexpr float TANK_TOP_SHUNT_RESISTANCE = ADS131M08::CH5_SHUNT_RESISTANCE; -constexpr float TANK_BOTTOM_SHUNT_RESISTANCE = ADS131M08::CH6_SHUNT_RESISTANCE; -constexpr float ENGINE_SHUNT_RESISTANCE = ADS131M08::CH4_SHUNT_RESISTANCE; +constexpr float OX_TANK_TOP_SHUNT_RESISTANCE = ADS131M08::CH5_SHUNT_RESISTANCE; +constexpr float OX_TANK_BOTTOM_0_SHUNT_RESISTANCE = + ADS131M08::CH6_SHUNT_RESISTANCE; +constexpr float OX_TANK_BOTTOM_1_SHUNT_RESISTANCE = + ADS131M08::CH0_SHUNT_RESISTANCE; +constexpr float N2_TANK_SHUNT_RESISTANCE = ADS131M08::CH1_SHUNT_RESISTANCE; +constexpr float ENGINE_SHUNT_RESISTANCE = ADS131M08::CH4_SHUNT_RESISTANCE; constexpr float MIN_CURRENT = 4; constexpr float MAX_CURRENT = 20; -constexpr float TANK_TOP_MAX_PRESSURE = 100; // bar -constexpr float TANK_BOTTOM_MAX_PRESSURE = 100; // bar -constexpr float ENGINE_MAX_PRESSURE = 40; // bar +// TODO: check these values +constexpr float OX_TANK_TOP_MAX_PRESSURE = 100; // bar +constexpr float OX_TANK_BOTTOM_0_MAX_PRESSURE = 100; // bar +constexpr float OX_TANK_BOTTOM_1_MAX_PRESSURE = 100; // bar +constexpr float N2_TANK_MAX_PRESSURE = 100; // TODO: CHECK +constexpr float ENGINE_MAX_PRESSURE = 40; // bar } // namespace Trafag namespace Kulite @@ -156,6 +173,12 @@ constexpr float TANK_P1_TEMP = 34.0f; } // namespace Kulite +namespace MAX31856 +{ +constexpr Hertz PERIOD = 10_hz; +constexpr bool ENABLED = true; +} // namespace MAX31856 + namespace InternalADC { constexpr Boardcore::InternalADC::Channel VBAT_CH = @@ -171,4 +194,4 @@ constexpr bool ENABLED = true; } // namespace Config -} // namespace Motor +} // namespace Engine diff --git a/src/Motor/HIL/HIL.cpp b/src/Engine/HIL/HIL.cpp similarity index 73% rename from src/Motor/HIL/HIL.cpp rename to src/Engine/HIL/HIL.cpp index 4f5f6ded024e30901093f6d300c3f6bc811bac4e..768d2d07e20390e6c7ec3c622a2b6f7fca3e1069 100644 --- a/src/Motor/HIL/HIL.cpp +++ b/src/Engine/HIL/HIL.cpp @@ -22,24 +22,24 @@ #include "HIL.h" -#include <Motor/Actuators/Actuators.h> -#include <Motor/Buses.h> -#include <Motor/Configs/HILSimulationConfig.h> +#include <Engine/Actuators/Actuators.h> +#include <Engine/Buses.h> +#include <Engine/Configs/HILSimulationConfig.h> #include <common/Events.h> #include <events/EventBroker.h> #include <hil/HIL.h> #include "HILData.h" -namespace Motor +namespace Engine { -MotorHILPhasesManager::MotorHILPhasesManager( +EngineHILPhasesManager::EngineHILPhasesManager( std::function<Boardcore::TimedTrajectoryPoint()> getCurrentPosition) - : Boardcore::HILPhasesManager<MotorFlightPhases, SimulatorData, + : Boardcore::HILPhasesManager<EngineFlightPhases, SimulatorData, ActuatorData>(getCurrentPosition) { - flagsFlightPhases = {{MotorFlightPhases::SIMULATION_STARTED, false}}; + flagsFlightPhases = {{EngineFlightPhases::SIMULATION_STARTED, false}}; prev_flagsFlightPhases = flagsFlightPhases; @@ -54,14 +54,14 @@ MotorHILPhasesManager::MotorHILPhasesManager( eventBroker.subscribe(this, Common::TOPIC_FSR); eventBroker.subscribe(this, Common::TOPIC_NAS); eventBroker.subscribe(this, Common::TOPIC_TMTC); - eventBroker.subscribe(this, Common::TOPIC_MOTOR); + eventBroker.subscribe(this, Common::TOPIC_ENGINE); eventBroker.subscribe(this, Common::TOPIC_TARS); eventBroker.subscribe(this, Common::TOPIC_ALT); } -void MotorHILPhasesManager::processFlagsImpl( +void EngineHILPhasesManager::processFlagsImpl( const SimulatorData& simulatorData, - std::vector<MotorFlightPhases>& changed_flags) + std::vector<EngineFlightPhases>& changed_flags) { if (simulatorData.signal == static_cast<float>(HILSignal::SIMULATION_STARTED)) @@ -77,24 +77,24 @@ void MotorHILPhasesManager::processFlagsImpl( } // set true when the first packet from the simulator arrives - if (isSetTrue(MotorFlightPhases::SIMULATION_STARTED)) + if (isSetTrue(EngineFlightPhases::SIMULATION_STARTED)) { t_start = Boardcore::TimestampTimer::getTimestamp(); printf("[HIL] ------- SIMULATION STARTED ! ------- \n"); - changed_flags.push_back(MotorFlightPhases::SIMULATION_STARTED); + changed_flags.push_back(EngineFlightPhases::SIMULATION_STARTED); } } -void MotorHILPhasesManager::printOutcomes() +void EngineHILPhasesManager::printOutcomes() { printf("OUTCOMES: (times dt from liftoff)\n\n"); printf("Simulation time: %.3f [sec]\n\n", (double)(t_stop - t_start) / 1000000.0f); } -void MotorHILPhasesManager::handleEventImpl( - const Boardcore::Event& e, std::vector<MotorFlightPhases>& changed_flags) +void EngineHILPhasesManager::handleEventImpl( + const Boardcore::Event& e, std::vector<EngineFlightPhases>& changed_flags) { switch (e) { @@ -103,18 +103,18 @@ void MotorHILPhasesManager::handleEventImpl( } } -MotorHIL::MotorHIL() - : Boardcore::HIL<MotorFlightPhases, SimulatorData, ActuatorData>( +EngineHIL::EngineHIL() + : Boardcore::HIL<EngineFlightPhases, SimulatorData, ActuatorData>( nullptr, nullptr, [this]() { return updateActuatorData(); }, 1000 / Config::HIL::SIMULATION_RATE.value()) { } -bool MotorHIL::start() +bool EngineHIL::start() { auto& hilUsart = getModule<Buses>()->getHILUart(); - hilPhasesManager = new MotorHILPhasesManager( + hilPhasesManager = new EngineHILPhasesManager( [&]() { Boardcore::TimedTrajectoryPoint timedTrajectoryPoint; @@ -122,22 +122,25 @@ bool MotorHIL::start() return timedTrajectoryPoint; }); - hilTransceiver = new MotorHILTransceiver(hilUsart, hilPhasesManager); + hilTransceiver = new EngineHILTransceiver(hilUsart, hilPhasesManager); - return Boardcore::HIL<MotorFlightPhases, SimulatorData, + return Boardcore::HIL<EngineFlightPhases, SimulatorData, ActuatorData>::start(); } -ActuatorData MotorHIL::updateActuatorData() +ActuatorData EngineHIL::updateActuatorData() { auto actuators = getModule<Actuators>(); ActuatorsStateHIL actuatorsStateHIL{ (actuators->getServoPosition(MAIN_VALVE)), - (actuators->getServoPosition(VENTING_VALVE))}; + (actuators->getServoPosition(OX_VENTING_VALVE)), + (actuators->getServoPosition(NITROGEN_VALVE)), + (actuators->getServoPosition(N2_QUENCHING_VALVE)), + }; // Returning the feedback for the simulator return ActuatorData{actuatorsStateHIL}; } -} // namespace Motor +} // namespace Engine diff --git a/src/Motor/HIL/HIL.h b/src/Engine/HIL/HIL.h similarity index 72% rename from src/Motor/HIL/HIL.h rename to src/Engine/HIL/HIL.h index 67569f4d6fd7e01034ebadc7100387650c959b1c..1d274d89efdfb01a659e407c54fadbca78bd806a 100644 --- a/src/Motor/HIL/HIL.h +++ b/src/Engine/HIL/HIL.h @@ -22,57 +22,57 @@ #pragma once -#include <Motor/Actuators/Actuators.h> -#include <Motor/Buses.h> -#include <Motor/Configs/HILSimulationConfig.h> +#include <Engine/Actuators/Actuators.h> +#include <Engine/Buses.h> +#include <Engine/Configs/HILSimulationConfig.h> #include <common/Events.h> #include <events/EventBroker.h> #include <hil/HIL.h> #include "HILData.h" -namespace Motor +namespace Engine { -class MotorHILTransceiver - : public Boardcore::HILTransceiver<MotorFlightPhases, SimulatorData, +class EngineHILTransceiver + : public Boardcore::HILTransceiver<EngineFlightPhases, SimulatorData, ActuatorData> { - using Boardcore::HILTransceiver<MotorFlightPhases, SimulatorData, + using Boardcore::HILTransceiver<EngineFlightPhases, SimulatorData, ActuatorData>::HILTransceiver; }; -class MotorHILPhasesManager - : public Boardcore::HILPhasesManager<MotorFlightPhases, SimulatorData, +class EngineHILPhasesManager + : public Boardcore::HILPhasesManager<EngineFlightPhases, SimulatorData, ActuatorData> { public: - explicit MotorHILPhasesManager( + explicit EngineHILPhasesManager( std::function<Boardcore::TimedTrajectoryPoint()> getCurrentPosition); void processFlagsImpl( const SimulatorData& simulatorData, - std::vector<MotorFlightPhases>& changed_flags) override; + std::vector<EngineFlightPhases>& changed_flags) override; void printOutcomes(); private: void handleEventImpl( const Boardcore::Event& e, - std::vector<MotorFlightPhases>& changed_flags) override; + std::vector<EngineFlightPhases>& changed_flags) override; }; -class MotorHIL - : public Boardcore::HIL<MotorFlightPhases, SimulatorData, ActuatorData>, +class EngineHIL + : public Boardcore::HIL<EngineFlightPhases, SimulatorData, ActuatorData>, public Boardcore::InjectableWithDeps<Buses, Actuators> { public: - MotorHIL(); + EngineHIL(); bool start() override; private: ActuatorData updateActuatorData(); }; -} // namespace Motor +} // namespace Engine diff --git a/src/Motor/HIL/HILData.h b/src/Engine/HIL/HILData.h similarity index 66% rename from src/Motor/HIL/HILData.h rename to src/Engine/HIL/HILData.h index 14051e4528417bad2beada7bcfcb63fd08ad21a9..133b0e0a115c50bdd8738a98de452e0265faf26c 100644 --- a/src/Motor/HIL/HILData.h +++ b/src/Engine/HIL/HILData.h @@ -22,14 +22,14 @@ #pragma once -#include <Motor/Configs/HILSimulationConfig.h> +#include <Engine/Configs/HILSimulationConfig.h> #include <sensors/HILSimulatorData.h> -namespace Motor +namespace Engine { // Sensors Data -using MotorHILChamberBarometerData = +using EngineHILChamberBarometerData = Boardcore::BarometerSimulatorData<Config::HIL::N_DATA_BARO_CHAMBER>; enum class HILSignal : int @@ -39,24 +39,31 @@ enum class HILSignal : int SIMULATION_FORCE_LAUNCH = 3 }; -enum class MotorFlightPhases +enum class EngineFlightPhases { SIMULATION_STARTED }; struct ActuatorsStateHIL { - float mainValvePercentage = 0; - float ventingValvePercentage = 0; + float mainValvePercentage = 0; + float oxVentingValvePercentage = 0; + float nitrogenValvePercentage = 0; + float n2QuenchingValvePercentage = 0; ActuatorsStateHIL() - : mainValvePercentage(0.0f), ventingValvePercentage(0.0f) + : mainValvePercentage(0.0f), oxVentingValvePercentage(0.0f), + nitrogenValvePercentage(0.0f), n2QuenchingValvePercentage(0.0f) { } - ActuatorsStateHIL(float mainValvePercentage, float ventingValvePercentage) + ActuatorsStateHIL(float mainValvePercentage, float oxVentingValvePercentage, + float nitrogenValvePercentage, + float n2QuenchingValvePercentage) : mainValvePercentage(mainValvePercentage), - ventingValvePercentage(ventingValvePercentage) + oxVentingValvePercentage(oxVentingValvePercentage), + nitrogenValvePercentage(nitrogenValvePercentage), + n2QuenchingValvePercentage(n2QuenchingValvePercentage) { } @@ -64,8 +71,11 @@ struct ActuatorsStateHIL { printf( "mainValve: %f perc\n" - "venting: %f perc\n", - mainValvePercentage * 100, ventingValvePercentage * 100); + "oxVenting: %f perc\n" + "nitrogen: %f perc\n" + "n2Quenching: %f perc\n", + mainValvePercentage * 100, oxVentingValvePercentage * 100, + nitrogenValvePercentage * 100, n2QuenchingValvePercentage * 100); } }; @@ -78,7 +88,7 @@ struct ActuatorsStateHIL */ struct SimulatorData { - MotorHILChamberBarometerData pressureChamber; + EngineHILChamberBarometerData pressureChamber; float signal; }; @@ -99,4 +109,4 @@ struct ActuatorData void print() { actuatorsState.print(); } }; -} // namespace Motor +} // namespace Engine diff --git a/src/Motor/PersistentVars/PersistentVars.cpp b/src/Engine/PersistentVars/PersistentVars.cpp similarity index 97% rename from src/Motor/PersistentVars/PersistentVars.cpp rename to src/Engine/PersistentVars/PersistentVars.cpp index 4864e564dc232d94d199a555b393487e555d5ed6..bc0b2bf480cf816957e02602fbbc3e60c9b9fb5a 100644 --- a/src/Motor/PersistentVars/PersistentVars.cpp +++ b/src/Engine/PersistentVars/PersistentVars.cpp @@ -29,7 +29,7 @@ using namespace miosix; static bool PRESERVE hilMode = false; -namespace Motor +namespace Engine { namespace PersistentVars @@ -45,4 +45,4 @@ bool getHilMode() { return hilMode; } } // namespace PersistentVars -} // namespace Motor +} // namespace Engine diff --git a/src/Motor/PersistentVars/PersistentVars.h b/src/Engine/PersistentVars/PersistentVars.h similarity index 96% rename from src/Motor/PersistentVars/PersistentVars.h rename to src/Engine/PersistentVars/PersistentVars.h index ab9c6031845ce88437a7c9768e9aebc5ced305cf..676ec37240b4500be985f796f5a7834ebfcc050b 100644 --- a/src/Motor/PersistentVars/PersistentVars.h +++ b/src/Engine/PersistentVars/PersistentVars.h @@ -22,7 +22,7 @@ #pragma once -namespace Motor +namespace Engine { namespace PersistentVars @@ -34,4 +34,4 @@ bool getHilMode(); } // namespace PersistentVars -} // namespace Motor +} // namespace Engine diff --git a/src/Motor/Sensors/HILSensors.h b/src/Engine/Sensors/HILSensors.h similarity index 90% rename from src/Motor/Sensors/HILSensors.h rename to src/Engine/Sensors/HILSensors.h index 8e46a0ef16cdbf500d4cd6c8a37414ce622e0fc6..4937641143006731c76b9cc91d5a00f9bc723168 100644 --- a/src/Motor/Sensors/HILSensors.h +++ b/src/Engine/Sensors/HILSensors.h @@ -21,7 +21,7 @@ */ #pragma once -#include <Motor/HIL/HIL.h> +#include <Engine/HIL/HIL.h> #include <common/CanConfig.h> #include <common/ReferenceConfig.h> #include <drivers/timer/TimestampTimer.h> @@ -30,12 +30,12 @@ #include "Sensors.h" -namespace Motor +namespace Engine { class HILSensors : public Boardcore::InjectableWithDeps<Boardcore::InjectableBase<Sensors>, - MotorHIL> + EngineHIL> { public: explicit HILSensors(bool enableHw) : Super{}, enableHw{enableHw} {} @@ -56,10 +56,10 @@ private: int getSampleCounter(int nData) { auto ts = miosix::getTime(); - auto tsSensorData = getModule<MotorHIL>()->getTimestampSimulatorData(); + auto tsSensorData = getModule<EngineHIL>()->getTimestampSimulatorData(); long long simulationPeriod = static_cast<long long>( - getModule<MotorHIL>()->getSimulationPeriod()) * + getModule<EngineHIL>()->getSimulationPeriod()) * 1e6; assert(ts >= tsSensorData && @@ -88,7 +88,7 @@ private: { Boardcore::PressureData data; - auto* sensorData = getModule<MotorHIL>()->getSensorData(); + auto* sensorData = getModule<EngineHIL>()->getSensorData(); int iCC = getSampleCounter(sensorData->pressureChamber.NDATA); @@ -101,4 +101,4 @@ private: bool enableHw; }; -} // namespace Motor +} // namespace Engine diff --git a/src/Motor/Sensors/KuliteThermocouple.h b/src/Engine/Sensors/KuliteThermocouple.h similarity index 96% rename from src/Motor/Sensors/KuliteThermocouple.h rename to src/Engine/Sensors/KuliteThermocouple.h index 99f241b0ccc7b5dd65ee8723bf49925f80b276d1..acdc04c2c3dac6406a74080cc69ae370e04c8674 100644 --- a/src/Motor/Sensors/KuliteThermocouple.h +++ b/src/Engine/Sensors/KuliteThermocouple.h @@ -22,12 +22,12 @@ #pragma once -#include <Motor/Sensors/SensorsData.h> +#include <Engine/Sensors/SensorsData.h> #include <sensors/Sensor.h> #include <functional> -namespace Motor +namespace Engine { class KuliteThermocouple : public Boardcore::Sensor<Boardcore::TemperatureData> @@ -61,4 +61,4 @@ private: const float offset; }; -} // namespace Motor +} // namespace Engine diff --git a/src/Motor/Sensors/Sensors.cpp b/src/Engine/Sensors/Sensors.cpp similarity index 61% rename from src/Motor/Sensors/Sensors.cpp rename to src/Engine/Sensors/Sensors.cpp index c930178caefaa881ba8822aeb866d65913b0601e..360dab1f76408d9ed3fdf494d4fd7314c62b2a11 100644 --- a/src/Motor/Sensors/Sensors.cpp +++ b/src/Engine/Sensors/Sensors.cpp @@ -22,12 +22,12 @@ #include "Sensors.h" -#include <Motor/Buses.h> -#include <Motor/Configs/SensorsConfig.h> -#include <Motor/Sensors/SensorsData.h> +#include <Engine/Buses.h> +#include <Engine/Configs/SensorsConfig.h> +#include <Engine/Sensors/SensorsData.h> #include <interfaces-impl/hwmapping.h> -using namespace Motor; +using namespace Engine; using namespace Boardcore; using namespace miosix; @@ -48,12 +48,16 @@ bool Sensors::start() if (Config::Sensors::ADS131M08::ENABLED) { ads131m08Init(); - topTankPressureInit(); - bottomTankPressureInit(); + oxTopTankPressureInit(); + oxBottomTankPressureInit(); + n2TankPressureInit(); ccPressureInit(); tankTempInit(); } + if (Config::Sensors::MAX31856::ENABLED) + thermocoupleInit(); + if (Config::Sensors::InternalADC::ENABLED) internalAdcInit(); @@ -97,20 +101,37 @@ LIS2MDLData Sensors::getLIS2MDLLastSample() return lis2mdl ? lis2mdl->getLastSample() : LIS2MDLData{}; } -LSM6DSRXData Sensors::getLSM6DSRXLastSample() +LSM6DSRXData Sensors::getLSM6DSRX0LastSample() +{ + return lsm6dsrx0 ? lsm6dsrx0->getLastSample() : LSM6DSRXData{}; +} + +LSM6DSRXData Sensors::getLSM6DSRX1LastSample() { - return lsm6dsrx ? lsm6dsrx->getLastSample() : LSM6DSRXData{}; + return lsm6dsrx1 ? lsm6dsrx1->getLastSample() : LSM6DSRXData{}; } -PressureData Sensors::getTopTankPressLastSample() +PressureData Sensors::getOxTopTankPressLastSample() { - return topTankPressure ? topTankPressure->getLastSample() : PressureData{}; + return oxTopTankPressure ? oxTopTankPressure->getLastSample() + : PressureData{}; } -PressureData Sensors::getBottomTankPressLastSample() +PressureData Sensors::getOxBottomTankPress0LastSample() { - return bottomTankPressure ? bottomTankPressure->getLastSample() - : PressureData{}; + return oxBottomTankPressure0 ? oxBottomTankPressure0->getLastSample() + : PressureData{}; +} + +PressureData Sensors::getOxBottomTankPress1LastSample() +{ + return oxBottomTankPressure1 ? oxBottomTankPressure1->getLastSample() + : PressureData{}; +} + +PressureData Sensors::getN2TankPressLastSample() +{ + return n2TankPressure ? n2TankPressure->getLastSample() : PressureData{}; } PressureData Sensors::getCCPressLastSample() @@ -123,6 +144,11 @@ TemperatureData Sensors::getTankTempLastSample() return tankTemp ? tankTemp->getLastSample() : TemperatureData{}; } +TemperatureData Sensors::getThermocoupleLastSample() +{ + return thermocouple ? thermocouple->getLastSample() : TemperatureData{}; +} + VoltageData Sensors::getBatteryVoltageLastSample() { auto sample = getInternalADCLastSample(); @@ -146,8 +172,11 @@ std::vector<SensorInfo> Sensors::getSensorInfos() if (lis2mdl) infos.push_back(manager->getSensorInfo(lis2mdl.get())); - if (lsm6dsrx) - infos.push_back(manager->getSensorInfo(lsm6dsrx.get())); + if (lsm6dsrx0) + infos.push_back(manager->getSensorInfo(lsm6dsrx0.get())); + + if (lsm6dsrx1) + infos.push_back(manager->getSensorInfo(lsm6dsrx1.get())); if (ads131m08) infos.push_back(manager->getSensorInfo(ads131m08.get())); @@ -155,11 +184,19 @@ std::vector<SensorInfo> Sensors::getSensorInfos() if (internalAdc) infos.push_back(manager->getSensorInfo(internalAdc.get())); - if (topTankPressure) - infos.push_back(manager->getSensorInfo(topTankPressure.get())); + if (oxTopTankPressure) + infos.push_back(manager->getSensorInfo(oxTopTankPressure.get())); + + if (oxBottomTankPressure0) + infos.push_back( + manager->getSensorInfo(oxBottomTankPressure0.get())); + + if (oxBottomTankPressure1) + infos.push_back( + manager->getSensorInfo(oxBottomTankPressure1.get())); - if (bottomTankPressure) - infos.push_back(manager->getSensorInfo(bottomTankPressure.get())); + if (n2TankPressure) + infos.push_back(manager->getSensorInfo(n2TankPressure.get())); if (ccPressure) infos.push_back(manager->getSensorInfo(ccPressure.get())); @@ -167,6 +204,9 @@ std::vector<SensorInfo> Sensors::getSensorInfos() if (tankTemp) infos.push_back(manager->getSensorInfo(tankTemp.get())); + if (thermocouple) + infos.push_back(manager->getSensorInfo(thermocouple.get())); + return infos; } else @@ -249,18 +289,34 @@ void Sensors::lsm6dsrxInit() LSM6DSRXConfig::FIFO_TIMESTAMP_DECIMATION::DEC_1; config.fifoTemperatureBdr = LSM6DSRXConfig::FIFO_TEMPERATURE_BDR::DISABLED; - lsm6dsrx = std::make_unique<LSM6DSRX>(getModule<Buses>()->getLSM6DSRX(), - sensors::LSM6DSRX::cs::getPin(), - spiConfig, config); + lsm6dsrx0 = std::make_unique<LSM6DSRX>(getModule<Buses>()->getLSM6DSRX(), + sensors::LSM6DSRX0::cs::getPin(), + spiConfig, config); + lsm6dsrx1 = std::make_unique<LSM6DSRX>(getModule<Buses>()->getLSM6DSRX(), + sensors::LSM6DSRX1::cs::getPin(), + spiConfig, config); +} + +void Sensors::lsm6dsrx0Callback() +{ + if (!lsm6dsrx0) + return; + + uint16_t lastFifoSize; + const auto lastFifo = lsm6dsrx0->getLastFifo(lastFifoSize); + + // For every instance inside the fifo log the sample + for (uint16_t i = 0; i < lastFifoSize; i++) + sdLogger.log(lastFifo.at(i)); } -void Sensors::lsm6dsrxCallback() +void Sensors::lsm6dsrx1Callback() { - if (!lsm6dsrx) + if (!lsm6dsrx1) return; uint16_t lastFifoSize; - const auto lastFifo = lsm6dsrx->getLastFifo(lastFifoSize); + const auto lastFifo = lsm6dsrx1->getLastFifo(lastFifoSize); // For every instance inside the fifo log the sample for (uint16_t i = 0; i < lastFifoSize; i++) @@ -290,19 +346,32 @@ void Sensors::ads131m08Init() // Configure all required channels config.channelsConfig[( - int)Config::Sensors::ADS131M08::TANK_TOP_PT_CHANNEL] = { + int)Config::Sensors::ADS131M08::OX_TANK_TOP_PT_CHANNEL] = { .enabled = true, .pga = ADS131M08Defs::PGA::PGA_1, .offset = 0, .gain = 1.0}; config.channelsConfig[( - int)Config::Sensors::ADS131M08::TANK_BOTTOM_PT_CHANNEL] = { + int)Config::Sensors::ADS131M08::OX_TANK_BOTTOM_0_PT_CHANNEL] = { .enabled = true, .pga = ADS131M08Defs::PGA::PGA_1, .offset = 0, .gain = 1.0}; + config.channelsConfig[( + int)Config::Sensors::ADS131M08::OX_TANK_BOTTOM_1_PT_CHANNEL] = { + .enabled = true, + .pga = ADS131M08Defs::PGA::PGA_1, + .offset = 0, + .gain = 1.0}; + + config.channelsConfig[(int)Config::Sensors::ADS131M08::N2_TANK_PT_CHANNEL] = + {.enabled = true, + .pga = ADS131M08Defs::PGA::PGA_1, + .offset = 0, + .gain = 1.0}; + config.channelsConfig[(int)Config::Sensors::ADS131M08::ENGINE_PT_CHANNEL] = {.enabled = true, .pga = ADS131M08Defs::PGA::PGA_1, @@ -335,44 +404,81 @@ void Sensors::internalAdcCallback() sdLogger.log(getInternalADCLastSample()); } -void Sensors::topTankPressureInit() +void Sensors::oxTopTankPressureInit() +{ + oxTopTankPressure = std::make_unique<TrafagPressureSensor>( + [this]() + { + auto sample = getADS131M08LastSample(); + return sample.getVoltage( + Config::Sensors::ADS131M08::OX_TANK_TOP_PT_CHANNEL); + }, + Config::Sensors::Trafag::OX_TANK_TOP_SHUNT_RESISTANCE, + Config::Sensors::Trafag::OX_TANK_TOP_MAX_PRESSURE, + Config::Sensors::Trafag::MIN_CURRENT, + Config::Sensors::Trafag::MAX_CURRENT); +} + +void Sensors::oxTopTankPressureCallback() { - topTankPressure = std::make_unique<TrafagPressureSensor>( + sdLogger.log(OxTopTankPressureData{getOxTopTankPressLastSample()}); +} + +void Sensors::oxBottomTankPressureInit() +{ + oxBottomTankPressure0 = std::make_unique<TrafagPressureSensor>( [this]() { auto sample = getADS131M08LastSample(); return sample.getVoltage( - Config::Sensors::ADS131M08::TANK_TOP_PT_CHANNEL); + Config::Sensors::ADS131M08::OX_TANK_BOTTOM_0_PT_CHANNEL); }, - Config::Sensors::Trafag::TANK_TOP_SHUNT_RESISTANCE, - Config::Sensors::Trafag::TANK_TOP_MAX_PRESSURE, + Config::Sensors::Trafag::OX_TANK_BOTTOM_0_SHUNT_RESISTANCE, + Config::Sensors::Trafag::OX_TANK_BOTTOM_0_MAX_PRESSURE, + Config::Sensors::Trafag::MIN_CURRENT, + Config::Sensors::Trafag::MAX_CURRENT); + + oxBottomTankPressure1 = std::make_unique<TrafagPressureSensor>( + [this]() + { + auto sample = getADS131M08LastSample(); + return sample.getVoltage( + Config::Sensors::ADS131M08::OX_TANK_BOTTOM_1_PT_CHANNEL); + }, + Config::Sensors::Trafag::OX_TANK_BOTTOM_1_SHUNT_RESISTANCE, + Config::Sensors::Trafag::OX_TANK_BOTTOM_1_MAX_PRESSURE, Config::Sensors::Trafag::MIN_CURRENT, Config::Sensors::Trafag::MAX_CURRENT); } -void Sensors::topTankPressureCallback() +void Sensors::oxBottomTankPressure0Callback() { - sdLogger.log(TopTankPressureData{getTopTankPressLastSample()}); + sdLogger.log(OxBottomTankPressureData{getOxBottomTankPress0LastSample()}); } -void Sensors::bottomTankPressureInit() +void Sensors::oxBottomTankPressure1Callback() { - bottomTankPressure = std::make_unique<TrafagPressureSensor>( + sdLogger.log(OxBottomTankPressureData{getOxBottomTankPress1LastSample()}); +} + +void Sensors::n2TankPressureInit() +{ + n2TankPressure = std::make_unique<TrafagPressureSensor>( [this]() { auto sample = getADS131M08LastSample(); return sample.getVoltage( - Config::Sensors::ADS131M08::TANK_BOTTOM_PT_CHANNEL); + Config::Sensors::ADS131M08::N2_TANK_PT_CHANNEL); }, - Config::Sensors::Trafag::TANK_BOTTOM_SHUNT_RESISTANCE, - Config::Sensors::Trafag::TANK_BOTTOM_MAX_PRESSURE, + Config::Sensors::Trafag::N2_TANK_SHUNT_RESISTANCE, + Config::Sensors::Trafag::N2_TANK_MAX_PRESSURE, Config::Sensors::Trafag::MIN_CURRENT, Config::Sensors::Trafag::MAX_CURRENT); } -void Sensors::bottomTankPressureCallback() +void Sensors::n2TankPressureCallback() { - sdLogger.log(BottomTankPressureData{getBottomTankPressLastSample()}); + sdLogger.log(N2TankPressureData{getN2TankPressLastSample()}); } void Sensors::ccPressureInit() @@ -412,6 +518,25 @@ void Sensors::tankTempInit() void Sensors::tankTempCallback() { sdLogger.log(getTankTempLastSample()); } +void Sensors::thermocoupleInit() +{ + SPIBusConfig spiConfig = MAX31856::getDefaultSPIConfig(); + spiConfig.clockDivider = SPI::ClockDivider::DIV_32; + + thermocouple = std::make_unique<MAX31856>( + getModule<Buses>()->getThermocouple(), + sensors::thermocouple::cs::getPin(), spiConfig, + MAX31856::ThermocoupleType::K_TYPE); // TODO: verify the type +} + +void Sensors::thermocoupleCallback() +{ + if (!thermocouple) + return; + + sdLogger.log(getThermocoupleLastSample()); +} + bool Sensors::sensorManagerInit() { SensorManager::SensorMap_t map; @@ -438,11 +563,18 @@ bool Sensors::sensorManagerInit() map.emplace(lis2mdl.get(), lis2mdlInfo); } - if (lsm6dsrx) + if (lsm6dsrx0) { - SensorInfo lsm6dsrxInfo{"LSM6DSRX", Config::Sensors::LSM6DSRX::RATE, - [this]() { lsm6dsrxCallback(); }}; - map.emplace(lsm6dsrx.get(), lsm6dsrxInfo); + SensorInfo lsm6dsrxInfo{"LSM6DSRX0", Config::Sensors::LSM6DSRX::RATE, + [this]() { lsm6dsrx0Callback(); }}; + map.emplace(lsm6dsrx0.get(), lsm6dsrxInfo); + } + + if (lsm6dsrx1) + { + SensorInfo lsm6dsrxInfo{"LSM6DSRX1", Config::Sensors::LSM6DSRX::RATE, + [this]() { lsm6dsrx1Callback(); }}; + map.emplace(lsm6dsrx1.get(), lsm6dsrxInfo); } if (ads131m08) @@ -460,18 +592,34 @@ bool Sensors::sensorManagerInit() map.emplace(internalAdc.get(), internalAdcInfo); } - if (topTankPressure) + if (oxTopTankPressure) + { + SensorInfo info{"OxTopTankPressure", Config::Sensors::ADS131M08::RATE, + [this]() { oxTopTankPressureCallback(); }}; + map.emplace(std::make_pair(oxTopTankPressure.get(), info)); + } + + if (oxBottomTankPressure0) + { + SensorInfo info{"OxBottomTankPressure0", + Config::Sensors::ADS131M08::RATE, + [this]() { oxBottomTankPressure0Callback(); }}; + map.emplace(std::make_pair(oxBottomTankPressure0.get(), info)); + } + + if (oxBottomTankPressure1) { - SensorInfo info{"TopTankPressure", Config::Sensors::ADS131M08::RATE, - [this]() { topTankPressureCallback(); }}; - map.emplace(std::make_pair(topTankPressure.get(), info)); + SensorInfo info{"OxBottomTankPressure1", + Config::Sensors::ADS131M08::RATE, + [this]() { oxBottomTankPressure1Callback(); }}; + map.emplace(std::make_pair(oxBottomTankPressure1.get(), info)); } - if (bottomTankPressure) + if (n2TankPressure) { - SensorInfo info{"BottomTankPressure", Config::Sensors::ADS131M08::RATE, - [this]() { bottomTankPressureCallback(); }}; - map.emplace(std::make_pair(bottomTankPressure.get(), info)); + SensorInfo info{"N2TankPressure", Config::Sensors::ADS131M08::RATE, + [this]() { n2TankPressureCallback(); }}; + map.emplace(std::make_pair(n2TankPressure.get(), info)); } if (ccPressure) @@ -488,6 +636,13 @@ bool Sensors::sensorManagerInit() map.emplace(std::make_pair(tankTemp.get(), info)); } + if (thermocouple) + { + SensorInfo info("MAX31856", Config::Sensors::MAX31856::PERIOD, + [this]() { thermocoupleCallback(); }); + map.emplace(std::make_pair(thermocouple.get(), info)); + } + manager = std::make_unique<SensorManager>(map, &getSensorsScheduler()); return manager->start(); } diff --git a/src/Motor/Sensors/Sensors.h b/src/Engine/Sensors/Sensors.h similarity index 69% rename from src/Motor/Sensors/Sensors.h rename to src/Engine/Sensors/Sensors.h index ce8b56fd4bd487e79ab297a08b26d6c06ee8a06c..73bb192eb2ab4ffad34d002bea38adeee187e90e 100644 --- a/src/Motor/Sensors/Sensors.h +++ b/src/Engine/Sensors/Sensors.h @@ -22,9 +22,9 @@ #pragma once -#include <Motor/BoardScheduler.h> -#include <Motor/Buses.h> -#include <Motor/Sensors/KuliteThermocouple.h> +#include <Engine/BoardScheduler.h> +#include <Engine/Buses.h> +#include <Engine/Sensors/KuliteThermocouple.h> #include <drivers/adc/InternalADC.h> #include <scheduler/TaskScheduler.h> #include <sensors/ADS131M08/ADS131M08.h> @@ -32,6 +32,7 @@ #include <sensors/LIS2MDL/LIS2MDL.h> #include <sensors/LPS22DF/LPS22DF.h> #include <sensors/LSM6DSRX/LSM6DSRX.h> +#include <sensors/MAX31856/MAX31856.h> #include <sensors/SensorManager.h> #include <sensors/analog/TrafagPressureSensor.h> #include <utils/DependencyManager/DependencyManager.h> @@ -39,7 +40,7 @@ #include <memory> #include <vector> -namespace Motor +namespace Engine { class Sensors : public Boardcore::InjectableWithDeps<Buses, BoardScheduler> @@ -54,13 +55,17 @@ public: Boardcore::LPS22DFData getLPS22DFLastSample(); Boardcore::H3LIS331DLData getH3LIS331DLLastSample(); Boardcore::LIS2MDLData getLIS2MDLLastSample(); - Boardcore::LSM6DSRXData getLSM6DSRXLastSample(); + Boardcore::LSM6DSRXData getLSM6DSRX0LastSample(); + Boardcore::LSM6DSRXData getLSM6DSRX1LastSample(); - Boardcore::PressureData getTopTankPressLastSample(); - Boardcore::PressureData getBottomTankPressLastSample(); + Boardcore::PressureData getOxTopTankPressLastSample(); + Boardcore::PressureData getOxBottomTankPress0LastSample(); + Boardcore::PressureData getOxBottomTankPress1LastSample(); + Boardcore::PressureData getN2TankPressLastSample(); Boardcore::PressureData getCCPressLastSample(); Boardcore::TemperatureData getTankTempLastSample(); Boardcore::VoltageData getBatteryVoltageLastSample(); + Boardcore::TemperatureData getThermocoupleLastSample(); std::vector<Boardcore::SensorInfo> getSensorInfos(); @@ -73,13 +78,17 @@ protected: std::unique_ptr<Boardcore::LPS22DF> lps22df; std::unique_ptr<Boardcore::H3LIS331DL> h3lis331dl; std::unique_ptr<Boardcore::LIS2MDL> lis2mdl; - std::unique_ptr<Boardcore::LSM6DSRX> lsm6dsrx; + std::unique_ptr<Boardcore::LSM6DSRX> lsm6dsrx0; + std::unique_ptr<Boardcore::LSM6DSRX> lsm6dsrx1; std::unique_ptr<Boardcore::ADS131M08> ads131m08; std::unique_ptr<Boardcore::InternalADC> internalAdc; + std::unique_ptr<Boardcore::MAX31856> thermocouple; // Analog sensors - std::unique_ptr<Boardcore::TrafagPressureSensor> topTankPressure; - std::unique_ptr<Boardcore::TrafagPressureSensor> bottomTankPressure; + std::unique_ptr<Boardcore::TrafagPressureSensor> oxTopTankPressure; + std::unique_ptr<Boardcore::TrafagPressureSensor> oxBottomTankPressure0; + std::unique_ptr<Boardcore::TrafagPressureSensor> oxBottomTankPressure1; + std::unique_ptr<Boardcore::TrafagPressureSensor> n2TankPressure; std::unique_ptr<Boardcore::TrafagPressureSensor> ccPressure; std::unique_ptr<KuliteThermocouple> tankTemp; @@ -95,8 +104,10 @@ private: void lis2mdlInit(); void lis2mdlCallback(); + /// @brief Initialize both lsm6dsrx sensors. void lsm6dsrxInit(); - void lsm6dsrxCallback(); + void lsm6dsrx0Callback(); + void lsm6dsrx1Callback(); void ads131m08Init(); void ads131m08Callback(); @@ -104,11 +115,19 @@ private: void internalAdcInit(); void internalAdcCallback(); - void topTankPressureInit(); - void topTankPressureCallback(); + void thermocoupleInit(); + void thermocoupleCallback(); - void bottomTankPressureInit(); - void bottomTankPressureCallback(); + void oxTopTankPressureInit(); + void oxTopTankPressureCallback(); + + /// @brief Initialize both ox bottom pressure sensors. + void oxBottomTankPressureInit(); + void oxBottomTankPressure0Callback(); + void oxBottomTankPressure1Callback(); + + void n2TankPressureInit(); + void n2TankPressureCallback(); void ccPressureInit(); void ccPressureCallback(); @@ -122,4 +141,4 @@ private: Boardcore::PrintLogger logger = Boardcore::Logging::getLogger("sensors"); }; -} // namespace Motor +} // namespace Engine diff --git a/src/Motor/Sensors/SensorsData.h b/src/Engine/Sensors/SensorsData.h similarity index 72% rename from src/Motor/Sensors/SensorsData.h rename to src/Engine/Sensors/SensorsData.h index b205266fb42ecaabaff0f7a4ea0ccf4f78683822..16772d834807dcc0e023399668f54afc94ccacd8 100644 --- a/src/Motor/Sensors/SensorsData.h +++ b/src/Engine/Sensors/SensorsData.h @@ -23,27 +23,37 @@ #pragma once #include <sensors/SensorData.h> -namespace Motor +namespace Engine { -struct TopTankPressureData : Boardcore::PressureData +struct OxTopTankPressureData : Boardcore::PressureData { - explicit TopTankPressureData(const Boardcore::PressureData& data) + explicit OxTopTankPressureData(const Boardcore::PressureData& data) : Boardcore::PressureData{data} { } - TopTankPressureData() {} + OxTopTankPressureData() {} }; -struct BottomTankPressureData : Boardcore::PressureData +struct OxBottomTankPressureData : Boardcore::PressureData { - explicit BottomTankPressureData(const Boardcore::PressureData& data) + explicit OxBottomTankPressureData(const Boardcore::PressureData& data) : Boardcore::PressureData{data} { } - BottomTankPressureData() {} + OxBottomTankPressureData() {} +}; + +struct N2TankPressureData : Boardcore::PressureData +{ + explicit N2TankPressureData(const Boardcore::PressureData& data) + : Boardcore::PressureData{data} + { + } + + N2TankPressureData() {} }; struct CCPressureData : Boardcore::PressureData @@ -56,4 +66,4 @@ struct CCPressureData : Boardcore::PressureData CCPressureData() {} }; -} // namespace Motor +} // namespace Engine diff --git a/src/Motor/motor-entry.cpp b/src/Engine/engine-entry.cpp similarity index 93% rename from src/Motor/motor-entry.cpp rename to src/Engine/engine-entry.cpp index 24888615fa0dfbfb684fe90cecd3916e47b63876..84530f1eb5c44d8910c9e295d577ba7e6667ce69 100644 --- a/src/Motor/motor-entry.cpp +++ b/src/Engine/engine-entry.cpp @@ -20,14 +20,14 @@ * THE SOFTWARE. */ -#include <Motor/Actuators/Actuators.h> -#include <Motor/BoardScheduler.h> -#include <Motor/Buses.h> -#include <Motor/CanHandler/CanHandler.h> -#include <Motor/HIL/HIL.h> -#include <Motor/PersistentVars/PersistentVars.h> -#include <Motor/Sensors/HILSensors.h> -#include <Motor/Sensors/Sensors.h> +#include <Engine/Actuators/Actuators.h> +#include <Engine/BoardScheduler.h> +#include <Engine/Buses.h> +#include <Engine/CanHandler/CanHandler.h> +#include <Engine/HIL/HIL.h> +#include <Engine/PersistentVars/PersistentVars.h> +#include <Engine/Sensors/HILSensors.h> +#include <Engine/Sensors/Sensors.h> #include <diagnostic/CpuMeter/CpuMeter.h> #include <diagnostic/PrintLogger.h> #include <interfaces-impl/hwmapping.h> @@ -38,7 +38,7 @@ #include <iostream> using namespace Boardcore; -using namespace Motor; +using namespace Engine; using namespace miosix; int main() @@ -61,10 +61,10 @@ int main() Logger& sdLogger = Logger::getInstance(); // HIL - MotorHIL* hil = nullptr; + EngineHIL* hil = nullptr; if (PersistentVars::getHilMode()) { - hil = new MotorHIL(); + hil = new EngineHIL(); initResult = initResult && manager.insert(hil); } diff --git a/src/Main/CanHandler/CanHandler.cpp b/src/Main/CanHandler/CanHandler.cpp index dccecff947c75969bdef38f54279c015e53ef5cb..14d183a56c30d075e83a8a30f6976992e73c8f5e 100644 --- a/src/Main/CanHandler/CanHandler.cpp +++ b/src/Main/CanHandler/CanHandler.cpp @@ -42,7 +42,7 @@ CanHandler::CanHandler() static_cast<uint8_t>(CanConfig::Board::BROADCAST)); protocol.addFilter(static_cast<uint8_t>(CanConfig::Board::RIG), static_cast<uint8_t>(CanConfig::Board::BROADCAST)); - protocol.addFilter(static_cast<uint8_t>(CanConfig::Board::MOTOR), + protocol.addFilter(static_cast<uint8_t>(CanConfig::Board::ENGINE), static_cast<uint8_t>(CanConfig::Board::BROADCAST)); } @@ -244,11 +244,11 @@ void CanHandler::handleSensor(const Canbus::CanMessage& msg) break; } - case CanConfig::SensorId::MOTOR_BOARD_VOLTAGE: + case CanConfig::SensorId::ENGINE_BOARD_VOLTAGE: { CanVoltageData data = voltageDataFromCanMessage(msg); sdLogger.log(data); - sensors->setCanMotorBatteryVoltage(data); + sensors->setCanEngineBatteryVoltage(data); break; } @@ -293,14 +293,14 @@ void CanHandler::handleStatus(const Canbus::CanMessage& msg) break; } - case CanConfig::Board::MOTOR: + case CanConfig::Board::ENGINE: { - status.motorLastStatus = getTime(); - status.motorState = deviceStatus.state; + status.engineLastStatus = getTime(); + status.engineState = deviceStatus.state; - status.motorLogNumber = deviceStatus.logNumber; - status.motorLogGood = deviceStatus.logGood; - status.motorHil = deviceStatus.hil; + status.engineLogNumber = deviceStatus.logNumber; + status.engineLogGood = deviceStatus.logGood; + status.engineHil = deviceStatus.hil; break; } diff --git a/src/Main/CanHandler/CanHandler.h b/src/Main/CanHandler/CanHandler.h index 1ea17ea7c31752d7ca620ff205cda0736bac3b63..e4de6ea4115d92301a9c4f46518e1c6b2ad20352 100644 --- a/src/Main/CanHandler/CanHandler.h +++ b/src/Main/CanHandler/CanHandler.h @@ -46,18 +46,18 @@ public: { long long rigLastStatus = 0; long long payloadLastStatus = 0; - long long motorLastStatus = 0; + long long engineLastStatus = 0; uint8_t rigState = 0; uint8_t payloadState = 0; - uint8_t motorState = 0; + uint8_t engineState = 0; bool rigArmed = false; bool payloadArmed = false; - uint16_t motorLogNumber = 0; - bool motorLogGood = true; - bool motorHil = false; + uint16_t engineLogNumber = 0; + bool engineLogGood = true; + bool engineHil = false; bool isRigConnected() { @@ -70,23 +70,23 @@ public: (payloadLastStatus + Config::CanHandler::STATUS_TIMEOUT.count()); } - bool isMotorConnected() + bool isEngineConnected() { return miosix::getTime() <= - (motorLastStatus + + (engineLastStatus + Config::CanHandler::STATUS_TIMEOUT.count()); } uint8_t getRigState() { return rigState; } uint8_t getPayloadState() { return payloadState; } - uint8_t getMotorState() { return motorState; } + uint8_t getEngineState() { return engineState; } bool isRigArmed() { return rigArmed; } bool isPayloadArmed() { return payloadArmed; } - uint16_t getMotorLogNumber() { return motorLogNumber; } - bool isMotorLogGood() { return motorLogGood; } - bool isMotorHil() { return motorHil; } + uint16_t getEngineLogNumber() { return engineLogNumber; } + bool isEngineLogGood() { return engineLogGood; } + bool isEngineHil() { return engineHil; } }; CanHandler(); diff --git a/src/Main/HIL/HIL.cpp b/src/Main/HIL/HIL.cpp index 04e501dd53d7ebb5e6433208052a6f3768f9826b..4917954b828cc4bc04941c2b981618e555addcf8 100644 --- a/src/Main/HIL/HIL.cpp +++ b/src/Main/HIL/HIL.cpp @@ -76,7 +76,7 @@ MainHILPhasesManager::MainHILPhasesManager( eventBroker.subscribe(this, Common::TOPIC_FSR); eventBroker.subscribe(this, Common::TOPIC_NAS); eventBroker.subscribe(this, Common::TOPIC_TMTC); - eventBroker.subscribe(this, Common::TOPIC_MOTOR); + eventBroker.subscribe(this, Common::TOPIC_ENGINE); eventBroker.subscribe(this, Common::TOPIC_TARS); eventBroker.subscribe(this, Common::TOPIC_ALT); } @@ -134,7 +134,7 @@ void MainHILPhasesManager::printOutcomes() printf("Simulation time: %.3f [sec]\n\n", (double)(t_stop - t_start) / 1000000.0f); - printf("Motor stopped burning (simulation flag): \n"); + printf("Engine stopped burning (simulation flag): \n"); outcomes[MainFlightPhases::SIM_BURNING].print(t_liftoff); printf("Airbrakes exit shadowmode: \n"); @@ -193,7 +193,7 @@ void MainHILPhasesManager::handleEventImpl( getCurrentPosition().z, getCurrentPosition().vz); changed_flags.push_back(MainFlightPhases::LIFTOFF); break; - case Common::Events::FLIGHT_MOTOR_SHUTDOWN: + case Common::Events::FLIGHT_ENGINE_SHUTDOWN: printf("[HIL] ------- SHUTDOWN -------: %f, %f \n", getCurrentPosition().z, getCurrentPosition().vz); changed_flags.push_back(MainFlightPhases::SHUTDOWN); diff --git a/src/Main/Radio/Radio.cpp b/src/Main/Radio/Radio.cpp index 6adb0c5a21d8d79d13b3b6dce8e03f355245b35d..e6f75d6d826683a67703972f27c98b6e54df0269 100644 --- a/src/Main/Radio/Radio.cpp +++ b/src/Main/Radio/Radio.cpp @@ -838,10 +838,10 @@ bool Radio::enqueueSystemTm(uint8_t tmId) CanHandler::CanStatus canStatus = getModule<CanHandler>()->getCanStatus(); tm.payload_board_state = canStatus.getPayloadState(); - tm.motor_board_state = canStatus.getMotorState(); + tm.motor_board_state = canStatus.getEngineState(); tm.payload_can_status = canStatus.isPayloadConnected() ? 1 : 0; - tm.motor_can_status = canStatus.isMotorConnected() ? 1 : 0; + tm.motor_can_status = canStatus.isEngineConnected() ? 1 : 0; tm.rig_can_status = canStatus.isRigConnected() ? 1 : 0; tm.hil_state = PersistentVars::getHilMode() ? 1 : 0; @@ -873,7 +873,7 @@ bool Radio::enqueueSystemTm(uint8_t tmId) tm.tank_temperature = sensors->getCanTankTempLastSample().temperature; tm.battery_voltage = - sensors->getCanMotorBatteryVoltageLastSample().voltage; + sensors->getCanEngineBatteryVoltageLastSample().voltage; // Valve states tm.main_valve_state = @@ -885,9 +885,9 @@ bool Radio::enqueueSystemTm(uint8_t tmId) CanHandler::CanStatus canStatus = getModule<CanHandler>()->getCanStatus(); - tm.log_number = canStatus.getMotorLogNumber(); - tm.log_good = canStatus.isMotorLogGood() ? 1 : 0; - tm.hil_state = canStatus.isMotorHil() ? 1 : 0; + tm.log_number = canStatus.getEngineLogNumber(); + tm.log_good = canStatus.isEngineLogGood() ? 1 : 0; + tm.hil_state = canStatus.isEngineHil() ? 1 : 0; mavlink_msg_motor_tm_encode(Config::Radio::MAV_SYSTEM_ID, Config::Radio::MAV_COMPONENT_ID, &msg, diff --git a/src/Main/Sensors/HILSensors.h b/src/Main/Sensors/HILSensors.h index dfc34428f039a6345f6fdd747593f68ac4fc8260..d7f6e0d3d0cf80574eafcd90fd3fb6d79cf54c30 100644 --- a/src/Main/Sensors/HILSensors.h +++ b/src/Main/Sensors/HILSensors.h @@ -67,7 +67,7 @@ private: if (!Config::HIL::IS_FULL_HIL) { // Adding to sensorManager's scheduler a task to "sample" the - // combustion chamber pressure coming from motor + // combustion chamber pressure coming from engine getSensorsScheduler().addTask([this]() { setCanCCPress(updateCCData()); }, Config::HIL::BARO_CHAMBER_RATE); diff --git a/src/Main/Sensors/Sensors.cpp b/src/Main/Sensors/Sensors.cpp index edeaa29a201d0906de3580ea26f7d9f40e1e11f5..f9e8de2a68ec2fa9773c2bc7c7bb8ed726c4888b 100644 --- a/src/Main/Sensors/Sensors.cpp +++ b/src/Main/Sensors/Sensors.cpp @@ -418,10 +418,10 @@ TemperatureData Sensors::getCanTankTempLastSample() return canTankTemperature; } -VoltageData Sensors::getCanMotorBatteryVoltageLastSample() +VoltageData Sensors::getCanEngineBatteryVoltageLastSample() { Lock<FastMutex> lock{canMutex}; - return canMotorBatteryVoltage; + return canEngineBatteryVoltage; } void Sensors::setCanPitotDynamicPress(PressureData data) @@ -460,10 +460,10 @@ void Sensors::setCanTankTemp(TemperatureData data) canTankTemperature = data; } -void Sensors::setCanMotorBatteryVoltage(VoltageData data) +void Sensors::setCanEngineBatteryVoltage(VoltageData data) { Lock<FastMutex> lock{canMutex}; - canMotorBatteryVoltage = data; + canEngineBatteryVoltage = data; } std::vector<SensorInfo> Sensors::getSensorInfos() diff --git a/src/Main/Sensors/Sensors.h b/src/Main/Sensors/Sensors.h index bb4bda036790ec8de7cd525d634c4b1e412ff6da..73abbc4feaa5d57d004401a5293cd73472175030 100644 --- a/src/Main/Sensors/Sensors.h +++ b/src/Main/Sensors/Sensors.h @@ -104,7 +104,7 @@ public: Boardcore::PressureData getCanBottomTankPressLastSample(); Boardcore::PressureData getCanCCPressLastSample(); Boardcore::TemperatureData getCanTankTempLastSample(); - Boardcore::VoltageData getCanMotorBatteryVoltageLastSample(); + Boardcore::VoltageData getCanEngineBatteryVoltageLastSample(); std::vector<Boardcore::SensorInfo> getSensorInfos(); @@ -115,7 +115,7 @@ public: void setCanBottomTankPress(Boardcore::PressureData data); void setCanCCPress(Boardcore::PressureData data); void setCanTankTemp(Boardcore::TemperatureData data); - void setCanMotorBatteryVoltage(Boardcore::VoltageData data); + void setCanEngineBatteryVoltage(Boardcore::VoltageData data); protected: virtual bool postSensorCreationHook() { return true; } @@ -132,7 +132,7 @@ protected: Boardcore::PressureData canTopTankPressure; Boardcore::PressureData canBottomTankPressure; Boardcore::TemperatureData canTankTemperature; - Boardcore::VoltageData canMotorBatteryVoltage; + Boardcore::VoltageData canEngineBatteryVoltage; // Digital sensors std::unique_ptr<Boardcore::LPS22DF> lps22df; diff --git a/src/Main/StateMachines/ABKController/ABKController.cpp b/src/Main/StateMachines/ABKController/ABKController.cpp index 085527243c396d6eea6b8b848c22d69b17450996..2b3c792184ada13924bead22cf3b2d03a0d5dd40 100644 --- a/src/Main/StateMachines/ABKController/ABKController.cpp +++ b/src/Main/StateMachines/ABKController/ABKController.cpp @@ -148,9 +148,9 @@ void ABKController::state_armed(const Event& event) break; } - case FLIGHT_MOTOR_SHUTDOWN: + case FLIGHT_ENGINE_SHUTDOWN: { - // Enable only after motor shutdown + // Enable only after engine shutdown transition(&ABKController::state_shadow_mode); break; } diff --git a/src/Main/StateMachines/FlightModeManager/FlightModeManager.cpp b/src/Main/StateMachines/FlightModeManager/FlightModeManager.cpp index 285c16e63f3d01857bb8add942c0e432fb0317fd..097b3bf21b7bc59367f6e92a7d1d80a87742c6bb 100644 --- a/src/Main/StateMachines/FlightModeManager/FlightModeManager.cpp +++ b/src/Main/StateMachines/FlightModeManager/FlightModeManager.cpp @@ -608,7 +608,7 @@ State FlightModeManager::state_unpowered_ascent(const Event& event) { updateAndLogStatus(FlightModeManagerState::UNPOWERED_ASCENT); - EventBroker::getInstance().post(FLIGHT_MOTOR_SHUTDOWN, + EventBroker::getInstance().post(FLIGHT_ENGINE_SHUTDOWN, TOPIC_FLIGHT); apogeeTimeoutEvent = EventBroker::getInstance().postDelayed( diff --git a/src/Main/StateMachines/MEAController/MEAController.cpp b/src/Main/StateMachines/MEAController/MEAController.cpp index cc463d7fbf5696f965df960c270f7237ed094e36..64318038707327962b7646bd74bfd0faf8064796 100644 --- a/src/Main/StateMachines/MEAController/MEAController.cpp +++ b/src/Main/StateMachines/MEAController/MEAController.cpp @@ -298,7 +298,7 @@ void MEAController::state_shadow_mode(const Event& event) break; } - case FLIGHT_MOTOR_SHUTDOWN: + case FLIGHT_ENGINE_SHUTDOWN: { transition(&MEAController::state_active_unpowered); break; @@ -328,7 +328,7 @@ void MEAController::state_active(const Event& event) break; } - case FLIGHT_MOTOR_SHUTDOWN: + case FLIGHT_ENGINE_SHUTDOWN: { transition(&MEAController::state_active_unpowered); break; diff --git a/src/Payload/CanHandler/CanHandler.cpp b/src/Payload/CanHandler/CanHandler.cpp index ed916b236205c86b410608f4e73ff1fe109023f4..c529aa1a672f01d87d0ef523e1366830df54c574 100644 --- a/src/Payload/CanHandler/CanHandler.cpp +++ b/src/Payload/CanHandler/CanHandler.cpp @@ -53,10 +53,10 @@ bool CanStatus::isRigConnected() rigLastStatus + nanoseconds{config::Status::TIMEOUT}.count(); } -bool CanStatus::isMotorConnected() +bool CanStatus::isEngineConnected() { return miosix::getTime() <= - motorLastStatus + nanoseconds{config::Status::TIMEOUT}.count(); + engineLastStatus + nanoseconds{config::Status::TIMEOUT}.count(); } bool CanHandler::start() @@ -91,12 +91,12 @@ bool CanHandler::start() return false; } - // Add MOTOR filter - filterAdded = protocol->addFilter(static_cast<uint8_t>(Board::MOTOR), + // Add ENGINE filter + filterAdded = protocol->addFilter(static_cast<uint8_t>(Board::ENGINE), static_cast<uint8_t>(Board::BROADCAST)); if (!filterAdded) { - LOG_ERR(logger, "Failed to add MOTOR filter"); + LOG_ERR(logger, "Failed to add ENGINE filter"); return false; } @@ -281,14 +281,14 @@ void CanHandler::handleStatus(const CanMessage& msg) break; } - case Board::MOTOR: + case Board::ENGINE: { - status.motorLastStatus = miosix::getTime(); - status.motorState = deviceStatus.state; + status.engineLastStatus = miosix::getTime(); + status.engineState = deviceStatus.state; - status.motorLogNumber = deviceStatus.logNumber; - status.motorLogGood = deviceStatus.logGood; - status.motorHil = deviceStatus.hil; + status.engineLogNumber = deviceStatus.logNumber; + status.engineLogGood = deviceStatus.logGood; + status.engineHil = deviceStatus.hil; break; } diff --git a/src/Payload/CanHandler/CanHandler.h b/src/Payload/CanHandler/CanHandler.h index 6087184b68c4b0387bee60e8781b5d5e0756398b..e793bba964427a991307f789ba55e1950eb36e09 100644 --- a/src/Payload/CanHandler/CanHandler.h +++ b/src/Payload/CanHandler/CanHandler.h @@ -38,22 +38,22 @@ struct CanStatus { int64_t mainLastStatus = 0; ///< Timestamp of last main status message int64_t rigLastStatus = 0; ///< Timestamp of last rig status message - int64_t motorLastStatus = 0; ///< Timestamp of last motor status message + int64_t engineLastStatus = 0; ///< Timestamp of last engine status message uint8_t mainState = 0; uint8_t rigState = 0; - uint8_t motorState = 0; + uint8_t engineState = 0; bool mainArmed = false; bool rigArmed = false; - int16_t motorLogNumber = -1; - bool motorLogGood = false; - bool motorHil = false; + int16_t engineLogNumber = -1; + bool engineLogGood = false; + bool engineHil = false; bool isMainConnected(); bool isRigConnected(); - bool isMotorConnected(); + bool isEngineConnected(); }; class CanHandler diff --git a/src/Payload/HIL/HIL.cpp b/src/Payload/HIL/HIL.cpp index 304f82bd25caf309ef4580a9b69384e1dc36d469..3c9319d95d668a294b6173f1b31a0348960d1f61 100644 --- a/src/Payload/HIL/HIL.cpp +++ b/src/Payload/HIL/HIL.cpp @@ -53,7 +53,7 @@ PayloadHILPhasesManager::PayloadHILPhasesManager( {PayloadFlightPhases::ARMED, false}, {PayloadFlightPhases::LIFTOFF_PIN_DETACHED, false}, {PayloadFlightPhases::LIFTOFF, false}, - {PayloadFlightPhases::MOTOR_SHUTDOWN, false}, + {PayloadFlightPhases::ENGINE_SHUTDOWN, false}, {PayloadFlightPhases::AEROBRAKES, false}, {PayloadFlightPhases::APOGEE, false}, {PayloadFlightPhases::PARA1, false}, @@ -73,7 +73,7 @@ PayloadHILPhasesManager::PayloadHILPhasesManager( eventBroker.subscribe(this, Common::TOPIC_FSR); eventBroker.subscribe(this, Common::TOPIC_NAS); eventBroker.subscribe(this, Common::TOPIC_TMTC); - eventBroker.subscribe(this, Common::TOPIC_MOTOR); + eventBroker.subscribe(this, Common::TOPIC_ENGINE); eventBroker.subscribe(this, Common::TOPIC_TARS); eventBroker.subscribe(this, Common::TOPIC_ALT); } @@ -121,8 +121,8 @@ void PayloadHILPhasesManager::printOutcomes() printf("Simulation time: %.3f [sec]\n\n", (double)(t_stop - t_start) / 1000000.0f); - printf("Motor shutdown: \n"); - outcomes[PayloadFlightPhases::MOTOR_SHUTDOWN].print(t_liftoff); + printf("Engine shutdown: \n"); + outcomes[PayloadFlightPhases::ENGINE_SHUTDOWN].print(t_liftoff); printf("Apogee: \n"); outcomes[PayloadFlightPhases::APOGEE].print(t_liftoff); @@ -179,12 +179,12 @@ void PayloadHILPhasesManager::handleEventImpl( getCurrentPosition().z, getCurrentPosition().vz); changed_flags.push_back(PayloadFlightPhases::LIFTOFF); break; - case Common::Events::FLIGHT_MOTOR_SHUTDOWN: - setFlagFlightPhase(PayloadFlightPhases::MOTOR_SHUTDOWN, true); - registerOutcomes(PayloadFlightPhases::MOTOR_SHUTDOWN); - printf("[HIL] ------- MOTOR SHUTDOWN ! ------- %f, %f \n", + case Common::Events::FLIGHT_ENGINE_SHUTDOWN: + setFlagFlightPhase(PayloadFlightPhases::ENGINE_SHUTDOWN, true); + registerOutcomes(PayloadFlightPhases::ENGINE_SHUTDOWN); + printf("[HIL] ------- ENGINE SHUTDOWN ! ------- %f, %f \n", getCurrentPosition().z, getCurrentPosition().vz); - changed_flags.push_back(PayloadFlightPhases::MOTOR_SHUTDOWN); + changed_flags.push_back(PayloadFlightPhases::ENGINE_SHUTDOWN); break; case Common::Events::FLIGHT_APOGEE_DETECTED: case Common::Events::CAN_APOGEE_DETECTED: diff --git a/src/Payload/HIL/HILData.h b/src/Payload/HIL/HILData.h index 3dd0597783ad688da95fc0b9ed8a71ec564b59eb..11e6807d693f97715a09ea394dc6f7deed4251bf 100644 --- a/src/Payload/HIL/HILData.h +++ b/src/Payload/HIL/HILData.h @@ -67,7 +67,7 @@ enum class PayloadFlightPhases ARMED, LIFTOFF_PIN_DETACHED, LIFTOFF, - MOTOR_SHUTDOWN, + ENGINE_SHUTDOWN, AEROBRAKES, APOGEE, PARA1, diff --git a/src/Payload/Radio/MessageHandler.cpp b/src/Payload/Radio/MessageHandler.cpp index 42e9172d053267c0b80b2b2c7aa32f85d18e1b25..599aabcee342e424184dd354498bad91ba84abd8 100644 --- a/src/Payload/Radio/MessageHandler.cpp +++ b/src/Payload/Radio/MessageHandler.cpp @@ -678,10 +678,10 @@ bool Radio::MavlinkBackend::enqueueSystemTm(SystemTMList tmId) auto canStatus = parent.getModule<CanHandler>()->getCanStatus(); tm.main_board_state = canStatus.mainState; - tm.motor_board_state = canStatus.motorState; + tm.motor_board_state = canStatus.engineState; tm.main_can_status = canStatus.isMainConnected(); - tm.motor_can_status = canStatus.isMotorConnected(); + tm.motor_can_status = canStatus.isEngineConnected(); tm.rig_can_status = canStatus.isRigConnected(); tm.hil_state = PersistentVars::getHilMode(); @@ -732,11 +732,11 @@ bool Radio::MavlinkBackend::enqueueSystemTm(SystemTMList tmId) tm.combustion_chamber_pressure = -1.0f; tm.tank_temperature = -1.0f; tm.battery_voltage = -1.0f; - tm.log_good = canStatus.motorLogGood; - tm.log_number = canStatus.motorLogNumber; + tm.log_good = canStatus.engineLogGood; + tm.log_number = canStatus.engineLogNumber; tm.main_valve_state = 255; tm.venting_valve_state = 255; - tm.hil_state = canStatus.motorHil; + tm.hil_state = canStatus.engineHil; mavlink_msg_motor_tm_encode(config::Mavlink::SYSTEM_ID, config::Mavlink::COMPONENT_ID, &msg, diff --git a/src/common/CanConfig.h b/src/common/CanConfig.h index 579c5c920467014e2a7f97eeb8dc296bc620e170..8ccda3495f7d4e8bb83539bc64215bed95a59fcb 100644 --- a/src/common/CanConfig.h +++ b/src/common/CanConfig.h @@ -67,7 +67,7 @@ enum class Board : uint8_t RIG, MAIN, PAYLOAD, - MOTOR + ENGINE }; enum class SensorId : uint8_t @@ -77,13 +77,15 @@ enum class SensorId : uint8_t PITOT_STATIC_PRESSURE, PITOT_TOTAL_PRESSURE, CC_PRESSURE, - BOTTOM_TANK_PRESSURE, - TOP_TANK_PRESSURE, + OX_BOTTOM_TANK_PRESSURE_0, + OX_BOTTOM_TANK_PRESSURE_1, + OX_TOP_TANK_PRESSURE, + N2_TANK_PRESSURE, TANK_TEMPERATURE, - MOTOR_ACTUATORS_CURRENT, + ENGINE_ACTUATORS_CURRENT, MAIN_BOARD_CURRENT, PAYLOAD_BOARD_CURRENT, - MOTOR_BOARD_VOLTAGE + ENGINE_BOARD_VOLTAGE }; enum class EventId : uint8_t diff --git a/src/common/Events.h b/src/common/Events.h index 5e02ec8629f033da64bcd0977960a9cdf8687d63..967aeaade1c8993594911af766cad8d9a4e8e9ed 100644 --- a/src/common/Events.h +++ b/src/common/Events.h @@ -89,7 +89,7 @@ enum Events : uint8_t FLIGHT_LANDING_TIMEOUT, FLIGHT_LAUNCH_PIN_DETACHED, FLIGHT_LIFTOFF, - FLIGHT_MOTOR_SHUTDOWN, + FLIGHT_ENGINE_SHUTDOWN, FLIGHT_MISSION_TIMEOUT, FLIGHT_NC_DETACHED, FLIGHT_WING_DESCENT, @@ -142,36 +142,36 @@ enum Events : uint8_t TMTC_ARP_CALIBRATE, TMTC_ARP_ENTER_TEST_MODE, TMTC_ARP_EXIT_TEST_MODE, - MOTOR_START_TARS, - MOTOR_STOP_TARS, - MOTOR_OX_FIL_OPEN, - MOTOR_OX_FIL_CLOSE, - MOTOR_OX_REL_OPEN, - MOTOR_OX_REL_CLOSE, - MOTOR_OX_DET_OPEN, - MOTOR_OX_DET_CLOSE, - MOTOR_N2_3W_OPEN, - MOTOR_N2_3W_CLOSE, - MOTOR_N2_FIL_OPEN, - MOTOR_N2_FIL_CLOSE, - MOTOR_N2_REL_OPEN, - MOTOR_N2_REL_CLOSE, - MOTOR_N2_DET_OPEN, - MOTOR_N2_DET_CLOSE, - MOTOR_NITR_OPEN, - MOTOR_NITR_CLOSE, - MOTOR_OX_VEN_OPEN, - MOTOR_OX_VEN_CLOSE, - MOTOR_N2_QUE_OPEN, - MOTOR_N2_QUE_CLOSE, - MOTOR_MAIN_OPEN, - MOTOR_MAIN_CLOSE, - MOTOR_IGNITION, - MOTOR_MANUAL_ACTION, - MOTOR_OPEN_OXIDANT, - MOTOR_COOLING_TIMEOUT, - MOTOR_SHADOW_MODE_TIMEOUT, - MOTOR_OPEN_CHAMBER, + ENGINE_START_TARS, + ENGINE_STOP_TARS, + ENGINE_OX_FIL_OPEN, + ENGINE_OX_FIL_CLOSE, + ENGINE_OX_REL_OPEN, + ENGINE_OX_REL_CLOSE, + ENGINE_OX_DET_OPEN, + ENGINE_OX_DET_CLOSE, + ENGINE_N2_3W_OPEN, + ENGINE_N2_3W_CLOSE, + ENGINE_N2_FIL_OPEN, + ENGINE_N2_FIL_CLOSE, + ENGINE_N2_REL_OPEN, + ENGINE_N2_REL_CLOSE, + ENGINE_N2_DET_OPEN, + ENGINE_N2_DET_CLOSE, + ENGINE_NITR_OPEN, + ENGINE_NITR_CLOSE, + ENGINE_OX_VEN_OPEN, + ENGINE_OX_VEN_CLOSE, + ENGINE_N2_QUE_OPEN, + ENGINE_N2_QUE_CLOSE, + ENGINE_MAIN_OPEN, + ENGINE_MAIN_CLOSE, + ENGINE_IGNITION, + ENGINE_MANUAL_ACTION, + ENGINE_OPEN_OXIDANT, + ENGINE_COOLING_TIMEOUT, + ENGINE_SHADOW_MODE_TIMEOUT, + ENGINE_OPEN_CHAMBER, TARS_WASHING_DONE, TARS_CHECK_PRESSURE_STABILIZE, TARS_PRESSURE_STABILIZED, @@ -237,7 +237,7 @@ inline std::string getEventString(uint8_t event) {FLIGHT_LANDING_DETECTED, "FLIGHT_LANDING_DETECTED"}, {FLIGHT_LAUNCH_PIN_DETACHED, "FLIGHT_LAUNCH_PIN_DETACHED"}, {FLIGHT_LIFTOFF, "FLIGHT_LIFTOFF"}, - {FLIGHT_MOTOR_SHUTDOWN, "FLIGHT_MOTOR_SHUTDOWN"}, + {FLIGHT_ENGINE_SHUTDOWN, "FLIGHT_ENGINE_SHUTDOWN"}, {FLIGHT_LANDING_TIMEOUT, "FLIGHT_LANDING_TIMEOUT"}, {FLIGHT_NC_DETACHED, "FLIGHT_NC_DETACHED"}, {FLIGHT_MISSION_TIMEOUT, "FLIGHT_MISSION_TIMEOUT"}, @@ -291,36 +291,36 @@ inline std::string getEventString(uint8_t event) {TMTC_ARP_FOLLOW, "TMTC_ARP_FOLLOW"}, {TMTC_ARP_ENTER_TEST_MODE, "TMTC_ARP_ENTER_TEST_MODE"}, {TMTC_ARP_EXIT_TEST_MODE, "TMTC_ARP_EXIT_TEST_MODE"}, - {MOTOR_START_TARS, "MOTOR_START_TARS"}, - {MOTOR_STOP_TARS, "MOTOR_STOP_TARS"}, - {MOTOR_OX_FIL_OPEN, "MOTOR_OX_FIL_OPEN"}, - {MOTOR_OX_FIL_CLOSE, "MOTOR_OX_FIL_CLOSE"}, - {MOTOR_OX_REL_OPEN, "MOTOR_OX_REL_OPEN"}, - {MOTOR_OX_REL_CLOSE, "MOTOR_OX_REL_CLOSE"}, - {MOTOR_OX_DET_OPEN, "MOTOR_OX_DET_OPEN"}, - {MOTOR_OX_DET_CLOSE, "MOTOR_OX_DET_CLOSE"}, - {MOTOR_N2_3W_OPEN, "MOTOR_N2_3W_OPEN"}, - {MOTOR_N2_3W_CLOSE, "MOTOR_N2_3W_CLOSE"}, - {MOTOR_N2_FIL_OPEN, "MOTOR_N2_FIL_OPEN"}, - {MOTOR_N2_FIL_CLOSE, "MOTOR_N2_FIL_CLOSE"}, - {MOTOR_N2_REL_OPEN, "MOTOR_N2_REL_OPEN"}, - {MOTOR_N2_REL_CLOSE, "MOTOR_N2_REL_CLOSE"}, - {MOTOR_N2_DET_OPEN, "MOTOR_N2_DET_OPEN"}, - {MOTOR_N2_DET_CLOSE, "MOTOR_N2_DET_CLOSE"}, - {MOTOR_NITR_OPEN, "MOTOR_NITR_OPEN"}, - {MOTOR_NITR_CLOSE, "MOTOR_NITR_CLOSE"}, - {MOTOR_OX_VEN_OPEN, "MOTOR_OX_VEN_OPEN"}, - {MOTOR_OX_VEN_CLOSE, "MOTOR_OX_VEN_CLOSE"}, - {MOTOR_N2_QUE_OPEN, "MOTOR_N2_QUE_OPEN"}, - {MOTOR_N2_QUE_CLOSE, "MOTOR_N2_QUE_CLOSE"}, - {MOTOR_MAIN_OPEN, "MOTOR_MAIN_OPEN"}, - {MOTOR_MAIN_CLOSE, "MOTOR_MAIN_CLOSE"}, - {MOTOR_IGNITION, "MOTOR_IGNITION"}, - {MOTOR_MANUAL_ACTION, "MOTOR_MANUAL_ACTION"}, - {MOTOR_OPEN_OXIDANT, "MOTOR_OPEN_OXIDANT"}, - {MOTOR_COOLING_TIMEOUT, "MOTOR_COOLING_TIMEOUT"}, - {MOTOR_SHADOW_MODE_TIMEOUT, "MOTOR_SHADOW_MODE_TIMEOUT"}, - {MOTOR_OPEN_CHAMBER, "MOTOR_OPEN_CHAMBER"}, + {ENGINE_START_TARS, "ENGINE_START_TARS"}, + {ENGINE_STOP_TARS, "ENGINE_STOP_TARS"}, + {ENGINE_OX_FIL_OPEN, "ENGINE_OX_FIL_OPEN"}, + {ENGINE_OX_FIL_CLOSE, "ENGINE_OX_FIL_CLOSE"}, + {ENGINE_OX_REL_OPEN, "ENGINE_OX_REL_OPEN"}, + {ENGINE_OX_REL_CLOSE, "ENGINE_OX_REL_CLOSE"}, + {ENGINE_OX_DET_OPEN, "ENGINE_OX_DET_OPEN"}, + {ENGINE_OX_DET_CLOSE, "ENGINE_OX_DET_CLOSE"}, + {ENGINE_N2_3W_OPEN, "ENGINE_N2_3W_OPEN"}, + {ENGINE_N2_3W_CLOSE, "ENGINE_N2_3W_CLOSE"}, + {ENGINE_N2_FIL_OPEN, "ENGINE_N2_FIL_OPEN"}, + {ENGINE_N2_FIL_CLOSE, "ENGINE_N2_FIL_CLOSE"}, + {ENGINE_N2_REL_OPEN, "ENGINE_N2_REL_OPEN"}, + {ENGINE_N2_REL_CLOSE, "ENGINE_N2_REL_CLOSE"}, + {ENGINE_N2_DET_OPEN, "ENGINE_N2_DET_OPEN"}, + {ENGINE_N2_DET_CLOSE, "ENGINE_N2_DET_CLOSE"}, + {ENGINE_NITR_OPEN, "ENGINE_NITR_OPEN"}, + {ENGINE_NITR_CLOSE, "ENGINE_NITR_CLOSE"}, + {ENGINE_OX_VEN_OPEN, "ENGINE_OX_VEN_OPEN"}, + {ENGINE_OX_VEN_CLOSE, "ENGINE_OX_VEN_CLOSE"}, + {ENGINE_N2_QUE_OPEN, "ENGINE_N2_QUE_OPEN"}, + {ENGINE_N2_QUE_CLOSE, "ENGINE_N2_QUE_CLOSE"}, + {ENGINE_MAIN_OPEN, "ENGINE_MAIN_OPEN"}, + {ENGINE_MAIN_CLOSE, "ENGINE_MAIN_CLOSE"}, + {ENGINE_IGNITION, "ENGINE_IGNITION"}, + {ENGINE_MANUAL_ACTION, "ENGINE_MANUAL_ACTION"}, + {ENGINE_OPEN_OXIDANT, "ENGINE_OPEN_OXIDANT"}, + {ENGINE_COOLING_TIMEOUT, "ENGINE_COOLING_TIMEOUT"}, + {ENGINE_SHADOW_MODE_TIMEOUT, "ENGINE_SHADOW_MODE_TIMEOUT"}, + {ENGINE_OPEN_CHAMBER, "ENGINE_OPEN_CHAMBER"}, {TARS_WASHING_DONE, "TARS_WASHING_DONE"}, {TARS_CHECK_PRESSURE_STABILIZE, "TARS_CHECK_PRESSURE_STABILIZE"}, {TARS_PRESSURE_STABILIZED, "TARS_PRESSURE_STABILIZED"}, diff --git a/src/common/Topics.h b/src/common/Topics.h index 37c83378b8c33e1938504aea4c94ad625728e2af..3033e9f634bfb5868f184a5c76fca1a13d1805a3 100644 --- a/src/common/Topics.h +++ b/src/common/Topics.h @@ -42,7 +42,7 @@ enum Topics : uint8_t TOPIC_FSR, TOPIC_NAS, TOPIC_TMTC, - TOPIC_MOTOR, + TOPIC_ENGINE, TOPIC_TARS, TOPIC_ALT, TOPIC_WING, @@ -51,6 +51,6 @@ enum Topics : uint8_t const std::vector<uint8_t> TOPICS_LIST{ TOPIC_ABK, TOPIC_ADA, TOPIC_MEA, TOPIC_ARP, TOPIC_DPL, TOPIC_CAN, TOPIC_FLIGHT, TOPIC_FMM, TOPIC_FSR, TOPIC_NAS, - TOPIC_TMTC, TOPIC_MOTOR, TOPIC_TARS, TOPIC_ALT, TOPIC_WING}; + TOPIC_TMTC, TOPIC_ENGINE, TOPIC_TARS, TOPIC_ALT, TOPIC_WING}; } // namespace Common