AP_Math: add const to quaternion API

This commit is contained in:
Andrew Tridgell 2013-12-30 14:07:47 +11:00
parent 2e9744d0b3
commit 96df09fd08
2 changed files with 6 additions and 6 deletions

View File

@ -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),

View File

@ -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) {