mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Math: remove rotateXY and rotateXYinv
This commit is contained in:
parent
dac59cb5da
commit
80d9092993
@ -116,44 +116,6 @@ void Matrix3<T>::rotate(const Vector3<T> &g)
|
|||||||
(*this) += temp_matrix;
|
(*this) += temp_matrix;
|
||||||
}
|
}
|
||||||
|
|
||||||
// apply an additional rotation from a body frame gyro vector
|
|
||||||
// to a rotation matrix.
|
|
||||||
template <typename T>
|
|
||||||
void Matrix3<T>::rotateXY(const Vector3<T> &g)
|
|
||||||
{
|
|
||||||
Matrix3<T> 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 <typename T>
|
|
||||||
void Matrix3<T>::rotateXYinv(const Vector3<T> &g)
|
|
||||||
{
|
|
||||||
Matrix3<T> 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
|
re-normalise a rotation matrix
|
||||||
*/
|
*/
|
||||||
@ -296,8 +258,6 @@ void Matrix3<T>::from_axis_angle(const Vector3<T> &v, float theta)
|
|||||||
// only define for float
|
// only define for float
|
||||||
template void Matrix3<float>::zero(void);
|
template void Matrix3<float>::zero(void);
|
||||||
template void Matrix3<float>::rotate(const Vector3<float> &g);
|
template void Matrix3<float>::rotate(const Vector3<float> &g);
|
||||||
template void Matrix3<float>::rotateXY(const Vector3<float> &g);
|
|
||||||
template void Matrix3<float>::rotateXYinv(const Vector3<float> &g);
|
|
||||||
template void Matrix3<float>::normalize(void);
|
template void Matrix3<float>::normalize(void);
|
||||||
template void Matrix3<float>::from_euler(float roll, float pitch, float yaw);
|
template void Matrix3<float>::from_euler(float roll, float pitch, float yaw);
|
||||||
template void Matrix3<float>::to_euler(float *roll, float *pitch, float *yaw) const;
|
template void Matrix3<float>::to_euler(float *roll, float *pitch, float *yaw) const;
|
||||||
@ -315,8 +275,6 @@ template Vector2<float> Matrix3<float>::mulXY(const Vector3<float> &v) const;
|
|||||||
|
|
||||||
template void Matrix3<double>::zero(void);
|
template void Matrix3<double>::zero(void);
|
||||||
template void Matrix3<double>::rotate(const Vector3<double> &g);
|
template void Matrix3<double>::rotate(const Vector3<double> &g);
|
||||||
template void Matrix3<double>::rotateXY(const Vector3<double> &g);
|
|
||||||
template void Matrix3<double>::rotateXYinv(const Vector3<double> &g);
|
|
||||||
template void Matrix3<double>::from_euler(float roll, float pitch, float yaw);
|
template void Matrix3<double>::from_euler(float roll, float pitch, float yaw);
|
||||||
template void Matrix3<double>::to_euler(float *roll, float *pitch, float *yaw) const;
|
template void Matrix3<double>::to_euler(float *roll, float *pitch, float *yaw) const;
|
||||||
template Vector3<double> Matrix3<double>::operator *(const Vector3<double> &v) const;
|
template Vector3<double> Matrix3<double>::operator *(const Vector3<double> &v) const;
|
||||||
|
@ -252,14 +252,6 @@ public:
|
|||||||
// to a rotation matrix.
|
// to a rotation matrix.
|
||||||
void rotate(const Vector3<T> &g);
|
void rotate(const Vector3<T> &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<T> &g);
|
|
||||||
|
|
||||||
// apply an additional inverse rotation to a rotation matrix but
|
|
||||||
// only use X, Y elements from rotation vector
|
|
||||||
void rotateXYinv(const Vector3<T> &g);
|
|
||||||
|
|
||||||
// create rotation matrix for rotation about the vector v by angle theta
|
// create rotation matrix for rotation about the vector v by angle theta
|
||||||
// See: https://en.wikipedia.org/wiki/Rotation_matrix#General_rotations
|
// See: https://en.wikipedia.org/wiki/Rotation_matrix#General_rotations
|
||||||
// "Rotation matrix from axis and angle"
|
// "Rotation matrix from axis and angle"
|
||||||
|
Loading…
Reference in New Issue
Block a user