mirror of https://github.com/ArduPilot/ardupilot
AP_Arming: Enable and Disable the fence when vehicle is armed/disarmed
AP_Arming: Use auto enable flag to arm fence only when armed (as per enum) AP_Arming: Config defines are not available in AP_Arming Since config definitions are not available in AP_Arming, we can still rely on singleton access of the AC_Fence object. AP_Arming: Perform fence checks for all vehicles
This commit is contained in:
parent
87b66b4b49
commit
0e73b7bce1
|
@ -1141,7 +1141,8 @@ bool AP_Arming::pre_arm_checks(bool report)
|
|||
& osd_checks(report)
|
||||
& visodom_checks(report)
|
||||
& aux_auth_checks(report)
|
||||
& disarm_switch_checks(report);
|
||||
& disarm_switch_checks(report)
|
||||
& fence_checks(report);
|
||||
}
|
||||
|
||||
bool AP_Arming::arm_checks(AP_Arming::Method method)
|
||||
|
@ -1167,6 +1168,14 @@ bool AP_Arming::arm_checks(AP_Arming::Method method)
|
|||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
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);
|
||||
}
|
||||
}
|
||||
|
||||
// note that this will prepare AP_Logger to start logging
|
||||
// so should be the last check to be done before arming
|
||||
|
@ -1235,6 +1244,13 @@ bool AP_Arming::disarm(const AP_Arming::Method method, bool do_disarm_checks)
|
|||
}
|
||||
#endif
|
||||
|
||||
AC_Fence *fence = AP::fence();
|
||||
if (fence != nullptr) {
|
||||
if(fence->auto_enabled() == AC_Fence::AutoEnable::ONLY_WHEN_ARMED) {
|
||||
fence->enable(false);
|
||||
}
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue