From 80d90929930172dbcf8fdc42f174efffbdc3fc5e Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Tue, 9 Aug 2016 11:31:18 -0700 Subject: [PATCH] AP_Math: remove rotateXY and rotateXYinv --- libraries/AP_Math/matrix3.cpp | 42 ----------------------------------- libraries/AP_Math/matrix3.h | 8 ------- 2 files changed, 50 deletions(-) diff --git a/libraries/AP_Math/matrix3.cpp b/libraries/AP_Math/matrix3.cpp index 20af4af216..a6ce6e64f6 100644 --- a/libraries/AP_Math/matrix3.cpp +++ b/libraries/AP_Math/matrix3.cpp @@ -116,44 +116,6 @@ void Matrix3::rotate(const Vector3 &g) (*this) += temp_matrix; } -// apply an additional rotation from a body frame gyro vector -// to a rotation matrix. -template -void Matrix3::rotateXY(const Vector3 &g) -{ - Matrix3 temp_matrix; - temp_matrix.a.x = -a.z * g.y; - temp_matrix.a.y = a.z * g.x; - temp_matrix.a.z = a.x * g.y - a.y * g.x; - temp_matrix.b.x = -b.z * g.y; - temp_matrix.b.y = b.z * g.x; - temp_matrix.b.z = b.x * g.y - b.y * g.x; - temp_matrix.c.x = -c.z * g.y; - temp_matrix.c.y = c.z * g.x; - temp_matrix.c.z = c.x * g.y - c.y * g.x; - - (*this) += temp_matrix; -} - -// apply an additional inverse rotation to a rotation matrix but -// only use X, Y elements from rotation vector -template -void Matrix3::rotateXYinv(const Vector3 &g) -{ - Matrix3 temp_matrix; - temp_matrix.a.x = a.z * g.y; - temp_matrix.a.y = - a.z * g.x; - temp_matrix.a.z = - a.x * g.y + a.y * g.x; - temp_matrix.b.x = b.z * g.y; - temp_matrix.b.y = - b.z * g.x; - temp_matrix.b.z = - b.x * g.y + b.y * g.x; - temp_matrix.c.x = c.z * g.y; - temp_matrix.c.y = - c.z * g.x; - temp_matrix.c.z = - c.x * g.y + c.y * g.x; - - (*this) += temp_matrix; -} - /* re-normalise a rotation matrix */ @@ -296,8 +258,6 @@ void Matrix3::from_axis_angle(const Vector3 &v, float theta) // only define for float template void Matrix3::zero(void); template void Matrix3::rotate(const Vector3 &g); -template void Matrix3::rotateXY(const Vector3 &g); -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; @@ -315,8 +275,6 @@ template Vector2 Matrix3::mulXY(const Vector3 &v) const; template void Matrix3::zero(void); template void Matrix3::rotate(const Vector3 &g); -template void Matrix3::rotateXY(const Vector3 &g); -template void Matrix3::rotateXYinv(const Vector3 &g); template void Matrix3::from_euler(float roll, float pitch, float yaw); template void Matrix3::to_euler(float *roll, float *pitch, float *yaw) const; template Vector3 Matrix3::operator *(const Vector3 &v) const; diff --git a/libraries/AP_Math/matrix3.h b/libraries/AP_Math/matrix3.h index cb20322a44..2009f7da85 100644 --- a/libraries/AP_Math/matrix3.h +++ b/libraries/AP_Math/matrix3.h @@ -252,14 +252,6 @@ public: // to a rotation matrix. void rotate(const Vector3 &g); - // apply an additional rotation from a body frame gyro vector - // to a rotation matrix but only use X, Y elements from gyro vector - void rotateXY(const Vector3 &g); - - // apply an additional inverse rotation to a rotation matrix but - // only use X, Y elements from rotation vector - void rotateXYinv(const Vector3 &g); - // create rotation matrix for rotation about the vector v by angle theta // See: https://en.wikipedia.org/wiki/Rotation_matrix#General_rotations // "Rotation matrix from axis and angle"