mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
AC_WPNav: lowering waypoint radius minimum to 5cm
This commit is contained in:
parent
17e258d347
commit
9ebe5d7de9
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user