mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 00:53:57 -03:00
AP_Math: control: remove unneeded normalisation.
This commit is contained in:
parent
092730c32e
commit
ead64a39f8
@ -58,7 +58,6 @@ void update_vel_accel_xy(Vector2f& vel, const Vector2f& accel, float dt, const V
|
|||||||
Vector2f delta_vel = accel * dt;
|
Vector2f delta_vel = accel * dt;
|
||||||
if (!is_zero(limit.length_squared())) {
|
if (!is_zero(limit.length_squared())) {
|
||||||
// zero delta_vel if it will increase the velocity error
|
// zero delta_vel if it will increase the velocity error
|
||||||
limit.normalize();
|
|
||||||
if (is_positive(delta_vel * limit)) {
|
if (is_positive(delta_vel * limit)) {
|
||||||
delta_vel.zero();
|
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())) {
|
if (!is_zero(limit.length_squared())) {
|
||||||
// zero delta_vel if it will increase the velocity error
|
// zero delta_vel if it will increase the velocity error
|
||||||
limit.normalize();
|
|
||||||
if (is_positive(delta_pos * limit)) {
|
if (is_positive(delta_pos * limit)) {
|
||||||
delta_pos.zero();
|
delta_pos.zero();
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user