Browse Source

global: use static method to construct AP_InertialSensor

master
Lucas De Marchi 8 years ago committed by Francisco Ferreira
parent
commit
87b30b4552
  1. 2
      APMrover2/Rover.h
  2. 2
      AntennaTracker/Tracker.h
  3. 2
      ArduCopter/Copter.h
  4. 2
      ArduPlane/Plane.h
  5. 2
      ArduSub/Sub.h
  6. 2
      Tools/Replay/Replay.h
  7. 3
      libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp
  8. 2
      libraries/AP_InertialSensor/examples/INS_generic/INS_generic.cpp
  9. 2
      libraries/AP_Mission/examples/AP_Mission_test/AP_Mission_test.cpp
  10. 2
      libraries/AP_Module/examples/ModuleTest/ModuleTest.cpp
  11. 2
      libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.cpp
  12. 2
      libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp

2
APMrover2/Rover.h

@ -154,7 +154,7 @@ private: @@ -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;

2
AntennaTracker/Tracker.h

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

2
ArduCopter/Copter.h

@ -199,7 +199,7 @@ private: @@ -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 {

2
ArduPlane/Plane.h

@ -203,7 +203,7 @@ private: @@ -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};

2
ArduSub/Sub.h

@ -168,7 +168,7 @@ private: @@ -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 {

2
Tools/Replay/Replay.h

@ -58,7 +58,7 @@ public: @@ -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();

3
libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp

@ -13,8 +13,7 @@ void loop(); @@ -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();

2
libraries/AP_InertialSensor/examples/INS_generic/INS_generic.cpp

@ -8,7 +8,7 @@ @@ -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();

2
libraries/AP_Mission/examples/AP_Mission_test/AP_Mission_test.cpp

@ -14,7 +14,7 @@ public: @@ -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();

2
libraries/AP_Module/examples/ModuleTest/ModuleTest.cpp

@ -13,7 +13,7 @@ void loop(); @@ -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;

2
libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.cpp

@ -24,7 +24,7 @@ public: @@ -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,

2
libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp

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

Loading…
Cancel
Save