mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_AHRS: cope with the changed semantics of airspeed.use()
This commit is contained in:
parent
850b3b89ea
commit
ed0a56cc3c
@ -126,7 +126,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) const
|
bool AP_AHRS::airspeed_estimate(float *airspeed_ret) const
|
||||||
{
|
{
|
||||||
if (_airspeed && _airspeed->use()) {
|
if (airspeed_sensor_enabled()) {
|
||||||
*airspeed_ret = _airspeed->get_airspeed();
|
*airspeed_ret = _airspeed->get_airspeed();
|
||||||
if (_wind_max > 0 && _gps.status() >= AP_GPS::GPS_OK_FIX_2D) {
|
if (_wind_max > 0 && _gps.status() >= AP_GPS::GPS_OK_FIX_2D) {
|
||||||
// constrain the airspeed by the ground speed
|
// constrain the airspeed by the ground speed
|
||||||
|
@ -260,7 +260,7 @@ public:
|
|||||||
// return true if airspeed comes from an airspeed sensor, as
|
// return true if airspeed comes from an airspeed sensor, as
|
||||||
// opposed to an IMU estimate
|
// opposed to an IMU estimate
|
||||||
bool airspeed_sensor_enabled(void) const {
|
bool airspeed_sensor_enabled(void) const {
|
||||||
return _airspeed != NULL && _airspeed->use();
|
return _airspeed != NULL && _airspeed->use() && _airspeed->healthy();
|
||||||
}
|
}
|
||||||
|
|
||||||
// return a ground vector estimate in meters/second, in North/East order
|
// return a ground vector estimate in meters/second, in North/East order
|
||||||
|
@ -559,7 +559,7 @@ AP_AHRS_DCM::drift_correction(float deltat)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
float airspeed;
|
float airspeed;
|
||||||
if (_airspeed && _airspeed->use()) {
|
if (airspeed_sensor_enabled()) {
|
||||||
airspeed = _airspeed->get_airspeed();
|
airspeed = _airspeed->get_airspeed();
|
||||||
} else {
|
} else {
|
||||||
airspeed = _last_airspeed;
|
airspeed = _last_airspeed;
|
||||||
@ -850,7 +850,7 @@ void AP_AHRS_DCM::estimate_wind(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
_last_wind_time = now;
|
_last_wind_time = now;
|
||||||
} else if (now - _last_wind_time > 2000 && _airspeed && _airspeed->use()) {
|
} else if (now - _last_wind_time > 2000 && airspeed_sensor_enabled()) {
|
||||||
// when flying straight use airspeed to get wind estimate if available
|
// when flying straight use airspeed to get wind estimate if available
|
||||||
Vector3f airspeed = _dcm_matrix.colx() * _airspeed->get_airspeed();
|
Vector3f airspeed = _dcm_matrix.colx() * _airspeed->get_airspeed();
|
||||||
Vector3f wind = velocity - (airspeed * get_EAS2TAS());
|
Vector3f wind = velocity - (airspeed * get_EAS2TAS());
|
||||||
@ -923,7 +923,7 @@ bool AP_AHRS_DCM::get_position(struct Location &loc) const
|
|||||||
bool AP_AHRS_DCM::airspeed_estimate(float *airspeed_ret) const
|
bool AP_AHRS_DCM::airspeed_estimate(float *airspeed_ret) const
|
||||||
{
|
{
|
||||||
bool ret = false;
|
bool ret = false;
|
||||||
if (_airspeed && _airspeed->use()) {
|
if (airspeed_sensor_enabled()) {
|
||||||
*airspeed_ret = _airspeed->get_airspeed();
|
*airspeed_ret = _airspeed->get_airspeed();
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user