From 40a6af831f28c7b0dac5e3ada909e5b36c177d6b Mon Sep 17 00:00:00 2001 From: George Zogopoulos Date: Fri, 30 Aug 2024 21:32:08 +0200 Subject: [PATCH] Plane: Using TRIM_THROTTLE when TKOFF_THR_MIN==0 This is related with the recent change of the TKOFF_THR_MIN default value from 60 to 0. --- ArduPlane/takeoff.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/takeoff.cpp b/ArduPlane/takeoff.cpp index e0f87f21d091f9..189b92184cfccd 100644 --- a/ArduPlane/takeoff.cpp +++ b/ArduPlane/takeoff.cpp @@ -258,7 +258,7 @@ void Plane::takeoff_calc_throttle() { if (aparm.takeoff_throttle_min != 0) { takeoff_state.throttle_lim_min = aparm.takeoff_throttle_min; } else { - takeoff_state.throttle_lim_min = aparm.throttle_min; + takeoff_state.throttle_lim_min = aparm.throttle_cruise; } // Raise min to force max throttle for TKOFF_THR_MAX_T after a takeoff.