AP_Airspeed: expose get_corrected_pressure()

needed for AP_Periph
This commit is contained in:
Andrew Tridgell 2020-03-16 16:09:10 +11:00
parent bfc4802b37
commit 0f6f684bab
1 changed files with 9 additions and 7 deletions

View File

@ -159,6 +159,14 @@ public:
uint8_t get_primary(void) const { return primary; }
static AP_Airspeed *get_singleton() { return _singleton; }
// return the current corrected pressure, public for AP_Periph
float get_corrected_pressure(uint8_t i) const {
return state[i].corrected_pressure;
}
float get_corrected_pressure(void) const {
return get_corrected_pressure(primary);
}
private:
static AP_Airspeed *_singleton;
@ -220,13 +228,7 @@ private:
// return the differential pressure in Pascal for the last airspeed reading for the requested instance
// returns 0 if the sensor is not enabled
float get_pressure(uint8_t i);
// return the current corrected pressure
float get_corrected_pressure(uint8_t i) const {
return state[i].corrected_pressure;
}
float get_corrected_pressure(void) const {
return get_corrected_pressure(primary);
}
// get the failure health probability
float get_health_failure_probability(uint8_t i) const {
return state[i].failures.health_probability;