mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: only fuse airspeed if healthy
This commit is contained in:
parent
d16af5448b
commit
5e72907730
|
@ -755,8 +755,9 @@ void NavEKF2_core::readAirSpdData()
|
|||
// know a new measurement is available
|
||||
const auto *aspeed = dal.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() * dal.get_EAS2TAS();
|
||||
timeTasReceived_ms = aspeed->last_update_ms();
|
||||
tasDataNew.time_ms = timeTasReceived_ms - frontend->tasDelay_ms;
|
||||
|
|
Loading…
Reference in New Issue