mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-27 11:08:29 -04:00
AC_WPNav: sanity check wpnav-radius
Occasionally users accidentally set the wpnav-radius to 0 and the vehicle gets stuck at waypoints
This commit is contained in:
parent
945a7bfaed
commit
f618359041
@ -142,8 +142,9 @@ AC_WPNav::AC_WPNav(const AP_InertialNav& inav, const AP_AHRS_View& ahrs, AC_PosC
|
|||||||
_flags.new_wp_destination = false;
|
_flags.new_wp_destination = false;
|
||||||
_flags.segment_type = SEGMENT_STRAIGHT;
|
_flags.segment_type = SEGMENT_STRAIGHT;
|
||||||
|
|
||||||
// sanity check loiter speed
|
// sanity check some parameters
|
||||||
_loiter_speed_cms = MAX(_loiter_speed_cms, WPNAV_LOITER_SPEED_MIN);
|
_loiter_speed_cms = MAX(_loiter_speed_cms, WPNAV_LOITER_SPEED_MIN);
|
||||||
|
_wp_radius_cm = MAX(_wp_radius_cm, WPNAV_WP_RADIUS_MIN);
|
||||||
}
|
}
|
||||||
|
|
||||||
///
|
///
|
||||||
|
@ -24,6 +24,7 @@
|
|||||||
#define WPNAV_WP_SPEED_MIN 20.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_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 200.0f // default waypoint radius in cm
|
||||||
|
#define WPNAV_WP_RADIUS_MIN 10.0f // minimum waypoint radius in cm
|
||||||
|
|
||||||
#define WPNAV_WP_SPEED_UP 250.0f // default maximum climb velocity
|
#define WPNAV_WP_SPEED_UP 250.0f // default maximum climb velocity
|
||||||
#define WPNAV_WP_SPEED_DOWN 150.0f // default maximum descent velocity
|
#define WPNAV_WP_SPEED_DOWN 150.0f // default maximum descent velocity
|
||||||
|
Loading…
Reference in New Issue
Block a user