mirror of https://github.com/ArduPilot/ardupilot
Copter: ignore switch changes during transitions in or out of radio failsafe
This commit is contained in:
parent
7cc8a9038f
commit
6b97994dcd
|
@ -9,7 +9,7 @@ static void read_control_switch()
|
||||||
|
|
||||||
// has switch moved?
|
// has switch moved?
|
||||||
// ignore flight mode changes if in failsafe
|
// ignore flight mode changes if in failsafe
|
||||||
if (oldSwitchPosition != switchPosition && !failsafe.radio) {
|
if (oldSwitchPosition != switchPosition && !failsafe.radio && failsafe.radio_counter == 0) {
|
||||||
switch_counter++;
|
switch_counter++;
|
||||||
if(switch_counter >= CONTROL_SWITCH_COUNTER) {
|
if(switch_counter >= CONTROL_SWITCH_COUNTER) {
|
||||||
oldSwitchPosition = switchPosition;
|
oldSwitchPosition = switchPosition;
|
||||||
|
|
Loading…
Reference in New Issue