|
|
|
@ -116,44 +116,6 @@ void Matrix3<T>::rotate(const Vector3<T> &g)
@@ -116,44 +116,6 @@ void Matrix3<T>::rotate(const Vector3<T> &g)
|
|
|
|
|
(*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 |
|
|
|
|
*/ |
|
|
|
@ -296,8 +258,6 @@ void Matrix3<T>::from_axis_angle(const Vector3<T> &v, float theta)
@@ -296,8 +258,6 @@ void Matrix3<T>::from_axis_angle(const Vector3<T> &v, float theta)
|
|
|
|
|
// only define for float
|
|
|
|
|
template void Matrix3<float>::zero(void); |
|
|
|
|
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>::from_euler(float roll, float pitch, float yaw); |
|
|
|
|
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;
@@ -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>::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>::to_euler(float *roll, float *pitch, float *yaw) const; |
|
|
|
|
template Vector3<double> Matrix3<double>::operator *(const Vector3<double> &v) const; |
|
|
|
|