From 85bb4ad88fea0f8ca6c872bc84d618ab94609f2d Mon Sep 17 00:00:00 2001 From: George Zogopoulos Date: Tue, 30 Jul 2024 12:13:29 +0200 Subject: [PATCH] Plane: Revert min throttle during transitions --- ArduPlane/servos.cpp | 14 ++++++++++---- 1 file changed, 10 insertions(+), 4 deletions(-) diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index 45eba977a3..4f7b1c4450 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -521,12 +521,10 @@ float Plane::apply_throttle_limits(float throttle_in) // Query the conditions where TKOFF_THR_MAX applies. const bool use_takeoff_throttle = -#if HAL_QUADPLANE_ENABLED - quadplane.in_transition() || -#endif (flight_stage == AP_FixedWing::FlightStage::TAKEOFF) || (flight_stage == AP_FixedWing::FlightStage::ABORT_LANDING); + // Handle throttle limits for takeoff conditions. if (use_takeoff_throttle) { if (aparm.takeoff_throttle_max != 0) { // Replace max throttle with the takeoff max throttle setting. @@ -534,7 +532,6 @@ float Plane::apply_throttle_limits(float throttle_in) // Or (in contrast) to give some extra throttle during the initial climb. max_throttle = aparm.takeoff_throttle_max.get(); } - // Do not allow min throttle to go below a lower threshold. // This is typically done to protect against premature stalls close to the ground. const bool use_throttle_range = (aparm.takeoff_options & (uint32_t)AP_FixedWing::TakeoffOption::THROTTLE_RANGE); @@ -556,6 +553,15 @@ float Plane::apply_throttle_limits(float throttle_in) min_throttle = 0; } + // Handle throttle limits for transition conditions. +#if HAL_QUADPLANE_ENABLED + if (quadplane.in_transition()) { + if (aparm.takeoff_throttle_max != 0) { + max_throttle = aparm.takeoff_throttle_max.get(); + } + } +#endif + // Compensate the limits for battery voltage drop. // This relaxes the limits when the battery is getting depleted. g2.fwd_batt_cmp.apply_min_max(min_throttle, max_throttle);