mirror of https://github.com/ArduPilot/ardupilot
Plane: allow mode switch on fence breach for RTL_AUTOLAND
when we are in a fence breach we by default disallow mode changes, but we need to allow for the switch to AUTO if the reason is we are entering a landing sequence, which is part of the RTL process which is the fence action
This commit is contained in:
parent
bdce9d5cb3
commit
71fdf37055
|
@ -248,8 +248,12 @@ bool Plane::set_mode(Mode &new_mode, const ModeReason reason)
|
||||||
|
|
||||||
#if AP_FENCE_ENABLED
|
#if AP_FENCE_ENABLED
|
||||||
// may not be allowed to change mode if recovering from fence breach
|
// may not be allowed to change mode if recovering from fence breach
|
||||||
if (hal.util->get_soft_armed() && fence.enabled() && fence.option_enabled(AC_Fence::OPTIONS::DISABLE_MODE_CHANGE) &&
|
if (hal.util->get_soft_armed() &&
|
||||||
fence.get_breaches() && in_fence_recovery()) {
|
fence.enabled() &&
|
||||||
|
fence.option_enabled(AC_Fence::OPTIONS::DISABLE_MODE_CHANGE) &&
|
||||||
|
fence.get_breaches() &&
|
||||||
|
in_fence_recovery() &&
|
||||||
|
reason != ModeReason::RTL_COMPLETE_SWITCHING_TO_FIXEDWING_AUTOLAND) {
|
||||||
gcs().send_text(MAV_SEVERITY_NOTICE,"Mode change to %s denied, in fence recovery", new_mode.name());
|
gcs().send_text(MAV_SEVERITY_NOTICE,"Mode change to %s denied, in fence recovery", new_mode.name());
|
||||||
AP_Notify::events.user_mode_change_failed = 1;
|
AP_Notify::events.user_mode_change_failed = 1;
|
||||||
return false;
|
return false;
|
||||||
|
|
Loading…
Reference in New Issue