AP_Airspeed: fixed airspeed filtering issue

this fixes an issue where an airspeed sensor that becomes unhealthy
can have an undue effect after the sensor becomes healthy again.

In a recent flight log the MS4525 airspeed sensor went unhealthy for a
few seconds, and at the same time gave a reading of 12m/s. The plane
was flying at 24m/s. While the sensor was unhealthy the code correctly
switched to the airspeed estimate, which was fine.

When the airspeed sensor become healthy again the IIR filter in
AP_Airspeed meant that the speed read at 12m/s initially, then came up
to 24m/s over a couple of seconds. This caused the VTOL motors to come
on for a few seconds.
This commit is contained in:
Andrew Tridgell 2018-06-11 08:45:11 +10:00
parent 10ca1e78e8
commit 8a2f1fdb3d

View File

@ -347,6 +347,7 @@ void AP_Airspeed::read(uint8_t i)
if (!enabled(i) || !sensor[i]) {
return;
}
bool prev_healthy = state[i].healthy;
float raw_pressure = get_pressure(i);
if (state[i].cal.start_ms != 0) {
update_calibration(i, raw_pressure);
@ -358,7 +359,14 @@ void AP_Airspeed::read(uint8_t i)
state[i].corrected_pressure = airspeed_pressure;
// filter before clamping positive
if (!prev_healthy) {
// if the previous state was not healthy then we should not
// use an IIR filter, otherwise a bad reading will last for
// some time after the sensor becomees healthy again
state[i].filtered_pressure = airspeed_pressure;
} else {
state[i].filtered_pressure = 0.7f * state[i].filtered_pressure + 0.3f * airspeed_pressure;
}
/*
we support different pitot tube setups so user can choose if