diff --git a/libraries/AC_WPNav/AC_WPNav.h b/libraries/AC_WPNav/AC_WPNav.h index de91866d28..a76a10be54 100644 --- a/libraries/AC_WPNav/AC_WPNav.h +++ b/libraries/AC_WPNav/AC_WPNav.h @@ -18,7 +18,7 @@ #define WPNAV_WP_SPEED_MIN 20.0f // minimum horizontal speed between waypoints in cm/s #define WPNAV_WP_TRACK_SPEED_MIN 50.0f // minimum speed along track of the target point the vehicle is chasing in cm/s (used as target slows down before reaching destination) #define WPNAV_WP_RADIUS 200.0f // default waypoint radius in cm -#define WPNAV_WP_RADIUS_MIN 10.0f // minimum waypoint radius in cm +#define WPNAV_WP_RADIUS_MIN 5.0f // minimum waypoint radius in cm #define WPNAV_WP_SPEED_UP 250.0f // default maximum climb velocity #define WPNAV_WP_SPEED_DOWN 150.0f // default maximum descent velocity