diff --git a/libraries/AP_Math/quaternion.cpp b/libraries/AP_Math/quaternion.cpp index a7443b82f7..76d6506641 100644 --- a/libraries/AP_Math/quaternion.cpp +++ b/libraries/AP_Math/quaternion.cpp @@ -20,7 +20,7 @@ #include "AP_Math.h" // return the rotation matrix equivalent for this quaternion -void Quaternion::rotation_matrix(Matrix3f &m) +void Quaternion::rotation_matrix(Matrix3f &m) const { float q3q3 = q3 * q3; float q3q4 = q3 * q4; @@ -44,7 +44,7 @@ void Quaternion::rotation_matrix(Matrix3f &m) } // convert a vector from earth to body frame -void Quaternion::earth_to_body(Vector3f &v) +void Quaternion::earth_to_body(Vector3f &v) const { Matrix3f m; // we reverse z before and afterwards because of the differing @@ -72,7 +72,7 @@ void Quaternion::from_euler(float roll, float pitch, float yaw) } // create eulers from a quaternion -void Quaternion::to_euler(float *roll, float *pitch, float *yaw) +void Quaternion::to_euler(float *roll, float *pitch, float *yaw) const { if (roll) { *roll = (atan2f(2.0f*(q1*q2 + q3*q4), diff --git a/libraries/AP_Math/quaternion.h b/libraries/AP_Math/quaternion.h index 4497d9ffe7..f4094173e0 100644 --- a/libraries/AP_Math/quaternion.h +++ b/libraries/AP_Math/quaternion.h @@ -50,16 +50,16 @@ public: } // return the rotation matrix equivalent for this quaternion - void rotation_matrix(Matrix3f &m); + void rotation_matrix(Matrix3f &m) const; // convert a vector from earth to body frame - void earth_to_body(Vector3f &v); + void earth_to_body(Vector3f &v) const; // create a quaternion from Euler angles void from_euler(float roll, float pitch, float yaw); // create eulers from a quaternion - void to_euler(float *roll, float *pitch, float *yaw); + void to_euler(float *roll, float *pitch, float *yaw) const; // allow a quaternion to be used as an array, 0 indexed float & operator[](uint8_t i) {