mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_Baro: added get_primary() method
This commit is contained in:
parent
edc3709653
commit
326ab0d7b8
@ -55,6 +55,9 @@ public:
|
|||||||
// check if all baros are healthy - used for SYS_STATUS report
|
// check if all baros are healthy - used for SYS_STATUS report
|
||||||
bool all_healthy(void) const;
|
bool all_healthy(void) const;
|
||||||
|
|
||||||
|
// get primary sensor
|
||||||
|
uint8_t get_primary(void) const { return _primary; }
|
||||||
|
|
||||||
// pressure in Pascal. Divide by 100 for millibars or hectopascals
|
// pressure in Pascal. Divide by 100 for millibars or hectopascals
|
||||||
float get_pressure(void) const { return get_pressure(_primary); }
|
float get_pressure(void) const { return get_pressure(_primary); }
|
||||||
float get_pressure(uint8_t instance) const { return sensors[instance].pressure; }
|
float get_pressure(uint8_t instance) const { return sensors[instance].pressure; }
|
||||||
|
Loading…
Reference in New Issue
Block a user