mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Airspeed: expose get_corrected_pressure()
needed for AP_Periph
This commit is contained in:
parent
bfc4802b37
commit
0f6f684bab
@ -160,6 +160,14 @@ public:
|
||||
|
||||
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;
|
||||
|
Loading…
Reference in New Issue
Block a user