mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Arming: do not enable minimim altitude fence on arming
call appropriate fence method for auto-enablement
This commit is contained in:
parent
8287d4f2d0
commit
3dbcbe0026
@ -1797,11 +1797,7 @@ bool AP_Arming::arm(AP_Arming::Method method, const bool do_arming_checks)
|
|||||||
if (armed) {
|
if (armed) {
|
||||||
auto *fence = AP::fence();
|
auto *fence = AP::fence();
|
||||||
if (fence != nullptr) {
|
if (fence != nullptr) {
|
||||||
// If a fence is set to auto-enable, turn on the fence
|
fence->auto_enable_fence_on_arming();
|
||||||
if (fence->auto_enabled() == AC_Fence::AutoEnable::ONLY_WHEN_ARMED) {
|
|
||||||
fence->enable(true);
|
|
||||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Fence: auto-enabled");
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
@ -1845,7 +1841,7 @@ bool AP_Arming::disarm(const AP_Arming::Method method, bool do_disarm_checks)
|
|||||||
AC_Fence *fence = AP::fence();
|
AC_Fence *fence = AP::fence();
|
||||||
if (fence != nullptr) {
|
if (fence != nullptr) {
|
||||||
if(fence->auto_enabled() == AC_Fence::AutoEnable::ONLY_WHEN_ARMED) {
|
if(fence->auto_enabled() == AC_Fence::AutoEnable::ONLY_WHEN_ARMED) {
|
||||||
fence->enable(false);
|
fence->enable_configured(false);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user