AP_AHRS: get airspeed sensor from singleton not AHRS object
This commit is contained in:
parent
f44e4aaefb
commit
55cb3e8ef0
@ -129,14 +129,6 @@ public:
|
||||
// this makes initial config easier
|
||||
void update_orientation();
|
||||
|
||||
void set_airspeed(AP_Airspeed *airspeed) {
|
||||
_airspeed = airspeed;
|
||||
}
|
||||
|
||||
const AP_Airspeed *get_airspeed(void) const {
|
||||
return _airspeed;
|
||||
}
|
||||
|
||||
// return the index of the primary core or -1 if no primary core selected
|
||||
virtual int8_t get_primary_core_index() const { return -1; }
|
||||
|
||||
@ -285,12 +277,14 @@ public:
|
||||
// return true if airspeed comes from an airspeed sensor, as
|
||||
// opposed to an IMU estimate
|
||||
bool airspeed_sensor_enabled(void) const {
|
||||
const AP_Airspeed *_airspeed = AP::airspeed();
|
||||
return _airspeed != nullptr && _airspeed->use() && _airspeed->healthy();
|
||||
}
|
||||
|
||||
// return true if airspeed comes from a specific airspeed sensor, as
|
||||
// opposed to an IMU estimate
|
||||
bool airspeed_sensor_enabled(uint8_t airspeed_index) const {
|
||||
const AP_Airspeed *_airspeed = AP::airspeed();
|
||||
return _airspeed != nullptr && _airspeed->use(airspeed_index) && _airspeed->healthy(airspeed_index);
|
||||
}
|
||||
|
||||
@ -661,7 +655,6 @@ protected:
|
||||
const OpticalFlow *_optflow;
|
||||
|
||||
// pointer to airspeed object, if available
|
||||
AP_Airspeed * _airspeed;
|
||||
|
||||
// time in microseconds of last compass update
|
||||
uint32_t _compass_last_update;
|
||||
|
@ -698,7 +698,7 @@ AP_AHRS_DCM::drift_correction(float deltat)
|
||||
}
|
||||
float airspeed;
|
||||
if (airspeed_sensor_enabled()) {
|
||||
airspeed = _airspeed->get_airspeed();
|
||||
airspeed = AP::airspeed()->get_airspeed();
|
||||
} else {
|
||||
airspeed = _last_airspeed;
|
||||
}
|
||||
@ -1007,7 +1007,7 @@ void AP_AHRS_DCM::estimate_wind(void)
|
||||
_last_wind_time = now;
|
||||
} else if (now - _last_wind_time > 2000 && airspeed_sensor_enabled()) {
|
||||
// when flying straight use airspeed to get wind estimate if available
|
||||
const Vector3f airspeed = _dcm_matrix.colx() * _airspeed->get_airspeed();
|
||||
const Vector3f airspeed = _dcm_matrix.colx() * AP::airspeed()->get_airspeed();
|
||||
const Vector3f wind = velocity - (airspeed * get_EAS2TAS());
|
||||
_wind = _wind * 0.92f + wind * 0.08f;
|
||||
}
|
||||
@ -1046,17 +1046,25 @@ bool AP_AHRS_DCM::get_position(struct Location &loc) const
|
||||
return _have_position;
|
||||
}
|
||||
|
||||
// return an airspeed estimate if available
|
||||
bool AP_AHRS_DCM::airspeed_estimate(float &airspeed_ret) const
|
||||
{
|
||||
return airspeed_estimate(_airspeed?_airspeed->get_primary():0, airspeed_ret);
|
||||
const auto *airspeed = AP::airspeed();
|
||||
if (airspeed == nullptr) {
|
||||
// airspeed_estimate will also make this nullptr check and act
|
||||
// appropriately when we call it with a dummy sensor ID.
|
||||
return airspeed_estimate(0, airspeed_ret);
|
||||
}
|
||||
return airspeed_estimate(airspeed->get_primary(), airspeed_ret);
|
||||
}
|
||||
|
||||
// return an airspeed estimate from a specific airspeed sensor instance if available
|
||||
// return an airspeed estimate:
|
||||
// - from a real sensor if available
|
||||
// - otherwise from a GPS-derived wind-triangle estimate (if GPS available)
|
||||
// - otherwise from a cached wind-triangle estimate value (but returning false)
|
||||
bool AP_AHRS_DCM::airspeed_estimate(uint8_t airspeed_index, float &airspeed_ret) const
|
||||
{
|
||||
if (airspeed_sensor_enabled(airspeed_index)) {
|
||||
airspeed_ret = _airspeed->get_airspeed(airspeed_index);
|
||||
airspeed_ret = AP::airspeed()->get_airspeed(airspeed_index);
|
||||
} else if (_flags.wind_estimation && have_gps()) {
|
||||
// estimate it via GPS speed and wind
|
||||
airspeed_ret = _last_airspeed;
|
||||
|
@ -2209,6 +2209,7 @@ uint8_t AP_AHRS_NavEKF::get_active_airspeed_index() const
|
||||
}
|
||||
#endif
|
||||
// for the rest, let the primary airspeed sensor be used
|
||||
const AP_Airspeed * _airspeed = AP::airspeed();
|
||||
if (_airspeed != nullptr) {
|
||||
return _airspeed->get_primary();
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user