mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: only fuse airspeed if healthy
This commit is contained in:
parent
e52a2a573d
commit
1d7519d0c9
|
@ -773,8 +773,8 @@ void NavEKF3_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) > frontend->sensorIntervalMin_ms) {
|
||||
aspeed->use() && aspeed->healthy() &&
|
||||
(aspeed->last_update_ms() - timeTasReceived_ms) > frontend->sensorIntervalMin_ms) {
|
||||
tasDataNew.tas = aspeed->get_raw_airspeed() * AP::ahrs().get_EAS2TAS();
|
||||
timeTasReceived_ms = aspeed->last_update_ms();
|
||||
tasDataNew.time_ms = timeTasReceived_ms - frontend->tasDelay_ms;
|
||||
|
|
Loading…
Reference in New Issue