mirror of https://github.com/ArduPilot/ardupilot
Copter: fully honour FENCE_OPTION to disable mode changes
when the user has chosen to disallow mode change during fence breach it should be fully implemented, without a landing exception. as requested by Pete, and discussed on dev call
This commit is contained in:
parent
f8e5c7c1c4
commit
a371a3eb89
|
@ -353,7 +353,6 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason)
|
|||
fence.enabled() &&
|
||||
fence.option_enabled(AC_Fence::OPTIONS::DISABLE_MODE_CHANGE) &&
|
||||
fence.get_breaches() &&
|
||||
!flightmode->is_landing() &&
|
||||
motors->armed() &&
|
||||
get_control_mode_reason() == ModeReason::FENCE_BREACHED &&
|
||||
!ap.land_complete) {
|
||||
|
|
Loading…
Reference in New Issue