mirror of https://github.com/ArduPilot/ardupilot
AP_Airspeed: Add hysteresis to consistency check
This commit is contained in:
parent
705c6e1a83
commit
b3f289d3d1
|
@ -56,7 +56,12 @@ void AP_Airspeed::check_sensor_ahrs_wind_max_failures(uint8_t i)
|
|||
}
|
||||
bool data_is_inconsistent;
|
||||
if ((AP_Airspeed::OptionsMask::USE_EKF_CONSISTENCY & _options) != 0) {
|
||||
data_is_inconsistent = state[i].failures.test_ratio > MAX(_wind_gate, 0.0f);
|
||||
float gate_size = MAX(_wind_gate, 0.0f);
|
||||
if (param[i].use == 0) {
|
||||
// require a smaller inconsistency for a disabled sensor to be declared consistent
|
||||
gate_size *= 0.7f;
|
||||
}
|
||||
data_is_inconsistent = state[i].failures.test_ratio > gate_size;
|
||||
} else {
|
||||
data_is_inconsistent = false;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue