From 713b08d830226384165b435604b9afa1212e639d Mon Sep 17 00:00:00 2001 From: "Dr.-Ing. Amilcar Do Carmo Lucas" Date: Thu, 5 Jan 2017 18:30:39 +0100 Subject: [PATCH] AC_WPNav: Reduced WPNAV_SPEED minimum to 20cm/s --- libraries/AC_WPNav/AC_WPNav.cpp | 2 +- libraries/AC_WPNav/AC_WPNav.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AC_WPNav/AC_WPNav.cpp b/libraries/AC_WPNav/AC_WPNav.cpp index b339dc9e02..c70c1a59fb 100644 --- a/libraries/AC_WPNav/AC_WPNav.cpp +++ b/libraries/AC_WPNav/AC_WPNav.cpp @@ -10,7 +10,7 @@ const AP_Param::GroupInfo AC_WPNav::var_info[] = { // @DisplayName: Waypoint Horizontal Speed Target // @Description: Defines the speed in cm/s which the aircraft will attempt to maintain horizontally during a WP mission // @Units: cm/s - // @Range: 0 2000 + // @Range: 20 2000 // @Increment: 50 // @User: Standard AP_GROUPINFO("SPEED", 0, AC_WPNav, _wp_speed_cms, WPNAV_WP_SPEED), diff --git a/libraries/AC_WPNav/AC_WPNav.h b/libraries/AC_WPNav/AC_WPNav.h index c706c69567..4eb5236664 100644 --- a/libraries/AC_WPNav/AC_WPNav.h +++ b/libraries/AC_WPNav/AC_WPNav.h @@ -21,7 +21,7 @@ #define WPNAV_LOITER_JERK_MAX_DEFAULT 1000.0f // maximum jerk in cm/s/s/s in loiter mode #define WPNAV_WP_SPEED 500.0f // default horizontal speed between waypoints in cm/s -#define WPNAV_WP_SPEED_MIN 100.0f // minimum horizontal speed between waypoints in cm/s +#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