From 139acc0530410762c4d1ec8b580737e662ec7ad6 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 21 Feb 2013 11:21:39 +1100 Subject: [PATCH] Plane: ignore control mode changes when in throttle failsafe this prevents the receiver causing a temporary mode change --- ArduPlane/control_modes.pde | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/ArduPlane/control_modes.pde b/ArduPlane/control_modes.pde index b6429ba035..3846615ea2 100644 --- a/ArduPlane/control_modes.pde +++ b/ArduPlane/control_modes.pde @@ -10,6 +10,12 @@ static void read_control_switch() // If we get this value we do not want to change modes. if(switchPosition == 255) return; + if (ch3_failsafe) { + // when we are in ch3_failsafe mode then RC input is not + // working, and we need to ignore the mode switch channel + return; + } + // we look for changes in the switch position. If the // RST_SWITCH_CH parameter is set, then it is a switch that can be // used to force re-reading of the control switch. This is useful