From 1e0f3f5398e6ba0177c52f3d2842f05463ab5be4 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 4 Jan 2014 15:58:27 +1100 Subject: [PATCH] AP_Math: make to_euler() const --- libraries/AP_Math/matrix3.cpp | 4 ++-- libraries/AP_Math/matrix3.h | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Math/matrix3.cpp b/libraries/AP_Math/matrix3.cpp index 1b47db137d..8d6a606c1c 100644 --- a/libraries/AP_Math/matrix3.cpp +++ b/libraries/AP_Math/matrix3.cpp @@ -47,7 +47,7 @@ void Matrix3::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 -void Matrix3::to_euler(float *roll, float *pitch, float *yaw) +void Matrix3::to_euler(float *roll, float *pitch, float *yaw) const { if (pitch != NULL) { *pitch = -safe_asin(c.x); @@ -182,7 +182,7 @@ 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); +template void Matrix3::to_euler(float *roll, float *pitch, float *yaw) 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 3e5c183be5..b8cd12d851 100644 --- a/libraries/AP_Math/matrix3.h +++ b/libraries/AP_Math/matrix3.h @@ -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.