AC_WPNav: Reduced WPNAV_SPEED minimum to 20cm/s

This commit is contained in:
Dr.-Ing. Amilcar Do Carmo Lucas 2017-01-05 18:30:39 +01:00 committed by Randy Mackay
parent 35d6dc141a
commit 713b08d830
2 changed files with 2 additions and 2 deletions

View File

@ -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),

View File

@ -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