AP_NavEKF2: only fuse airspeed if healthy

This commit is contained in:
Andrew Tridgell 2021-01-06 08:28:39 +11:00
parent 1d7519d0c9
commit 93eb226cdc
1 changed files with 2 additions and 2 deletions

View File

@ -732,8 +732,8 @@ void NavEKF2_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) {
aspeed->use() && aspeed->healthy() &&
aspeed->last_update_ms() != timeTasReceived_ms) {
tasDataNew.tas = aspeed->get_airspeed() * AP::ahrs().get_EAS2TAS();
timeTasReceived_ms = aspeed->last_update_ms();
tasDataNew.time_ms = timeTasReceived_ms - frontend->tasDelay_ms;