mirror of https://github.com/ArduPilot/ardupilot
AP_OpticalFlow: use vector rotate method
This commit is contained in:
parent
92b7cfbbb2
commit
a3f43b26ae
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue