From d857afcd6de643eb0ee19ceab899e26812b78169 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Mon, 11 Jul 2022 00:12:04 +0930 Subject: [PATCH] Defaults --- libraries/AC_Fence/AC_Fence.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AC_Fence/AC_Fence.cpp b/libraries/AC_Fence/AC_Fence.cpp index 083b8eb6af739..405b0d17271ec 100644 --- a/libraries/AC_Fence/AC_Fence.cpp +++ b/libraries/AC_Fence/AC_Fence.cpp @@ -27,7 +27,7 @@ extern const AP_HAL::HAL& hal; // default boundaries #define AC_FENCE_ALT_MAX_DEFAULT 100.0f // default max altitude is 100m -#define AC_FENCE_ALT_MIN_DEFAULT -10.0f // default maximum depth in meters +#define AC_FENCE_ALT_MIN_DEFAULT 15.0f // default maximum depth in meters #define AC_FENCE_CIRCLE_RADIUS_DEFAULT 300.0f // default circular fence radius is 300m #define AC_FENCE_ALT_MAX_BACKUP_DISTANCE 20.0f // after fence is broken we recreate the fence 20m further up #define AC_FENCE_ALT_MIN_BACKUP_DISTANCE 20.0f // after fence is broken we recreate the fence 20m further down