From 15a2e0c1c8df6aa07ed4740f162dfe8381292e18 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 10 Nov 2022 13:52:05 +1100 Subject: [PATCH] Plane: only apply THR_MIN if ICE has allow_throttle_while_disarmed this fixes the disarmed throttle to be zero on normal aircraft --- ArduPlane/servos.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index 4051981f9b..821a8026a5 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -890,7 +890,11 @@ void Plane::set_servos(void) // slew rate limit throttle throttle_slew_limit(SRV_Channel::k_throttle); + int8_t min_throttle = 0; #if AP_ICENGINE_ENABLED + if (g2.ice_control.allow_throttle_while_disarmed()) { + min_throttle = MAX(aparm.throttle_min.get(), 0); + } const float base_throttle = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle); #endif @@ -911,7 +915,6 @@ void Plane::set_servos(void) case AP_Arming::Required::YES_MIN_PWM: default: - int8_t min_throttle = MAX(aparm.throttle_min.get(),0); SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, min_throttle); SRV_Channels::set_output_scaled(SRV_Channel::k_throttleLeft, min_throttle); SRV_Channels::set_output_scaled(SRV_Channel::k_throttleRight, min_throttle);