mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-13 10:03:57 -03:00
AP_NavEKF2: only fuse airspeed if healthy
This commit is contained in:
parent
35d12ac712
commit
63f9acdaaa
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user