diff --git a/src/Parafoil/Actuators/Actuators.cpp b/src/Parafoil/Actuators/Actuators.cpp index 06dd1c262caf69a51ccadfd9589cca8b8c51f29e..a75f7d8041cd0c89ee24c5bf0f46bc67f7ccdd24 100644 --- a/src/Parafoil/Actuators/Actuators.cpp +++ b/src/Parafoil/Actuators/Actuators.cpp @@ -39,14 +39,14 @@ Actuators::Actuators() { leftServo.servo = std::make_unique<Servo>( config::LeftServo::TIMER, config::LeftServo::PWM_CH, - config::LeftServo::MIN_PULSE.value<Microsecond>(), - config::LeftServo::MAX_PULSE.value<Microsecond>()); + Microsecond{config::LeftServo::MIN_PULSE}.value(), + Microsecond{config::LeftServo::MAX_PULSE}.value()); leftServo.fullRangeAngle = config::LeftServo::ROTATION; rightServo.servo = std::make_unique<Servo>( config::RightServo::TIMER, config::RightServo::PWM_CH, - config::RightServo::MIN_PULSE.value<Microsecond>(), - config::RightServo::MAX_PULSE.value<Microsecond>()); + Microsecond{config::RightServo::MIN_PULSE}.value(), + Microsecond{config::RightServo::MAX_PULSE}.value()); rightServo.fullRangeAngle = config::RightServo::ROTATION; } @@ -85,8 +85,8 @@ bool Actuators::setServoAngle(ServosList servoId, Degree angle) miosix::Lock<miosix::FastMutex> lock(actuator->mutex); - actuator->servo->setPosition(angle.value<Degree>() / - actuator->fullRangeAngle.value<Degree>()); + actuator->servo->setPosition(angle.value() / + actuator->fullRangeAngle.value()); return true; } diff --git a/src/Parafoil/AltitudeTrigger/AltitudeTrigger.cpp b/src/Parafoil/AltitudeTrigger/AltitudeTrigger.cpp index bce21a162d73a050d6d0f0ea36aab70eb41891a2..c029ea89be576748073192edd7ae04bdd71834e3 100644 --- a/src/Parafoil/AltitudeTrigger/AltitudeTrigger.cpp +++ b/src/Parafoil/AltitudeTrigger/AltitudeTrigger.cpp @@ -67,7 +67,7 @@ bool AltitudeTrigger::isEnabled() { return running; } void AltitudeTrigger::setDeploymentAltitude(Meter altitude) { - targetAltitude = altitude.value<Meter>(); + targetAltitude = altitude.value(); } void AltitudeTrigger::update() diff --git a/src/Parafoil/AltitudeTrigger/AltitudeTrigger.h b/src/Parafoil/AltitudeTrigger/AltitudeTrigger.h index 816989fe5621ea72e9031731a56669351e8e7ba1..7531f60a6e4e993210589a8c33787e0914fd1e67 100644 --- a/src/Parafoil/AltitudeTrigger/AltitudeTrigger.h +++ b/src/Parafoil/AltitudeTrigger/AltitudeTrigger.h @@ -79,9 +79,9 @@ private: // altitude int confidence = 0; - std::atomic<float> targetAltitude{ - Config::AltitudeTrigger::DEPLOYMENT_ALTITUDE - .value<Boardcore::Units::Length::Meter>()}; + std::atomic<float> targetAltitude{Boardcore::Units::Length::Meter{ + Config::AltitudeTrigger::DEPLOYMENT_ALTITUDE} + .value()}; }; } // namespace Parafoil diff --git a/src/Parafoil/Configs/NASConfig.h b/src/Parafoil/Configs/NASConfig.h index 1c4e4728ba4441d3afd09c56ac7468fe9148bf2f..6a9e041dcbbd471d71a8659ae36e9029b6a59d8f 100644 --- a/src/Parafoil/Configs/NASConfig.h +++ b/src/Parafoil/Configs/NASConfig.h @@ -46,7 +46,7 @@ constexpr int CALIBRATION_SAMPLES_COUNT = 20; constexpr auto CALIBRATION_SLEEP_TIME = 100_ms; static const Boardcore::NASConfig CONFIG = { - .T = UPDATE_RATE_SECONDS.value<Second>(), + .T = UPDATE_RATE_SECONDS.value(), .SIGMA_BETA = 0.0001, .SIGMA_W = 0.0019, .SIGMA_ACC = 0.202, diff --git a/src/Parafoil/Radio/MessageHandler.cpp b/src/Parafoil/Radio/MessageHandler.cpp index 3c0a4c51ea6f43f84db15a1cc1bae0b1eadf6a61..b4cc140398110d0ad348edc57ecaa2a29dce1810 100644 --- a/src/Parafoil/Radio/MessageHandler.cpp +++ b/src/Parafoil/Radio/MessageHandler.cpp @@ -537,13 +537,13 @@ bool Radio::MavlinkBackend::enqueueSystemTm(SystemTMList tmId) // Servos tm.left_servo_angle = - parent.getModule<Actuators>() - ->getServoAngle(ServosList::PARAFOIL_LEFT_SERVO) - .value<Degree>(); + Degree{parent.getModule<Actuators>()->getServoAngle( + ServosList::PARAFOIL_LEFT_SERVO)} + .value(); tm.right_servo_angle = - parent.getModule<Actuators>() - ->getServoAngle(ServosList::PARAFOIL_RIGHT_SERVO) - .value<Degree>(); + Degree{parent.getModule<Actuators>()->getServoAngle( + ServosList::PARAFOIL_RIGHT_SERVO)} + .value(); // Algorithms tm.nas_n = nasState.n; @@ -563,8 +563,8 @@ bool Radio::MavlinkBackend::enqueueSystemTm(SystemTMList tmId) // Wind estimation auto wind = parent.getModule<WindEstimation>()->getPrediction(); - tm.wes_n = wind.vn.value<MeterPerSecond>(); - tm.wes_e = wind.ve.value<MeterPerSecond>(); + tm.wes_n = MeterPerSecond{wind.vn}.value(); + tm.wes_e = MeterPerSecond{wind.ve}.value(); tm.battery_voltage = sensors->getBatteryVoltage().batVoltage; // No integrated camera @@ -610,12 +610,12 @@ bool Radio::MavlinkBackend::enqueueSystemTm(SystemTMList tmId) tm.liftoff_ts = stats.dropTs; tm.liftoff_max_acc_ts = stats.dropMaxAccTs; tm.liftoff_max_acc = - stats.dropMaxAcc.value<MeterPerSecondSquared>(); + MeterPerSecondSquared{stats.dropMaxAcc}.value(); // Max speed stats tm.max_speed_ts = stats.maxSpeedTs; - tm.max_speed = stats.maxSpeed.value<MeterPerSecond>(); - tm.max_speed_altitude = stats.maxSpeedAlt.value<Meter>(); + tm.max_speed = MeterPerSecond{stats.maxSpeed}.value(); + tm.max_speed_altitude = Meter{stats.maxSpeedAlt}.value(); // Useless for parafoil tm.max_mach_ts = 0; @@ -639,8 +639,8 @@ bool Radio::MavlinkBackend::enqueueSystemTm(SystemTMList tmId) // Deployment stats tm.dpl_ts = stats.dplTs; tm.dpl_max_acc_ts = stats.dplMaxAccTs; - tm.dpl_alt = stats.dplAlt.value<Meter>(); - tm.dpl_max_acc = stats.dplMaxAcc.value<MeterPerSecondSquared>(); + tm.dpl_alt = Meter{stats.dplAlt}.value(); + tm.dpl_max_acc = MeterPerSecondSquared{stats.dplMaxAcc}.value(); // NAS reference values tm.ref_lat = ref.refLatitude; diff --git a/src/Parafoil/Radio/Radio.cpp b/src/Parafoil/Radio/Radio.cpp index c49ae1f02308104e294291412b0fb524e0137d74..bd2973380ea3bc5dcdeefcc291830192bab19a7d 100644 --- a/src/Parafoil/Radio/Radio.cpp +++ b/src/Parafoil/Radio/Radio.cpp @@ -72,7 +72,7 @@ bool Radio::start() { handleXbeeFrame(frame); }); Xbee::setDataRate(*transceiver, Config::Radio::Xbee::ENABLE_80KPS_DATA_RATE, - Config::Radio::Xbee::TIMEOUT.value<Millisecond>()); + Millisecond{Config::Radio::Xbee::TIMEOUT}.value()); // Set the static instance for handling radio interrupts staticTransceiver = transceiver.get(); @@ -81,8 +81,8 @@ bool Radio::start() radioMavlink.driver = std::make_unique<MavDriver>( transceiver.get(), [this](MavDriver*, const mavlink_message_t& msg) { handleRadioMessage(msg); }, - config::MavlinkDriver::SLEEP_AFTER_SEND.value<Millisecond>(), - config::MavlinkDriver::MAX_PKT_AGE.value<Millisecond>()); + Millisecond{config::MavlinkDriver::SLEEP_AFTER_SEND}.value(), + Millisecond{config::MavlinkDriver::MAX_PKT_AGE}.value()); if (!radioMavlink.driver->start()) { diff --git a/src/Parafoil/Sensors/Sensors.cpp b/src/Parafoil/Sensors/Sensors.cpp index 8866054608aaf179975bd8f02aac3acf154330d5..5d5148c72d415584a495a49465db793112e980bf 100644 --- a/src/Parafoil/Sensors/Sensors.cpp +++ b/src/Parafoil/Sensors/Sensors.cpp @@ -345,7 +345,7 @@ void Sensors::ubxGpsInit() ubxgps = std::make_unique<UBXGPSSpi>( getModule<Buses>()->spi1, hwmap::ubxgps::cs::getPin(), spiConfig, - config::UBXGPS::SAMPLING_RATE.value<Kilohertz>()); + Kilohertz{config::UBXGPS::SAMPLING_RATE}.value()); LOG_INFO(logger, "UBXGPS initialized!"); } diff --git a/src/Parafoil/StateMachines/FlightModeManager/FlightModeManager.cpp b/src/Parafoil/StateMachines/FlightModeManager/FlightModeManager.cpp index 5415f579975d4406124b0e731c39a216420f2b33..562f73a0f1fffee3b2ade80f0191723c08419a1e 100644 --- a/src/Parafoil/StateMachines/FlightModeManager/FlightModeManager.cpp +++ b/src/Parafoil/StateMachines/FlightModeManager/FlightModeManager.cpp @@ -449,7 +449,7 @@ State FlightModeManager::FlyingWingDescent(const Event& event) // Send the event to the WingController controlDelayId = EventBroker::getInstance().postDelayed( FLIGHT_WING_DESCENT, TOPIC_FLIGHT, - config::CONTROL_DELAY.value<Millisecond>()); + Millisecond{config::CONTROL_DELAY}.value()); getModule<FlightStatsRecorder>()->dropDetected( TimestampTimer::getTimestamp()); @@ -497,7 +497,7 @@ State FlightModeManager::Landed(const Event& event) TOPIC_FLIGHT); EventBroker::getInstance().postDelayed( FMM_STOP_LOGGING, TOPIC_FMM, - config::LOGGING_DELAY.value<Millisecond>()); + Millisecond{config::LOGGING_DELAY}.value()); return HANDLED; } diff --git a/src/Parafoil/StateMachines/NASController/NASController.cpp b/src/Parafoil/StateMachines/NASController/NASController.cpp index b71d3a8cfe4e14fa4cdbd7b1f3c336d183882c56..9ce2f16fa956520da3c59221695aaffdbded9232 100644 --- a/src/Parafoil/StateMachines/NASController/NASController.cpp +++ b/src/Parafoil/StateMachines/NASController/NASController.cpp @@ -224,7 +224,7 @@ void NASController::calibrate() baroSum += baro.pressure; - Thread::sleep(config::CALIBRATION_SLEEP_TIME.value<Millisecond>()); + Thread::sleep(Millisecond{config::CALIBRATION_SLEEP_TIME}.value()); } Vector3f meanAcc = accSum / config::CALIBRATION_SAMPLES_COUNT; @@ -344,7 +344,7 @@ void NASController::setReferenceAltitude(Meter altitude) miosix::Lock<miosix::FastMutex> l(nasMutex); auto ref = nas.getReferenceValues(); - ref.refAltitude = altitude.value<Meter>(); + ref.refAltitude = altitude.value(); nas.setReferenceValues(ref); } diff --git a/src/Parafoil/StateMachines/WingController/WingController.cpp b/src/Parafoil/StateMachines/WingController/WingController.cpp index 3536fa810ea760c8d07997135ac2f462e23f3ebb..3d47f9f0688a170e57262f85c5edb0be4a63774b 100644 --- a/src/Parafoil/StateMachines/WingController/WingController.cpp +++ b/src/Parafoil/StateMachines/WingController/WingController.cpp @@ -176,7 +176,7 @@ State WingController::FlyingDeployment(const Boardcore::Event& event) calibrationTimeoutEventId = EventBroker::getInstance().postDelayed( DPL_WES_CAL_DONE, TOPIC_DPL, - WES::CALIBRATION_TIMEOUT.value<Millisecond>()); + Millisecond{WES::CALIBRATION_TIMEOUT}.value()); getModule<WindEstimation>()->startAlgorithm(); getModule<Actuators>()->startTwirl(); @@ -431,12 +431,12 @@ void WingController::loadAlgorithms() step.servo2Angle = 120_deg; algorithm->addStep(step); - step.timestamp += STRAIGHT_FLIGHT_TIMEOUT.value<Microsecond>(); + step.timestamp += Microsecond{STRAIGHT_FLIGHT_TIMEOUT}.value(); step.servo1Angle = 0_deg; step.servo2Angle = 0_deg; algorithm->addStep(step); - step.timestamp += STRAIGHT_FLIGHT_TIMEOUT.value<Microsecond>(); + step.timestamp += Microsecond{STRAIGHT_FLIGHT_TIMEOUT}.value(); step.servo1Angle = 0_deg; step.servo2Angle = 0_deg; algorithm->addStep(step); @@ -456,32 +456,32 @@ void WingController::loadAlgorithms() step.servo2Angle = 0_deg; algorithm->addStep(step); - step.timestamp += WES::ROTATION_PERIOD.value<Microsecond>(); + step.timestamp += Microsecond{WES::ROTATION_PERIOD}.value(); step.servo1Angle = 0_deg; step.servo2Angle = RightServo::ROTATION / 2; algorithm->addStep(step); - step.timestamp += WES::ROTATION_PERIOD.value<Microsecond>(); + step.timestamp += Microsecond{WES::ROTATION_PERIOD}.value(); step.servo1Angle = 0_deg; step.servo2Angle = 0_deg; algorithm->addStep(step); - step.timestamp += WES::ROTATION_PERIOD.value<Microsecond>(); + step.timestamp += Microsecond{WES::ROTATION_PERIOD}.value(); step.servo1Angle = LeftServo::ROTATION; step.servo2Angle = RightServo::ROTATION; algorithm->addStep(step); - step.timestamp += WES::ROTATION_PERIOD.value<Microsecond>(); + step.timestamp += Microsecond{WES::ROTATION_PERIOD}.value(); step.servo1Angle = 0_deg; step.servo2Angle = RightServo::ROTATION / 2; algorithm->addStep(step); - step.timestamp += WES::ROTATION_PERIOD.value<Microsecond>(); + step.timestamp += Microsecond{WES::ROTATION_PERIOD}.value(); step.servo1Angle = 0_deg; step.servo2Angle = 0_deg; algorithm->addStep(step); - step.timestamp += WES::ROTATION_PERIOD.value<Microsecond>(); + step.timestamp += Microsecond{WES::ROTATION_PERIOD}.value(); step.servo1Angle = 0_deg; step.servo2Angle = 0_deg; algorithm->addStep(step); @@ -496,19 +496,19 @@ void WingController::loadAlgorithms() PARAFOIL_RIGHT_SERVO); WingAlgorithmData step; - step.timestamp = PROGRESSIVE_ROTATION_TIMEOUT.value<Microsecond>(); + step.timestamp = Microsecond{PROGRESSIVE_ROTATION_TIMEOUT}.value(); for (auto angle = 150_deg; angle >= 0_deg; angle -= WING_DECREMENT) { step.servo1Angle = angle; step.servo2Angle = 0_deg; algorithm->addStep(step); - step.timestamp += COMMAND_PERIOD.value<Microsecond>(); + step.timestamp += Microsecond{COMMAND_PERIOD}.value(); step.servo1Angle = 0_deg; step.servo2Angle = angle; algorithm->addStep(step); - step.timestamp += COMMAND_PERIOD.value<Microsecond>(); + step.timestamp += Microsecond{COMMAND_PERIOD}.value(); } algorithms[static_cast<size_t>(AlgorithmId::PROGRESSIVE_ROTATION)] = diff --git a/src/Parafoil/WindEstimation/WindEstimation.cpp b/src/Parafoil/WindEstimation/WindEstimation.cpp index be909e97baac5bd7e5785755485319683c5a3fde..c1b1e1c78e292c467fb02b5e46664d74e5303b73 100644 --- a/src/Parafoil/WindEstimation/WindEstimation.cpp +++ b/src/Parafoil/WindEstimation/WindEstimation.cpp @@ -133,9 +133,9 @@ void WindEstimation::updateCalibration() MeterPerSecond{gps.velocityEast}}; calibrationMatrix(nSampleCalibration, 0) = - gpsVelocity.vn.value<MeterPerSecond>(); + MeterPerSecond{gpsVelocity.vn}.value(); calibrationMatrix(nSampleCalibration, 1) = - gpsVelocity.ve.value<MeterPerSecond>(); + MeterPerSecond{gpsVelocity.ve}.value(); calibrationV2(nSampleCalibration) = gpsVelocity.normSquared(); velocity.vn += gpsVelocity.vn; @@ -155,10 +155,10 @@ void WindEstimation::updateCalibration() { calibrationMatrix(i, 0) = calibrationMatrix(i, 0) - - velocity.vn.value<MeterPerSecond>(); + MeterPerSecond{velocity.vn}.value(); calibrationMatrix(i, 1) = calibrationMatrix(i, 1) - - velocity.ve.value<MeterPerSecond>(); + MeterPerSecond{velocity.ve}.value(); calibrationV2(i) = 0.5f * (calibrationV2(i) - speedSquared); } @@ -232,10 +232,10 @@ void WindEstimation::updateAlgorithm() speedSquared = (speedSquared * nSampleAlgorithm + (gpsVelocity.normSquared())) / (nSampleAlgorithm + 1); - phi(0) = gpsVelocity.vn.value<MeterPerSecond>() - - velocity.vn.value<MeterPerSecond>(); - phi(1) = gpsVelocity.ve.value<MeterPerSecond>() - - velocity.ve.value<MeterPerSecond>(); + phi(0) = MeterPerSecond{gpsVelocity.vn}.value() - + MeterPerSecond{velocity.vn}.value(); + phi(1) = MeterPerSecond{gpsVelocity.ve}.value() - + MeterPerSecond{velocity.ve}.value(); y = 0.5f * ((gpsVelocity.normSquared()) - speedSquared); phiT = phi.transpose(); diff --git a/src/Parafoil/WindEstimation/WindEstimationData.h b/src/Parafoil/WindEstimation/WindEstimationData.h index a5faaee6f4646908a4ae65b6aff80076210bacf0..bc96cfdc105165301085b8d4f085935b28f0908b 100644 --- a/src/Parafoil/WindEstimation/WindEstimationData.h +++ b/src/Parafoil/WindEstimation/WindEstimationData.h @@ -60,21 +60,14 @@ struct GeoVelocity Boardcore::Units::Speed::MeterPerSecond ve{0}; // East velocity /** - * @brief Calculate the squared norm of the velocity vector. + * @brief Calculate the squared norm of the velocity vector. [m^2/s^2] */ float normSquared() const { - return vn.value<Boardcore::Units::Speed::MeterPerSecond>() * - vn.value<Boardcore::Units::Speed::MeterPerSecond>() + - ve.value<Boardcore::Units::Speed::MeterPerSecond>() * - ve.value<Boardcore::Units::Speed::MeterPerSecond>(); + return vn.value() * vn.value() + ve.value() * ve.value(); } - Eigen::Vector2f asVector() const - { - return {vn.value<Boardcore::Units::Speed::MeterPerSecond>(), - ve.value<Boardcore::Units::Speed::MeterPerSecond>()}; - } + Eigen::Vector2f asVector() const { return {vn.value(), ve.value()}; } }; } // namespace Parafoil diff --git a/src/Parafoil/Wing/AutomaticWingAlgorithm.cpp b/src/Parafoil/Wing/AutomaticWingAlgorithm.cpp index ce9113b51c46cb00a127cb5052fa5b596bab5e2d..490747420a736d7b3f8f55d34ec1f72328d1f695 100644 --- a/src/Parafoil/Wing/AutomaticWingAlgorithm.cpp +++ b/src/Parafoil/Wing/AutomaticWingAlgorithm.cpp @@ -45,7 +45,7 @@ AutomaticWingAlgorithm::AutomaticWingAlgorithm(float Kp, float Ki, : Super(servo1, servo2), guidance(guidance) { // PIController needs the sample period in floating point seconds - auto samplePeriod = 1.0f / UPDATE_RATE.value<Hertz>(); + auto samplePeriod = 1.0f / Hertz{UPDATE_RATE}.value(); controller = std::make_unique<PIController>(Kp, Ki, samplePeriod, PI::SATURATION_MIN_LIMIT, @@ -121,7 +121,7 @@ Degree AutomaticWingAlgorithm::algorithmStep(const NASState& state) // Call the PI with the just calculated error. The result is in RADIANS, // if positive we activate one servo, if negative the other // We also need to convert the result from radians back to degrees - auto result = Degree(Radian(controller->update(error.value<Radian>()))); + auto result = Degree(Radian(controller->update(Radian{error}.value()))); // Logs the outputs { @@ -139,7 +139,7 @@ Degree AutomaticWingAlgorithm::algorithmStep(const NASState& state) Radian AutomaticWingAlgorithm::angleDiff(Radian a, Radian b) { - auto diff = (a - b).value<Radian>(); + auto diff = (a - b).value(); // Angle difference if (diff < -Constants::PI || Constants::PI < diff)