mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS: make some more functions const
This commit is contained in:
parent
ce6529734c
commit
1bf135b36f
|
@ -272,7 +272,7 @@ AP_AHRS_DCM::_P_gain(float spin_rate)
|
||||||
}
|
}
|
||||||
|
|
||||||
// return true if we have and should use GPS
|
// 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) {
|
if (!_gps || _gps->status() <= GPS::NO_FIX || !_gps_use) {
|
||||||
return false;
|
return false;
|
||||||
|
@ -281,7 +281,7 @@ bool AP_AHRS_DCM::have_gps(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
// return true if we should use the compass for yaw correction
|
// 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()) {
|
if (!_compass || !_compass->use_for_yaw()) {
|
||||||
// no compass available
|
// no compass available
|
||||||
|
|
|
@ -60,7 +60,7 @@ public:
|
||||||
// if we have an estimate
|
// if we have an estimate
|
||||||
bool airspeed_estimate(float *airspeed_ret);
|
bool airspeed_estimate(float *airspeed_ret);
|
||||||
|
|
||||||
bool use_compass(void);
|
bool use_compass(void) const;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
float _ki;
|
float _ki;
|
||||||
|
@ -76,7 +76,7 @@ private:
|
||||||
float yaw_error_compass();
|
float yaw_error_compass();
|
||||||
void euler_angles(void);
|
void euler_angles(void);
|
||||||
void estimate_wind(Vector3f &velocity);
|
void estimate_wind(Vector3f &velocity);
|
||||||
bool have_gps(void);
|
bool have_gps(void) const;
|
||||||
|
|
||||||
// primary representation of attitude
|
// primary representation of attitude
|
||||||
Matrix3f _dcm_matrix;
|
Matrix3f _dcm_matrix;
|
||||||
|
|
Loading…
Reference in New Issue