mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS: don't reject airspeed using EKF if dead-reckoning
when dead-reckoning the EKF wind estimate can diverge from reality, leading to us rejecting a valid airspeed sensor. We are best off trusting airspeed if we are dead-reckoning
This commit is contained in:
parent
5f6a1f7f71
commit
6f5d3a0dfd
|
@ -771,11 +771,11 @@ bool AP_AHRS::airspeed_sensor_enabled(void) const
|
|||
if (fly_forward &&
|
||||
hal.util->get_soft_armed() &&
|
||||
get_filter_status(filter_status) &&
|
||||
filter_status.flags.rejecting_airspeed) {
|
||||
(filter_status.flags.rejecting_airspeed && !filter_status.flags.dead_reckoning)) {
|
||||
// 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
|
||||
// an armed fly_forward state and not dead reckoning. Then the
|
||||
// airspeed data is highly suspect and will be rejected. We
|
||||
// will use the synthentic airspeed instead
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
|
|
Loading…
Reference in New Issue