diff --git a/scripts/logdecoder/General/logdecoder.cpp b/scripts/logdecoder/General/logdecoder.cpp index 73451409ca657ab5d9168ba86829dfd049c4cba4..c2639f17f9dc77a5cce605effb5cb22d7846d97d 100644 --- a/scripts/logdecoder/General/logdecoder.cpp +++ b/scripts/logdecoder/General/logdecoder.cpp @@ -106,13 +106,17 @@ void registerTypes(Deserializer& ds) // RIGv2 ds.registerType<RIGv2::ADC1Data>(); + ds.registerType<RIGv2::ADC2Data>(); ds.registerType<RIGv2::TC1Data>(); - ds.registerType<RIGv2::VesselWeightData>(); - ds.registerType<RIGv2::TankWeightData>(); - ds.registerType<RIGv2::VesselPressureData>(); - ds.registerType<RIGv2::FillingPressureData>(); - ds.registerType<RIGv2::TopTankPressureData>(); - ds.registerType<RIGv2::BottomTankPressureData>(); + ds.registerType<RIGv2::OxVesselWeightData>(); + ds.registerType<RIGv2::OxTankWeightData>(); + ds.registerType<RIGv2::OxVesselPressureData>(); + ds.registerType<RIGv2::OxFillingPressureData>(); + ds.registerType<RIGv2::N2Vessel1PressureData>(); + ds.registerType<RIGv2::N2Vessel2PressureData>(); + ds.registerType<RIGv2::N2FillingPressureData>(); + ds.registerType<RIGv2::OxTankTopPressureData>(); + ds.registerType<RIGv2::OxTankBottomPressureData>(); ds.registerType<RIGv2::ActuatorsData>(); ds.registerType<RIGv2::GroundModeManagerData>(); ds.registerType<RIGv2::TarsActionData>(); diff --git a/scripts/logdecoder/RIGv2/logdecoder.cpp b/scripts/logdecoder/RIGv2/logdecoder.cpp index 6709b7eca9046bf014350cc9b2a115683a9757ed..666ae2f71b2185ac68989df5efbef11f8dccdc98 100644 --- a/scripts/logdecoder/RIGv2/logdecoder.cpp +++ b/scripts/logdecoder/RIGv2/logdecoder.cpp @@ -54,13 +54,17 @@ void registerTypes(Deserializer& ds) // Custom types ds.registerType<ADC1Data>(); + ds.registerType<ADC2Data>(); ds.registerType<TC1Data>(); - ds.registerType<VesselWeightData>(); - ds.registerType<TankWeightData>(); - ds.registerType<VesselPressureData>(); - ds.registerType<FillingPressureData>(); - ds.registerType<TopTankPressureData>(); - ds.registerType<BottomTankPressureData>(); + ds.registerType<OxVesselWeightData>(); + ds.registerType<OxTankWeightData>(); + ds.registerType<OxVesselPressureData>(); + ds.registerType<OxFillingPressureData>(); + ds.registerType<N2Vessel1PressureData>(); + ds.registerType<N2Vessel2PressureData>(); + ds.registerType<N2FillingPressureData>(); + ds.registerType<OxTankTopPressureData>(); + ds.registerType<OxTankBottomPressureData>(); ds.registerType<ActuatorsData>(); ds.registerType<GroundModeManagerData>(); ds.registerType<TarsActionData>(); diff --git a/skyward-boardcore b/skyward-boardcore index ef4e55b6575914cc021c4eb36173db9339d3a7c8..ead06db6a21548d24e3004a0027ae19a501bbaf1 160000 --- a/skyward-boardcore +++ b/skyward-boardcore @@ -1 +1 @@ -Subproject commit ef4e55b6575914cc021c4eb36173db9339d3a7c8 +Subproject commit ead06db6a21548d24e3004a0027ae19a501bbaf1 diff --git a/src/RIGv2/Actuators/Actuators.cpp b/src/RIGv2/Actuators/Actuators.cpp index 26e29428228639febb8bb89cd8f357a0b0207b54..4125625826a6f9270b8c9553e9d890479de1d956 100644 --- a/src/RIGv2/Actuators/Actuators.cpp +++ b/src/RIGv2/Actuators/Actuators.cpp @@ -1,5 +1,5 @@ -/* Copyright (c) 2024 Skyward Experimental Rocketry - * Authors: Davide Mor +/* Copyright (c) 2025 Skyward Experimental Rocketry + * Authors: Davide Mor, Niccolò Betto * * Permission is hereby granted, free of charge, to any person obtaining a copy * of this software and associated documentation files (the "Software"), to deal @@ -27,6 +27,9 @@ #include <common/Events.h> #include <drivers/timer/TimestampTimer.h> #include <events/EventBroker.h> +#include <interfaces-impl/hwmapping.h> + +#include "ActuatorsMacros.h" using namespace Boardcore; using namespace miosix; @@ -40,8 +43,8 @@ void Actuators::ServoInfo::openServoWithTime(uint32_t time) closeTs = currentTime + (time * Constants::NS_IN_MS); lastActionTs = currentTime; - if (openingEvent != 0) - EventBroker::getInstance().post(openingEvent, TOPIC_MOTOR); + if (config.openingEvent != 0) + EventBroker::getInstance().post(config.openingEvent, TOPIC_MOTOR); } void Actuators::ServoInfo::closeServo() @@ -49,8 +52,8 @@ void Actuators::ServoInfo::closeServo() closeTs = 0; lastActionTs = getTime(); - if (closingEvent != 0) - EventBroker::getInstance().post(closingEvent, TOPIC_MOTOR); + if (config.closingEvent != 0) + EventBroker::getInstance().post(config.closingEvent, TOPIC_MOTOR); } void Actuators::ServoInfo::unsafeSetServoPosition(float position) @@ -59,8 +62,8 @@ void Actuators::ServoInfo::unsafeSetServoPosition(float position) if (!servo) return; - position *= limit; - if (flipped) + position *= config.limit; + if (config.flipped) position = 1.0f - position; servo->setPosition(position); @@ -73,30 +76,30 @@ float Actuators::ServoInfo::getServoPosition() return 0.0f; float position = servo->getPosition(); - if (flipped) + if (config.flipped) position = 1.0f - position; - position /= limit; + position /= config.limit; return position; } float Actuators::ServoInfo::getMaxAperture() { - return getModule<Registry>()->getOrSetDefaultUnsafe(maxApertureKey, - defaultMaxAperture); + return getModule<Registry>()->getOrSetDefaultUnsafe( + config.maxApertureRegKey, config.defaultMaxAperture); } uint32_t Actuators::ServoInfo::getOpeningTime() { - return getModule<Registry>()->getOrSetDefaultUnsafe(openingTimeKey, - defaultOpeningTime); + return getModule<Registry>()->getOrSetDefaultUnsafe( + config.openingTimeRegKey, config.defaultOpeningTime); } bool Actuators::ServoInfo::setMaxAperture(float aperture) { if (aperture >= 0.0 && aperture <= 1.0) { - getModule<Registry>()->setUnsafe(maxApertureKey, aperture); + getModule<Registry>()->setUnsafe(config.maxApertureRegKey, aperture); return true; } else @@ -108,110 +111,24 @@ bool Actuators::ServoInfo::setMaxAperture(float aperture) bool Actuators::ServoInfo::setOpeningTime(uint32_t time) { - getModule<Registry>()->setUnsafe(openingTimeKey, time); + getModule<Registry>()->setUnsafe(config.openingTimeRegKey, time); return true; } Actuators::Actuators() + : infos{ + MAKE_SERVO(OX_FIL), MAKE_SERVO(OX_REL), + MAKE_DETACH_SERVO(OX_DET), + MAKE_SERVO(N2_FIL), MAKE_SERVO(N2_REL), + MAKE_DETACH_SERVO(N2_DET), MAKE_SERVO(NITR), + MAKE_SERVO(OX_VEN), MAKE_SERVO(N2_QUE), + MAKE_SERVO(MAIN), + }, n2_3wayValveInfo(MAKE_SIMPLE_SERVO(N2_3W)) { - // Initialize servos - infos[0].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[1].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[2].servo = std::make_unique<Servo>( - MIOSIX_SERVOS_3_TIM, TimerUtils::Channel::MIOSIX_SERVOS_3_CHANNEL, - Config::Servos::SERVO2_MIN_PULSE, Config::Servos::SERVO2_MAX_PULSE, - Config::Servos::FREQUENCY); - infos[3].servo = std::make_unique<Servo>( - MIOSIX_SERVOS_4_TIM, TimerUtils::Channel::MIOSIX_SERVOS_4_CHANNEL, - Config::Servos::MIN_PULSE, Config::Servos::MAX_PULSE, - Config::Servos::FREQUENCY); - // This servo is currently unusable, due to it sharing the same timer as - // miosix, TIM5 infos[4].servo = std::make_unique<Servo>( - // MIOSIX_SERVOS_5_TIM, TimerUtils::Channel::MIOSIX_SERVOS_5_CHANNEL, - // Config::Servos::MIN_PULSE, Config::Servos::MAX_PULSE, - // Config::Servos::FREQUENCY); - infos[5].servo = std::make_unique<Servo>( - MIOSIX_SERVOS_6_TIM, TimerUtils::Channel::MIOSIX_SERVOS_6_CHANNEL, - Config::Servos::MIN_PULSE, Config::Servos::MAX_PULSE, - Config::Servos::FREQUENCY); - infos[6].servo = std::make_unique<Servo>( - MIOSIX_SERVOS_7_TIM, TimerUtils::Channel::MIOSIX_SERVOS_7_CHANNEL, - Config::Servos::MIN_PULSE, Config::Servos::MAX_PULSE, - Config::Servos::FREQUENCY); - // This servo is currently unusable, due to it sharing the same timer as - // servo 1 infos[7].servo = std::make_unique<Servo>( - // MIOSIX_SERVOS_8_TIM, TimerUtils::Channel::MIOSIX_SERVOS_8_CHANNEL, - // Config::Servos::MIN_PULSE, Config::Servos::MAX_PULSE, - // Config::Servos::FREQUENCY); - infos[8].servo = std::make_unique<Servo>( - MIOSIX_SERVOS_9_TIM, TimerUtils::Channel::MIOSIX_SERVOS_9_CHANNEL, - Config::Servos::MIN_PULSE, Config::Servos::MAX_PULSE, - Config::Servos::FREQUENCY); - infos[9].servo = std::make_unique<Servo>( - MIOSIX_SERVOS_10_TIM, TimerUtils::Channel::MIOSIX_SERVOS_10_CHANNEL, - Config::Servos::MIN_PULSE, Config::Servos::MAX_PULSE, - Config::Servos::FREQUENCY); - - ServoInfo* info; - info = getServo(ServosList::FILLING_VALVE); - info->defaultMaxAperture = Config::Servos::DEFAULT_FILLING_MAX_APERTURE; - info->defaultOpeningTime = Config::Servos::DEFAULT_FILLING_OPENING_TIME; - info->limit = Config::Servos::FILLING_LIMIT; - info->flipped = Config::Servos::FILLING_FLIPPED; - info->openingEvent = Common::Events::MOTOR_OPEN_FILLING_VALVE; - info->closingEvent = Common::Events::MOTOR_CLOSE_FILLING_VALVE; - info->openingTimeKey = CONFIG_ID_FILLING_OPENING_TIME; - info->maxApertureKey = CONFIG_ID_FILLING_MAX_APERTURE; - info->unsafeSetServoPosition(0.0f); - - info = getServo(ServosList::RELEASE_VALVE); - info->defaultMaxAperture = Config::Servos::DEFAULT_RELEASE_MAX_APERTURE; - info->defaultOpeningTime = Config::Servos::DEFAULT_RELEASE_OPENING_TIME; - info->limit = Config::Servos::RELEASE_LIMIT; - info->flipped = Config::Servos::RELEASE_FLIPPED; - info->openingEvent = Common::Events::MOTOR_OPEN_RELEASE_VALVE; - info->closingEvent = Common::Events::MOTOR_CLOSE_RELEASE_VALVE; - info->openingTimeKey = CONFIG_ID_RELEASE_OPENING_TIME; - info->maxApertureKey = CONFIG_ID_RELEASE_MAX_APERTURE; - info->unsafeSetServoPosition(0.0f); - - info = getServo(ServosList::DISCONNECT_SERVO); - info->defaultMaxAperture = Config::Servos::DEFAULT_DISCONNECT_MAX_APERTURE; - info->defaultOpeningTime = Config::Servos::DEFAULT_DISCONNECT_OPENING_TIME; - info->limit = Config::Servos::DISCONNECT_LIMIT; - info->flipped = Config::Servos::DISCONNECT_FLIPPED; - info->openingEvent = Common::Events::MOTOR_DISCONNECT; - info->openingTimeKey = CONFIG_ID_DISCONNECT_OPENING_TIME; - info->maxApertureKey = CONFIG_ID_DISCONNECT_MAX_APERTURE; - info->unsafeSetServoPosition(0.0f); - - info = getServo(ServosList::MAIN_VALVE); - info->defaultMaxAperture = Config::Servos::DEFAULT_MAIN_MAX_APERTURE; - info->defaultOpeningTime = Config::Servos::DEFAULT_MAIN_OPENING_TIME; - info->limit = Config::Servos::MAIN_LIMIT; - info->flipped = Config::Servos::MAIN_FLIPPED; - info->openingEvent = Common::Events::MOTOR_OPEN_FEED_VALVE; - info->closingEvent = Common::Events::MOTOR_CLOSE_FEED_VALVE; - info->openingTimeKey = CONFIG_ID_MAIN_OPENING_TIME; - info->maxApertureKey = CONFIG_ID_MAIN_MAX_APERTURE; - info->unsafeSetServoPosition(0.0f); - - info = getServo(ServosList::VENTING_VALVE); - info->defaultMaxAperture = Config::Servos::DEFAULT_VENTING_MAX_APERTURE; - info->defaultOpeningTime = Config::Servos::DEFAULT_VENTING_OPENING_TIME; - info->limit = Config::Servos::VENTING_LIMIT; - info->flipped = Config::Servos::VENTING_FLIPPED; - info->openingEvent = Common::Events::MOTOR_OPEN_VENTING_VALVE; - info->closingEvent = Common::Events::MOTOR_CLOSE_VENTING_VALVE; - info->openingTimeKey = CONFIG_ID_VENTING_OPENING_TIME; - info->maxApertureKey = CONFIG_ID_VENTING_MAX_APERTURE; - info->unsafeSetServoPosition(0.0f); + for (auto& servo : infos) + servo.unsafeSetServoPosition(0.0f); + + n2_3wayValveInfo.unsafeSetServoPosition(0.0f); } bool Actuators::isStarted() { return started; } @@ -221,16 +138,9 @@ bool Actuators::start() TaskScheduler& scheduler = getModule<BoardScheduler>()->getActuatorsScheduler(); - infos[0].servo->enable(); - infos[1].servo->enable(); - infos[2].servo->enable(); - infos[3].servo->enable(); - // infos[4].servo->enable(); - infos[5].servo->enable(); - infos[6].servo->enable(); - // infos[7].servo->enable(); - infos[8].servo->enable(); - infos[9].servo->enable(); + // Enable all servos + for (ServoInfo& info : infos) + info.servo->enable(); uint8_t result = scheduler.addTask([this]() { updatePositionsTask(); }, @@ -328,7 +238,8 @@ void Actuators::closeAllServos() infos[idx].closeServo(); getModule<CanHandler>()->sendServoCloseCommand(ServosList::MAIN_VALVE); - getModule<CanHandler>()->sendServoCloseCommand(ServosList::VENTING_VALVE); + getModule<CanHandler>()->sendServoCloseCommand( + ServosList::N2O_VENTING_VALVE); } bool Actuators::setMaxAperture(ServosList servo, float aperture) @@ -366,36 +277,37 @@ bool Actuators::isCanServoOpen(ServosList servo) Lock<FastMutex> lock(infosMutex); if (servo == ServosList::MAIN_VALVE) return canMainOpen; - else if (servo == ServosList::VENTING_VALVE) + else if (servo == ServosList::N2O_VENTING_VALVE) return canVentingOpen; else return false; } -void Actuators::openNitrogen() +void Actuators::set3wayValveState(bool state) { - openNitrogenWithTime(Config::Actuators::NITROGEN_OPENING_TIME); + auto position = state ? 1.0f : 0.0f; + n2_3wayValveInfo.unsafeSetServoPosition(position); } -void Actuators::openNitrogenWithTime(uint32_t time) +void Actuators::openChamberWithTime(uint32_t time) { Lock<FastMutex> lock(infosMutex); long long currentTime = getTime(); - nitrogenCloseTs = currentTime + (time * Constants::NS_IN_MS); - nitrogenLastActionTs = currentTime; + chamberCloseTs = currentTime + (time * Constants::NS_IN_MS); + chamberLastActionTs = currentTime; } -void Actuators::closeNitrogen() +void Actuators::closeChamber() { Lock<FastMutex> lock(infosMutex); - nitrogenCloseTs = 0; + chamberCloseTs = 0; } -bool Actuators::isNitrogenOpen() +bool Actuators::isChamberOpen() { Lock<FastMutex> lock(infosMutex); - return nitrogenCloseTs != 0; + return chamberCloseTs != 0; } uint32_t Actuators::getServoOpeningTime(ServosList servo) @@ -423,7 +335,7 @@ void Actuators::setCanServoOpen(ServosList servo, bool open) Lock<FastMutex> lock(infosMutex); if (servo == ServosList::MAIN_VALVE) canMainOpen = open; - else if (servo == ServosList::VENTING_VALVE) + else if (servo == ServosList::N2O_VENTING_VALVE) canVentingOpen = open; } @@ -438,16 +350,26 @@ Actuators::ServoInfo* Actuators::getServo(ServosList servo) { switch (servo) { - case FILLING_VALVE: + case N2O_FILLING_VALVE: // OX_FIL return &infos[0]; - case RELEASE_VALVE: + case N2O_RELEASE_VALVE: // OX_REL return &infos[1]; - case DISCONNECT_SERVO: + case N2O_DETACH_SERVO: // OX_DET return &infos[2]; - case MAIN_VALVE: - return &infos[3]; - case VENTING_VALVE: + case N2_FILLING_VALVE: // N2_FIL + return &infos[4]; + case N2_RELEASE_VALVE: // N2_REL + return &infos[5]; + case N2_DETACH_SERVO: // N2_DET return &infos[6]; + case NITROGEN_VALVE: // NITR + return &infos[7]; + case N2O_VENTING_VALVE: // OX_VEN + return &infos[8]; + case N2_QUENCHING_VALVE: // N2_QUE + return &infos[9]; + case MAIN_VALVE: // MAIN + return &infos[10]; default: // Oh FUCK @@ -468,9 +390,9 @@ void Actuators::unsafeSetServoPosition(uint8_t idx, float position) sdLogger.log(data); } -void Actuators::unsafeOpenNitrogen() { relays::nitrogen::low(); } +void Actuators::unsafeOpenChamber() { relays::nitrogen::low(); } -void Actuators::unsafeCloseNitrogen() { relays::nitrogen::high(); } +void Actuators::unsafeCloseChamber() { relays::nitrogen::high(); } void Actuators::updatePositionsTask() { @@ -526,14 +448,14 @@ void Actuators::updatePositionsTask() } // Handle nitrogen logic - if (currentTime < nitrogenCloseTs) + if (currentTime < chamberCloseTs) { - unsafeOpenNitrogen(); + unsafeOpenChamber(); } else { - nitrogenCloseTs = 0; + chamberCloseTs = 0; - unsafeCloseNitrogen(); + unsafeCloseChamber(); } } diff --git a/src/RIGv2/Actuators/Actuators.h b/src/RIGv2/Actuators/Actuators.h index 58342d074134aca1e148f84f61740faa2c759adb..75c413fcceee00f97e8cab0fd121d29335cd903e 100644 --- a/src/RIGv2/Actuators/Actuators.h +++ b/src/RIGv2/Actuators/Actuators.h @@ -1,5 +1,5 @@ -/* Copyright (c) 2024 Skyward Experimental Rocketry - * Authors: Davide Mor +/* Copyright (c) 2025 Skyward Experimental Rocketry + * Authors: Davide Mor, Niccolò Betto * * Permission is hereby granted, free of charge, to any person obtaining a copy * of this software and associated documentation files (the "Software"), to deal @@ -26,7 +26,7 @@ #include <RIGv2/CanHandler/CanHandler.h> #include <RIGv2/Registry/Registry.h> #include <actuators/Servo/Servo.h> -#include <common/MavlinkLyra.h> +#include <common/MavlinkOrion.h> #include <miosix.h> #include <scheduler/TaskScheduler.h> @@ -41,29 +41,34 @@ class Actuators private: struct ServoInfo : public Boardcore::InjectableWithDeps<Registry> { + struct ServoConfig + { + float limit = 1.0; ///< Movement range limit + bool flipped = false; ///< Whether the servo is flipped + uint32_t defaultOpeningTime = 1000; // Default opening time [ms] + float defaultMaxAperture = 1.0; // Max aperture + + uint8_t openingEvent = 0; ///< Event to fire after opening + uint8_t closingEvent = 0; ///< Event to fire after closing + uint32_t openingTimeRegKey = + CONFIG_ID_DEFAULT_OPENING_TIME; ///< Registry key for opening + ///< time + uint32_t maxApertureRegKey = + CONFIG_ID_DEFAULT_MAX_APERTURE; ///< Registry key for max + ///< aperture + }; + + ServoInfo(std::unique_ptr<Boardcore::Servo> servo, + const ServoConfig& config) + : servo(std::move(servo)), config(config) + { + } + std::unique_ptr<Boardcore::Servo> servo; - // Hard limit of the aperture - float limit = 1.0; - // Should this servo be reversed? - bool flipped = false; - // How much time to stay open - uint32_t defaultOpeningTime = 100000; // Default 100s [ms] - // What angle is the maximum - float defaultMaxAperture = 1.0; - - // What event to fire while opening? - uint8_t openingEvent = 0; - // What event to fire while closing? - uint8_t closingEvent = 0; - // How much time to stay open - uint32_t openingTimeKey = CONFIG_ID_DEFAULT_OPENING_TIME; - // What angle is the maximum - uint32_t maxApertureKey = CONFIG_ID_DEFAULT_MAX_APERTURE; - - // Timestamp of when the servo should close, 0 if closed - long long closeTs = 0; - // Timestamp of last servo action (open/close) - long long lastActionTs = 0; + ServoConfig config; + + long long closeTs = 0; ///< Timestamp to close the servo (0 if closed) + long long lastActionTs = 0; ///< Timestamp of last servo action void openServoWithTime(uint32_t time); void closeServo(); @@ -92,10 +97,14 @@ public: bool setOpeningTime(ServosList servo, uint32_t time); bool isServoOpen(ServosList servo); bool isCanServoOpen(ServosList servo); - void openNitrogen(); - void openNitrogenWithTime(uint32_t time); - void closeNitrogen(); - bool isNitrogenOpen(); + + // N2 3-way valve control + void set3wayValveState(bool state); + + // Chamber valve control + void openChamberWithTime(uint32_t time); + void closeChamber(); + bool isChamberOpen(); uint32_t getServoOpeningTime(ServosList servo); float getServoMaxAperture(ServosList servo); @@ -114,25 +123,26 @@ private: ServoInfo* getServo(ServosList servo); void unsafeSetServoPosition(uint8_t idx, float position); - void unsafeOpenNitrogen(); - void unsafeCloseNitrogen(); + void unsafeOpenChamber(); + void unsafeCloseChamber(); void updatePositionsTask(); - Boardcore::Logger& sdLogger = Boardcore::Logger::getInstance(); - Boardcore::PrintLogger logger = Boardcore::Logging::getLogger("actuators"); - std::atomic<bool> started{false}; miosix::FastMutex infosMutex; - ServoInfo infos[10] = {}; - // Timestamp of when the servo should close, 0 if closed - long long nitrogenCloseTs = 0; - // Timestamp of last servo action (open/close) - long long nitrogenLastActionTs = 0; + ServoInfo infos[10]; + ServoInfo n2_3wayValveInfo; + + long long chamberCloseTs = + 0; ///< Timestamp to close the chamber (0 if closed) + long long chamberLastActionTs = 0; ///< Timestamp of last chamber action bool canMainOpen = false; bool canVentingOpen = false; + + Boardcore::Logger& sdLogger = Boardcore::Logger::getInstance(); + Boardcore::PrintLogger logger = Boardcore::Logging::getLogger("actuators"); }; } // namespace RIGv2 diff --git a/src/RIGv2/Actuators/ActuatorsMacros.h b/src/RIGv2/Actuators/ActuatorsMacros.h new file mode 100644 index 0000000000000000000000000000000000000000..3fa941e94ce2a205190c010c0a45dd4fabba331c --- /dev/null +++ b/src/RIGv2/Actuators/ActuatorsMacros.h @@ -0,0 +1,128 @@ +/* Copyright (c) 2025 Skyward Experimental Rocketry + * Author: Niccolò Betto + * + * 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. + */ + +#pragma once + +/** + * @file ActuatorsMacros.h + * @brief Macros for the Actuators module + * + * This file contains macros to simplify the creation of ServoInfo structs + * for the Actuators module. + * + * The hardware mapping (hwmapping.h), the actuators configuration + * (ActuatorsConfig.h) and the registry keys (Registry.h) have been created with + * a specific naming convention to allow the use of these macros, to reduce the + * amount of code repetition and to make the code more readable during servo + * creation. + * + * The following naming convention is used: + * - The servo name is an uppercase string code (e.g. OX_FIL) + * - Constants are expected to be in the Config::Servos namespace + * - The servo name is used to create the following constants: + * - MIOSIX_SERVOS_{servo}_TIM (hwmapping) + * - MIOSIX_SERVOS_{servo}_CHANNEL (hwmapping) + * - {servo}_LIMIT (ActuatorsConfig) + * - {servo}_FLIPPED (ActuatorsConfig) + * - Common::MOTOR_{servo}_OPEN (Events) + * - Common::MOTOR_{servo}_CLOSE (Events) + * - DEFAULT_{servo}_OPENING_TIME (ActuatorsConfig) + * - DEFAULT_{servo}_MAX_APERTURE (ActuatorsConfig) + * - CONFIG_ID_{servo}_OPENING_TIME (Registry) + * - CONFIG_ID_{servo}_MAX_APERTURE (Registry) + * - The following constants are used for all servos: + * - MIN_PULSE + * - MAX_PULSE + * - FREQUENCY + */ + +/** + * @brief Shorthand to create a ServoInfo struct from the servo name + */ +#define MAKE_SERVO(name) \ + ServoInfo \ + { \ + std::make_unique<Servo>( \ + MIOSIX_SERVOS_##name##_TIM, \ + TimerUtils::Channel::MIOSIX_SERVOS_##name##_CHANNEL, \ + Config::Servos::MIN_PULSE, Config::Servos::MAX_PULSE, \ + Config::Servos::FREQUENCY), \ + ServoInfo::ServoConfig \ + { \ + .limit = Config::Servos::name##_LIMIT, \ + .flipped = Config::Servos::name##_FLIPPED, \ + .defaultOpeningTime = \ + Config::Servos::DEFAULT_##name##_OPENING_TIME, \ + .defaultMaxAperture = \ + Config::Servos::DEFAULT_##name##_MAX_APERTURE, \ + .openingEvent = Common::MOTOR_##name##_OPEN, \ + .closingEvent = Common::MOTOR_##name##_CLOSE, \ + .openingTimeRegKey = CONFIG_ID_##name##_OPENING_TIME, \ + .maxApertureRegKey = CONFIG_ID_##name##_MAX_APERTURE \ + } \ + } + +/** + * @brief Shorthand to create a detach ServoInfo struct from the servo name + */ +#define MAKE_DETACH_SERVO(name) \ + ServoInfo \ + { \ + std::make_unique<Servo>( \ + MIOSIX_SERVOS_##name##_TIM, \ + TimerUtils::Channel::MIOSIX_SERVOS_##name##_CHANNEL, \ + Config::Servos::DETACH_MIN_PULSE, \ + Config::Servos::DETACH_MAX_PULSE, Config::Servos::FREQUENCY), \ + ServoInfo::ServoConfig \ + { \ + .limit = Config::Servos::name##_LIMIT, \ + .flipped = Config::Servos::name##_FLIPPED, \ + .defaultOpeningTime = \ + Config::Servos::DEFAULT_##name##_OPENING_TIME, \ + .defaultMaxAperture = \ + Config::Servos::DEFAULT_##name##_MAX_APERTURE, \ + .openingEvent = Common::MOTOR_##name##_OPEN, \ + .closingEvent = Common::MOTOR_##name##_CLOSE, \ + .openingTimeRegKey = CONFIG_ID_##name##_OPENING_TIME, \ + .maxApertureRegKey = CONFIG_ID_##name##_MAX_APERTURE \ + } \ + } + +/** + * @brief Shorthand to create a non-atomic ServoInfo struct from the servo name + */ +#define MAKE_SIMPLE_SERVO(name) \ + ServoInfo \ + { \ + std::make_unique<Servo>( \ + MIOSIX_SERVOS_##name##_TIM, \ + TimerUtils::Channel::MIOSIX_SERVOS_##name##_CHANNEL, \ + Config::Servos::MIN_PULSE, Config::Servos::MAX_PULSE, \ + Config::Servos::FREQUENCY), \ + ServoInfo::ServoConfig \ + { \ + .limit = Config::Servos::name##_LIMIT, \ + .flipped = Config::Servos::name##_FLIPPED, \ + .openingEvent = Common::MOTOR_##name##_OPEN, \ + .closingEvent = Common::MOTOR_##name##_CLOSE, \ + } \ + } diff --git a/src/RIGv2/CanHandler/CanHandler.cpp b/src/RIGv2/CanHandler/CanHandler.cpp index 055ae6e57bae3043a192eaaa1f7e61c2606e7efc..42494b83b2c866f4996629dfe1c0957cd47b9342 100644 --- a/src/RIGv2/CanHandler/CanHandler.cpp +++ b/src/RIGv2/CanHandler/CanHandler.cpp @@ -205,7 +205,7 @@ void CanHandler::handleSensor(const Canbus::CanMessage& msg) { CanPressureData data = pressureDataFromCanMessage(msg); sdLogger.log(data); - sensors->setCanCCPress(data); + sensors->setCanCombustionChamberPressure(data); break; } @@ -213,7 +213,7 @@ void CanHandler::handleSensor(const Canbus::CanMessage& msg) { CanPressureData data = pressureDataFromCanMessage(msg); sdLogger.log(data); - sensors->setCanTopTankPress(data); + sensors->setCanOxTankTopPressure(data); break; } @@ -221,7 +221,7 @@ void CanHandler::handleSensor(const Canbus::CanMessage& msg) { CanPressureData data = pressureDataFromCanMessage(msg); sdLogger.log(data); - sensors->setCanBottomTankPress(data); + sensors->setCanOxTankBottomPressure(data); break; } @@ -229,7 +229,7 @@ void CanHandler::handleSensor(const Canbus::CanMessage& msg) { CanTemperatureData data = temperatureDataFromCanMessage(msg); sdLogger.log(data); - sensors->setCanTankTemp(data); + sensors->setCanOxTankTemperature(data); break; } diff --git a/src/RIGv2/CanHandler/CanHandler.h b/src/RIGv2/CanHandler/CanHandler.h index 282d8eef931a444188179e981d0e906dd77257a3..0b8a305e5fc7c8cd8a7d1487d06ccdafd15e9b10 100644 --- a/src/RIGv2/CanHandler/CanHandler.h +++ b/src/RIGv2/CanHandler/CanHandler.h @@ -26,7 +26,7 @@ #include <RIGv2/Configs/CanHandlerConfig.h> #include <RIGv2/Sensors/Sensors.h> #include <common/CanConfig.h> -#include <common/MavlinkLyra.h> +#include <common/MavlinkOrion.h> #include <drivers/canbus/CanProtocol/CanProtocol.h> #include <utils/DependencyManager/DependencyManager.h> diff --git a/src/RIGv2/Configs/ActuatorsConfig.h b/src/RIGv2/Configs/ActuatorsConfig.h index bfa3ddf4397c4c2f6a7cc3fb2bf77fc4ffa98bfa..6a8f819fd472c5f3afc9a5a0091d1714f89884e7 100644 --- a/src/RIGv2/Configs/ActuatorsConfig.h +++ b/src/RIGv2/Configs/ActuatorsConfig.h @@ -1,5 +1,5 @@ -/* Copyright (c) 2024 Skyward Experimental Rocketry - * Authors: Davide Mor +/* Copyright (c) 2025 Skyward Experimental Rocketry + * Authors: Davide Mor, Niccolò Betto * * Permission is hereby granted, free of charge, to any person obtaining a copy * of this software and associated documentation files (the "Software"), to deal @@ -22,27 +22,26 @@ #pragma once -#include <interfaces-impl/hwmapping.h> #include <units/Frequency.h> +#include <chrono> + namespace RIGv2 { namespace Config { - namespace Servos { - /* linter off */ using namespace Boardcore::Units::Frequency; +/* linter off */ using namespace std::chrono; -// Generic pulse width for all servos +// Pulse width for all servos constexpr unsigned int MIN_PULSE = 500; constexpr unsigned int MAX_PULSE = 2440; -// Pulse width specific to SERVO 2 (disconnect servo) -// TODO(davide.mor): This actually needs tweaking -constexpr unsigned int SERVO2_MIN_PULSE = 900; -constexpr unsigned int SERVO2_MAX_PULSE = 2100; +// Pulse width for detach servos +constexpr unsigned int DETACH_MIN_PULSE = 900; +constexpr unsigned int DETACH_MAX_PULSE = 2100; constexpr unsigned int FREQUENCY = 333; @@ -50,36 +49,52 @@ constexpr Hertz SERVO_TIMINGS_CHECK_PERIOD = 10_hz; constexpr long long SERVO_CONFIDENCE_TIME = 500; // 0.5s constexpr float SERVO_CONFIDENCE = 0.02; // 2% -constexpr uint32_t DEFAULT_FILLING_OPENING_TIME = 15000; // 15s -constexpr uint32_t DEFAULT_VENTING_OPENING_TIME = 15000; // 15s -constexpr uint32_t DEFAULT_MAIN_OPENING_TIME = 6000; // 6s -constexpr uint32_t DEFAULT_RELEASE_OPENING_TIME = 10000; // 10s -constexpr uint32_t DEFAULT_DISCONNECT_OPENING_TIME = 2000; // 2s - -constexpr float DEFAULT_FILLING_MAX_APERTURE = 1.00f; -constexpr float DEFAULT_VENTING_MAX_APERTURE = 1.00f; -constexpr float DEFAULT_MAIN_MAX_APERTURE = 1.00f; -constexpr float DEFAULT_RELEASE_MAX_APERTURE = 1.00f; -constexpr float DEFAULT_DISCONNECT_MAX_APERTURE = 1.00f; - -constexpr float FILLING_LIMIT = 0.90f; -constexpr float VENTING_LIMIT = 0.90f; -constexpr float MAIN_LIMIT = 0.90f; -constexpr float RELEASE_LIMIT = 0.50f; -constexpr float DISCONNECT_LIMIT = 1.00f; - -constexpr bool FILLING_FLIPPED = true; -constexpr bool VENTING_FLIPPED = true; -constexpr bool MAIN_FLIPPED = true; -constexpr bool RELEASE_FLIPPED = true; -constexpr bool DISCONNECT_FLIPPED = false; +constexpr uint32_t DEFAULT_OX_FIL_OPENING_TIME = 15000; +constexpr uint32_t DEFAULT_OX_REL_OPENING_TIME = 10000; +constexpr uint32_t DEFAULT_OX_DET_OPENING_TIME = 2000; +constexpr uint32_t DEFAULT_N2_FIL_OPENING_TIME = 15000; +constexpr uint32_t DEFAULT_N2_REL_OPENING_TIME = 10000; +constexpr uint32_t DEFAULT_N2_DET_OPENING_TIME = 2000; +constexpr uint32_t DEFAULT_NITR_OPENING_TIME = 600000; +constexpr uint32_t DEFAULT_OX_VEN_OPENING_TIME = 15000; +constexpr uint32_t DEFAULT_N2_QUE_OPENING_TIME = 15000; +constexpr uint32_t DEFAULT_MAIN_OPENING_TIME = 6000; + +constexpr float DEFAULT_OX_FIL_MAX_APERTURE = 1.0; +constexpr float DEFAULT_OX_REL_MAX_APERTURE = 1.0; +constexpr float DEFAULT_OX_DET_MAX_APERTURE = 1.0; +constexpr float DEFAULT_N2_FIL_MAX_APERTURE = 1.0; +constexpr float DEFAULT_N2_REL_MAX_APERTURE = 1.0; +constexpr float DEFAULT_N2_DET_MAX_APERTURE = 1.0; +constexpr float DEFAULT_NITR_MAX_APERTURE = 1.0; +constexpr float DEFAULT_OX_VEN_MAX_APERTURE = 1.0; +constexpr float DEFAULT_N2_QUE_MAX_APERTURE = 1.0; +constexpr float DEFAULT_MAIN_MAX_APERTURE = 1.0; + +constexpr float OX_FIL_LIMIT = 0.9; +constexpr float OX_REL_LIMIT = 0.5; +constexpr float OX_DET_LIMIT = 1.0; +constexpr float N2_3W_LIMIT = 1.0; +constexpr float N2_FIL_LIMIT = 0.9; +constexpr float N2_REL_LIMIT = 0.5; +constexpr float N2_DET_LIMIT = 1.0; +constexpr float NITR_LIMIT = 0.9; +constexpr float OX_VEN_LIMIT = 0.9; +constexpr float N2_QUE_LIMIT = 0.9; +constexpr float MAIN_LIMIT = 0.9; + +constexpr bool OX_FIL_FLIPPED = true; +constexpr bool OX_REL_FLIPPED = true; +constexpr bool OX_DET_FLIPPED = false; +constexpr bool N2_3W_FLIPPED = true; +constexpr bool N2_FIL_FLIPPED = true; +constexpr bool N2_REL_FLIPPED = true; +constexpr bool N2_DET_FLIPPED = false; +constexpr bool NITR_FLIPPED = true; +constexpr bool OX_VEN_FLIPPED = true; +constexpr bool N2_QUE_FLIPPED = true; +constexpr bool MAIN_FLIPPED = true; } // namespace Servos - -namespace Actuators -{ -static constexpr uint32_t NITROGEN_OPENING_TIME = 5000; // 5s -} - } // namespace Config } // namespace RIGv2 diff --git a/src/RIGv2/Configs/GMMConfig.h b/src/RIGv2/Configs/GMMConfig.h index cc02af3a0d76b53b6a49e82835511bf81287ea2e..93e60c04514a2eadb1f9e5ffb0c615b7ae8e5624 100644 --- a/src/RIGv2/Configs/GMMConfig.h +++ b/src/RIGv2/Configs/GMMConfig.h @@ -33,8 +33,10 @@ namespace GroundModeManager constexpr uint32_t DEFAULT_IGNITION_WAITING_TIME = 3700; // [ms] -constexpr uint32_t MOTOR_COOLING_TIME = 1500; -constexpr uint32_t NITROGEN_TIME = 20000; // 20s +/// Delay between the main valve opening and the chamber valve opening +constexpr uint32_t DEFAULT_CHAMBER_VALVE_DELAY = 500; +// Time the chamber valve stays open +constexpr uint32_t DEFAULT_CHAMBER_VALVE_TIME = 6000; } // namespace GroundModeManager } // namespace Config diff --git a/src/RIGv2/Configs/RadioConfig.h b/src/RIGv2/Configs/RadioConfig.h index 98830ac094ccfdcb2c929d808389de2448c4a60f..af1b8643e9be58a52e7c29b74f2514fd5a38db79 100644 --- a/src/RIGv2/Configs/RadioConfig.h +++ b/src/RIGv2/Configs/RadioConfig.h @@ -22,7 +22,7 @@ #pragma once -#include <common/MavlinkLyra.h> +#include <common/MavlinkOrion.h> namespace RIGv2 { diff --git a/src/RIGv2/Configs/SensorsConfig.h b/src/RIGv2/Configs/SensorsConfig.h index 6348afffa34dd69e65e1faf4080f5758a064f72b..397a5bd8ac3759b9bd86a8d95dfbab42d4be0ea9 100644 --- a/src/RIGv2/Configs/SensorsConfig.h +++ b/src/RIGv2/Configs/SensorsConfig.h @@ -1,5 +1,5 @@ /* Copyright (c) 2024 Skyward Experimental Rocketry - * Authors: Davide Mor + * Authors: Davide Mor, Niccolò Betto * * Permission is hereby granted, free of charge, to any person obtaining a copy * of this software and associated documentation files (the "Software"), to deal @@ -42,31 +42,11 @@ namespace Sensors namespace ADS131M08 { - -constexpr Boardcore::ADS131M08Defs::OversamplingRatio OSR = - Boardcore::ADS131M08Defs::OversamplingRatio::OSR_8192; +constexpr auto OSR = Boardcore::ADS131M08Defs::OversamplingRatio::OSR_8192; constexpr bool GLOBAL_CHOP_MODE_EN = true; -constexpr float CH1_SHUNT_RESISTANCE = 29.4048; -constexpr float CH2_SHUNT_RESISTANCE = 29.5830; -constexpr float CH3_SHUNT_RESISTANCE = 29.4973; -constexpr float CH4_SHUNT_RESISTANCE = 29.8849; - -// ADC channels definitions for various sensors -constexpr Boardcore::ADS131M08Defs::Channel VESSEL_PT_CHANNEL = - Boardcore::ADS131M08Defs::Channel::CHANNEL_0; -constexpr Boardcore::ADS131M08Defs::Channel FILLING_PT_CHANNEL = - Boardcore::ADS131M08Defs::Channel::CHANNEL_1; -constexpr Boardcore::ADS131M08Defs::Channel BOTTOM_PT_CHANNEL = - Boardcore::ADS131M08Defs::Channel::CHANNEL_2; -constexpr Boardcore::ADS131M08Defs::Channel TOP_PT_CHANNEL = - Boardcore::ADS131M08Defs::Channel::CHANNEL_3; -constexpr Boardcore::ADS131M08Defs::Channel SERVO_CURRENT_CHANNEL = - Boardcore::ADS131M08Defs::Channel::CHANNEL_4; -constexpr Boardcore::ADS131M08Defs::Channel VESSEL_LC_CHANNEL = - Boardcore::ADS131M08Defs::Channel::CHANNEL_5; -constexpr Boardcore::ADS131M08Defs::Channel TANK_LC_CHANNEL = - Boardcore::ADS131M08Defs::Channel::CHANNEL_6; +constexpr Hertz PERIOD = 100_hz; +constexpr bool ENABLED = true; // Servo current sensor calibration data // - A: 0.0 V: 2.520 @@ -78,11 +58,39 @@ constexpr Boardcore::ADS131M08Defs::Channel TANK_LC_CHANNEL = // - A: 5.2 V: 2.441 constexpr float SERVO_CURRENT_SCALE = 4.5466; constexpr float SERVO_CURRENT_ZERO = 2.520 / SERVO_CURRENT_SCALE; - -constexpr Hertz PERIOD = 100_hz; -constexpr bool ENABLED = true; } // namespace ADS131M08 +namespace ADC_1 +{ +using Channel = Boardcore::ADS131M08Defs::Channel; + +constexpr auto OX_VESSEL_PT_CHANNEL = Channel::CHANNEL_0; +constexpr auto OX_FILLING_PT_CHANNEL = Channel::CHANNEL_1; +constexpr auto N2_VESSEL_1_PT_CHANNEL = Channel::CHANNEL_2; +constexpr auto N2_VESSEL_2_PT_CHANNEL = Channel::CHANNEL_3; +constexpr auto SERVO_CURRENT_CHANNEL = Channel::CHANNEL_4; +constexpr auto OX_VESSEL_LC_CHANNEL = Channel::CHANNEL_5; +constexpr auto OX_TANK_LC_CHANNEL = Channel::CHANNEL_6; +constexpr auto N2_FILLING_PT_CHANNEL = Channel::CHANNEL_7; + +constexpr float CH0_SHUNT_RESISTANCE = 29.4048; // TODO: check +constexpr float CH1_SHUNT_RESISTANCE = 29.5830; // TODO: check +constexpr float CH2_SHUNT_RESISTANCE = 29.4973; // TODO: check +constexpr float CH3_SHUNT_RESISTANCE = 29.8849; // TODO: check +constexpr float CH7_SHUNT_RESISTANCE = 29.0; // TODO: measure +} // namespace ADC_1 + +namespace ADC_2 +{ +using Channel = Boardcore::ADS131M08Defs::Channel; + +constexpr auto OX_TANK_TOP_PT_CHANNEL = Channel::CHANNEL_0; +constexpr auto OX_TANK_BOTTOM_PT_CHANNEL = Channel::CHANNEL_1; + +constexpr float CH0_SHUNT_RESISTANCE = 29.0; // TODO: measure +constexpr float CH1_SHUNT_RESISTANCE = 29.0; // TODO: measure +} // namespace ADC_2 + namespace MAX31856 { constexpr Hertz PERIOD = 10_hz; @@ -91,18 +99,25 @@ constexpr bool ENABLED = true; namespace Trafag { -constexpr float FILLING_SHUNT_RESISTANCE = ADS131M08::CH2_SHUNT_RESISTANCE; -constexpr float TANK_TOP_SHUNT_RESISTANCE = ADS131M08::CH4_SHUNT_RESISTANCE; -constexpr float TANK_BOTTOM_SHUNT_RESISTANCE = ADS131M08::CH3_SHUNT_RESISTANCE; -constexpr float VESSEL_SHUNT_RESISTANCE = ADS131M08::CH1_SHUNT_RESISTANCE; +constexpr float OX_VESSEL_SHUNT_RESISTANCE = ADC_1::CH0_SHUNT_RESISTANCE; +constexpr float OX_FILLING_SHUNT_RESISTANCE = ADC_1::CH1_SHUNT_RESISTANCE; +constexpr float N2_VESSEL1_SHUNT_RESISTANCE = ADC_1::CH2_SHUNT_RESISTANCE; +constexpr float N2_VESSEL2_SHUNT_RESISTANCE = ADC_1::CH3_SHUNT_RESISTANCE; +constexpr float N2_FILLING_SHUNT_RESISTANCE = ADC_1::CH7_SHUNT_RESISTANCE; +constexpr float OX_TANK_TOP_SHUNT_RESISTANCE = ADC_2::CH0_SHUNT_RESISTANCE; +constexpr float OX_TANK_BOTTOM_SHUNT_RESISTANCE = ADC_2::CH1_SHUNT_RESISTANCE; constexpr float MIN_CURRENT = 4; constexpr float MAX_CURRENT = 20; -constexpr float FILLING_MAX_PRESSURE = 100; // bar -constexpr float TANK_TOP_MAX_PRESSURE = 100; // bar -constexpr float TANK_BOTTOM_MAX_PRESSURE = 100; // bar -constexpr float VESSEL_MAX_PRESSURE = 400; // bar +// TODO: check depending on which trafags are used +constexpr float OX_VESSEL_MAX_PRESSURE = 100; // bar +constexpr float OX_FILLING_MAX_PRESSURE = 250; // bar +constexpr float N2_VESSEL1_MAX_PRESSURE = 400; // bar +constexpr float N2_VESSEL2_MAX_PRESSURE = 400; // bar +constexpr float N2_FILLING_MAX_PRESSURE = 400; // bar +constexpr float OX_TANK_TOP_MAX_PRESSURE = 250; // bar +constexpr float OX_TANK_BOTTOM_MAX_PRESSURE = 100; // bar } // namespace Trafag namespace LoadCell @@ -123,7 +138,7 @@ constexpr float TANK_P1_MASS = 6.916; // LC Vessel sensor calibration data // - 1.866kg V: 0.00027 // - 5.050kg V: 0.00073 -// - 6.916kg V: 0.00100 +// - 6.916kg V: 0.00100000941 constexpr float VESSEL_P0_VOLTAGE = 0.00027; constexpr float VESSEL_P0_MASS = 1.866; constexpr float VESSEL_P1_VOLTAGE = 0.0010; @@ -139,12 +154,20 @@ constexpr float VESSEL_P0_MASS = 4.985; constexpr float VESSEL_P1_VOLTAGE = 0.00030895; constexpr float VESSEL_P1_MASS = 10.177; +/* +// LC Vessel sensor calibration data (post 08/11/2024, old flipping) +// - 0kg V: -0.009553 +// - 8.720kg V: -0.010958 (−31125.124875125 kg/v) +constexpr float VESSEL_P0_VOLTAGE = -0.009553; +constexpr float VESSEL_P0_MASS = 0.0; +constexpr float VESSEL_P1_VOLTAGE = -0.010958; +constexpr float VESSEL_P1_MASS = 8.720; +*/ } // namespace LoadCell namespace InternalADC { -constexpr Boardcore::InternalADC::Channel BATTERY_VOLTAGE_CHANNEL = - Boardcore::InternalADC::CH14; +constexpr auto BATTERY_VOLTAGE_CHANNEL = Boardcore::InternalADC::CH14; constexpr float BATTERY_VOLTAGE_SCALE = 4.7917; constexpr Hertz PERIOD = 10_hz; diff --git a/src/RIGv2/Radio/Radio.cpp b/src/RIGv2/Radio/Radio.cpp index 5e7bdc47aaf2ac5870f6952b5fe21d35e833ab20..d35a38d320976c5db850cdb0160b87ef4697b56c 100644 --- a/src/RIGv2/Radio/Radio.cpp +++ b/src/RIGv2/Radio/Radio.cpp @@ -259,6 +259,26 @@ void Radio::handleMessage(const mavlink_message_t& msg) break; } + case MAVLINK_MSG_ID_SET_NITROGEN_TIME_TC: + { + // Chamber valve opening time + uint32_t timing = mavlink_msg_set_nitrogen_time_tc_get_timing(&msg); + getModule<GroundModeManager>()->setChamberTime(timing); + + enqueueAck(msg); + break; + } + + case MAVLINK_MSG_ID_SET_COOLING_TIME_TC: + { + // Chamber valve delay after main valve opening + uint32_t timing = mavlink_msg_set_cooling_time_tc_get_timing(&msg); + getModule<GroundModeManager>()->setChamberDelay(timing); + + enqueueAck(msg); + break; + } + default: { // Unrecognized packet @@ -344,6 +364,17 @@ void Radio::enqueueRegistry() mavlink_message_t msg; const char* name = configurationIdToName(id); + // A safe copy function for key names + auto copyKeyName = [](auto& dest, const char* src) + { + // Ensure dest is not a pointer + static_assert(sizeof(dest) != sizeof(char*)); + + constexpr size_t maxKeyLen = sizeof(dest) / sizeof(dest[0]) - 1; + std::strncpy(dest, src, maxKeyLen); + dest[maxKeyLen] = '\0'; // Ensure null-termination + }; + switch (value.getType()) { case TypesEnum::UINT32: @@ -352,7 +383,7 @@ void Radio::enqueueRegistry() tm.timestamp = TimestampTimer::getTimestamp(); tm.key_id = id; - strcpy(tm.key_name, name); + copyKeyName(tm.key_name, name); value.get(tm.value); mavlink_msg_registry_int_tm_encode( @@ -366,7 +397,7 @@ void Radio::enqueueRegistry() tm.timestamp = TimestampTimer::getTimestamp(); tm.key_id = id; - strcpy(tm.key_name, name); + copyKeyName(tm.key_name, name); value.get(tm.value); mavlink_msg_registry_float_tm_encode( @@ -380,7 +411,7 @@ void Radio::enqueueRegistry() tm.timestamp = TimestampTimer::getTimestamp(); tm.key_id = id; - strcpy(tm.key_name, name); + copyKeyName(tm.key_name, name); Coordinates coord; value.get(coord); tm.latitude = coord.latitude; @@ -515,15 +546,19 @@ bool Radio::enqueueSystemTm(uint8_t tmId) tm.timestamp = TimestampTimer::getTimestamp(); // Sensors - tm.loadcell_rocket = sensors->getTankWeightLastSample().load; - tm.loadcell_vessel = sensors->getVesselWeightLastSample().load; - tm.filling_pressure = sensors->getFillingPressLastSample().pressure; - tm.vessel_pressure = sensors->getVesselPressLastSample().pressure; - tm.battery_voltage = sensors->getBatteryVoltageLastSample().voltage; - tm.current_consumption = - sensors->getServoCurrentLastSample().current; + tm.rocket_mass = sensors->getOxTankWeight().load; + tm.n2o_vessel_mass = sensors->getOxVesselWeight().load; + + tm.n2o_vessel_pressure = sensors->getOxVesselPressure().pressure; + tm.n2o_filling_pressure = sensors->getOxFillingPressure().pressure; + tm.n2_filling_pressure = sensors->getN2FillingPressure().pressure; + tm.n2_vessel_1_pressure = sensors->getN2Vessel1Pressure().pressure; + tm.n2_vessel_2_pressure = sensors->getN2Vessel2Pressure().pressure; + + tm.battery_voltage = sensors->getBatteryVoltage().voltage; + tm.current_consumption = sensors->getServoCurrent().current; tm.umbilical_current_consumption = - sensors->getUmbilicalCurrentLastSample().current; + sensors->getUmbilicalCurrent().current; // Log data LoggerStats stats = sdLogger.getStats(); @@ -540,15 +575,28 @@ bool Radio::enqueueSystemTm(uint8_t tmId) sdLogger.log(cpuStats); // Valve states - tm.filling_valve_state = - actuators->isServoOpen(ServosList::FILLING_VALVE) ? 1 : 0; - tm.venting_valve_state = - actuators->isServoOpen(ServosList::VENTING_VALVE) ? 1 : 0; - tm.release_valve_state = - actuators->isServoOpen(ServosList::RELEASE_VALVE) ? 1 : 0; + tm.n2o_filling_valve_state = + actuators->isServoOpen(ServosList::N2O_FILLING_VALVE); + tm.n2o_release_valve_state = + actuators->isServoOpen(ServosList::N2O_RELEASE_VALVE); + tm.n2o_detach_state = 0; // TODO + tm.n2o_venting_valve_state = + actuators->isServoOpen(ServosList::N2O_VENTING_VALVE); + + tm.n2_filling_valve_state = + actuators->isServoOpen(ServosList::N2_FILLING_VALVE); + tm.n2_release_valve_state = + actuators->isServoOpen(ServosList::N2_RELEASE_VALVE); + tm.n2_detach_state = + actuators->isServoOpen(ServosList::N2_DETACH_SERVO); + tm.n2_quenching_valve_state = 0; // TODO + tm.n2_3way_valve_state = 0; // TODO + tm.main_valve_state = - actuators->isServoOpen(ServosList::MAIN_VALVE) ? 1 : 0; - tm.nitrogen_valve_state = actuators->isNitrogenOpen() ? 1 : 0; + actuators->isServoOpen(ServosList::MAIN_VALVE); + tm.nitrogen_valve_state = + actuators->isServoOpen(ServosList::NITROGEN_VALVE); + tm.ignition_state = actuators->isChamberOpen(); // Internal states tm.gmm_state = getModule<GroundModeManager>()->getState(); @@ -586,21 +634,20 @@ bool Radio::enqueueSystemTm(uint8_t tmId) tm.timestamp = TimestampTimer::getTimestamp(); // Sensors (either CAN or local) - tm.top_tank_pressure = - sensors->getTopTankPressLastSample().pressure; + tm.top_tank_pressure = sensors->getOxTankTopPressure().pressure; tm.bottom_tank_pressure = - sensors->getBottomTankPressLastSample().pressure; + sensors->getOxTankBottomPressure().pressure; tm.combustion_chamber_pressure = - sensors->getCCPressLastSample().pressure; - tm.tank_temperature = sensors->getTankTempLastSample().temperature; - tm.battery_voltage = - sensors->getMotorBatteryVoltageLastSample().voltage; + sensors->getCombustionChamberPressure().pressure; + tm.tank_temperature = sensors->getOxTankTemperature().temperature; + tm.battery_voltage = sensors->getMotorBatteryVoltage().voltage; // Valve states tm.main_valve_state = actuators->isCanServoOpen(ServosList::MAIN_VALVE) ? 1 : 0; tm.venting_valve_state = - actuators->isCanServoOpen(ServosList::VENTING_VALVE) ? 1 : 0; + actuators->isCanServoOpen(ServosList::N2O_VENTING_VALVE) ? 1 + : 0; // Can data CanHandler::CanStatus canStatus = @@ -652,12 +699,39 @@ bool Radio::enqueueSensorTm(uint8_t tmId) tm.channel_7 = data.getVoltage(ADS131M08Defs::Channel::CHANNEL_7).voltage; tm.timestamp = data.timestamp; - strcpy(tm.sensor_name, "ADS131M08"); + strcpy(tm.sensor_name, "ADS131M08_1"); mavlink_msg_adc_tm_encode(Config::Radio::MAV_SYSTEM_ID, Config::Radio::MAV_COMPONENT_ID, &msg, &tm); enqueuePacket(msg); + + data = getModule<Sensors>()->getADC2LastSample(); + + tm.channel_0 = + data.getVoltage(ADS131M08Defs::Channel::CHANNEL_0).voltage; + tm.channel_1 = + data.getVoltage(ADS131M08Defs::Channel::CHANNEL_1).voltage; + tm.channel_2 = + data.getVoltage(ADS131M08Defs::Channel::CHANNEL_2).voltage; + tm.channel_3 = + data.getVoltage(ADS131M08Defs::Channel::CHANNEL_3).voltage; + tm.channel_4 = + data.getVoltage(ADS131M08Defs::Channel::CHANNEL_4).voltage; + tm.channel_5 = + data.getVoltage(ADS131M08Defs::Channel::CHANNEL_5).voltage; + tm.channel_6 = + data.getVoltage(ADS131M08Defs::Channel::CHANNEL_6).voltage; + tm.channel_7 = + data.getVoltage(ADS131M08Defs::Channel::CHANNEL_7).voltage; + tm.timestamp = data.timestamp; + strcpy(tm.sensor_name, "ADS131M08_2"); + + mavlink_msg_adc_tm_encode(Config::Radio::MAV_SYSTEM_ID, + Config::Radio::MAV_COMPONENT_ID, &msg, + &tm); + enqueuePacket(msg); + return true; } @@ -666,8 +740,7 @@ bool Radio::enqueueSensorTm(uint8_t tmId) mavlink_message_t msg; mavlink_pressure_tm_t tm; - PressureData data = - getModule<Sensors>()->getVesselPressLastSample(); + PressureData data = getModule<Sensors>()->getOxVesselPressure(); tm.timestamp = data.pressureTimestamp; tm.pressure = data.pressure; @@ -685,8 +758,7 @@ bool Radio::enqueueSensorTm(uint8_t tmId) mavlink_message_t msg; mavlink_pressure_tm_t tm; - PressureData data = - getModule<Sensors>()->getFillingPressLastSample(); + PressureData data = getModule<Sensors>()->getOxFillingPressure(); tm.timestamp = data.pressureTimestamp; tm.pressure = data.pressure; @@ -704,8 +776,7 @@ bool Radio::enqueueSensorTm(uint8_t tmId) mavlink_message_t msg; mavlink_pressure_tm_t tm; - PressureData data = - getModule<Sensors>()->getBottomTankPressLastSample(); + PressureData data = getModule<Sensors>()->getOxTankBottomPressure(); tm.timestamp = data.pressureTimestamp; tm.pressure = data.pressure; @@ -723,8 +794,7 @@ bool Radio::enqueueSensorTm(uint8_t tmId) mavlink_message_t msg; mavlink_pressure_tm_t tm; - PressureData data = - getModule<Sensors>()->getTopTankPressLastSample(); + PressureData data = getModule<Sensors>()->getOxTankTopPressure(); tm.timestamp = data.pressureTimestamp; tm.pressure = data.pressure; @@ -760,8 +830,7 @@ bool Radio::enqueueSensorTm(uint8_t tmId) mavlink_message_t msg; mavlink_load_tm_t tm; - LoadCellData data = - getModule<Sensors>()->getVesselWeightLastSample(); + LoadCellData data = getModule<Sensors>()->getOxVesselWeight(); tm.timestamp = data.loadTimestamp; tm.load = data.load; @@ -779,7 +848,7 @@ bool Radio::enqueueSensorTm(uint8_t tmId) mavlink_message_t msg; mavlink_load_tm_t tm; - LoadCellData data = getModule<Sensors>()->getTankWeightLastSample(); + LoadCellData data = getModule<Sensors>()->getOxTankWeight(); tm.timestamp = data.loadTimestamp; tm.load = data.load; @@ -797,8 +866,7 @@ bool Radio::enqueueSensorTm(uint8_t tmId) mavlink_message_t msg; mavlink_voltage_tm_t tm; - VoltageData data = - getModule<Sensors>()->getBatteryVoltageLastSample(); + VoltageData data = getModule<Sensors>()->getBatteryVoltage(); tm.timestamp = data.voltageTimestamp; tm.voltage = data.voltage; @@ -833,81 +901,124 @@ void Radio::handleConrigState(const mavlink_message_t& msg) mavlink_conrig_state_tc_t state; mavlink_msg_conrig_state_tc_decode(&msg, &state); +#define BUTTON_PRESSED(btn) (lastConrigState.btn == 0 && state.btn == 1) +#define BUTTON_CHANGED(btn) (lastConrigState.btn != state.btn) + + // Use a debounce time to prevent updates too close to each other + // that may be caused by interference on the buttons + auto debounceTime = msToNs(Config::Radio::LAST_COMMAND_THRESHOLD); long long currentTime = getTime(); - if (currentTime > - lastManualActuation + - (Config::Radio::LAST_COMMAND_THRESHOLD * Constants::NS_IN_MS)) + + if (currentTime > lastManualActuation + debounceTime) { // Ok we can accept new commands - if (oldConrigState.arm_switch == 0 && state.arm_switch == 1) + if (BUTTON_PRESSED(arm_switch)) { // The ARM switch was pressed EventBroker::getInstance().post(MOTOR_MANUAL_ACTION, TOPIC_TARS); EventBroker::getInstance().post(TMTC_ARM, TOPIC_MOTOR); - lastManualActuation = currentTime; } - if (oldConrigState.ignition_btn == 0 && state.ignition_btn == 1) + if (BUTTON_PRESSED(ignition_btn)) { // The ignition switch was pressed EventBroker::getInstance().post(MOTOR_MANUAL_ACTION, TOPIC_TARS); EventBroker::getInstance().post(MOTOR_IGNITION, TOPIC_MOTOR); - lastManualActuation = currentTime; } - if (oldConrigState.filling_valve_btn == 0 && - state.filling_valve_btn == 1) + if (BUTTON_PRESSED(n2o_filling_btn)) { - // The filling switch was pressed + // The N2O filling switch was pressed EventBroker::getInstance().post(MOTOR_MANUAL_ACTION, TOPIC_TARS); - getModule<Actuators>()->toggleServo(ServosList::FILLING_VALVE); + getModule<Actuators>()->toggleServo(ServosList::N2O_FILLING_VALVE); + lastManualActuation = currentTime; + } + if (BUTTON_PRESSED(n2o_release_btn)) + { + // The N2O release switch was pressed + EventBroker::getInstance().post(MOTOR_MANUAL_ACTION, TOPIC_TARS); + getModule<Actuators>()->toggleServo(ServosList::N2O_RELEASE_VALVE); lastManualActuation = currentTime; } - if (oldConrigState.quick_connector_btn == 0 && - state.quick_connector_btn == 1) + if (BUTTON_PRESSED(n2o_detach_btn)) { - // The quick conector switch was pressed + // The N2O detach switch was pressed EventBroker::getInstance().post(MOTOR_MANUAL_ACTION, TOPIC_TARS); - getModule<Actuators>()->toggleServo(ServosList::DISCONNECT_SERVO); + getModule<Actuators>()->toggleServo(ServosList::N2O_DETACH_SERVO); + lastManualActuation = currentTime; + } + if (BUTTON_PRESSED(n2o_venting_btn)) + { + // The N2O venting switch was pressed + EventBroker::getInstance().post(MOTOR_MANUAL_ACTION, TOPIC_TARS); + getModule<Actuators>()->toggleServo(ServosList::N2O_VENTING_VALVE); lastManualActuation = currentTime; } - if (oldConrigState.release_pressure_btn == 0 && - state.release_pressure_btn == 1) + if (BUTTON_PRESSED(n2_filling_btn)) { - // The release switch was pressed + // The N2 filling switch was pressed EventBroker::getInstance().post(MOTOR_MANUAL_ACTION, TOPIC_TARS); - getModule<Actuators>()->toggleServo(ServosList::RELEASE_VALVE); + getModule<Actuators>()->toggleServo(ServosList::N2_FILLING_VALVE); + lastManualActuation = currentTime; + } + if (BUTTON_PRESSED(n2_release_btn)) + { + // The N2 release switch was pressed + EventBroker::getInstance().post(MOTOR_MANUAL_ACTION, TOPIC_TARS); + getModule<Actuators>()->toggleServo(ServosList::N2_RELEASE_VALVE); lastManualActuation = currentTime; } - if (oldConrigState.venting_valve_btn == 0 && - state.venting_valve_btn == 1) + if (BUTTON_PRESSED(n2_detach_btn)) { - // The venting switch was pressed + // The N2 detach switch was pressed EventBroker::getInstance().post(MOTOR_MANUAL_ACTION, TOPIC_TARS); - getModule<Actuators>()->toggleServo(ServosList::VENTING_VALVE); + getModule<Actuators>()->toggleServo(ServosList::N2_DETACH_SERVO); + lastManualActuation = currentTime; + } + if (BUTTON_PRESSED(n2_quenching_btn)) + { + // The N2 quenching switch was pressed + EventBroker::getInstance().post(MOTOR_MANUAL_ACTION, TOPIC_TARS); + getModule<Actuators>()->toggleServo(ServosList::N2_QUENCHING_VALVE); lastManualActuation = currentTime; } - if (oldConrigState.start_tars_btn == 0 && state.start_tars_btn == 1) + // TODO: tars3 + if (BUTTON_PRESSED(tars_btn)) { // The TARS switch was pressed EventBroker::getInstance().post(MOTOR_START_TARS, TOPIC_TARS); + lastManualActuation = currentTime; + } + if (BUTTON_PRESSED(nitrogen_btn)) + { + // The nitrogen switch was pressed + EventBroker::getInstance().post(MOTOR_MANUAL_ACTION, TOPIC_TARS); + getModule<Actuators>()->toggleServo(ServosList::NITROGEN_VALVE); + lastManualActuation = currentTime; + } + + if (BUTTON_CHANGED(n2_3way_btn)) + { + // The 3-way valve switch was pressed + EventBroker::getInstance().post(MOTOR_MANUAL_ACTION, TOPIC_TARS); + getModule<Actuators>()->set3wayValveState(state.n2_3way_btn); lastManualActuation = currentTime; } } // Special case for disarming, that can be done bypassing the timeout - if (oldConrigState.arm_switch == 1 && state.arm_switch == 0) + if (lastConrigState.arm_switch == 1 && state.arm_switch == 0) { EventBroker::getInstance().post(MOTOR_MANUAL_ACTION, TOPIC_TARS); EventBroker::getInstance().post(TMTC_DISARM, TOPIC_MOTOR); @@ -915,5 +1026,5 @@ void Radio::handleConrigState(const mavlink_message_t& msg) lastManualActuation = currentTime; } - oldConrigState = state; + lastConrigState = state; } diff --git a/src/RIGv2/Radio/Radio.h b/src/RIGv2/Radio/Radio.h index 26a32da17469e7c7b3a031d438fd882120b6bd0d..37b61efd88fd975781b7d097e29bf8f486a774a1 100644 --- a/src/RIGv2/Radio/Radio.h +++ b/src/RIGv2/Radio/Radio.h @@ -31,7 +31,7 @@ #include <RIGv2/Sensors/Sensors.h> #include <RIGv2/StateMachines/GroundModeManager/GroundModeManager.h> #include <RIGv2/StateMachines/TARS1/TARS1.h> -#include <common/MavlinkLyra.h> +#include <common/MavlinkOrion.h> #include <interfaces-impl/hwmapping.h> #include <radio/MavlinkDriver/MavlinkDriver.h> #include <radio/SX1278/SX1278Lora.h> @@ -88,7 +88,8 @@ private: // Last time a ConRIG state triggered an actuation [ns] long long lastManualActuation = 0; - mavlink_conrig_state_tc_t oldConrigState; + // Last ConRIG state received and processed + mavlink_conrig_state_tc_t lastConrigState; }; } // namespace RIGv2 diff --git a/src/RIGv2/Registry/Registry.cpp b/src/RIGv2/Registry/Registry.cpp index 847764c6014b729205183d8d8869229616515b8e..bd02273bdf5872cfd8feb9fe904f524f5c1fdca6 100644 --- a/src/RIGv2/Registry/Registry.cpp +++ b/src/RIGv2/Registry/Registry.cpp @@ -33,32 +33,57 @@ const char* RIGv2::configurationIdToName(ConfigurationId id) { switch (id) { - case CONFIG_ID_FILLING_OPENING_TIME: - return "FillingOpeningTime"; - case CONFIG_ID_VENTING_OPENING_TIME: - return "VentingOpeningTime"; + case CONFIG_ID_OX_FIL_OPENING_TIME: + return "OX_FIL_OPENING_TIME"; + case CONFIG_ID_OX_FIL_MAX_APERTURE: + return "OX_FIL_MAX_APERTURE"; + case CONFIG_ID_OX_REL_OPENING_TIME: + return "OX_REL_OPENING_TIME"; + case CONFIG_ID_OX_REL_MAX_APERTURE: + return "OX_REL_MAX_APERTURE"; + case CONFIG_ID_OX_DET_OPENING_TIME: + return "OX_DET_OPENING_TIME"; + case CONFIG_ID_OX_DET_MAX_APERTURE: + return "OX_DET_MAX_APERTURE"; + case CONFIG_ID_OX_VEN_OPENING_TIME: + return "OX_VEN_OPENING_TIME"; + case CONFIG_ID_OX_VEN_MAX_APERTURE: + return "OX_VEN_MAX_APERTURE"; + case CONFIG_ID_N2_FIL_OPENING_TIME: + return "N2_FIL_OPENING_TIME"; + case CONFIG_ID_N2_FIL_MAX_APERTURE: + return "N2_FIL_MAX_APERTURE"; + case CONFIG_ID_N2_REL_OPENING_TIME: + return "N2_REL_OPENING_TIME"; + case CONFIG_ID_N2_REL_MAX_APERTURE: + return "N2_REL_MAX_APERTURE"; + case CONFIG_ID_N2_DET_OPENING_TIME: + return "N2_DET_OPENING_TIME"; + case CONFIG_ID_N2_DET_MAX_APERTURE: + return "N2_DET_MAX_APERTURE"; + case CONFIG_ID_N2_QUE_OPENING_TIME: + return "N2_QUE_OPENING_TIME"; + case CONFIG_ID_N2_QUE_MAX_APERTURE: + return "N2_QUE_MAX_APERTURE"; case CONFIG_ID_MAIN_OPENING_TIME: - return "MainOpeningTime"; - case CONFIG_ID_RELEASE_OPENING_TIME: - return "ReleaseOpeningTime"; - case CONFIG_ID_DISCONNECT_OPENING_TIME: - return "DisconOpeningTime"; - case CONFIG_ID_FILLING_MAX_APERTURE: - return "FillingMaxAperture"; - case CONFIG_ID_VENTING_MAX_APERTURE: - return "VentingMaxAperture"; + return "MAIN_OPENING_TIME"; case CONFIG_ID_MAIN_MAX_APERTURE: - return "MainMaxAperture"; - case CONFIG_ID_RELEASE_MAX_APERTURE: - return "ReleaseMaxAperture"; - case CONFIG_ID_DISCONNECT_MAX_APERTURE: - return "DisconMaxAperture"; + return "MAIN_MAX_APERTURE"; + case CONFIG_ID_NITR_OPENING_TIME: + return "NITR_OPENING_TIME"; + case CONFIG_ID_NITR_MAX_APERTURE: + return "NITR_MAX_APERTURE"; case CONFIG_ID_IGNITION_TIME: - return "IgnitionTime"; + return "IGNITION_TIME"; case CONFIG_ID_DEFAULT_OPENING_TIME: - return "DefOpeningTime"; + return "DEFAULT_OPENING_TIME"; case CONFIG_ID_DEFAULT_MAX_APERTURE: - return "DefMaxAperture"; + return "DEFAULT_MAX_APERTURE"; + case CONFIG_ID_CHAMBER_TIME: + return "CHAMBER_TIME"; + case CONFIG_ID_CHAMBER_DELAY: + return "CHAMBER_DELAY"; + default: return "<invalid>"; } diff --git a/src/RIGv2/Registry/Registry.h b/src/RIGv2/Registry/Registry.h index 81164f3179ff2f48c30ab108fb59ccaff21aad1e..6f26a39340e105f7393b17a61e31fa2e56d505ae 100644 --- a/src/RIGv2/Registry/Registry.h +++ b/src/RIGv2/Registry/Registry.h @@ -30,19 +30,50 @@ namespace RIGv2 enum ConfigurationKeys { - CONFIG_ID_FILLING_OPENING_TIME = 1, - CONFIG_ID_VENTING_OPENING_TIME = 2, - CONFIG_ID_MAIN_OPENING_TIME = 3, - CONFIG_ID_RELEASE_OPENING_TIME = 4, - CONFIG_ID_DISCONNECT_OPENING_TIME = 5, - CONFIG_ID_FILLING_MAX_APERTURE = 6, - CONFIG_ID_VENTING_MAX_APERTURE = 7, - CONFIG_ID_MAIN_MAX_APERTURE = 8, - CONFIG_ID_RELEASE_MAX_APERTURE = 9, - CONFIG_ID_DISCONNECT_MAX_APERTURE = 10, - CONFIG_ID_IGNITION_TIME = 11, - CONFIG_ID_DEFAULT_OPENING_TIME = 12, - CONFIG_ID_DEFAULT_MAX_APERTURE = 13, + // N2O + CONFIG_ID_OX_FIL_OPENING_TIME, + CONFIG_ID_OX_FIL_MAX_APERTURE, + + CONFIG_ID_OX_REL_OPENING_TIME, + CONFIG_ID_OX_REL_MAX_APERTURE, + + CONFIG_ID_OX_DET_OPENING_TIME, + CONFIG_ID_OX_DET_MAX_APERTURE, + + CONFIG_ID_OX_VEN_OPENING_TIME, + CONFIG_ID_OX_VEN_MAX_APERTURE, + + // N2 + CONFIG_ID_N2_FIL_OPENING_TIME, + CONFIG_ID_N2_FIL_MAX_APERTURE, + + CONFIG_ID_N2_REL_OPENING_TIME, + CONFIG_ID_N2_REL_MAX_APERTURE, + + CONFIG_ID_N2_DET_OPENING_TIME, + CONFIG_ID_N2_DET_MAX_APERTURE, + + CONFIG_ID_N2_QUE_OPENING_TIME, + CONFIG_ID_N2_QUE_MAX_APERTURE, + + // Main & Nitrogen + CONFIG_ID_MAIN_OPENING_TIME, + CONFIG_ID_MAIN_MAX_APERTURE, + + CONFIG_ID_NITR_OPENING_TIME, + CONFIG_ID_NITR_MAX_APERTURE, + + // Ignition parameters + CONFIG_ID_IGNITION_TIME, + + // Default valve parameters + CONFIG_ID_DEFAULT_OPENING_TIME, + CONFIG_ID_DEFAULT_MAX_APERTURE, + + // Chamber valve parameters + CONFIG_ID_CHAMBER_TIME, // Time the chamber valve stays open + CONFIG_ID_CHAMBER_DELAY, // Delay of opening the chamber valve after + // opening the main valve }; const char* configurationIdToName(Boardcore::ConfigurationId id); diff --git a/src/RIGv2/Sensors/Sensors.cpp b/src/RIGv2/Sensors/Sensors.cpp index cf83ecd54f1cdb5b89c415926e450b47b1970b13..a6f3aed8463e97951d09bc7171b119663598069a 100644 --- a/src/RIGv2/Sensors/Sensors.cpp +++ b/src/RIGv2/Sensors/Sensors.cpp @@ -1,5 +1,5 @@ /* Copyright (c) 2024 Skyward Experimental Rocketry - * Authors: Davide Mor + * Authors: Davide Mor, Niccolò Betto * * Permission is hereby granted, free of charge, to any person obtaining a copy * of this software and associated documentation files (the "Software"), to deal @@ -40,12 +40,13 @@ bool Sensors::start() if (Config::Sensors::ADS131M08::ENABLED) { adc1Init(); - vesselPressureInit(); - fillingPressureInit(); - topTankPressureInit(); - bottomTankPressureInit(); - vesselWeightInit(); - tankWeightInit(); + adc2Init(); + oxVesselPressureInit(); + oxFillingPressureInit(); + oxTankTopPressureInit(); + oxTankBottomPressureInit(); + oxVesselWeightInit(); + oxTankWeightInit(); } if (Config::Sensors::MAX31856::ENABLED) @@ -71,99 +72,123 @@ ADS131M08Data Sensors::getADC1LastSample() return adc1 ? adc1->getLastSample() : ADS131M08Data{}; } +ADS131M08Data Sensors::getADC2LastSample() +{ + return adc2 ? adc2->getLastSample() : ADS131M08Data{}; +} + MAX31856Data Sensors::getTc1LastSample() { return tc1 ? tc1->getLastSample() : MAX31856Data{}; } -PressureData Sensors::getVesselPressLastSample() +PressureData Sensors::getOxVesselPressure() +{ + return oxVesselPressure ? oxVesselPressure->getLastSample() + : PressureData{}; +} + +PressureData Sensors::getOxFillingPressure() { - return vesselPressure ? vesselPressure->getLastSample() : PressureData{}; + return oxFillingPressure ? oxFillingPressure->getLastSample() + : PressureData{}; } -PressureData Sensors::getFillingPressLastSample() +PressureData Sensors::getN2Vessel1Pressure() { - return fillingPressure ? fillingPressure->getLastSample() : PressureData{}; + return n2Vessel1Pressure ? n2Vessel1Pressure->getLastSample() + : PressureData{}; } -PressureData Sensors::getTopTankPressLastSample() +PressureData Sensors::getN2Vessel2Pressure() +{ + return n2Vessel2Pressure ? n2Vessel2Pressure->getLastSample() + : PressureData{}; +} + +PressureData Sensors::getN2FillingPressure() +{ + return n2FillingPressure ? n2FillingPressure->getLastSample() + : PressureData{}; +} + +PressureData Sensors::getOxTankTopPressure() { if (useCanData) { - return getCanTopTankPressLastSample(); + return getCanOxTankTopPressure(); } else { - return topTankPressure ? topTankPressure->getLastSample() - : PressureData{}; + return oxTankTopPressure ? oxTankTopPressure->getLastSample() + : PressureData{}; } } -PressureData Sensors::getBottomTankPressLastSample() +PressureData Sensors::getOxTankBottomPressure() { if (useCanData) { - return getCanBottomTankPressLastSample(); + return getCanOxTankBottomPressure(); } else { - return bottomTankPressure ? bottomTankPressure->getLastSample() - : PressureData{}; + return oxTankBottomPressure ? oxTankBottomPressure->getLastSample() + : PressureData{}; } } -PressureData Sensors::getCCPressLastSample() +PressureData Sensors::getCombustionChamberPressure() { if (useCanData) - return getCanCCPressLastSample(); + return getCanCombustionChamberPressure(); else return PressureData{}; } -TemperatureData Sensors::getTankTempLastSample() +TemperatureData Sensors::getOxTankTemperature() { if (useCanData) - return getCanTankTempLastSample(); + return getCanTankTemperature(); else return getTc1LastSample(); } -LoadCellData Sensors::getVesselWeightLastSample() +LoadCellData Sensors::getOxVesselWeight() { - if (vesselWeight) - return vesselWeight->getLastSample(); + if (oxVesselWeight) + return oxVesselWeight->getLastSample(); else return {}; } -LoadCellData Sensors::getTankWeightLastSample() +LoadCellData Sensors::getOxTankWeight() { - if (tankWeight) - return tankWeight->getLastSample(); + if (oxTankWeight) + return oxTankWeight->getLastSample(); else return {}; } -CurrentData Sensors::getUmbilicalCurrentLastSample() +CurrentData Sensors::getUmbilicalCurrent() { - // TODO: Implement this + // TODO: Implement umbilical current return {}; } -CurrentData Sensors::getServoCurrentLastSample() +CurrentData Sensors::getServoCurrent() { auto sample = getADC1LastSample(); float current = - (sample - .voltage[(int)Config::Sensors::ADS131M08::SERVO_CURRENT_CHANNEL] - + (sample.voltage[(int)Config::Sensors::ADC_1::SERVO_CURRENT_CHANNEL] - Config::Sensors::ADS131M08::SERVO_CURRENT_ZERO) * Config::Sensors::ADS131M08::SERVO_CURRENT_SCALE; // Current reading are flipped return {sample.timestamp, -current / 5.0f * 50.0f}; } -VoltageData Sensors::getBatteryVoltageLastSample() +VoltageData Sensors::getBatteryVoltage() { auto sample = getInternalADCLastSample(); @@ -174,66 +199,66 @@ VoltageData Sensors::getBatteryVoltageLastSample() return {sample.timestamp, voltage}; } -VoltageData Sensors::getMotorBatteryVoltageLastSample() +VoltageData Sensors::getMotorBatteryVoltage() { if (useCanData) - return getCanMotorBatteryVoltageLastSample(); + return getCanMotorBatteryVoltage(); else return VoltageData{}; } -PressureData Sensors::getCanTopTankPressLastSample() +PressureData Sensors::getCanOxTankTopPressure() { Lock<FastMutex> lock{canMutex}; - return canTopTankPressure; + return canOxTankBottomPressure; } -PressureData Sensors::getCanBottomTankPressLastSample() +PressureData Sensors::getCanOxTankBottomPressure() { Lock<FastMutex> lock{canMutex}; - return canBottomTankPressure; + return canOxTankTopPressure; } -PressureData Sensors::getCanCCPressLastSample() +PressureData Sensors::getCanCombustionChamberPressure() { Lock<FastMutex> lock{canMutex}; - return canCCPressure; + return canCombustionChamberPressure; } -TemperatureData Sensors::getCanTankTempLastSample() +TemperatureData Sensors::getCanTankTemperature() { Lock<FastMutex> lock{canMutex}; - return canTankTemperature; + return canOxTankTemperature; } -VoltageData Sensors::getCanMotorBatteryVoltageLastSample() +VoltageData Sensors::getCanMotorBatteryVoltage() { Lock<FastMutex> lock{canMutex}; return canMotorBatteryVoltage; } -void Sensors::setCanTopTankPress(PressureData data) +void Sensors::setCanOxTankTopPressure(PressureData data) { Lock<FastMutex> lock{canMutex}; - canTopTankPressure = data; + canOxTankBottomPressure = data; } -void Sensors::setCanBottomTankPress(PressureData data) +void Sensors::setCanOxTankBottomPressure(PressureData data) { Lock<FastMutex> lock{canMutex}; - canBottomTankPressure = data; + canOxTankTopPressure = data; } -void Sensors::setCanCCPress(PressureData data) +void Sensors::setCanCombustionChamberPressure(PressureData data) { Lock<FastMutex> lock{canMutex}; - canCCPressure = data; + canCombustionChamberPressure = data; } -void Sensors::setCanTankTemp(TemperatureData data) +void Sensors::setCanOxTankTemperature(TemperatureData data) { Lock<FastMutex> lock{canMutex}; - canTankTemperature = data; + canOxTankTemperature = data; } void Sensors::setCanMotorBatteryVoltage(VoltageData data) @@ -246,20 +271,20 @@ void Sensors::switchToCanSensors() { useCanData = true; } void Sensors::calibrate() { - Stats vesselStats, tankStats; + Stats oxVesselStats, oxTankStats; for (unsigned int i = 0; i < Config::Sensors::LoadCell::CALIBRATE_SAMPLE_COUNT; i++) { // Tank readings WITHOUT offsets - vesselStats.add(vesselWeight->getLastSample().load); - tankStats.add(tankWeight->getLastSample().load); + oxVesselStats.add(oxVesselWeight->getLastSample().load); + oxTankStats.add(oxTankWeight->getLastSample().load); Thread::sleep(Config::Sensors::LoadCell::CALIBRATE_SAMPLE_PERIOD); } - vesselWeight->updateOffset(vesselStats.getStats().mean); - tankWeight->updateOffset(tankStats.getStats().mean); + oxVesselWeight->updateOffset(oxVesselStats.getStats().mean); + oxTankWeight->updateOffset(oxTankStats.getStats().mean); } std::vector<SensorInfo> Sensors::getSensorInfos() @@ -268,32 +293,25 @@ std::vector<SensorInfo> Sensors::getSensorInfos() { std::vector<SensorInfo> infos{}; - if (vesselWeight) - infos.push_back(manager->getSensorInfo(vesselWeight.get())); - - if (tankWeight) - infos.push_back(manager->getSensorInfo(tankWeight.get())); - - if (vesselPressure) - infos.push_back(manager->getSensorInfo(vesselPressure.get())); - - if (fillingPressure) - infos.push_back(manager->getSensorInfo(fillingPressure.get())); - - if (topTankPressure) - infos.push_back(manager->getSensorInfo(topTankPressure.get())); - - if (bottomTankPressure) - infos.push_back(manager->getSensorInfo(bottomTankPressure.get())); - - if (internalAdc) - infos.push_back(manager->getSensorInfo(internalAdc.get())); - - if (adc1) - infos.push_back(manager->getSensorInfo(adc1.get())); - - if (tc1) - infos.push_back(manager->getSensorInfo(tc1.get())); +#define PUSH_SENSOR_INFO(instance, name) \ + if (instance) \ + infos.push_back(manager->getSensorInfo(instance.get())); \ + else \ + infos.push_back(SensorInfo { #name, 0, nullptr, false }) + + PUSH_SENSOR_INFO(adc1, "ADC1"); + PUSH_SENSOR_INFO(adc2, "ADC2"); + PUSH_SENSOR_INFO(tc1, "TC1"); + PUSH_SENSOR_INFO(internalAdc, "InternalADC"); + PUSH_SENSOR_INFO(oxVesselPressure, "OxVesselPressure"); + PUSH_SENSOR_INFO(oxFillingPressure, "OxFillingPressure"); + PUSH_SENSOR_INFO(n2Vessel1Pressure, "N2Vessel1Pressure"); + PUSH_SENSOR_INFO(n2Vessel2Pressure, "N2Vessel2Pressure"); + PUSH_SENSOR_INFO(n2FillingPressure, "N2FillingPressure"); + PUSH_SENSOR_INFO(oxTankTopPressure, "OxTankTopPressure"); + PUSH_SENSOR_INFO(oxTankBottomPressure, "OxTankBotPressure"); + PUSH_SENSOR_INFO(oxVesselWeight, "OxVesselWeight"); + PUSH_SENSOR_INFO(oxTankWeight, "OxTankWeight"); return infos; } @@ -333,65 +351,101 @@ void Sensors::adc1Init() Config::Sensors::ADS131M08::GLOBAL_CHOP_MODE_EN; // Disable all channels - config.channelsConfig[0].enabled = false; - config.channelsConfig[1].enabled = false; - config.channelsConfig[2].enabled = false; - config.channelsConfig[3].enabled = false; - config.channelsConfig[4].enabled = false; - config.channelsConfig[5].enabled = false; - config.channelsConfig[6].enabled = false; - config.channelsConfig[7].enabled = false; + for (auto& channel : config.channelsConfig) + channel.enabled = false; // Configure all required channels - config.channelsConfig[(int)Config::Sensors::ADS131M08::VESSEL_PT_CHANNEL] = + config.channelsConfig[(int)Config::Sensors::ADC_1::OX_VESSEL_PT_CHANNEL] = { + .enabled = true, + .pga = ADS131M08Defs::PGA::PGA_1, + .offset = 0, + .gain = 1.0}; + + config.channelsConfig[(int)Config::Sensors::ADC_1::OX_FILLING_PT_CHANNEL] = + {.enabled = true, + .pga = ADS131M08Defs::PGA::PGA_1, + .offset = 0, + .gain = 1.0}; + + config.channelsConfig[(int)Config::Sensors::ADC_1::N2_VESSEL_1_PT_CHANNEL] = {.enabled = true, .pga = ADS131M08Defs::PGA::PGA_1, .offset = 0, .gain = 1.0}; - config.channelsConfig[(int)Config::Sensors::ADS131M08::FILLING_PT_CHANNEL] = + config.channelsConfig[(int)Config::Sensors::ADC_1::N2_VESSEL_2_PT_CHANNEL] = {.enabled = true, .pga = ADS131M08Defs::PGA::PGA_1, .offset = 0, .gain = 1.0}; - config.channelsConfig[(int)Config::Sensors::ADS131M08::BOTTOM_PT_CHANNEL] = + config.channelsConfig[(int)Config::Sensors::ADC_1::SERVO_CURRENT_CHANNEL] = {.enabled = true, .pga = ADS131M08Defs::PGA::PGA_1, .offset = 0, .gain = 1.0}; - config.channelsConfig[(int)Config::Sensors::ADS131M08::TOP_PT_CHANNEL] = { + config.channelsConfig[(int)Config::Sensors::ADC_1::OX_VESSEL_LC_CHANNEL] = { .enabled = true, - .pga = ADS131M08Defs::PGA::PGA_1, + .pga = ADS131M08Defs::PGA::PGA_32, .offset = 0, .gain = 1.0}; - config.channelsConfig[( - int)Config::Sensors::ADS131M08::SERVO_CURRENT_CHANNEL] = { + config.channelsConfig[(int)Config::Sensors::ADC_1::OX_TANK_LC_CHANNEL] = { .enabled = true, - .pga = ADS131M08Defs::PGA::PGA_1, + .pga = ADS131M08Defs::PGA::PGA_32, .offset = 0, .gain = 1.0}; - config.channelsConfig[(int)Config::Sensors::ADS131M08::VESSEL_LC_CHANNEL] = + config.channelsConfig[(int)Config::Sensors::ADC_1::N2_FILLING_PT_CHANNEL] = {.enabled = true, - .pga = ADS131M08Defs::PGA::PGA_32, + .pga = ADS131M08Defs::PGA::PGA_1, .offset = 0, .gain = 1.0}; - config.channelsConfig[(int)Config::Sensors::ADS131M08::TANK_LC_CHANNEL] = { + adc1 = std::make_unique<ADS131M08>(getModule<Buses>()->getADS131M08_1(), + sensors::ADS131_1::cs::getPin(), + spiConfig, config); +} + +void Sensors::adc1Callback() { sdLogger.log(ADC1Data{getADC1LastSample()}); } + +void Sensors::adc2Init() +{ + SPIBusConfig spiConfig = {}; + spiConfig.mode = SPI::Mode::MODE_0; + spiConfig.clockDivider = SPI::ClockDivider::DIV_32; + + ADS131M08::Config config = {}; + // Setup global configurations + config.oversamplingRatio = Config::Sensors::ADS131M08::OSR; + config.globalChopModeEnabled = + Config::Sensors::ADS131M08::GLOBAL_CHOP_MODE_EN; + + // Disable all channels + for (auto& channel : config.channelsConfig) + channel.enabled = false; + + // Configure all required channels + config.channelsConfig[(int)Config::Sensors::ADC_2::OX_TANK_TOP_PT_CHANNEL] = + {.enabled = true, + .pga = ADS131M08Defs::PGA::PGA_1, + .offset = 0, + .gain = 1.0}; + + config.channelsConfig[( + int)Config::Sensors::ADC_2::OX_TANK_BOTTOM_PT_CHANNEL] = { .enabled = true, - .pga = ADS131M08Defs::PGA::PGA_32, + .pga = ADS131M08Defs::PGA::PGA_1, .offset = 0, .gain = 1.0}; - adc1 = std::make_unique<ADS131M08>(getModule<Buses>()->getADS131M08_1(), - sensors::ADS131_1::cs::getPin(), + adc2 = std::make_unique<ADS131M08>(getModule<Buses>()->getADS131M08_2(), + sensors::ADS131_2::cs::getPin(), spiConfig, config); } -void Sensors::adc1Callback() { sdLogger.log(ADC1Data{getADC1LastSample()}); } +void Sensors::adc2Callback() { sdLogger.log(ADC2Data{getADC2LastSample()}); } void Sensors::tc1Init() { @@ -405,94 +459,155 @@ void Sensors::tc1Init() void Sensors::tc1Callback() { sdLogger.log(TC1Data{getTc1LastSample()}); } -void Sensors::vesselPressureInit() +void Sensors::oxVesselPressureInit() { - vesselPressure = std::make_unique<TrafagPressureSensor>( + oxVesselPressure = std::make_unique<TrafagPressureSensor>( [this]() { auto sample = getADC1LastSample(); return sample.getVoltage( - Config::Sensors::ADS131M08::VESSEL_PT_CHANNEL); + Config::Sensors::ADC_1::OX_VESSEL_PT_CHANNEL); }, - Config::Sensors::Trafag::VESSEL_SHUNT_RESISTANCE, - Config::Sensors::Trafag::VESSEL_MAX_PRESSURE, + Config::Sensors::Trafag::OX_VESSEL_SHUNT_RESISTANCE, + Config::Sensors::Trafag::OX_VESSEL_MAX_PRESSURE, Config::Sensors::Trafag::MIN_CURRENT, Config::Sensors::Trafag::MAX_CURRENT); } -void Sensors::vesselPressureCallback() +void Sensors::oxVesselPressureCallback() { - sdLogger.log(VesselPressureData{getVesselPressLastSample()}); + sdLogger.log(OxVesselPressureData{getOxVesselPressure()}); } -void Sensors::fillingPressureInit() +void Sensors::oxFillingPressureInit() { - fillingPressure = std::make_unique<TrafagPressureSensor>( + oxFillingPressure = std::make_unique<TrafagPressureSensor>( [this]() { auto sample = getADC1LastSample(); return sample.getVoltage( - Config::Sensors::ADS131M08::FILLING_PT_CHANNEL); + Config::Sensors::ADC_1::OX_FILLING_PT_CHANNEL); }, - Config::Sensors::Trafag::FILLING_SHUNT_RESISTANCE, - Config::Sensors::Trafag::FILLING_MAX_PRESSURE, + Config::Sensors::Trafag::OX_FILLING_SHUNT_RESISTANCE, + Config::Sensors::Trafag::OX_FILLING_MAX_PRESSURE, Config::Sensors::Trafag::MIN_CURRENT, Config::Sensors::Trafag::MAX_CURRENT); } -void Sensors::fillingPressureCallback() +void Sensors::oxFillingPressureCallback() { - sdLogger.log(FillingPressureData{getFillingPressLastSample()}); + sdLogger.log(OxFillingPressureData{getOxFillingPressure()}); } -void Sensors::topTankPressureInit() +void Sensors::n2Vessel1PressureInit() { - topTankPressure = std::make_unique<TrafagPressureSensor>( + n2Vessel1Pressure = std::make_unique<TrafagPressureSensor>( [this]() { auto sample = getADC1LastSample(); return sample.getVoltage( - Config::Sensors::ADS131M08::TOP_PT_CHANNEL); + Config::Sensors::ADC_1::N2_VESSEL_1_PT_CHANNEL); }, - Config::Sensors::Trafag::TANK_TOP_SHUNT_RESISTANCE, - Config::Sensors::Trafag::TANK_TOP_MAX_PRESSURE, + Config::Sensors::Trafag::N2_VESSEL1_SHUNT_RESISTANCE, + Config::Sensors::Trafag::N2_VESSEL1_MAX_PRESSURE, Config::Sensors::Trafag::MIN_CURRENT, Config::Sensors::Trafag::MAX_CURRENT); } -void Sensors::topTankPressureCallback() +void Sensors::n2Vessel1PressureCallback() { - sdLogger.log(TopTankPressureData{topTankPressure->getLastSample()}); + sdLogger.log(N2Vessel1PressureData{getN2Vessel1Pressure()}); } -void Sensors::bottomTankPressureInit() +void Sensors::n2Vessel2PressureInit() { - bottomTankPressure = std::make_unique<TrafagPressureSensor>( + n2Vessel2Pressure = std::make_unique<TrafagPressureSensor>( [this]() { auto sample = getADC1LastSample(); return sample.getVoltage( - Config::Sensors::ADS131M08::BOTTOM_PT_CHANNEL); + Config::Sensors::ADC_1::N2_VESSEL_2_PT_CHANNEL); + }, + Config::Sensors::Trafag::N2_VESSEL2_SHUNT_RESISTANCE, + Config::Sensors::Trafag::N2_VESSEL2_MAX_PRESSURE, + Config::Sensors::Trafag::MIN_CURRENT, + Config::Sensors::Trafag::MAX_CURRENT); +} + +void Sensors::n2Vessel2PressureCallback() +{ + sdLogger.log(N2Vessel2PressureData{getN2Vessel2Pressure()}); +} + +void Sensors::n2FillingPressureInit() +{ + n2FillingPressure = std::make_unique<TrafagPressureSensor>( + [this]() + { + auto sample = getADC1LastSample(); + return sample.getVoltage( + Config::Sensors::ADC_1::N2_FILLING_PT_CHANNEL); + }, + Config::Sensors::Trafag::N2_FILLING_SHUNT_RESISTANCE, + Config::Sensors::Trafag::N2_FILLING_MAX_PRESSURE, + Config::Sensors::Trafag::MIN_CURRENT, + Config::Sensors::Trafag::MAX_CURRENT); +} + +void Sensors::n2FillingPressureCallback() +{ + sdLogger.log(N2FillingPressureData{getN2FillingPressure()}); +} + +void Sensors::oxTankTopPressureInit() +{ + oxTankTopPressure = std::make_unique<TrafagPressureSensor>( + [this]() + { + auto sample = getADC2LastSample(); + return sample.getVoltage( + Config::Sensors::ADC_2::OX_TANK_TOP_PT_CHANNEL); }, - Config::Sensors::Trafag::TANK_BOTTOM_SHUNT_RESISTANCE, - Config::Sensors::Trafag::TANK_BOTTOM_MAX_PRESSURE, + 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::bottomTankPressureCallback() +void Sensors::oxTankTopPressureCallback() { - sdLogger.log(BottomTankPressureData{bottomTankPressure->getLastSample()}); + sdLogger.log(OxTankTopPressureData{oxTankTopPressure->getLastSample()}); } -void Sensors::vesselWeightInit() +void Sensors::oxTankBottomPressureInit() { - vesselWeight = std::make_unique<TwoPointAnalogLoadCell>( + oxTankBottomPressure = std::make_unique<TrafagPressureSensor>( + [this]() + { + auto sample = getADC2LastSample(); + return sample.getVoltage( + Config::Sensors::ADC_2::OX_TANK_BOTTOM_PT_CHANNEL); + }, + Config::Sensors::Trafag::OX_TANK_BOTTOM_SHUNT_RESISTANCE, + Config::Sensors::Trafag::OX_TANK_BOTTOM_MAX_PRESSURE, + Config::Sensors::Trafag::MIN_CURRENT, + Config::Sensors::Trafag::MAX_CURRENT); +} + +void Sensors::oxTankBottomPressureCallback() +{ + sdLogger.log( + OxTankBottomPressureData{oxTankBottomPressure->getLastSample()}); +} + +void Sensors::oxVesselWeightInit() +{ + oxVesselWeight = std::make_unique<TwoPointAnalogLoadCell>( [this]() { auto sample = getADC1LastSample(); return sample.getVoltage( - Config::Sensors::ADS131M08::VESSEL_LC_CHANNEL); + Config::Sensors::ADC_1::OX_VESSEL_LC_CHANNEL); }, Config::Sensors::LoadCell::VESSEL_P0_VOLTAGE, Config::Sensors::LoadCell::VESSEL_P0_MASS, @@ -500,19 +615,19 @@ void Sensors::vesselWeightInit() Config::Sensors::LoadCell::VESSEL_P1_MASS); } -void Sensors::vesselWeightCallback() +void Sensors::oxVesselWeightCallback() { - sdLogger.log(VesselWeightData{getVesselWeightLastSample()}); + sdLogger.log(OxVesselWeightData{getOxVesselWeight()}); } -void Sensors::tankWeightInit() +void Sensors::oxTankWeightInit() { - tankWeight = std::make_unique<TwoPointAnalogLoadCell>( + oxTankWeight = std::make_unique<TwoPointAnalogLoadCell>( [this]() { auto sample = getADC1LastSample(); return sample.getVoltage( - Config::Sensors::ADS131M08::TANK_LC_CHANNEL); + Config::Sensors::ADC_1::OX_TANK_LC_CHANNEL); }, Config::Sensors::LoadCell::TANK_P0_VOLTAGE, Config::Sensors::LoadCell::TANK_P0_MASS, @@ -520,9 +635,9 @@ void Sensors::tankWeightInit() Config::Sensors::LoadCell::TANK_P1_MASS); } -void Sensors::tankWeightCallback() +void Sensors::oxTankWeightCallback() { - sdLogger.log(TankWeightData{getTankWeightLastSample()}); + sdLogger.log(OxTankWeightData{getOxTankWeight()}); } bool Sensors::sensorManagerInit() @@ -534,7 +649,7 @@ bool Sensors::sensorManagerInit() if (internalAdc) { - SensorInfo info("InternalAdc", Config::Sensors::InternalADC::PERIOD, + SensorInfo info("InternalADC", Config::Sensors::InternalADC::PERIOD, [this]() { internalAdcCallback(); }); map.emplace(internalAdc.get(), info); } @@ -546,6 +661,13 @@ bool Sensors::sensorManagerInit() map.emplace(std::make_pair(adc1.get(), info)); } + if (adc2) + { + SensorInfo info("ADS131M08_2", Config::Sensors::ADS131M08::PERIOD, + [this]() { adc2Callback(); }); + map.emplace(std::make_pair(adc2.get(), info)); + } + if (tc1) { SensorInfo info("MAX31856_1", Config::Sensors::MAX31856::PERIOD, @@ -553,47 +675,67 @@ bool Sensors::sensorManagerInit() map.emplace(std::make_pair(tc1.get(), info)); } - if (vesselPressure) + if (oxVesselPressure) + { + SensorInfo info("OxVesselPressure", Config::Sensors::ADS131M08::PERIOD, + [this]() { oxVesselPressureCallback(); }); + map.emplace(std::make_pair(oxVesselPressure.get(), info)); + } + + if (oxFillingPressure) + { + SensorInfo info("OxFillingPressure", Config::Sensors::ADS131M08::PERIOD, + [this]() { oxFillingPressureCallback(); }); + map.emplace(std::make_pair(oxFillingPressure.get(), info)); + } + + if (n2Vessel1Pressure) + { + SensorInfo info("N2Vessel1Pressure", Config::Sensors::ADS131M08::PERIOD, + [this]() { n2Vessel1PressureCallback(); }); + map.emplace(std::make_pair(n2Vessel1Pressure.get(), info)); + } + + if (n2Vessel2Pressure) { - SensorInfo info("VesselPressure", Config::Sensors::ADS131M08::PERIOD, - [this]() { vesselPressureCallback(); }); - map.emplace(std::make_pair(vesselPressure.get(), info)); + SensorInfo info("N2Vessel2Pressure", Config::Sensors::ADS131M08::PERIOD, + [this]() { n2Vessel2PressureCallback(); }); + map.emplace(std::make_pair(n2Vessel2Pressure.get(), info)); } - if (fillingPressure) + if (n2FillingPressure) { - SensorInfo info("FillingPressure", Config::Sensors::ADS131M08::PERIOD, - [this]() { fillingPressureCallback(); }); - map.emplace(std::make_pair(fillingPressure.get(), info)); + SensorInfo info("N2FillingPressure", Config::Sensors::ADS131M08::PERIOD, + [this]() { n2FillingPressureCallback(); }); + map.emplace(std::make_pair(n2FillingPressure.get(), info)); } - if (topTankPressure) + if (oxTankTopPressure) { - SensorInfo info("TopTankPressure", Config::Sensors::ADS131M08::PERIOD, - [this]() { topTankPressureCallback(); }); - map.emplace(std::make_pair(topTankPressure.get(), info)); + SensorInfo info("OxTankTopPressure", Config::Sensors::ADS131M08::PERIOD, + [this]() { oxTankTopPressureCallback(); }); + map.emplace(std::make_pair(oxTankTopPressure.get(), info)); } - if (bottomTankPressure) + if (oxTankBottomPressure) { - SensorInfo info("BottomTankPressure", - Config::Sensors::ADS131M08::PERIOD, - [this]() { bottomTankPressureCallback(); }); - map.emplace(std::make_pair(bottomTankPressure.get(), info)); + SensorInfo info("OxTankBotPressure", Config::Sensors::ADS131M08::PERIOD, + [this]() { oxTankBottomPressureCallback(); }); + map.emplace(std::make_pair(oxTankBottomPressure.get(), info)); } - if (vesselWeight) + if (oxVesselWeight) { - SensorInfo info("VesselWeight", Config::Sensors::ADS131M08::PERIOD, - [this]() { vesselWeightCallback(); }); - map.emplace(std::make_pair(vesselWeight.get(), info)); + SensorInfo info("OxVesselWeight", Config::Sensors::ADS131M08::PERIOD, + [this]() { oxVesselWeightCallback(); }); + map.emplace(std::make_pair(oxVesselWeight.get(), info)); } - if (tankWeight) + if (oxTankWeight) { - SensorInfo info("TankWeight", Config::Sensors::ADS131M08::PERIOD, - [this]() { tankWeightCallback(); }); - map.emplace(std::make_pair(tankWeight.get(), info)); + SensorInfo info("OxTankWeight", Config::Sensors::ADS131M08::PERIOD, + [this]() { oxTankWeightCallback(); }); + map.emplace(std::make_pair(oxTankWeight.get(), info)); } manager = std::make_unique<SensorManager>(map, &scheduler); diff --git a/src/RIGv2/Sensors/Sensors.h b/src/RIGv2/Sensors/Sensors.h index c349b48b95fc2b8e668de38f629501d4cd6d3866..06a5ceb1f46d841d454c63717cfd155ad9a94bd5 100644 --- a/src/RIGv2/Sensors/Sensors.h +++ b/src/RIGv2/Sensors/Sensors.h @@ -1,5 +1,5 @@ /* Copyright (c) 2024 Skyward Experimental Rocketry - * Authors: Davide Mor + * Authors: Davide Mor, Niccolò Betto * * Permission is hereby granted, free of charge, to any person obtaining a copy * of this software and associated documentation files (the "Software"), to deal @@ -55,55 +55,70 @@ public: // Getters for raw data coming from sensors Boardcore::InternalADCData getInternalADCLastSample(); Boardcore::ADS131M08Data getADC1LastSample(); + Boardcore::ADS131M08Data getADC2LastSample(); Boardcore::MAX31856Data getTc1LastSample(); // Getters for processed data - Boardcore::PressureData getVesselPressLastSample(); - Boardcore::PressureData getFillingPressLastSample(); - Boardcore::PressureData getTopTankPressLastSample(); - Boardcore::PressureData getBottomTankPressLastSample(); - Boardcore::PressureData getCCPressLastSample(); - Boardcore::TemperatureData getTankTempLastSample(); - Boardcore::LoadCellData getVesselWeightLastSample(); - Boardcore::LoadCellData getTankWeightLastSample(); - Boardcore::CurrentData getUmbilicalCurrentLastSample(); - Boardcore::CurrentData getServoCurrentLastSample(); - Boardcore::VoltageData getBatteryVoltageLastSample(); - Boardcore::VoltageData getMotorBatteryVoltageLastSample(); - - Boardcore::PressureData getCanTopTankPressLastSample(); - Boardcore::PressureData getCanBottomTankPressLastSample(); - Boardcore::PressureData getCanCCPressLastSample(); - Boardcore::TemperatureData getCanTankTempLastSample(); - Boardcore::VoltageData getCanMotorBatteryVoltageLastSample(); + Boardcore::PressureData getOxVesselPressure(); + Boardcore::PressureData getOxFillingPressure(); + Boardcore::PressureData getN2Vessel1Pressure(); + Boardcore::PressureData getN2Vessel2Pressure(); + Boardcore::PressureData getN2FillingPressure(); + Boardcore::PressureData getOxTankTopPressure(); + Boardcore::PressureData getOxTankBottomPressure(); + Boardcore::PressureData getCombustionChamberPressure(); + + Boardcore::TemperatureData getOxTankTemperature(); + Boardcore::LoadCellData getOxVesselWeight(); + Boardcore::LoadCellData getOxTankWeight(); + + Boardcore::CurrentData getUmbilicalCurrent(); + Boardcore::CurrentData getServoCurrent(); + Boardcore::VoltageData getBatteryVoltage(); + Boardcore::VoltageData getMotorBatteryVoltage(); + + Boardcore::PressureData getCanOxTankTopPressure(); + Boardcore::PressureData getCanOxTankBottomPressure(); + Boardcore::PressureData getCanCombustionChamberPressure(); + Boardcore::TemperatureData getCanTankTemperature(); + Boardcore::VoltageData getCanMotorBatteryVoltage(); std::vector<Boardcore::SensorInfo> getSensorInfos(); - void setCanTopTankPress(Boardcore::PressureData data); - void setCanBottomTankPress(Boardcore::PressureData data); - void setCanCCPress(Boardcore::PressureData data); - void setCanTankTemp(Boardcore::TemperatureData data); + void setCanOxTankTopPressure(Boardcore::PressureData data); + void setCanOxTankBottomPressure(Boardcore::PressureData data); + void setCanCombustionChamberPressure(Boardcore::PressureData data); + void setCanOxTankTemperature(Boardcore::TemperatureData data); void setCanMotorBatteryVoltage(Boardcore::VoltageData data); void switchToCanSensors(); private: - void vesselPressureInit(); - void vesselPressureCallback(); + void oxVesselPressureInit(); + void oxVesselPressureCallback(); - void fillingPressureInit(); - void fillingPressureCallback(); + void oxFillingPressureInit(); + void oxFillingPressureCallback(); - void topTankPressureInit(); - void topTankPressureCallback(); + void n2Vessel1PressureInit(); + void n2Vessel1PressureCallback(); - void bottomTankPressureInit(); - void bottomTankPressureCallback(); + void n2Vessel2PressureInit(); + void n2Vessel2PressureCallback(); - void vesselWeightInit(); - void vesselWeightCallback(); + void n2FillingPressureInit(); + void n2FillingPressureCallback(); - void tankWeightInit(); - void tankWeightCallback(); + void oxTankTopPressureInit(); + void oxTankTopPressureCallback(); + + void oxTankBottomPressureInit(); + void oxTankBottomPressureCallback(); + + void oxVesselWeightInit(); + void oxVesselWeightCallback(); + + void oxTankWeightInit(); + void oxTankWeightCallback(); void internalAdcInit(); void internalAdcCallback(); @@ -111,6 +126,9 @@ private: void adc1Init(); void adc1Callback(); + void adc2Init(); + void adc2Callback(); + void tc1Init(); void tc1Callback(); @@ -123,22 +141,28 @@ private: std::atomic<bool> useCanData{false}; miosix::FastMutex canMutex; - Boardcore::PressureData canCCPressure; - Boardcore::PressureData canBottomTankPressure; - Boardcore::PressureData canTopTankPressure; - Boardcore::TemperatureData canTankTemperature; + + Boardcore::PressureData canOxTankTopPressure; + Boardcore::PressureData canOxTankBottomPressure; + Boardcore::PressureData canCombustionChamberPressure; + // TODO: N2 tank pressure from CAN + Boardcore::TemperatureData canOxTankTemperature; Boardcore::VoltageData canMotorBatteryVoltage; // Analog sensors - std::unique_ptr<Boardcore::TrafagPressureSensor> vesselPressure; - std::unique_ptr<Boardcore::TrafagPressureSensor> fillingPressure; - std::unique_ptr<Boardcore::TrafagPressureSensor> topTankPressure; - std::unique_ptr<Boardcore::TrafagPressureSensor> bottomTankPressure; - std::unique_ptr<Boardcore::TwoPointAnalogLoadCell> vesselWeight; - std::unique_ptr<Boardcore::TwoPointAnalogLoadCell> tankWeight; + std::unique_ptr<Boardcore::TrafagPressureSensor> oxVesselPressure; + std::unique_ptr<Boardcore::TrafagPressureSensor> oxFillingPressure; + std::unique_ptr<Boardcore::TrafagPressureSensor> n2Vessel1Pressure; + std::unique_ptr<Boardcore::TrafagPressureSensor> n2Vessel2Pressure; + std::unique_ptr<Boardcore::TrafagPressureSensor> n2FillingPressure; + std::unique_ptr<Boardcore::TrafagPressureSensor> oxTankTopPressure; + std::unique_ptr<Boardcore::TrafagPressureSensor> oxTankBottomPressure; + std::unique_ptr<Boardcore::TwoPointAnalogLoadCell> oxVesselWeight; + std::unique_ptr<Boardcore::TwoPointAnalogLoadCell> oxTankWeight; // Digital sensors std::unique_ptr<Boardcore::ADS131M08> adc1; + std::unique_ptr<Boardcore::ADS131M08> adc2; std::unique_ptr<Boardcore::MAX31856> tc1; std::unique_ptr<Boardcore::InternalADC> internalAdc; std::unique_ptr<Boardcore::SensorManager> manager; diff --git a/src/RIGv2/Sensors/SensorsData.h b/src/RIGv2/Sensors/SensorsData.h index 5f418da1ef30262444e114f47359ae3954a11428..c598c0a2a0f9d87e8fc19f7e0df682450a0a194b 100644 --- a/src/RIGv2/Sensors/SensorsData.h +++ b/src/RIGv2/Sensors/SensorsData.h @@ -1,5 +1,5 @@ /* Copyright (c) 2024 Skyward Experimental Rocketry - * Authors: Davide Mor + * Authors: Davide Mor, Niccolò Betto * * Permission is hereby granted, free of charge, to any person obtaining a copy * of this software and associated documentation files (the "Software"), to deal @@ -39,6 +39,16 @@ struct ADC1Data : Boardcore::ADS131M08Data ADC1Data() {} }; +struct ADC2Data : Boardcore::ADS131M08Data +{ + explicit ADC2Data(const Boardcore::ADS131M08Data& data) + : Boardcore::ADS131M08Data(data) + { + } + + ADC2Data() {} +}; + struct TC1Data : Boardcore::MAX31856Data { explicit TC1Data(const Boardcore::MAX31856Data& data) @@ -49,64 +59,94 @@ struct TC1Data : Boardcore::MAX31856Data TC1Data() {} }; -struct VesselWeightData : Boardcore::LoadCellData +struct OxVesselWeightData : Boardcore::LoadCellData { - explicit VesselWeightData(const Boardcore::LoadCellData& data) + explicit OxVesselWeightData(const Boardcore::LoadCellData& data) : Boardcore::LoadCellData(data) { } - VesselWeightData() {} + OxVesselWeightData() {} }; -struct TankWeightData : Boardcore::LoadCellData +struct OxTankWeightData : Boardcore::LoadCellData { - explicit TankWeightData(const Boardcore::LoadCellData& data) + explicit OxTankWeightData(const Boardcore::LoadCellData& data) : Boardcore::LoadCellData(data) { } - TankWeightData() {} + OxTankWeightData() {} +}; + +struct OxVesselPressureData : Boardcore::PressureData +{ + explicit OxVesselPressureData(const Boardcore::PressureData& data) + : Boardcore::PressureData(data) + { + } + + OxVesselPressureData() {} +}; + +struct OxFillingPressureData : Boardcore::PressureData +{ + explicit OxFillingPressureData(const Boardcore::PressureData& data) + : Boardcore::PressureData(data) + { + } + + OxFillingPressureData() {} +}; + +struct N2Vessel1PressureData : Boardcore::PressureData +{ + explicit N2Vessel1PressureData(const Boardcore::PressureData& data) + : Boardcore::PressureData(data) + { + } + + N2Vessel1PressureData() {} }; -struct VesselPressureData : Boardcore::PressureData +struct N2Vessel2PressureData : Boardcore::PressureData { - explicit VesselPressureData(const Boardcore::PressureData& data) + explicit N2Vessel2PressureData(const Boardcore::PressureData& data) : Boardcore::PressureData(data) { } - VesselPressureData() {} + N2Vessel2PressureData() {} }; -struct FillingPressureData : Boardcore::PressureData +struct N2FillingPressureData : Boardcore::PressureData { - explicit FillingPressureData(const Boardcore::PressureData& data) + explicit N2FillingPressureData(const Boardcore::PressureData& data) : Boardcore::PressureData(data) { } - FillingPressureData() {} + N2FillingPressureData() {} }; -struct TopTankPressureData : Boardcore::PressureData +struct OxTankTopPressureData : Boardcore::PressureData { - explicit TopTankPressureData(const Boardcore::PressureData& data) + explicit OxTankTopPressureData(const Boardcore::PressureData& data) : Boardcore::PressureData(data) { } - TopTankPressureData() {} + OxTankTopPressureData() {} }; -struct BottomTankPressureData : Boardcore::PressureData +struct OxTankBottomPressureData : Boardcore::PressureData { - explicit BottomTankPressureData(const Boardcore::PressureData& data) + explicit OxTankBottomPressureData(const Boardcore::PressureData& data) : Boardcore::PressureData(data) { } - BottomTankPressureData() {} + OxTankBottomPressureData() {} }; } // namespace RIGv2 diff --git a/src/RIGv2/StateMachines/GroundModeManager/GroundModeManager.cpp b/src/RIGv2/StateMachines/GroundModeManager/GroundModeManager.cpp index 2b372417e9c13014f71c6c9e89cbca9058f85936..31bdd3790246b5de2ad450242b65f4928be021db 100644 --- a/src/RIGv2/StateMachines/GroundModeManager/GroundModeManager.cpp +++ b/src/RIGv2/StateMachines/GroundModeManager/GroundModeManager.cpp @@ -47,6 +47,16 @@ void GroundModeManager::setIgnitionTime(uint32_t time) getModule<Registry>()->setUnsafe(CONFIG_ID_IGNITION_TIME, time); } +void GroundModeManager::setChamberTime(uint32_t time) +{ + getModule<Registry>()->setUnsafe(CONFIG_ID_CHAMBER_TIME, time); +} + +void GroundModeManager::setChamberDelay(uint32_t time) +{ + getModule<Registry>()->setUnsafe(CONFIG_ID_CHAMBER_DELAY, time); +} + State GroundModeManager::state_idle(const Event& event) { switch (event) @@ -194,7 +204,11 @@ State GroundModeManager::state_disarmed(const Event& event) case TMTC_OPEN_NITROGEN: { - getModule<Actuators>()->openNitrogen(); + uint32_t chamberTime = getModule<Registry>()->getOrSetDefaultUnsafe( + CONFIG_ID_CHAMBER_TIME, + Config::GroundModeManager::DEFAULT_CHAMBER_VALVE_TIME); + + getModule<Actuators>()->openChamberWithTime(chamberTime); return HANDLED; } @@ -227,7 +241,7 @@ State GroundModeManager::state_armed(const Event& event) getModule<CanHandler>()->sendEvent(CanConfig::EventId::ARM); getModule<Actuators>()->armLightOn(); getModule<Actuators>()->closeAllServos(); - getModule<Actuators>()->closeNitrogen(); + getModule<Actuators>()->closeChamber(); return HANDLED; } @@ -248,7 +262,10 @@ State GroundModeManager::state_armed(const Event& event) case TMTC_OPEN_NITROGEN: { - getModule<Actuators>()->openNitrogen(); + uint32_t chamberTime = getModule<Registry>()->getOrSetDefaultUnsafe( + CONFIG_ID_CHAMBER_TIME, + Config::GroundModeManager::DEFAULT_CHAMBER_VALVE_TIME); + getModule<Actuators>()->openChamberWithTime(chamberTime); // Nitrogen causes automatic disarm return transition(&GroundModeManager::state_disarmed); @@ -286,10 +303,10 @@ State GroundModeManager::state_firing(const Event& event) // Stop ignition and close all servos getModule<Actuators>()->igniterOff(); getModule<Actuators>()->closeAllServos(); + getModule<Actuators>()->closeChamber(); // Disable all events EventBroker::getInstance().removeDelayed(openOxidantDelayEventId); - EventBroker::getInstance().removeDelayed(coolingDelayEventId); return HANDLED; } @@ -307,7 +324,11 @@ State GroundModeManager::state_firing(const Event& event) case TMTC_OPEN_NITROGEN: { // Open nitrogen - getModule<Actuators>()->openNitrogen(); + uint32_t chamberTime = getModule<Registry>()->getOrSetDefaultUnsafe( + CONFIG_ID_CHAMBER_TIME, + Config::GroundModeManager::DEFAULT_CHAMBER_VALVE_TIME); + + getModule<Actuators>()->openChamberWithTime(chamberTime); return transition(&GroundModeManager::state_disarmed); } @@ -315,9 +336,6 @@ State GroundModeManager::state_firing(const Event& event) case MOTOR_COOLING_TIMEOUT: // Normal firing end case TMTC_DISARM: // Abort signal { - getModule<Actuators>()->openNitrogenWithTime( - Config::GroundModeManager::NITROGEN_TIME); - return transition(&GroundModeManager::state_disarmed); } @@ -389,6 +407,14 @@ State GroundModeManager::state_oxidizer(const Event& event) getModule<Actuators>()->openServo(ServosList::MAIN_VALVE); + uint32_t chamberDelay = + getModule<Registry>()->getOrSetDefaultUnsafe( + CONFIG_ID_CHAMBER_DELAY, + Config::GroundModeManager::DEFAULT_CHAMBER_VALVE_DELAY); + + EventBroker::getInstance().postDelayed(MOTOR_OPEN_CHAMBER, + TOPIC_MOTOR, chamberDelay); + return HANDLED; } @@ -407,8 +433,15 @@ State GroundModeManager::state_oxidizer(const Event& event) return HANDLED; } - case MOTOR_CLOSE_FEED_VALVE: + case MOTOR_OPEN_CHAMBER: { + uint32_t chamberTime = getModule<Registry>()->getOrSetDefaultUnsafe( + CONFIG_ID_CHAMBER_TIME, + Config::GroundModeManager::DEFAULT_CHAMBER_VALVE_TIME); + + // Open the chamber valve + getModule<Actuators>()->openChamberWithTime(chamberTime); + return transition(&GroundModeManager::state_cooling); } @@ -427,10 +460,6 @@ State GroundModeManager::state_cooling(const Event& event) { updateAndLogStatus(GroundModeManagerState::COOLING); - coolingDelayEventId = EventBroker::getInstance().postDelayed( - MOTOR_COOLING_TIMEOUT, TOPIC_MOTOR, - Config::GroundModeManager::MOTOR_COOLING_TIME); - return HANDLED; } diff --git a/src/RIGv2/StateMachines/GroundModeManager/GroundModeManager.h b/src/RIGv2/StateMachines/GroundModeManager/GroundModeManager.h index a4939c0cbbbc7720bc3f11c37f67bc31edbe1963..3abbb141c5042d7e5edf3313e2b8f4dc150ce9e4 100644 --- a/src/RIGv2/StateMachines/GroundModeManager/GroundModeManager.h +++ b/src/RIGv2/StateMachines/GroundModeManager/GroundModeManager.h @@ -51,6 +51,10 @@ public: void setIgnitionTime(uint32_t time); + void setChamberTime(uint32_t time); + + void setChamberDelay(uint32_t time); + private: Boardcore::State state_idle(const Boardcore::Event& event); Boardcore::State state_init(const Boardcore::Event& event); @@ -70,7 +74,6 @@ private: std::atomic<GroundModeManagerState> state{GroundModeManagerState::IDLE}; uint16_t openOxidantDelayEventId = -1; - uint16_t coolingDelayEventId = -1; }; } // namespace RIGv2 diff --git a/src/RIGv2/StateMachines/TARS1/TARS1.cpp b/src/RIGv2/StateMachines/TARS1/TARS1.cpp index 5b0f879d6ee4252d57bf60c0893bbbbf5318ee5f..b6806abf3b158366ba876131d98024c2cbd8c86a 100644 --- a/src/RIGv2/StateMachines/TARS1/TARS1.cpp +++ b/src/RIGv2/StateMachines/TARS1/TARS1.cpp @@ -104,13 +104,13 @@ void TARS1::state_refueling(const Event& event) logAction(TarsActionType::WASHING); // Start washing - actuators->openServoWithTime(ServosList::VENTING_VALVE, + actuators->openServoWithTime(ServosList::N2O_VENTING_VALVE, Config::TARS1::WASHING_OPENING_TIME); // Wait a bit so that the servo don't actuate at the same time Thread::sleep(Config::TARS1::WASHING_TIME_DELAY); - actuators->openServoWithTime(ServosList::FILLING_VALVE, + actuators->openServoWithTime(ServosList::N2O_FILLING_VALVE, Config::TARS1::WASHING_OPENING_TIME); // After double the time we opened the valve, move to the next phase @@ -127,7 +127,7 @@ void TARS1::state_refueling(const Event& event) logAction(TarsActionType::OPEN_FILLING); // Open the filling for a long time - actuators->openServoWithTime(ServosList::FILLING_VALVE, + actuators->openServoWithTime(ServosList::N2O_FILLING_VALVE, Config::TARS1::FILLING_OPENING_TIME); nextDelayedEventId = EventBroker::getInstance().postDelayed( @@ -176,11 +176,11 @@ void TARS1::state_refueling(const Event& event) logAction(TarsActionType::OPEN_VENTING); // Open the venting and check for pressure stabilization - actuators->openServo(ServosList::VENTING_VALVE); + actuators->openServo(ServosList::N2O_VENTING_VALVE); // Calculate next check time based on the time the valve stays open unsigned int nextCheckTime = - actuators->getServoOpeningTime(ServosList::VENTING_VALVE) + + actuators->getServoOpeningTime(ServosList::N2O_VENTING_VALVE) + Config::TARS1::PRESSURE_STABILIZE_WAIT_TIME * 5; nextDelayedEventId = EventBroker::getInstance().postDelayed( @@ -257,8 +257,8 @@ void TARS1::sample() { Sensors* sensors = getModule<Sensors>(); - pressureFilter.add(sensors->getBottomTankPressLastSample().pressure); - massFilter.add(sensors->getTankWeightLastSample().load); + pressureFilter.add(sensors->getOxTankBottomPressure().pressure); + massFilter.add(sensors->getOxTankWeight().load); medianSamples++; if (medianSamples == Config::TARS1::MEDIAN_SAMPLE_NUMBER) diff --git a/src/RIGv2/rig-v2-entry.cpp b/src/RIGv2/rig-v2-entry.cpp index ebc6174462b608020ed3757a216a2adaf8dbbdb6..b8ec84e95f5c374fc1cbf0caed1bce28ce6375f1 100644 --- a/src/RIGv2/rig-v2-entry.cpp +++ b/src/RIGv2/rig-v2-entry.cpp @@ -208,8 +208,12 @@ int main() std::cout << "Sensor status:" << std::endl; for (auto info : sensors->getSensorInfos()) { + auto statusStr = !info.isEnabled ? "Disabled" + : info.isInitialized ? "Ok" + : "Error"; + std::cout << "\t" << std::setw(16) << std::left << info.id << " " - << (info.isInitialized ? "Ok" : "Error") << std::endl; + << statusStr << std::endl; } // Periodic statistics diff --git a/src/common/Events.h b/src/common/Events.h index fc524997e62255a4e295a0af299ca491f8c49618..6a93c35fd34cf4c15d0db586bad1ee8812253b5e 100644 --- a/src/common/Events.h +++ b/src/common/Events.h @@ -144,20 +144,34 @@ enum Events : uint8_t TMTC_ARP_EXIT_TEST_MODE, MOTOR_START_TARS, MOTOR_STOP_TARS, - MOTOR_OPEN_VENTING_VALVE, - MOTOR_CLOSE_VENTING_VALVE, - MOTOR_OPEN_FILLING_VALVE, - MOTOR_CLOSE_FILLING_VALVE, - MOTOR_OPEN_RELEASE_VALVE, - MOTOR_CLOSE_RELEASE_VALVE, - MOTOR_DISCONNECT, + 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_OPEN_FEED_VALVE, - MOTOR_CLOSE_FEED_VALVE, MOTOR_MANUAL_ACTION, MOTOR_OPEN_OXIDANT, MOTOR_COOLING_TIMEOUT, MOTOR_SHADOW_MODE_TIMEOUT, + MOTOR_OPEN_CHAMBER, TARS_WASHING_DONE, TARS_CHECK_PRESSURE_STABILIZE, TARS_PRESSURE_STABILIZED, @@ -279,20 +293,23 @@ inline std::string getEventString(uint8_t event) {TMTC_ARP_EXIT_TEST_MODE, "TMTC_ARP_EXIT_TEST_MODE"}, {MOTOR_START_TARS, "MOTOR_START_TARS"}, {MOTOR_STOP_TARS, "MOTOR_STOP_TARS"}, - {MOTOR_OPEN_VENTING_VALVE, "MOTOR_OPEN_VENTING_VALVE"}, - {MOTOR_CLOSE_VENTING_VALVE, "MOTOR_CLOSE_VENTING_VALVE"}, - {MOTOR_OPEN_FILLING_VALVE, "MOTOR_OPEN_FILLING_VALVE"}, - {MOTOR_CLOSE_FILLING_VALVE, "MOTOR_CLOSE_FILLING_VALVE"}, - {MOTOR_OPEN_RELEASE_VALVE, "MOTOR_OPEN_RELEASE_VALVE"}, - {MOTOR_CLOSE_RELEASE_VALVE, "MOTOR_CLOSE_RELEASE_VALVE"}, - {MOTOR_DISCONNECT, "MOTOR_DISCONNECT"}, + {MOTOR_OX_FIL_OPEN, "MOTOR_OX_FIL_OPEN"}, + {MOTOR_OX_REL_OPEN, "MOTOR_OX_REL_OPEN"}, + {MOTOR_OX_DET_OPEN, "MOTOR_OX_DET_OPEN"}, + {MOTOR_N2_3W_OPEN, "MOTOR_N2_3W_OPEN"}, + {MOTOR_N2_FIL_OPEN, "MOTOR_N2_FIL_OPEN"}, + {MOTOR_N2_REL_OPEN, "MOTOR_N2_REL_OPEN"}, + {MOTOR_N2_DET_OPEN, "MOTOR_N2_DET_OPEN"}, + {MOTOR_NITR_OPEN, "MOTOR_NITR_OPEN"}, + {MOTOR_OX_VEN_OPEN, "MOTOR_OX_VEN_OPEN"}, + {MOTOR_N2_QUE_OPEN, "MOTOR_N2_QUE_OPEN"}, + {MOTOR_MAIN_OPEN, "MOTOR_MAIN_OPEN"}, {MOTOR_IGNITION, "MOTOR_IGNITION"}, - {MOTOR_OPEN_FEED_VALVE, "MOTOR_OPEN_FEED_VALVE"}, - {MOTOR_CLOSE_FEED_VALVE, "MOTOR_CLOSE_FEED_VALVE"}, {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"}, {TARS_WASHING_DONE, "TARS_WASHING_DONE"}, {TARS_CHECK_PRESSURE_STABILIZE, "TARS_CHECK_PRESSURE_STABILIZE"}, {TARS_PRESSURE_STABILIZED, "TARS_PRESSURE_STABILIZED"},