From e227187e72a1c277576df57e1e413a7b2bbce187 Mon Sep 17 00:00:00 2001 From: George Zogopoulos Date: Thu, 25 Jul 2024 21:29:22 +0200 Subject: [PATCH] AP_TECS: Converted parameter TKOFF_MODE to TKOFF_OPTIONS --- libraries/AP_TECS/AP_TECS.cpp | 3 ++- libraries/AP_Vehicle/AP_FixedWing.h | 7 ++++++- 2 files changed, 8 insertions(+), 2 deletions(-) diff --git a/libraries/AP_TECS/AP_TECS.cpp b/libraries/AP_TECS/AP_TECS.cpp index 9d1d00e460..e3843a02ae 100644 --- a/libraries/AP_TECS/AP_TECS.cpp +++ b/libraries/AP_TECS/AP_TECS.cpp @@ -1462,7 +1462,8 @@ void AP_TECS::_update_throttle_limits() { // If less min throttle is allowed during takeoff, use it. bool use_takeoff_throttle = _flight_stage == AP_FixedWing::FlightStage::TAKEOFF || _flight_stage == AP_FixedWing::FlightStage::ABORT_LANDING; - use_takeoff_throttle = use_takeoff_throttle && (aparm.takeoff_mode == 1) && (aparm.takeoff_throttle_min != 0); + const bool use_throttle_range = (aparm.takeoff_options & (uint32_t)AP_FixedWing::TakeoffOption::THROTTLE_RANGE); + use_takeoff_throttle = use_takeoff_throttle && (use_throttle_range == 1) && (aparm.takeoff_throttle_min != 0); if ( use_takeoff_throttle ) { _THRminf = MIN(_THRminf, aparm.takeoff_throttle_min * 0.01f); } diff --git a/libraries/AP_Vehicle/AP_FixedWing.h b/libraries/AP_Vehicle/AP_FixedWing.h index ee51dcf1cd..722c53dcaf 100644 --- a/libraries/AP_Vehicle/AP_FixedWing.h +++ b/libraries/AP_Vehicle/AP_FixedWing.h @@ -12,7 +12,7 @@ struct AP_FixedWing { AP_Int8 throttle_cruise; AP_Int8 takeoff_throttle_max; AP_Int8 takeoff_throttle_min; - AP_Int8 takeoff_mode; + AP_Int32 takeoff_options; AP_Int16 airspeed_min; AP_Int16 airspeed_max; AP_Float airspeed_cruise; @@ -51,4 +51,9 @@ struct AP_FixedWing { LAND = 4, ABORT_LANDING = 7 }; + + // Bitfields of TKOFF_OPTIONS + enum class TakeoffOption { + THROTTLE_RANGE = (1U << 0), // Unset: Max throttle. Set: Throttle range. + }; };