AP_Arming: do not enable minimim altitude fence on arming

call appropriate fence method for auto-enablement
This commit is contained in:
Andy Piper 2024-01-19 12:30:46 +00:00 committed by Peter Barker
parent 8287d4f2d0
commit 3dbcbe0026
1 changed files with 2 additions and 6 deletions

View File

@ -1797,11 +1797,7 @@ bool AP_Arming::arm(AP_Arming::Method method, const bool do_arming_checks)
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");
}
fence->auto_enable_fence_on_arming();
}
}
#endif
@ -1845,7 +1841,7 @@ bool AP_Arming::disarm(const AP_Arming::Method method, bool do_disarm_checks)
AC_Fence *fence = AP::fence();
if (fence != nullptr) {
if(fence->auto_enabled() == AC_Fence::AutoEnable::ONLY_WHEN_ARMED) {
fence->enable(false);
fence->enable_configured(false);
}
}
#endif