mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
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:
parent
63cdf38eb3
commit
99b82c16eb
@ -605,6 +605,14 @@ void AP_Airspeed::read(uint8_t i)
|
|||||||
return;
|
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 raw_pressure = get_pressure(i);
|
||||||
float airspeed_pressure = raw_pressure - get_offset(i);
|
float airspeed_pressure = raw_pressure - get_offset(i);
|
||||||
|
|
||||||
@ -612,7 +620,6 @@ void AP_Airspeed::read(uint8_t i)
|
|||||||
state[i].corrected_pressure = airspeed_pressure;
|
state[i].corrected_pressure = airspeed_pressure;
|
||||||
|
|
||||||
#ifndef HAL_BUILD_AP_PERIPH
|
#ifndef HAL_BUILD_AP_PERIPH
|
||||||
bool prev_healthy = state[i].healthy;
|
|
||||||
if (state[i].cal.start_ms != 0) {
|
if (state[i].cal.start_ms != 0) {
|
||||||
update_calibration(i, raw_pressure);
|
update_calibration(i, raw_pressure);
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user