mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
global: use static method to construct AP_Baro
This commit is contained in:
parent
c5c1d5abfe
commit
91feec0e14
@ -152,7 +152,7 @@ private:
|
|||||||
|
|
||||||
// sensor drivers
|
// sensor drivers
|
||||||
AP_GPS gps;
|
AP_GPS gps;
|
||||||
AP_Baro barometer;
|
AP_Baro barometer = AP_Baro::create();
|
||||||
Compass compass;
|
Compass compass;
|
||||||
AP_InertialSensor ins;
|
AP_InertialSensor ins;
|
||||||
RangeFinder rangefinder { serial_manager, ROTATION_NONE };
|
RangeFinder rangefinder { serial_manager, ROTATION_NONE };
|
||||||
|
@ -106,7 +106,7 @@ private:
|
|||||||
|
|
||||||
AP_GPS gps;
|
AP_GPS gps;
|
||||||
|
|
||||||
AP_Baro barometer;
|
AP_Baro barometer = AP_Baro::create();
|
||||||
|
|
||||||
Compass compass;
|
Compass compass;
|
||||||
|
|
||||||
|
@ -197,7 +197,7 @@ private:
|
|||||||
// flight modes convenience array
|
// flight modes convenience array
|
||||||
AP_Int8 *flight_modes;
|
AP_Int8 *flight_modes;
|
||||||
|
|
||||||
AP_Baro barometer;
|
AP_Baro barometer = AP_Baro::create();
|
||||||
Compass compass;
|
Compass compass;
|
||||||
AP_InertialSensor ins;
|
AP_InertialSensor ins;
|
||||||
|
|
||||||
|
@ -200,7 +200,7 @@ private:
|
|||||||
// flight modes convenience array
|
// flight modes convenience array
|
||||||
AP_Int8 *flight_modes = &g.flight_mode1;
|
AP_Int8 *flight_modes = &g.flight_mode1;
|
||||||
|
|
||||||
AP_Baro barometer;
|
AP_Baro barometer = AP_Baro::create();
|
||||||
Compass compass;
|
Compass compass;
|
||||||
|
|
||||||
AP_InertialSensor ins;
|
AP_InertialSensor ins;
|
||||||
|
@ -166,7 +166,7 @@ private:
|
|||||||
AP_LeakDetector leak_detector;
|
AP_LeakDetector leak_detector;
|
||||||
|
|
||||||
TSYS01 celsius;
|
TSYS01 celsius;
|
||||||
AP_Baro barometer;
|
AP_Baro barometer = AP_Baro::create();
|
||||||
Compass compass;
|
Compass compass;
|
||||||
AP_InertialSensor ins;
|
AP_InertialSensor ins;
|
||||||
|
|
||||||
|
@ -59,7 +59,7 @@ public:
|
|||||||
void load_parameters(void);
|
void load_parameters(void);
|
||||||
|
|
||||||
AP_InertialSensor ins;
|
AP_InertialSensor ins;
|
||||||
AP_Baro barometer;
|
AP_Baro barometer = AP_Baro::create();
|
||||||
AP_GPS gps;
|
AP_GPS gps;
|
||||||
Compass compass;
|
Compass compass;
|
||||||
AP_SerialManager serial_manager;
|
AP_SerialManager serial_manager;
|
||||||
|
@ -19,7 +19,7 @@ AP_InertialSensor ins;
|
|||||||
Compass compass;
|
Compass compass;
|
||||||
|
|
||||||
AP_GPS gps;
|
AP_GPS gps;
|
||||||
AP_Baro barometer;
|
static AP_Baro barometer = AP_Baro::create();
|
||||||
AP_SerialManager serial_manager;
|
AP_SerialManager serial_manager;
|
||||||
|
|
||||||
class DummyVehicle {
|
class DummyVehicle {
|
||||||
|
@ -8,7 +8,7 @@
|
|||||||
|
|
||||||
const AP_HAL::HAL &hal = AP_HAL::get_HAL();
|
const AP_HAL::HAL &hal = AP_HAL::get_HAL();
|
||||||
|
|
||||||
static AP_Baro barometer;
|
static AP_Baro barometer = AP_Baro::create();
|
||||||
|
|
||||||
static uint32_t timer;
|
static uint32_t timer;
|
||||||
static uint8_t counter;
|
static uint8_t counter;
|
||||||
|
@ -15,7 +15,7 @@ public:
|
|||||||
|
|
||||||
private:
|
private:
|
||||||
AP_InertialSensor ins;
|
AP_InertialSensor ins;
|
||||||
AP_Baro baro;
|
AP_Baro baro = AP_Baro::create();
|
||||||
AP_GPS gps;
|
AP_GPS gps;
|
||||||
Compass compass;
|
Compass compass;
|
||||||
AP_AHRS_DCM ahrs{ins, baro, gps};
|
AP_AHRS_DCM ahrs{ins, baro, gps};
|
||||||
|
@ -15,7 +15,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
|||||||
// sensor declaration
|
// sensor declaration
|
||||||
AP_InertialSensor ins;
|
AP_InertialSensor ins;
|
||||||
AP_GPS gps;
|
AP_GPS gps;
|
||||||
AP_Baro baro;
|
static AP_Baro baro = AP_Baro::create();
|
||||||
AP_SerialManager serial_manager;
|
AP_SerialManager serial_manager;
|
||||||
|
|
||||||
// choose which AHRS system to use
|
// choose which AHRS system to use
|
||||||
|
@ -22,7 +22,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
|||||||
class DummyVehicle {
|
class DummyVehicle {
|
||||||
public:
|
public:
|
||||||
AP_GPS gps;
|
AP_GPS gps;
|
||||||
AP_Baro barometer;
|
AP_Baro barometer = AP_Baro::create();
|
||||||
Compass compass;
|
Compass compass;
|
||||||
AP_InertialSensor ins;
|
AP_InertialSensor ins;
|
||||||
AP_SerialManager serial_manager;
|
AP_SerialManager serial_manager;
|
||||||
|
Loading…
Reference in New Issue
Block a user