Browse Source

AP_AHRS: made a few methods const

master
Andrew Tridgell 12 years ago
parent
commit
7ad293e270
  1. 4
      libraries/AP_AHRS/AP_AHRS.h
  2. 4
      libraries/AP_AHRS/AP_AHRS_DCM.h
  3. 4
      libraries/AP_AHRS/AP_AHRS_HIL.h
  4. 4
      libraries/AP_AHRS/AP_AHRS_MPU6000.h

4
libraries/AP_AHRS/AP_AHRS.h

@ -85,7 +85,7 @@ public: @@ -85,7 +85,7 @@ public:
float get_roll_rate_earth(void);
// return a smoothed and corrected gyro vector
virtual Vector3f get_gyro(void) = 0;
virtual const Vector3f get_gyro(void) const = 0;
// return the current estimate of the gyro drift
virtual Vector3f get_gyro_drift(void) = 0;
@ -109,7 +109,7 @@ public: @@ -109,7 +109,7 @@ public:
// return a DCM rotation matrix representing our current
// attitude
virtual Matrix3f get_dcm_matrix(void) = 0;
virtual const Matrix3f get_dcm_matrix(void) const = 0;
// get our current position, either from GPS or via
// dead-reckoning. Return true if a position is available,

4
libraries/AP_AHRS/AP_AHRS_DCM.h

@ -25,10 +25,10 @@ public: @@ -25,10 +25,10 @@ public:
}
// return the smoothed gyro vector corrected for drift
Vector3f get_gyro(void) {
const Vector3f get_gyro(void) const {
return _omega + _omega_P + _omega_yaw_P;
}
Matrix3f get_dcm_matrix(void) {
const Matrix3f get_dcm_matrix(void) const {
return _dcm_matrix;
}

4
libraries/AP_AHRS/AP_AHRS_HIL.h

@ -8,11 +8,11 @@ public: @@ -8,11 +8,11 @@ public:
AP_AHRS_HIL(AP_InertialSensor *ins, GPS *&gps) : AP_AHRS(ins, gps) {}
// Accessors
Vector3f get_gyro(void) {
const Vector3f get_gyro(void) const {
return _omega;
}
Matrix3f get_dcm_matrix(void) {
const Matrix3f get_dcm_matrix(void) const {
Matrix3f m;
m.from_euler(roll, pitch, yaw);
return m;

4
libraries/AP_AHRS/AP_AHRS_MPU6000.h

@ -40,11 +40,11 @@ public: @@ -40,11 +40,11 @@ public:
void init();
// return the smoothed gyro vector corrected for drift
Vector3f get_gyro(void) {
const Vector3f get_gyro(void) const {
return _ins->get_gyro();
}
Matrix3f get_dcm_matrix(void) {
const Matrix3f get_dcm_matrix(void) const {
return _dcm_matrix;
}

Loading…
Cancel
Save