From 290962305726be398d46849d7363190fa6ef557c Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Thu, 30 Jul 2020 13:26:49 -0700 Subject: [PATCH] Plane: Ensure that only one form of throttle nudging is active at once --- ArduPlane/radio.cpp | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/ArduPlane/radio.cpp b/ArduPlane/radio.cpp index bfc066811d..a499f37b49 100644 --- a/ArduPlane/radio.cpp +++ b/ArduPlane/radio.cpp @@ -186,6 +186,8 @@ void Plane::read_radio() control_failsafe(); + airspeed_nudge_cm = 0; + throttle_nudge = 0; if (g.throttle_nudge && channel_throttle->get_control_in() > 50 && geofence_stickmixing()) { float nudge = (channel_throttle->get_control_in() - 50) * 0.02f; if (ahrs.airspeed_sensor_enabled()) { @@ -193,9 +195,6 @@ void Plane::read_radio() } else { throttle_nudge = (aparm.throttle_max - aparm.throttle_cruise) * nudge; } - } else { - airspeed_nudge_cm = 0; - throttle_nudge = 0; } rudder_arm_disarm_check();