mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_AHRS: make a pair of methods static on AP_AHRS_Backend
these don't use any information from the specific backend, but they are called within the backends so making them static on that class is handy
This commit is contained in:
parent
a5bfd58524
commit
12a06ee0ae
@ -325,7 +325,7 @@ void AP_AHRS::update_state(void)
|
||||
state.primary_accel = _get_primary_accel_index();
|
||||
state.primary_core = _get_primary_core_index();
|
||||
state.wind_estimate_ok = _wind_estimate(state.wind_estimate);
|
||||
state.EAS2TAS = dcm.get_EAS2TAS();
|
||||
state.EAS2TAS = AP_AHRS_Backend::get_EAS2TAS();
|
||||
state.airspeed_ok = _airspeed_estimate(state.airspeed);
|
||||
state.airspeed_true_ok = _airspeed_estimate_true(state.airspeed_true);
|
||||
state.airspeed_vec_ok = _airspeed_vector_true(state.airspeed_vec);
|
||||
@ -786,7 +786,7 @@ bool AP_AHRS::_wind_estimate(Vector3f &wind) const
|
||||
*/
|
||||
bool AP_AHRS::airspeed_sensor_enabled(void) const
|
||||
{
|
||||
if (!dcm.airspeed_sensor_enabled()) {
|
||||
if (!AP_AHRS_Backend::airspeed_sensor_enabled()) {
|
||||
return false;
|
||||
}
|
||||
nav_filter_status filter_status;
|
||||
|
@ -155,7 +155,7 @@ public:
|
||||
// opposed to an IMU estimate
|
||||
bool airspeed_sensor_enabled(uint8_t airspeed_index) const {
|
||||
// FIXME: make this a method on the active backend
|
||||
return dcm.airspeed_sensor_enabled(airspeed_index);
|
||||
return AP_AHRS_Backend::airspeed_sensor_enabled(airspeed_index);
|
||||
}
|
||||
|
||||
// return a synthetic airspeed estimate (one derived from sensors
|
||||
|
@ -330,7 +330,7 @@ void AP_AHRS::Log_Write_Home_And_Origin()
|
||||
}
|
||||
|
||||
// get apparent to true airspeed ratio
|
||||
float AP_AHRS_Backend::get_EAS2TAS(void) const {
|
||||
float AP_AHRS_Backend::get_EAS2TAS(void) {
|
||||
return AP::baro().get_EAS2TAS();
|
||||
}
|
||||
|
||||
|
@ -146,11 +146,11 @@ public:
|
||||
}
|
||||
|
||||
// get apparent to true airspeed ratio
|
||||
float get_EAS2TAS(void) const;
|
||||
static float get_EAS2TAS(void);
|
||||
|
||||
// return true if airspeed comes from an airspeed sensor, as
|
||||
// opposed to an IMU estimate
|
||||
bool airspeed_sensor_enabled(void) const {
|
||||
static bool airspeed_sensor_enabled(void) {
|
||||
#if AP_AIRSPEED_ENABLED
|
||||
const AP_Airspeed *_airspeed = AP::airspeed();
|
||||
return _airspeed != nullptr && _airspeed->use() && _airspeed->healthy();
|
||||
@ -161,7 +161,7 @@ public:
|
||||
|
||||
// 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 {
|
||||
static bool airspeed_sensor_enabled(uint8_t airspeed_index) {
|
||||
#if AP_AIRSPEED_ENABLED
|
||||
const AP_Airspeed *_airspeed = AP::airspeed();
|
||||
return _airspeed != nullptr && _airspeed->use(airspeed_index) && _airspeed->healthy(airspeed_index);
|
||||
|
Loading…
Reference in New Issue
Block a user