mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Plane: prevent failsafe from changing mode during landing
this prevents RC or GCS failsafe from triggering a mode change during a landing
This commit is contained in:
parent
87486739d1
commit
5f4b5c4b94
@ -40,6 +40,13 @@ void Plane::failsafe_short_on_event(enum failsafe_state fstype, ModeReason reaso
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
case Mode::Number::AUTO:
|
case Mode::Number::AUTO:
|
||||||
|
if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND ||
|
||||||
|
quadplane.in_vtol_land_sequence()) {
|
||||||
|
// don't failsafe in a landing sequence
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
FALLTHROUGH;
|
||||||
|
|
||||||
case Mode::Number::AVOID_ADSB:
|
case Mode::Number::AVOID_ADSB:
|
||||||
case Mode::Number::GUIDED:
|
case Mode::Number::GUIDED:
|
||||||
case Mode::Number::LOITER:
|
case Mode::Number::LOITER:
|
||||||
@ -110,6 +117,13 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype, ModeReason reason
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
case Mode::Number::AUTO:
|
case Mode::Number::AUTO:
|
||||||
|
if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND ||
|
||||||
|
quadplane.in_vtol_land_sequence()) {
|
||||||
|
// don't failsafe in a landing sequence
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
FALLTHROUGH;
|
||||||
|
|
||||||
case Mode::Number::AVOID_ADSB:
|
case Mode::Number::AVOID_ADSB:
|
||||||
case Mode::Number::GUIDED:
|
case Mode::Number::GUIDED:
|
||||||
if(g.fs_action_long == FS_ACTION_LONG_PARACHUTE) {
|
if(g.fs_action_long == FS_ACTION_LONG_PARACHUTE) {
|
||||||
|
Loading…
Reference in New Issue
Block a user