Browse Source

AHRS: make get_error_rp and get_error_yaw const

master
Randy Mackay 10 years ago
parent
commit
c6f71ea2e0
  1. 4
      libraries/AP_AHRS/AP_AHRS.h
  2. 4
      libraries/AP_AHRS/AP_AHRS_NavEKF.cpp
  3. 4
      libraries/AP_AHRS/AP_AHRS_NavEKF.h

4
libraries/AP_AHRS/AP_AHRS.h

@ -217,11 +217,11 @@ public:
// return the average size of the roll/pitch error estimate // return the average size of the roll/pitch error estimate
// since last call // since last call
virtual float get_error_rp(void) = 0; virtual float get_error_rp(void) const = 0;
// return the average size of the yaw error estimate // return the average size of the yaw error estimate
// since last call // since last call
virtual float get_error_yaw(void) = 0; virtual float get_error_yaw(void) const = 0;
// return a DCM rotation matrix representing our current // return a DCM rotation matrix representing our current
// attitude // attitude

4
libraries/AP_AHRS/AP_AHRS_NavEKF.cpp

@ -193,12 +193,12 @@ bool AP_AHRS_NavEKF::get_position(struct Location &loc) const
} }
// status reporting of estimated errors // status reporting of estimated errors
float AP_AHRS_NavEKF::get_error_rp(void) float AP_AHRS_NavEKF::get_error_rp(void) const
{ {
return AP_AHRS_DCM::get_error_rp(); return AP_AHRS_DCM::get_error_rp();
} }
float AP_AHRS_NavEKF::get_error_yaw(void) float AP_AHRS_NavEKF::get_error_yaw(void) const
{ {
return AP_AHRS_DCM::get_error_yaw(); return AP_AHRS_DCM::get_error_yaw();
} }

4
libraries/AP_AHRS/AP_AHRS_NavEKF.h

@ -64,8 +64,8 @@ public:
bool get_position(struct Location &loc) const; bool get_position(struct Location &loc) const;
// status reporting of estimated error // status reporting of estimated error
float get_error_rp(void); float get_error_rp(void) const;
float get_error_yaw(void); float get_error_yaw(void) const;
// return a wind estimation vector, in m/s // return a wind estimation vector, in m/s
Vector3f wind_estimate(void); Vector3f wind_estimate(void);

Loading…
Cancel
Save