mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 17:48:35 -04:00
AP_AHRS: use EKF rejecting_airspeed flag
stop using airspeed sensor when EKF is rejecting the sensor
This commit is contained in:
parent
9dcff1a23f
commit
01ac314837
@ -816,6 +816,28 @@ Vector3f AP_AHRS::wind_estimate(void) const
|
|||||||
return wind;
|
return wind;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
return true if a real airspeed sensor is enabled
|
||||||
|
*/
|
||||||
|
bool AP_AHRS::airspeed_sensor_enabled(void) const
|
||||||
|
{
|
||||||
|
if (!dcm.airspeed_sensor_enabled()) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
nav_filter_status filter_status;
|
||||||
|
if (fly_forward &&
|
||||||
|
hal.util->get_soft_armed() &&
|
||||||
|
get_filter_status(filter_status) &&
|
||||||
|
filter_status.flags.rejecting_airspeed) {
|
||||||
|
// special case for when backend is rejecting airspeed data in
|
||||||
|
// an armed fly_forward state. Then the airspeed data is
|
||||||
|
// highly suspect and will be rejected. We will use the
|
||||||
|
// synthentic airspeed instead
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
// 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
|
||||||
bool AP_AHRS::airspeed_estimate(float &airspeed_ret) const
|
bool AP_AHRS::airspeed_estimate(float &airspeed_ret) const
|
||||||
|
@ -158,10 +158,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;
|
||||||
// FIXME: make this "using_airspeed_sensor"?
|
|
||||||
return dcm.airspeed_sensor_enabled();
|
|
||||||
}
|
|
||||||
|
|
||||||
// return true if airspeed comes from a specific airspeed sensor, as
|
// return true if airspeed comes from a specific airspeed sensor, as
|
||||||
// opposed to an IMU estimate
|
// opposed to an IMU estimate
|
||||||
|
Loading…
Reference in New Issue
Block a user