AP_Airspeed: fixed handling of unhealthy airspeed

this fixes a bug introduced in
https://github.com/ArduPilot/ardupilot/pull/22416 which results in
using bad airspeed data on timeout. The prev_health variable is
updated by the get_pressure call
This commit is contained in:
Andrew Tridgell 2023-08-10 13:26:18 +10:00 committed by Peter Barker
parent cbd2b199eb
commit faa4d28851
1 changed files with 8 additions and 1 deletions

View File

@ -609,6 +609,14 @@ void AP_Airspeed::read(uint8_t i)
return;
}
#ifndef HAL_BUILD_AP_PERIPH
/*
get the healthy state before we call get_pressure() as
get_pressure() overwrites the healthy state
*/
bool prev_healthy = state[i].healthy;
#endif
float raw_pressure = get_pressure(i);
float airspeed_pressure = raw_pressure - get_offset(i);
@ -616,7 +624,6 @@ void AP_Airspeed::read(uint8_t i)
state[i].corrected_pressure = airspeed_pressure;
#ifndef HAL_BUILD_AP_PERIPH
bool prev_healthy = state[i].healthy;
if (state[i].cal.start_ms != 0) {
update_calibration(i, raw_pressure);
}