Skip to content
Snippets Groups Projects
Commit c932626d authored by Randy Mackay's avatar Randy Mackay
Browse files

WPNav: reduce loiter speed used to correct pos error

Contributed by Leonard Hall
This should reduce the aggressiveness of the response when we experience
a GPS glitch
parent 352a25e5
No related branches found
No related tags found
No related merge requests found
...@@ -271,7 +271,7 @@ void AC_WPNav::update_loiter() ...@@ -271,7 +271,7 @@ void AC_WPNav::update_loiter()
translate_loiter_target_movements(dt); translate_loiter_target_movements(dt);
// run loiter position controller // run loiter position controller
get_loiter_position_to_velocity(dt, _loiter_speed_cms); get_loiter_position_to_velocity(dt, WPNAV_LOITER_SPEED_MAX_TO_CORRECT_ERROR);
} }
/// calculate_loiter_leash_length - calculates the maximum distance in cm that the target position may be from the current location /// calculate_loiter_leash_length - calculates the maximum distance in cm that the target position may be from the current location
......
...@@ -20,6 +20,7 @@ ...@@ -20,6 +20,7 @@
#define WPNAV_LOITER_SPEED 500.0f // maximum default loiter speed in cm/s #define WPNAV_LOITER_SPEED 500.0f // maximum default loiter speed in cm/s
#define WPNAV_LOITER_ACCEL_MAX 250.0f // maximum acceleration in loiter mode #define WPNAV_LOITER_ACCEL_MAX 250.0f // maximum acceleration in loiter mode
#define WPNAV_LOITER_ACCEL_MIN 25.0f // minimum acceleration in loiter mode #define WPNAV_LOITER_ACCEL_MIN 25.0f // minimum acceleration in loiter mode
#define WPNAV_LOITER_SPEED_MAX_TO_CORRECT_ERROR 200.0f // maximum speed used to correct position error (i.e. not including feed forward)
#define MAX_LEAN_ANGLE 4500 // default maximum lean angle #define MAX_LEAN_ANGLE 4500 // default maximum lean angle
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment