AP_Airspeed: Health: use reading from correct airspeed sensor

This commit is contained in:
Iampete1 2022-03-01 17:38:29 +00:00 committed by Andrew Tridgell
parent 587254e5a5
commit 9c4188d730

View File

@ -28,8 +28,7 @@ void AP_Airspeed::check_sensor_ahrs_wind_max_failures(uint8_t i)
return; return;
} }
const float aspeed = get_airspeed(); if (state[i].airspeed <= 0) {
if (aspeed <= 0) {
// invalid estimate // invalid estimate
return; return;
} }
@ -44,7 +43,7 @@ void AP_Airspeed::check_sensor_ahrs_wind_max_failures(uint8_t i)
} }
return; return;
} }
const float speed_diff = fabsf(aspeed-gps.ground_speed()); const float speed_diff = fabsf(state[i].airspeed-gps.ground_speed());
// update health_probability with LowPassFilter // update health_probability with LowPassFilter
if (speed_diff > _wind_max) { if (speed_diff > _wind_max) {