mirror of https://github.com/ArduPilot/ardupilot
AP_Airspeed: log health failure probability
This commit is contained in:
parent
c9af223579
commit
74299906b1
|
@ -125,6 +125,12 @@ public:
|
|||
}
|
||||
float get_EAS2TAS(void) const { return get_EAS2TAS(primary); }
|
||||
|
||||
// get the failure health probability
|
||||
float get_health_failure_probability(uint8_t i) const {
|
||||
return state[i].failures.health_probability;
|
||||
}
|
||||
float get_health_failure_probability(void) const { return get_health_failure_probability(primary); }
|
||||
|
||||
// update airspeed ratio calibration
|
||||
void update_calibration(const Vector3f &vground, int16_t max_airspeed_allowed_during_cal);
|
||||
|
||||
|
|
|
@ -6,9 +6,7 @@
|
|||
void AP_Airspeed::check_sensor_failures()
|
||||
{
|
||||
for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
|
||||
if(AP_Airspeed::OptionsMask::ON_FAILURE_AHRS_WIND_MAX_DO_DISABLE & _options) {
|
||||
check_sensor_ahrs_wind_max_failures(i);
|
||||
}
|
||||
check_sensor_ahrs_wind_max_failures(i);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue