AP_Math: make to_euler() const

This commit is contained in:
Andrew Tridgell 2014-01-04 15:58:27 +11:00
parent 90c41981ac
commit 1e0f3f5398
2 changed files with 3 additions and 3 deletions

View File

@ -47,7 +47,7 @@ void Matrix3<T>::from_euler(float roll, float pitch, float yaw)
// calculate euler angles from a rotation matrix
// this is based on http://gentlenav.googlecode.com/files/EulerAngles.pdf
template <typename T>
void Matrix3<T>::to_euler(float *roll, float *pitch, float *yaw)
void Matrix3<T>::to_euler(float *roll, float *pitch, float *yaw) const
{
if (pitch != NULL) {
*pitch = -safe_asin(c.x);
@ -182,7 +182,7 @@ 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>::from_euler(float roll, float pitch, float yaw);
template void Matrix3<float>::to_euler(float *roll, float *pitch, float *yaw);
template void Matrix3<float>::to_euler(float *roll, float *pitch, float *yaw) const;
template Vector3<float> Matrix3<float>::operator *(const Vector3<float> &v) const;
template Vector3<float> Matrix3<float>::mul_transpose(const Vector3<float> &v) const;
template Matrix3<float> Matrix3<float>::operator *(const Matrix3<float> &m) const;

View File

@ -206,7 +206,7 @@ public:
void from_euler(float roll, float pitch, float yaw);
// create eulers from a rotation matrix
void to_euler(float *roll, float *pitch, float *yaw);
void to_euler(float *roll, float *pitch, float *yaw) const;
// apply an additional rotation from a body frame gyro vector
// to a rotation matrix.