AP_Math: control: remove unneeded normalisation.

This commit is contained in:
Iampete1 2021-11-20 00:33:04 +00:00 committed by Andrew Tridgell
parent 8563c8125a
commit 34266ce8ab
1 changed files with 0 additions and 2 deletions

View File

@ -58,7 +58,6 @@ void update_vel_accel_xy(Vector2f& vel, const Vector2f& accel, float dt, const V
Vector2f delta_vel = accel * dt;
if (!is_zero(limit.length_squared())) {
// zero delta_vel if it will increase the velocity error
limit.normalize();
if (is_positive(delta_vel * limit)) {
delta_vel.zero();
}
@ -75,7 +74,6 @@ void update_pos_vel_accel_xy(Vector2p& pos, Vector2f& vel, const Vector2f& accel
if (!is_zero(limit.length_squared())) {
// zero delta_vel if it will increase the velocity error
limit.normalize();
if (is_positive(delta_pos * limit)) {
delta_pos.zero();
}