mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: ignore control mode changes when in throttle failsafe
this prevents the receiver causing a temporary mode change
This commit is contained in:
parent
1ebaa14a99
commit
139acc0530
@ -10,6 +10,12 @@ static void read_control_switch()
|
|||||||
// If we get this value we do not want to change modes.
|
// If we get this value we do not want to change modes.
|
||||||
if(switchPosition == 255) return;
|
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
|
// we look for changes in the switch position. If the
|
||||||
// RST_SWITCH_CH parameter is set, then it is a switch that can be
|
// 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
|
// used to force re-reading of the control switch. This is useful
|
||||||
|
Loading…
Reference in New Issue
Block a user