@ -152,7 +152,7 @@ private:
// sensor drivers
AP_GPS gps;
AP_Baro barometer;
AP_Baro barometer = AP_Baro::create();
Compass compass;
AP_InertialSensor ins;
RangeFinder rangefinder { serial_manager, ROTATION_NONE };
@ -106,7 +106,7 @@ private:
@ -197,7 +197,7 @@ private:
// flight modes convenience array
AP_Int8 *flight_modes;
@ -200,7 +200,7 @@ private:
AP_Int8 *flight_modes = &g.flight_mode1;
@ -166,7 +166,7 @@ private:
AP_LeakDetector leak_detector;
TSYS01 celsius;
@ -59,7 +59,7 @@ public:
void load_parameters(void);
AP_SerialManager serial_manager;
@ -19,7 +19,7 @@ AP_InertialSensor ins;
static AP_Baro barometer = AP_Baro::create();
class DummyVehicle {
@ -8,7 +8,7 @@
const AP_HAL::HAL &hal = AP_HAL::get_HAL();
static AP_Baro barometer;
static uint32_t timer;
static uint8_t counter;
@ -15,7 +15,7 @@ public:
private:
AP_Baro baro;
AP_Baro baro = AP_Baro::create();
AP_AHRS_DCM ahrs{ins, baro, gps};
@ -15,7 +15,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
// sensor declaration
static AP_Baro baro = AP_Baro::create();
// choose which AHRS system to use
@ -22,7 +22,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
public: