mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_Baro: make AP_Baro a singleton
for AP_Airspeed
This commit is contained in:
parent
d7bbf9bf66
commit
e23a2c5254
@ -130,11 +130,16 @@ const AP_Param::GroupInfo AP_Baro::var_info[] = {
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
// singleton instance
|
||||
AP_Baro *AP_Baro::_instance;
|
||||
|
||||
/*
|
||||
AP_Baro constructor
|
||||
*/
|
||||
AP_Baro::AP_Baro()
|
||||
{
|
||||
_instance = this;
|
||||
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
}
|
||||
|
||||
|
@ -27,6 +27,15 @@ public:
|
||||
// constructor
|
||||
AP_Baro();
|
||||
|
||||
/* Do not allow copies */
|
||||
AP_Baro(const AP_Baro &other) = delete;
|
||||
AP_Baro &operator=(const AP_Baro&) = delete;
|
||||
|
||||
// get singleton
|
||||
static AP_Baro *get_instance(void) {
|
||||
return _instance;
|
||||
}
|
||||
|
||||
// barometer types
|
||||
typedef enum {
|
||||
BARO_TYPE_AIR,
|
||||
@ -161,6 +170,9 @@ public:
|
||||
void set_pressure_correction(uint8_t instance, float p_correction);
|
||||
|
||||
private:
|
||||
// singleton
|
||||
static AP_Baro *_instance;
|
||||
|
||||
// how many drivers do we have?
|
||||
uint8_t _num_drivers;
|
||||
AP_Baro_Backend *drivers[BARO_MAX_DRIVERS];
|
||||
|
Loading…
Reference in New Issue
Block a user