From 3a3397d926ba8a6c946f05ef39530989041d50eb Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Mar 2014 17:22:24 +1100 Subject: [PATCH] Plane: fixup throttle trim on failsafe --- ArduPlane/radio.pde | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduPlane/radio.pde b/ArduPlane/radio.pde index 2af61ee83b..23261f6e38 100644 --- a/ArduPlane/radio.pde +++ b/ArduPlane/radio.pde @@ -191,11 +191,11 @@ static void control_failsafe(uint16_t pwm) { if (hal.scheduler->millis() - failsafe.last_valid_rc_ms > 1000 || rc_failsafe_active()) { // we do not have valid RC input. Set all primary channel - // control inputs to the trim value + // control inputs to the trim value and throttle to min channel_roll->radio_in = channel_roll->radio_trim; channel_pitch->radio_in = channel_pitch->radio_trim; channel_rudder->radio_in = channel_rudder->radio_trim; - channel_throttle->radio_in = channel_throttle->radio_trim; + channel_throttle->radio_in = channel_throttle->radio_min; channel_roll->control_in = 0; channel_pitch->control_in = 0; channel_rudder->control_in = 0;