mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
WPNav: stopping point projection uses wp_leash
This commit is contained in:
parent
a2ea053c90
commit
fff56c4720
@ -137,7 +137,7 @@ void AC_WPNav::get_stopping_point(const Vector3f& position, const Vector3f& velo
|
|||||||
linear_distance = _wp_accel_cms/(2.0f*kP*kP);
|
linear_distance = _wp_accel_cms/(2.0f*kP*kP);
|
||||||
target_dist = linear_distance + (vel_total*vel_total)/(2.0f*_wp_accel_cms);
|
target_dist = linear_distance + (vel_total*vel_total)/(2.0f*_wp_accel_cms);
|
||||||
}
|
}
|
||||||
target_dist = constrain_float(target_dist, 0, _loiter_leash*2.0f);
|
target_dist = constrain_float(target_dist, 0, _wp_leash_xy*2.0f);
|
||||||
|
|
||||||
target.x = position.x + (target_dist * velocity.x / vel_total);
|
target.x = position.x + (target_dist * velocity.x / vel_total);
|
||||||
target.y = position.y + (target_dist * velocity.y / vel_total);
|
target.y = position.y + (target_dist * velocity.y / vel_total);
|
||||||
|
Loading…
Reference in New Issue
Block a user