mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Math: correct descriptions of quaternion functions
This commit is contained in:
parent
b5f7fca254
commit
be076e5b1a
@ -51,7 +51,7 @@ void QuaternionT<T>::rotation_matrix(Matrix3d &m) const
|
|||||||
m.c.z = 1.0f-2.0f*(q2q2 + q3q3);
|
m.c.z = 1.0f-2.0f*(q2q2 + q3q3);
|
||||||
}
|
}
|
||||||
|
|
||||||
// return the rotation matrix equivalent for this quaternion
|
// populate the supplied rotation matrix equivalent from this quaternion
|
||||||
template <typename T>
|
template <typename T>
|
||||||
void QuaternionT<T>::rotation_matrix(Matrix3f &m) const
|
void QuaternionT<T>::rotation_matrix(Matrix3f &m) const
|
||||||
{
|
{
|
||||||
@ -76,7 +76,7 @@ void QuaternionT<T>::rotation_matrix(Matrix3f &m) const
|
|||||||
m.c.z = 1.0f-2.0f*(q2q2 + q3q3);
|
m.c.z = 1.0f-2.0f*(q2q2 + q3q3);
|
||||||
}
|
}
|
||||||
|
|
||||||
// return the rotation matrix equivalent for this quaternion
|
// make this quaternion equivalent to the supplied matrix
|
||||||
// Thanks to Martin John Baker
|
// Thanks to Martin John Baker
|
||||||
// http://www.euclideanspace.com/maths/geometry/rotations/conversions/matrixToQuaternion/index.htm
|
// http://www.euclideanspace.com/maths/geometry/rotations/conversions/matrixToQuaternion/index.htm
|
||||||
template <typename T>
|
template <typename T>
|
||||||
|
@ -63,11 +63,11 @@ public:
|
|||||||
return isnan(q1) || isnan(q2) || isnan(q3) || isnan(q4);
|
return isnan(q1) || isnan(q2) || isnan(q3) || isnan(q4);
|
||||||
}
|
}
|
||||||
|
|
||||||
// return the rotation matrix equivalent for this quaternion
|
// populate the supplied rotation matrix equivalent from this quaternion
|
||||||
void rotation_matrix(Matrix3f &m) const;
|
void rotation_matrix(Matrix3f &m) const;
|
||||||
void rotation_matrix(Matrix3d &m) const;
|
void rotation_matrix(Matrix3d &m) const;
|
||||||
|
|
||||||
// return the rotation matrix equivalent for this quaternion
|
// make this quaternion equivalent to the supplied matrix
|
||||||
void from_rotation_matrix(const Matrix3<T> &m);
|
void from_rotation_matrix(const Matrix3<T> &m);
|
||||||
|
|
||||||
// create a quaternion from a given rotation
|
// create a quaternion from a given rotation
|
||||||
|
Loading…
Reference in New Issue
Block a user