From 78e9846f4e89cc6cdb276d8bc1bc48441f5a420a Mon Sep 17 00:00:00 2001 From: muramura Date: Sat, 19 Aug 2023 03:30:22 +0900 Subject: [PATCH] AC_Fence: Change the description to match the actual value(NFC) --- libraries/AC_Fence/AC_Fence.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AC_Fence/AC_Fence.cpp b/libraries/AC_Fence/AC_Fence.cpp index d2569877d7..e0196fadc6 100644 --- a/libraries/AC_Fence/AC_Fence.cpp +++ b/libraries/AC_Fence/AC_Fence.cpp @@ -35,7 +35,7 @@ extern const AP_HAL::HAL& hal; #define AC_FENCE_MANUAL_RECOVERY_TIME_MIN 10000 // pilot has 10seconds to recover during which time the autopilot will not attempt to re-take control #if APM_BUILD_TYPE(APM_BUILD_ArduPlane) -#define AC_FENCE_CIRCLE_RADIUS_BACKUP_DISTANCE 100.0 // after fence is broken we recreate the fence 50m further out +#define AC_FENCE_CIRCLE_RADIUS_BACKUP_DISTANCE 100.0 // after fence is broken we recreate the fence 100m further out #else #define AC_FENCE_CIRCLE_RADIUS_BACKUP_DISTANCE 20.0 // after fence is broken we recreate the fence 20m further out #endif @@ -518,7 +518,7 @@ bool AC_Fence::check_fence_circle() if (!(_breached_fences & AC_FENCE_TYPE_CIRCLE) || (!is_zero(_circle_radius_backup) && _home_distance >= _circle_radius_backup)) { // new breach - // create a backup fence 20m further out + // create a backup fence 20m or 100m further out record_breach(AC_FENCE_TYPE_CIRCLE); _circle_radius_backup = _home_distance + AC_FENCE_CIRCLE_RADIUS_BACKUP_DISTANCE; return true;