From 7e36beb0e2013b26c9c82081dacbf0f5ecd4a33b Mon Sep 17 00:00:00 2001 From: George Zogopoulos Date: Mon, 26 Aug 2024 14:56:35 +0200 Subject: [PATCH] Plane: In transition use TRIM_THROTTLE when TKOFF_THR_MIN==0 --- ArduPlane/Parameters.cpp | 2 +- ArduPlane/servos.cpp | 2 ++ 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index 2c4d9cfed6c56..bbb8d234486ea 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -156,7 +156,7 @@ const AP_Param::Info Plane::var_info[] = { // @Range: 0 100 // @Increment: 1 // @User: Standard - ASCALAR(takeoff_throttle_min, "TKOFF_THR_MIN", 60), + ASCALAR(takeoff_throttle_min, "TKOFF_THR_MIN", 0), // @Param: TKOFF_OPTIONS // @DisplayName: Takeoff options diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index 92662c074820d..496255a75a54c 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -567,6 +567,8 @@ float Plane::apply_throttle_limits(float throttle_in) ) { if (aparm.takeoff_throttle_min.get() != 0) { min_throttle = MAX(min_throttle, aparm.takeoff_throttle_min.get()); + } else { + min_throttle = MAX(min_throttle, aparm.throttle_cruise.get()); } } }