mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
AP_Baro: add static create method
This commit is contained in:
parent
c34104b369
commit
c5c1d5abfe
@ -24,8 +24,13 @@ class AP_Baro
|
|||||||
friend class AP_Baro_SITL; // for access to sensors[]
|
friend class AP_Baro_SITL; // for access to sensors[]
|
||||||
|
|
||||||
public:
|
public:
|
||||||
// constructor
|
static AP_Baro create() { return AP_Baro{}; }
|
||||||
AP_Baro();
|
|
||||||
|
constexpr AP_Baro(AP_Baro &&other) = default;
|
||||||
|
|
||||||
|
/* Do not allow copies */
|
||||||
|
AP_Baro(const AP_Baro &other) = delete;
|
||||||
|
AP_Baro &operator=(const AP_Baro&) = delete;
|
||||||
|
|
||||||
// barometer types
|
// barometer types
|
||||||
typedef enum {
|
typedef enum {
|
||||||
@ -161,6 +166,8 @@ public:
|
|||||||
void set_pressure_correction(uint8_t instance, float p_correction);
|
void set_pressure_correction(uint8_t instance, float p_correction);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
AP_Baro();
|
||||||
|
|
||||||
// how many drivers do we have?
|
// how many drivers do we have?
|
||||||
uint8_t _num_drivers;
|
uint8_t _num_drivers;
|
||||||
AP_Baro_Backend *drivers[BARO_MAX_DRIVERS];
|
AP_Baro_Backend *drivers[BARO_MAX_DRIVERS];
|
||||||
|
Loading…
Reference in New Issue
Block a user