diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp index b4b38272f6..172d9bbffc 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp @@ -773,8 +773,8 @@ void NavEKF3_core::readAirSpdData() // know a new measurement is available const AP_Airspeed *aspeed = _ahrs->get_airspeed(); if (aspeed && - aspeed->use() && - (aspeed->last_update_ms() - timeTasReceived_ms) > frontend->sensorIntervalMin_ms) { + aspeed->use() && aspeed->healthy() && + (aspeed->last_update_ms() - timeTasReceived_ms) > frontend->sensorIntervalMin_ms) { tasDataNew.tas = aspeed->get_raw_airspeed() * AP::ahrs().get_EAS2TAS(); timeTasReceived_ms = aspeed->last_update_ms(); tasDataNew.time_ms = timeTasReceived_ms - frontend->tasDelay_ms;