mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-11 02:13:57 -04:00
AP_Math: added quaternion.from_rotation_matrix()
This commit is contained in:
parent
c6b24c521b
commit
689f230d40
@ -43,6 +43,54 @@ void Quaternion::rotation_matrix(Matrix3f &m) const
|
|||||||
m.c.z = 1-2*(q2q2 + q3q3);
|
m.c.z = 1-2*(q2q2 + q3q3);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// return the rotation matrix equivalent for this quaternion
|
||||||
|
// Thanks to Martin John Baker
|
||||||
|
// http://www.euclideanspace.com/maths/geometry/rotations/conversions/matrixToQuaternion/index.htm
|
||||||
|
void Quaternion::from_rotation_matrix(const Matrix3f &m)
|
||||||
|
{
|
||||||
|
const float &m00 = m.a.x;
|
||||||
|
const float &m11 = m.b.y;
|
||||||
|
const float &m22 = m.c.z;
|
||||||
|
const float &m10 = m.b.x;
|
||||||
|
const float &m01 = m.a.y;
|
||||||
|
const float &m20 = m.c.x;
|
||||||
|
const float &m02 = m.a.z;
|
||||||
|
const float &m21 = m.c.y;
|
||||||
|
const float &m12 = m.b.z;
|
||||||
|
float &qw = q1;
|
||||||
|
float &qx = q2;
|
||||||
|
float &qy = q3;
|
||||||
|
float &qz = q4;
|
||||||
|
|
||||||
|
float tr = m00 + m11 + m22;
|
||||||
|
|
||||||
|
if (tr > 0) {
|
||||||
|
float S = sqrtf(tr+1) * 2;
|
||||||
|
qw = 0.25f * S;
|
||||||
|
qx = (m21 - m12) / S;
|
||||||
|
qy = (m02 - m20) / S;
|
||||||
|
qz = (m10 - m01) / S;
|
||||||
|
} else if ((m00 > m11) && (m00 > m22)) {
|
||||||
|
float S = sqrtf(1.0 + m00 - m11 - m22) * 2;
|
||||||
|
qw = (m21 - m12) / S;
|
||||||
|
qx = 0.25f * S;
|
||||||
|
qy = (m01 + m10) / S;
|
||||||
|
qz = (m02 + m20) / S;
|
||||||
|
} else if (m11 > m22) {
|
||||||
|
float S = sqrtf(1.0 + m11 - m00 - m22) * 2;
|
||||||
|
qw = (m02 - m20) / S;
|
||||||
|
qx = (m01 + m10) / S;
|
||||||
|
qy = 0.25f * S;
|
||||||
|
qz = (m12 + m21) / S;
|
||||||
|
} else {
|
||||||
|
float S = sqrtf(1.0 + m22 - m00 - m11) * 2;
|
||||||
|
qw = (m10 - m01) / S;
|
||||||
|
qx = (m02 + m20) / S;
|
||||||
|
qy = (m12 + m21) / S;
|
||||||
|
qz = 0.25f * S;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// convert a vector from earth to body frame
|
// convert a vector from earth to body frame
|
||||||
void Quaternion::earth_to_body(Vector3f &v) const
|
void Quaternion::earth_to_body(Vector3f &v) const
|
||||||
{
|
{
|
||||||
|
@ -55,6 +55,8 @@ public:
|
|||||||
// return the rotation matrix equivalent for this quaternion
|
// return the rotation matrix equivalent for this quaternion
|
||||||
void rotation_matrix(Matrix3f &m) const;
|
void rotation_matrix(Matrix3f &m) const;
|
||||||
|
|
||||||
|
void from_rotation_matrix(const Matrix3f &m);
|
||||||
|
|
||||||
// convert a vector from earth to body frame
|
// convert a vector from earth to body frame
|
||||||
void earth_to_body(Vector3f &v) const;
|
void earth_to_body(Vector3f &v) const;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user