global: use static method to construct AP_Baro

This commit is contained in:
Lucas De Marchi 2017-08-08 00:50:14 -07:00 committed by Francisco Ferreira
parent c5c1d5abfe
commit 91feec0e14
11 changed files with 11 additions and 11 deletions

View File

@ -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 };

View File

@ -106,7 +106,7 @@ private:
AP_GPS gps; AP_GPS gps;
AP_Baro barometer; AP_Baro barometer = AP_Baro::create();
Compass compass; Compass compass;

View File

@ -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;

View File

@ -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;

View File

@ -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;

View File

@ -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;

View File

@ -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 {

View File

@ -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;

View File

@ -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};

View File

@ -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

View File

@ -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;