Skip to content

Commit

Permalink
global: use static method to construct AP_GPS
Browse files Browse the repository at this point in the history
  • Loading branch information
lucasdemarchi authored and OXINARF committed Sep 26, 2017
1 parent 2cb2727 commit 8094482
Show file tree
Hide file tree
Showing 11 changed files with 11 additions and 12 deletions.
2 changes: 1 addition & 1 deletion APMrover2/Rover.h
Original file line number Diff line number Diff line change
Expand Up @@ -151,7 +151,7 @@ class Rover : public AP_HAL::HAL::Callbacks {
DataFlash_Class DataFlash;

// sensor drivers
AP_GPS gps;
AP_GPS gps = AP_GPS::create();
AP_Baro barometer = AP_Baro::create();
Compass compass = Compass::create();
AP_InertialSensor ins = AP_InertialSensor::create();
Expand Down
2 changes: 1 addition & 1 deletion AntennaTracker/Tracker.h
Original file line number Diff line number Diff line change
Expand Up @@ -104,7 +104,7 @@ class Tracker : public AP_HAL::HAL::Callbacks {

DataFlash_Class DataFlash;

AP_GPS gps;
AP_GPS gps = AP_GPS::create();

AP_Baro barometer = AP_Baro::create();

Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -192,7 +192,7 @@ class Copter : public AP_HAL::HAL::Callbacks {
// Dataflash
DataFlash_Class DataFlash;

AP_GPS gps;
AP_GPS gps = AP_GPS::create();

// flight modes convenience array
AP_Int8 *flight_modes;
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -195,7 +195,7 @@ class Plane : public AP_HAL::HAL::Callbacks {
int32_t pitch_limit_min_cd;

// Sensors
AP_GPS gps;
AP_GPS gps = AP_GPS::create();

// flight modes convenience array
AP_Int8 *flight_modes = &g.flight_mode1;
Expand Down
2 changes: 1 addition & 1 deletion ArduSub/Sub.h
Original file line number Diff line number Diff line change
Expand Up @@ -161,7 +161,7 @@ class Sub : public AP_HAL::HAL::Callbacks {
// Dataflash
DataFlash_Class DataFlash;

AP_GPS gps;
AP_GPS gps = AP_GPS::create();

AP_LeakDetector leak_detector;

Expand Down
2 changes: 1 addition & 1 deletion Tools/Replay/Replay.h
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ class ReplayVehicle {

AP_InertialSensor ins = AP_InertialSensor::create();
AP_Baro barometer = AP_Baro::create();
AP_GPS gps;
AP_GPS gps = AP_GPS::create();
Compass compass = Compass::create();
AP_SerialManager serial_manager;
RangeFinder rng {serial_manager, ROTATION_PITCH_270};
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ static AP_InertialSensor ins = AP_InertialSensor::create();

static Compass compass = Compass::create();

AP_GPS gps;
static AP_GPS gps = AP_GPS::create();
static AP_Baro barometer = AP_Baro::create();
AP_SerialManager serial_manager;

Expand Down
3 changes: 1 addition & 2 deletions libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,8 +41,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
AP_BoardLED board_led;

// This example uses GPS system. Create it.
AP_GPS gps;

static AP_GPS gps = AP_GPS::create();
// Serial manager is needed for UART comunications
AP_SerialManager serial_manager;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ class MissionTest {
private:
AP_InertialSensor ins = AP_InertialSensor::create();
AP_Baro baro = AP_Baro::create();
AP_GPS gps;
AP_GPS gps = AP_GPS::create();
Compass compass = Compass::create();
AP_AHRS_DCM ahrs{ins, baro, gps};

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Module/examples/ModuleTest/ModuleTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();

// sensor declaration
static AP_InertialSensor ins = AP_InertialSensor::create();
AP_GPS gps;
static AP_GPS gps = AP_GPS::create();
static AP_Baro baro = AP_Baro::create();
AP_SerialManager serial_manager;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();

class DummyVehicle {
public:
AP_GPS gps;
AP_GPS gps = AP_GPS::create();
AP_Baro barometer = AP_Baro::create();
Compass compass = Compass::create();
AP_InertialSensor ins = AP_InertialSensor::create();
Expand Down

0 comments on commit 8094482

Please sign in to comment.