AP_AHRS: make some more functions const

This commit is contained in:
tobias 2013-07-08 11:25:40 +10:00 committed by Andrew Tridgell
parent ce6529734c
commit 1bf135b36f
2 changed files with 4 additions and 4 deletions

View File

@ -272,7 +272,7 @@ AP_AHRS_DCM::_P_gain(float spin_rate)
}
// return true if we have and should use GPS
bool AP_AHRS_DCM::have_gps(void)
bool AP_AHRS_DCM::have_gps(void) const
{
if (!_gps || _gps->status() <= GPS::NO_FIX || !_gps_use) {
return false;
@ -281,7 +281,7 @@ bool AP_AHRS_DCM::have_gps(void)
}
// return true if we should use the compass for yaw correction
bool AP_AHRS_DCM::use_compass(void)
bool AP_AHRS_DCM::use_compass(void) const
{
if (!_compass || !_compass->use_for_yaw()) {
// no compass available

View File

@ -60,7 +60,7 @@ public:
// if we have an estimate
bool airspeed_estimate(float *airspeed_ret);
bool use_compass(void);
bool use_compass(void) const;
private:
float _ki;
@ -76,7 +76,7 @@ private:
float yaw_error_compass();
void euler_angles(void);
void estimate_wind(Vector3f &velocity);
bool have_gps(void);
bool have_gps(void) const;
// primary representation of attitude
Matrix3f _dcm_matrix;