diff --git a/libraries/AP_Math/matrix3.cpp b/libraries/AP_Math/matrix3.cpp index eb97972aa7..abbf619c6e 100644 --- a/libraries/AP_Math/matrix3.cpp +++ b/libraries/AP_Math/matrix3.cpp @@ -58,6 +58,43 @@ void Matrix3::to_euler(float *roll, float *pitch, float *yaw) const } } +/* + calculate Euler angles (312 convention) for the matrix. + See http://www.atacolorado.com/eulersequences.doc + vector is returned in r, p, y order +*/ +template +Vector3 Matrix3::to_euler312() const +{ + return Vector3(asinf(c.y), + atan2f(-c.x, c.z), + atan2f(-a.y, b.y)); +} + +/* + fill the matrix from Euler angles in radians in 312 convention +*/ +template +void Matrix3::from_euler312(float roll, float pitch, float yaw) +{ + float c3 = cosf(pitch); + float s3 = sinf(pitch); + float s2 = sinf(roll); + float c2 = cosf(roll); + float s1 = sinf(yaw); + float c1 = cosf(yaw); + + a.x = c1 * c3 - s1 * s2 * s3; + b.y = c1 * c2; + c.z = c3 * c2; + a.y = -c2*s1; + a.z = s3*c1 + c3*s2*s1; + b.x = c3*s1 + s3*s2*c1; + b.z = s1*s3 - s2*c1*c3; + c.x = -s3*c2; + c.y = s2; +} + // apply an additional rotation from a body frame gyro vector // to a rotation matrix. template @@ -197,6 +234,8 @@ template void Matrix3::rotateXYinv(const Vector3 &g); template void Matrix3::normalize(void); template void Matrix3::from_euler(float roll, float pitch, float yaw); template void Matrix3::to_euler(float *roll, float *pitch, float *yaw) const; +template void Matrix3::from_euler312(float roll, float pitch, float yaw); +template Vector3 Matrix3::to_euler312(void) const; template Vector3 Matrix3::operator *(const Vector3 &v) const; template Vector3 Matrix3::mul_transpose(const Vector3 &v) const; template Matrix3 Matrix3::operator *(const Matrix3 &m) const; diff --git a/libraries/AP_Math/matrix3.h b/libraries/AP_Math/matrix3.h index bb04dcc91c..f620b1fa25 100644 --- a/libraries/AP_Math/matrix3.h +++ b/libraries/AP_Math/matrix3.h @@ -208,6 +208,18 @@ public: // create eulers from a rotation matrix void to_euler(float *roll, float *pitch, float *yaw) const; + /* + calculate Euler angles (312 convention) for the matrix. + See http://www.atacolorado.com/eulersequences.doc + vector is returned in r, p, y order + */ + Vector3 to_euler312() const; + + /* + fill the matrix from Euler angles in radians in 312 convention + */ + void from_euler312(float roll, float pitch, float yaw); + // apply an additional rotation from a body frame gyro vector // to a rotation matrix. void rotate(const Vector3 &g);