AP_AHRS: Change airspeed_estimate to const in children of AP_AHRS

Allows roll/pitch controllers to use DCM's airspeed estimate. Thanks to Kevin Hester for assistance in finding this.
This commit is contained in:
Jonathan Challinger 2014-02-24 17:43:59 -08:00 committed by Andrew Tridgell
parent 72a91ccbca
commit f321a5f241
4 changed files with 4 additions and 4 deletions

View File

@ -872,7 +872,7 @@ bool AP_AHRS_DCM::get_position(struct Location &loc)
}
// return an airspeed estimate if available
bool AP_AHRS_DCM::airspeed_estimate(float *airspeed_ret)
bool AP_AHRS_DCM::airspeed_estimate(float *airspeed_ret) const
{
bool ret = false;
if (_airspeed && _airspeed->use()) {

View File

@ -74,7 +74,7 @@ public:
// return an airspeed estimate if available. return true
// if we have an estimate
bool airspeed_estimate(float *airspeed_ret);
bool airspeed_estimate(float *airspeed_ret) const;
bool use_compass(void);

View File

@ -132,7 +132,7 @@ Vector3f AP_AHRS_NavEKF::wind_estimate(void)
// return an airspeed estimate if available. return true
// if we have an estimate
bool AP_AHRS_NavEKF::airspeed_estimate(float *airspeed_ret)
bool AP_AHRS_NavEKF::airspeed_estimate(float *airspeed_ret) const
{
return AP_AHRS_DCM::airspeed_estimate(airspeed_ret);
}

View File

@ -67,7 +67,7 @@ public:
// return an airspeed estimate if available. return true
// if we have an estimate
bool airspeed_estimate(float *airspeed_ret);
bool airspeed_estimate(float *airspeed_ret) const;
// true if compass is being used
bool use_compass(void);