mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_Math: small formatting fix to quaternion rotation_matrix
No functional change
This commit is contained in:
parent
8afd29cc85
commit
7f933140c7
@ -35,13 +35,13 @@ void Quaternion::rotation_matrix(Matrix3f &m) const
|
||||
float q4q4 = q4 * q4;
|
||||
|
||||
m.a.x = 1.0f-2.0f*(q3q3 + q4q4);
|
||||
m.a.y = 2.0f*(q2q3 - q1q4);
|
||||
m.a.z = 2.0f*(q2q4 + q1q3);
|
||||
m.b.x = 2.0f*(q2q3 + q1q4);
|
||||
m.a.y = 2.0f*(q2q3 - q1q4);
|
||||
m.a.z = 2.0f*(q2q4 + q1q3);
|
||||
m.b.x = 2.0f*(q2q3 + q1q4);
|
||||
m.b.y = 1.0f-2.0f*(q2q2 + q4q4);
|
||||
m.b.z = 2.0f*(q3q4 - q1q2);
|
||||
m.c.x = 2.0f*(q2q4 - q1q3);
|
||||
m.c.y = 2.0f*(q3q4 + q1q2);
|
||||
m.b.z = 2.0f*(q3q4 - q1q2);
|
||||
m.c.x = 2.0f*(q2q4 - q1q3);
|
||||
m.c.y = 2.0f*(q3q4 + q1q2);
|
||||
m.c.z = 1.0f-2.0f*(q2q2 + q3q3);
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user