mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_Airspeed: rename get_health_failure_probability to get_health_probability
This commit is contained in:
parent
8a4f256ad5
commit
7ced9b0d32
@ -689,7 +689,7 @@ void AP_Airspeed::Log_Airspeed()
|
||||
offset : get_offset(i),
|
||||
use : use(i),
|
||||
healthy : healthy(i),
|
||||
health_prob : get_health_failure_probability(i),
|
||||
health_prob : get_health_probability(i),
|
||||
primary : get_primary()
|
||||
};
|
||||
AP::logger().WriteBlock(&pkt, sizeof(pkt));
|
||||
|
@ -266,12 +266,12 @@ private:
|
||||
// returns 0 if the sensor is not enabled
|
||||
float get_pressure(uint8_t i);
|
||||
|
||||
// get the failure health probability
|
||||
float get_health_failure_probability(uint8_t i) const {
|
||||
// get the health probability
|
||||
float get_health_probability(uint8_t i) const {
|
||||
return state[i].failures.health_probability;
|
||||
}
|
||||
float get_health_failure_probability(void) const {
|
||||
return get_health_failure_probability(primary);
|
||||
float get_health_probability(void) const {
|
||||
return get_health_probability(primary);
|
||||
}
|
||||
|
||||
void update_calibration(uint8_t i, float raw_pressure);
|
||||
|
Loading…
Reference in New Issue
Block a user