mirror of https://github.com/ArduPilot/ardupilot
AP_Arming: fixed auto-enable of fence with forced arm
when a user forced armed and had FENCE_AUTOENABLE=3 for enable on arming then the fence did not enable
This commit is contained in:
parent
e6280e6d37
commit
16d617c62d
|
@ -1479,16 +1479,6 @@ bool AP_Arming::arm_checks(AP_Arming::Method method)
|
|||
}
|
||||
}
|
||||
|
||||
#if AP_FENCE_ENABLED
|
||||
AC_Fence *fence = AP::fence();
|
||||
if (fence != nullptr) {
|
||||
// If a fence is set to auto-enable, turn on the fence
|
||||
if(fence->auto_enabled() == AC_Fence::AutoEnable::ONLY_WHEN_ARMED) {
|
||||
fence->enable(true);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
// note that this will prepare AP_Logger to start logging
|
||||
// so should be the last check to be done before arming
|
||||
|
||||
|
@ -1565,6 +1555,19 @@ bool AP_Arming::arm(AP_Arming::Method method, const bool do_arming_checks)
|
|||
}
|
||||
#endif
|
||||
|
||||
#if AP_FENCE_ENABLED
|
||||
if (armed) {
|
||||
auto *fence = AP::fence();
|
||||
if (fence != nullptr) {
|
||||
// If a fence is set to auto-enable, turn on the fence
|
||||
if (fence->auto_enabled() == AC_Fence::AutoEnable::ONLY_WHEN_ARMED) {
|
||||
fence->enable(true);
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Fence: auto-enabled");
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
return armed;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue