mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
global: use static method to construct AP_GPS
This commit is contained in:
parent
2cb2727a31
commit
8094482f21
@ -151,7 +151,7 @@ private:
|
|||||||
DataFlash_Class DataFlash;
|
DataFlash_Class DataFlash;
|
||||||
|
|
||||||
// sensor drivers
|
// sensor drivers
|
||||||
AP_GPS gps;
|
AP_GPS gps = AP_GPS::create();
|
||||||
AP_Baro barometer = AP_Baro::create();
|
AP_Baro barometer = AP_Baro::create();
|
||||||
Compass compass = Compass::create();
|
Compass compass = Compass::create();
|
||||||
AP_InertialSensor ins = AP_InertialSensor::create();
|
AP_InertialSensor ins = AP_InertialSensor::create();
|
||||||
|
@ -104,7 +104,7 @@ private:
|
|||||||
|
|
||||||
DataFlash_Class DataFlash;
|
DataFlash_Class DataFlash;
|
||||||
|
|
||||||
AP_GPS gps;
|
AP_GPS gps = AP_GPS::create();
|
||||||
|
|
||||||
AP_Baro barometer = AP_Baro::create();
|
AP_Baro barometer = AP_Baro::create();
|
||||||
|
|
||||||
|
@ -192,7 +192,7 @@ private:
|
|||||||
// Dataflash
|
// Dataflash
|
||||||
DataFlash_Class DataFlash;
|
DataFlash_Class DataFlash;
|
||||||
|
|
||||||
AP_GPS gps;
|
AP_GPS gps = AP_GPS::create();
|
||||||
|
|
||||||
// flight modes convenience array
|
// flight modes convenience array
|
||||||
AP_Int8 *flight_modes;
|
AP_Int8 *flight_modes;
|
||||||
|
@ -195,7 +195,7 @@ private:
|
|||||||
int32_t pitch_limit_min_cd;
|
int32_t pitch_limit_min_cd;
|
||||||
|
|
||||||
// Sensors
|
// Sensors
|
||||||
AP_GPS gps;
|
AP_GPS gps = AP_GPS::create();
|
||||||
|
|
||||||
// flight modes convenience array
|
// flight modes convenience array
|
||||||
AP_Int8 *flight_modes = &g.flight_mode1;
|
AP_Int8 *flight_modes = &g.flight_mode1;
|
||||||
|
@ -161,7 +161,7 @@ private:
|
|||||||
// Dataflash
|
// Dataflash
|
||||||
DataFlash_Class DataFlash;
|
DataFlash_Class DataFlash;
|
||||||
|
|
||||||
AP_GPS gps;
|
AP_GPS gps = AP_GPS::create();
|
||||||
|
|
||||||
AP_LeakDetector leak_detector;
|
AP_LeakDetector leak_detector;
|
||||||
|
|
||||||
|
@ -60,7 +60,7 @@ public:
|
|||||||
|
|
||||||
AP_InertialSensor ins = AP_InertialSensor::create();
|
AP_InertialSensor ins = AP_InertialSensor::create();
|
||||||
AP_Baro barometer = AP_Baro::create();
|
AP_Baro barometer = AP_Baro::create();
|
||||||
AP_GPS gps;
|
AP_GPS gps = AP_GPS::create();
|
||||||
Compass compass = Compass::create();
|
Compass compass = Compass::create();
|
||||||
AP_SerialManager serial_manager;
|
AP_SerialManager serial_manager;
|
||||||
RangeFinder rng {serial_manager, ROTATION_PITCH_270};
|
RangeFinder rng {serial_manager, ROTATION_PITCH_270};
|
||||||
|
@ -17,7 +17,7 @@ static AP_InertialSensor ins = AP_InertialSensor::create();
|
|||||||
|
|
||||||
static Compass compass = Compass::create();
|
static Compass compass = Compass::create();
|
||||||
|
|
||||||
AP_GPS gps;
|
static AP_GPS gps = AP_GPS::create();
|
||||||
static AP_Baro barometer = AP_Baro::create();
|
static AP_Baro barometer = AP_Baro::create();
|
||||||
AP_SerialManager serial_manager;
|
AP_SerialManager serial_manager;
|
||||||
|
|
||||||
|
@ -41,8 +41,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
|||||||
AP_BoardLED board_led;
|
AP_BoardLED board_led;
|
||||||
|
|
||||||
// This example uses GPS system. Create it.
|
// This example uses GPS system. Create it.
|
||||||
AP_GPS gps;
|
static AP_GPS gps = AP_GPS::create();
|
||||||
|
|
||||||
// Serial manager is needed for UART comunications
|
// Serial manager is needed for UART comunications
|
||||||
AP_SerialManager serial_manager;
|
AP_SerialManager serial_manager;
|
||||||
|
|
||||||
|
@ -16,7 +16,7 @@ public:
|
|||||||
private:
|
private:
|
||||||
AP_InertialSensor ins = AP_InertialSensor::create();
|
AP_InertialSensor ins = AP_InertialSensor::create();
|
||||||
AP_Baro baro = AP_Baro::create();
|
AP_Baro baro = AP_Baro::create();
|
||||||
AP_GPS gps;
|
AP_GPS gps = AP_GPS::create();
|
||||||
Compass compass = Compass::create();
|
Compass compass = Compass::create();
|
||||||
AP_AHRS_DCM ahrs{ins, baro, gps};
|
AP_AHRS_DCM ahrs{ins, baro, gps};
|
||||||
|
|
||||||
|
@ -14,7 +14,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
|||||||
|
|
||||||
// sensor declaration
|
// sensor declaration
|
||||||
static AP_InertialSensor ins = AP_InertialSensor::create();
|
static AP_InertialSensor ins = AP_InertialSensor::create();
|
||||||
AP_GPS gps;
|
static AP_GPS gps = AP_GPS::create();
|
||||||
static AP_Baro baro = AP_Baro::create();
|
static AP_Baro baro = AP_Baro::create();
|
||||||
AP_SerialManager serial_manager;
|
AP_SerialManager serial_manager;
|
||||||
|
|
||||||
|
@ -21,7 +21,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
|||||||
|
|
||||||
class DummyVehicle {
|
class DummyVehicle {
|
||||||
public:
|
public:
|
||||||
AP_GPS gps;
|
AP_GPS gps = AP_GPS::create();
|
||||||
AP_Baro barometer = AP_Baro::create();
|
AP_Baro barometer = AP_Baro::create();
|
||||||
Compass compass = Compass::create();
|
Compass compass = Compass::create();
|
||||||
AP_InertialSensor ins = AP_InertialSensor::create();
|
AP_InertialSensor ins = AP_InertialSensor::create();
|
||||||
|
Loading…
Reference in New Issue
Block a user