From d4c4daca1643b51f809cd4acce9371472cf3cd58 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 15 Mar 2017 09:08:13 +0900 Subject: [PATCH] AC_WPNav: speed-up and down parameter min to 10cm/s --- libraries/AC_WPNav/AC_WPNav.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AC_WPNav/AC_WPNav.cpp b/libraries/AC_WPNav/AC_WPNav.cpp index d6b42cd8ab..bdee51cb69 100644 --- a/libraries/AC_WPNav/AC_WPNav.cpp +++ b/libraries/AC_WPNav/AC_WPNav.cpp @@ -28,7 +28,7 @@ const AP_Param::GroupInfo AC_WPNav::var_info[] = { // @DisplayName: Waypoint Climb Speed Target // @Description: Defines the speed in cm/s which the aircraft will attempt to maintain while climbing during a WP mission // @Units: cm/s - // @Range: 0 1000 + // @Range: 10 1000 // @Increment: 50 // @User: Standard AP_GROUPINFO("SPEED_UP", 2, AC_WPNav, _wp_speed_up_cms, WPNAV_WP_SPEED_UP), @@ -37,7 +37,7 @@ const AP_Param::GroupInfo AC_WPNav::var_info[] = { // @DisplayName: Waypoint Descent Speed Target // @Description: Defines the speed in cm/s which the aircraft will attempt to maintain while descending during a WP mission // @Units: cm/s - // @Range: 0 500 + // @Range: 10 500 // @Increment: 10 // @User: Standard AP_GROUPINFO("SPEED_DN", 3, AC_WPNav, _wp_speed_down_cms, WPNAV_WP_SPEED_DOWN),