From ead64a39f88ca1b42e01f4053987ac8e7c05d46f Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 20 Nov 2021 00:33:04 +0000 Subject: [PATCH] AP_Math: control: remove unneeded normalisation. --- libraries/AP_Math/control.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/libraries/AP_Math/control.cpp b/libraries/AP_Math/control.cpp index 1f28aee248..18399fe77c 100644 --- a/libraries/AP_Math/control.cpp +++ b/libraries/AP_Math/control.cpp @@ -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(); }