Copter: ignore switch changes during transitions in or out of radio failsafe

This commit is contained in:
Randy Mackay 2013-09-26 19:36:49 +09:00
parent 7cc8a9038f
commit 6b97994dcd
1 changed files with 1 additions and 1 deletions

View File

@ -9,7 +9,7 @@ static void read_control_switch()
// has switch moved?
// ignore flight mode changes if in failsafe
if (oldSwitchPosition != switchPosition && !failsafe.radio) {
if (oldSwitchPosition != switchPosition && !failsafe.radio && failsafe.radio_counter == 0) {
switch_counter++;
if(switch_counter >= CONTROL_SWITCH_COUNTER) {
oldSwitchPosition = switchPosition;