AP_AHRS: make airspeed_estimate const
This commit is contained in:
parent
87226fed97
commit
410d356979
@ -117,7 +117,7 @@ const AP_Param::GroupInfo AP_AHRS::var_info[] PROGMEM = {
|
|||||||
};
|
};
|
||||||
|
|
||||||
// return airspeed estimate if available
|
// return airspeed estimate if available
|
||||||
bool AP_AHRS::airspeed_estimate(float *airspeed_ret)
|
bool AP_AHRS::airspeed_estimate(float *airspeed_ret) const
|
||||||
{
|
{
|
||||||
if (_airspeed && _airspeed->use()) {
|
if (_airspeed && _airspeed->use()) {
|
||||||
*airspeed_ret = _airspeed->get_airspeed();
|
*airspeed_ret = _airspeed->get_airspeed();
|
||||||
|
@ -173,11 +173,11 @@ public:
|
|||||||
|
|
||||||
// return an airspeed estimate if available. return true
|
// return an airspeed estimate if available. return true
|
||||||
// if we have an estimate
|
// if we have an estimate
|
||||||
virtual bool airspeed_estimate(float *airspeed_ret);
|
virtual bool airspeed_estimate(float *airspeed_ret) const;
|
||||||
|
|
||||||
// return a true airspeed estimate (navigation airspeed) if
|
// return a true airspeed estimate (navigation airspeed) if
|
||||||
// available. return true if we have an estimate
|
// available. return true if we have an estimate
|
||||||
bool airspeed_estimate_true(float *airspeed_ret) {
|
bool airspeed_estimate_true(float *airspeed_ret) const {
|
||||||
if (!airspeed_estimate(airspeed_ret)) {
|
if (!airspeed_estimate(airspeed_ret)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user