mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
ACM : Added larger WP radius for fast waypoints so we don't loose speed angling in on the WP at the last second.
This commit is contained in:
parent
9a568385b0
commit
3ad08b7ffc
@ -563,7 +563,7 @@ static int16_t waypoint_speed_gov;
|
|||||||
static int32_t long_error, lat_error;
|
static int32_t long_error, lat_error;
|
||||||
// Are we navigating while holding a positon? This is set to false once the speed drops below 1m/s
|
// Are we navigating while holding a positon? This is set to false once the speed drops below 1m/s
|
||||||
static boolean loiter_override;
|
static boolean loiter_override;
|
||||||
|
static int16_t waypoint_radius;
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
// Orientation
|
// Orientation
|
||||||
|
@ -403,6 +403,9 @@ static void reset_nav_params(void)
|
|||||||
|
|
||||||
// make sure we stick to Nav yaw on takeoff
|
// make sure we stick to Nav yaw on takeoff
|
||||||
auto_yaw = nav_yaw;
|
auto_yaw = nav_yaw;
|
||||||
|
|
||||||
|
// revert to smaller radius set in params
|
||||||
|
waypoint_radius = g.waypoint_radius;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -452,7 +452,7 @@ static bool verify_nav_wp()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// Did we pass the WP? // Distance checking
|
// Did we pass the WP? // Distance checking
|
||||||
if((wp_distance <= (g.waypoint_radius * 100)) || check_missed_wp()){
|
if((wp_distance <= (waypoint_radius * 100)) || check_missed_wp()){
|
||||||
|
|
||||||
// if we have a distance calc error, wp_distance may be less than 0
|
// if we have a distance calc error, wp_distance may be less than 0
|
||||||
if(wp_distance > 0){
|
if(wp_distance > 0){
|
||||||
|
@ -260,8 +260,10 @@ static int16_t get_desired_speed(int16_t max_speed, bool _slow)
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
if(fast_corner){
|
if(fast_corner){
|
||||||
|
waypoint_radius = g.waypoint_radius * 2;
|
||||||
//max_speed = max_speed;
|
//max_speed = max_speed;
|
||||||
}else{
|
}else{
|
||||||
|
waypoint_radius = g.waypoint_radius;
|
||||||
max_speed = min(max_speed, (wp_distance - g.waypoint_radius) / 3);
|
max_speed = min(max_speed, (wp_distance - g.waypoint_radius) / 3);
|
||||||
max_speed = max(max_speed, WAYPOINT_SPEED_MIN); // go at least 100cm/s
|
max_speed = max(max_speed, WAYPOINT_SPEED_MIN); // go at least 100cm/s
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user