From 63f9acdaaaaf01c64b2852d978d676d144e885b6 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 6 Jan 2021 08:28:39 +1100 Subject: [PATCH] AP_NavEKF2: only fuse airspeed if healthy --- libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp index 6e4ee699a2..e9b28f0a5a 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp @@ -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;