mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-25 01:58:29 -04:00
AP_NavEKF2: only fuse airspeed if healthy
This commit is contained in:
parent
d16af5448b
commit
5e72907730
@ -756,6 +756,7 @@ void NavEKF2_core::readAirSpdData()
|
|||||||
const auto *aspeed = dal.airspeed();
|
const auto *aspeed = dal.airspeed();
|
||||||
if (aspeed &&
|
if (aspeed &&
|
||||||
aspeed->use() &&
|
aspeed->use() &&
|
||||||
|
aspeed->healthy() &&
|
||||||
aspeed->last_update_ms() != timeTasReceived_ms) {
|
aspeed->last_update_ms() != timeTasReceived_ms) {
|
||||||
tasDataNew.tas = aspeed->get_airspeed() * dal.get_EAS2TAS();
|
tasDataNew.tas = aspeed->get_airspeed() * dal.get_EAS2TAS();
|
||||||
timeTasReceived_ms = aspeed->last_update_ms();
|
timeTasReceived_ms = aspeed->last_update_ms();
|
||||||
|
Loading…
Reference in New Issue
Block a user