mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_NavEKF3: only fuse airspeed if healthy
This commit is contained in:
parent
5e72907730
commit
2071a19a40
@ -815,6 +815,7 @@ void NavEKF3_core::readAirSpdData()
|
||||
const auto *airspeed = dal.airspeed();
|
||||
if (airspeed &&
|
||||
airspeed->use(selected_airspeed) &&
|
||||
airspeed->healthy(selected_airspeed) &&
|
||||
(airspeed->last_update_ms(selected_airspeed) - timeTasReceived_ms) > frontend->sensorIntervalMin_ms) {
|
||||
tasDataNew.tas = airspeed->get_airspeed(selected_airspeed) * dal.get_EAS2TAS();
|
||||
timeTasReceived_ms = airspeed->last_update_ms(selected_airspeed);
|
||||
|
Loading…
Reference in New Issue
Block a user