Browse Source

global: use static method to construct Compass

master
Lucas De Marchi 8 years ago committed by Francisco Ferreira
parent
commit
c1a957fbf3
  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. 2
      libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp
  8. 2
      libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.cpp
  9. 2
      libraries/AP_Mission/examples/AP_Mission_test/AP_Mission_test.cpp
  10. 2
      libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.cpp

2
APMrover2/Rover.h

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

2
AntennaTracker/Tracker.h

@ -108,7 +108,7 @@ private: @@ -108,7 +108,7 @@ private:
AP_Baro barometer = AP_Baro::create();
Compass compass;
Compass compass = Compass::create();
AP_InertialSensor ins;

2
ArduCopter/Copter.h

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

2
ArduPlane/Plane.h

@ -201,7 +201,7 @@ private: @@ -201,7 +201,7 @@ private:
AP_Int8 *flight_modes = &g.flight_mode1;
AP_Baro barometer = AP_Baro::create();
Compass compass;
Compass compass = Compass::create();
AP_InertialSensor ins;

2
ArduSub/Sub.h

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

2
Tools/Replay/Replay.h

@ -61,7 +61,7 @@ public: @@ -61,7 +61,7 @@ public:
AP_InertialSensor ins;
AP_Baro barometer = AP_Baro::create();
AP_GPS gps;
Compass compass;
Compass compass = Compass::create();
AP_SerialManager serial_manager;
RangeFinder rng {serial_manager, ROTATION_PITCH_270};
NavEKF2 EKF2{&ahrs, barometer, rng};

2
libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp

@ -16,7 +16,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); @@ -16,7 +16,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
// INS and Baro declaration
AP_InertialSensor ins;
Compass compass;
static Compass compass = Compass::create();
AP_GPS gps;
static AP_Baro barometer = AP_Baro::create();

2
libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.cpp

@ -9,7 +9,7 @@ @@ -9,7 +9,7 @@
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
static Compass compass;
static Compass compass = Compass::create();
uint32_t timer;

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

@ -17,7 +17,7 @@ private: @@ -17,7 +17,7 @@ private:
AP_InertialSensor ins;
AP_Baro baro = AP_Baro::create();
AP_GPS gps;
Compass compass;
Compass compass = Compass::create();
AP_AHRS_DCM ahrs{ins, baro, gps};
// global constants that control how many verify calls must be made for a command before it completes

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

@ -23,7 +23,7 @@ class DummyVehicle { @@ -23,7 +23,7 @@ class DummyVehicle {
public:
AP_GPS gps;
AP_Baro barometer = AP_Baro::create();
Compass compass;
Compass compass = Compass::create();
AP_InertialSensor ins;
AP_SerialManager serial_manager;
RangeFinder sonar {serial_manager, ROTATION_PITCH_270};

Loading…
Cancel
Save