From d3d6bed58486815f2f9dc9b9e9fd9da45cae76b7 Mon Sep 17 00:00:00 2001 From: murata Date: Fri, 26 Apr 2019 18:33:51 +0900 Subject: [PATCH] AP_WPNav: Change the value of the minimum effective radius --- libraries/AC_WPNav/AC_WPNav.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AC_WPNav/AC_WPNav.cpp b/libraries/AC_WPNav/AC_WPNav.cpp index f877aae2f8..4b2b688a6b 100644 --- a/libraries/AC_WPNav/AC_WPNav.cpp +++ b/libraries/AC_WPNav/AC_WPNav.cpp @@ -19,7 +19,7 @@ const AP_Param::GroupInfo AC_WPNav::var_info[] = { // @DisplayName: Waypoint Radius // @Description: Defines the distance from a waypoint, that when crossed indicates the wp has been hit. // @Units: cm - // @Range: 10 1000 + // @Range: 5 1000 // @Increment: 1 // @User: Standard AP_GROUPINFO("RADIUS", 1, AC_WPNav, _wp_radius_cm, WPNAV_WP_RADIUS),