mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 17:48:35 -04:00
Plane: don't failsafe when in RTL_AUTOLAND landing sequence
when in AUTO and already in the landing sequence then don't trigger a failsafe
This commit is contained in:
parent
f5deacfb80
commit
546cd0efb2
@ -12,6 +12,9 @@ bool Plane::failsafe_in_landing_sequence() const
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
if (mission.get_in_landing_sequence_flag()) {
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user