mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Copter: lengthen loiter stopping point
This will make stops less aggressive when entering loiter at very high speeds (more 7.5m/s)
This commit is contained in:
parent
400c1bd7b7
commit
46d65150af
@ -123,7 +123,7 @@ void AC_WPNav::get_stopping_point(const Vector3f& position, const Vector3f& velo
|
||||
linear_distance = MAX_LOITER_POS_ACCEL/(2*kP*kP);
|
||||
target_dist = linear_distance + (vel_total*vel_total)/(2*MAX_LOITER_POS_ACCEL);
|
||||
}
|
||||
target_dist = constrain_float(target_dist, 0, _loiter_leash);
|
||||
target_dist = constrain_float(target_dist, 0, _loiter_leash*2.0);
|
||||
|
||||
target.x = position.x + (target_dist * velocity.x / vel_total);
|
||||
target.y = position.y + (target_dist * velocity.y / vel_total);
|
||||
|
Loading…
Reference in New Issue
Block a user