mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Airspeed: Health: use reading from correct airspeed sensor
This commit is contained in:
parent
587254e5a5
commit
9c4188d730
@ -28,8 +28,7 @@ void AP_Airspeed::check_sensor_ahrs_wind_max_failures(uint8_t i)
|
||||
return;
|
||||
}
|
||||
|
||||
const float aspeed = get_airspeed();
|
||||
if (aspeed <= 0) {
|
||||
if (state[i].airspeed <= 0) {
|
||||
// invalid estimate
|
||||
return;
|
||||
}
|
||||
@ -44,7 +43,7 @@ void AP_Airspeed::check_sensor_ahrs_wind_max_failures(uint8_t i)
|
||||
}
|
||||
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
|
||||
if (speed_diff > _wind_max) {
|
||||
|
Loading…
Reference in New Issue
Block a user