mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
Plane: prevent rapid RTL/AUTO switching on fence breach
don't switch back to RTL if already in a DO_LAND_START sequence
This commit is contained in:
parent
ce27ec2276
commit
27cbe5dbbb
@ -65,6 +65,12 @@ void Plane::fence_check()
|
||||
case AC_FENCE_ACTION_GUIDED_THROTTLE_PASS:
|
||||
case AC_FENCE_ACTION_RTL_AND_LAND:
|
||||
if (fence_act == AC_FENCE_ACTION_RTL_AND_LAND) {
|
||||
if (control_mode == &mode_auto &&
|
||||
mission.get_in_landing_sequence_flag() &&
|
||||
(g.rtl_autoland == 1 || g.rtl_autoland == 2)) {
|
||||
// already landing
|
||||
return;
|
||||
}
|
||||
set_mode(mode_rtl, ModeReason::FENCE_BREACHED);
|
||||
} else {
|
||||
set_mode(mode_guided, ModeReason::FENCE_BREACHED);
|
||||
|
Loading…
Reference in New Issue
Block a user