AP_OpticalFlow: use vector rotate method

This commit is contained in:
Peter Barker 2023-07-14 10:43:55 +10:00 committed by Andrew Tridgell
parent 92b7cfbbb2
commit a3f43b26ae
1 changed files with 1 additions and 6 deletions

View File

@ -41,12 +41,7 @@ void OpticalFlow_backend::_applyYaw(Vector2f &v)
if (is_zero(yawAngleRad)) {
return;
}
float cosYaw = cosf(yawAngleRad);
float sinYaw = sinf(yawAngleRad);
float x = v.x;
float y = v.y;
v.x = cosYaw * x - sinYaw * y;
v.y = sinYaw * x + cosYaw * y;
v.rotate(yawAngleRad);
}
#endif