global: use static method to construct AP_InertialSensor

This commit is contained in:
Lucas De Marchi 2017-08-08 08:18:19 -07:00 committed by Francisco Ferreira
parent d566567d87
commit 87b30b4552
12 changed files with 12 additions and 13 deletions

View File

@ -154,7 +154,7 @@ private:
AP_GPS gps;
AP_Baro barometer = AP_Baro::create();
Compass compass = Compass::create();
AP_InertialSensor ins;
AP_InertialSensor ins = AP_InertialSensor::create();
RangeFinder rangefinder { serial_manager, ROTATION_NONE };
AP_Button button;

View File

@ -110,7 +110,7 @@ private:
Compass compass = Compass::create();
AP_InertialSensor ins;
AP_InertialSensor ins = AP_InertialSensor::create();
RangeFinder rng {serial_manager, ROTATION_NONE};

View File

@ -199,7 +199,7 @@ private:
AP_Baro barometer = AP_Baro::create();
Compass compass = Compass::create();
AP_InertialSensor ins;
AP_InertialSensor ins = AP_InertialSensor::create();
RangeFinder rangefinder {serial_manager, ROTATION_PITCH_270};
struct {

View File

@ -203,7 +203,7 @@ private:
AP_Baro barometer = AP_Baro::create();
Compass compass = Compass::create();
AP_InertialSensor ins;
AP_InertialSensor ins = AP_InertialSensor::create();
RangeFinder rangefinder {serial_manager, ROTATION_PITCH_270};

View File

@ -168,7 +168,7 @@ private:
TSYS01 celsius;
AP_Baro barometer = AP_Baro::create();
Compass compass = Compass::create();
AP_InertialSensor ins;
AP_InertialSensor ins = AP_InertialSensor::create();
RangeFinder rangefinder {serial_manager, ROTATION_PITCH_270};
struct {

View File

@ -58,7 +58,7 @@ public:
void setup();
void load_parameters(void);
AP_InertialSensor ins;
AP_InertialSensor ins = AP_InertialSensor::create();
AP_Baro barometer = AP_Baro::create();
AP_GPS gps;
Compass compass = Compass::create();

View File

@ -13,8 +13,7 @@ void loop();
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
// INS and Baro declaration
AP_InertialSensor ins;
static AP_InertialSensor ins = AP_InertialSensor::create();
static Compass compass = Compass::create();

View File

@ -8,7 +8,7 @@
const AP_HAL::HAL &hal = AP_HAL::get_HAL();
AP_InertialSensor ins;
static AP_InertialSensor ins = AP_InertialSensor::create();
static void display_offsets_and_scaling();
static void run_test();

View File

@ -14,7 +14,7 @@ public:
void loop();
private:
AP_InertialSensor ins;
AP_InertialSensor ins = AP_InertialSensor::create();
AP_Baro baro = AP_Baro::create();
AP_GPS gps;
Compass compass = Compass::create();

View File

@ -13,7 +13,7 @@ void loop();
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
// sensor declaration
AP_InertialSensor ins;
static AP_InertialSensor ins = AP_InertialSensor::create();
AP_GPS gps;
static AP_Baro baro = AP_Baro::create();
AP_SerialManager serial_manager;

View File

@ -24,7 +24,7 @@ public:
AP_GPS gps;
AP_Baro barometer = AP_Baro::create();
Compass compass = Compass::create();
AP_InertialSensor ins;
AP_InertialSensor ins = AP_InertialSensor::create();
AP_SerialManager serial_manager;
RangeFinder sonar {serial_manager, ROTATION_PITCH_270};
AP_AHRS_NavEKF ahrs{ins, barometer, gps, sonar, EKF2, EKF3,

View File

@ -16,7 +16,7 @@ public:
private:
AP_InertialSensor ins;
AP_InertialSensor ins = AP_InertialSensor::create();
AP_Scheduler scheduler;
uint32_t ins_counter;