mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
global: use static method to construct Compass
This commit is contained in:
parent
320260a151
commit
c1a957fbf3
@ -153,7 +153,7 @@ private:
|
|||||||
// sensor drivers
|
// sensor drivers
|
||||||
AP_GPS gps;
|
AP_GPS gps;
|
||||||
AP_Baro barometer = AP_Baro::create();
|
AP_Baro barometer = AP_Baro::create();
|
||||||
Compass compass;
|
Compass compass = Compass::create();
|
||||||
AP_InertialSensor ins;
|
AP_InertialSensor ins;
|
||||||
RangeFinder rangefinder { serial_manager, ROTATION_NONE };
|
RangeFinder rangefinder { serial_manager, ROTATION_NONE };
|
||||||
AP_Button button;
|
AP_Button button;
|
||||||
|
@ -108,7 +108,7 @@ private:
|
|||||||
|
|
||||||
AP_Baro barometer = AP_Baro::create();
|
AP_Baro barometer = AP_Baro::create();
|
||||||
|
|
||||||
Compass compass;
|
Compass compass = Compass::create();
|
||||||
|
|
||||||
AP_InertialSensor ins;
|
AP_InertialSensor ins;
|
||||||
|
|
||||||
|
@ -198,7 +198,7 @@ private:
|
|||||||
AP_Int8 *flight_modes;
|
AP_Int8 *flight_modes;
|
||||||
|
|
||||||
AP_Baro barometer = AP_Baro::create();
|
AP_Baro barometer = AP_Baro::create();
|
||||||
Compass compass;
|
Compass compass = Compass::create();
|
||||||
AP_InertialSensor ins;
|
AP_InertialSensor ins;
|
||||||
|
|
||||||
RangeFinder rangefinder {serial_manager, ROTATION_PITCH_270};
|
RangeFinder rangefinder {serial_manager, ROTATION_PITCH_270};
|
||||||
|
@ -201,7 +201,7 @@ private:
|
|||||||
AP_Int8 *flight_modes = &g.flight_mode1;
|
AP_Int8 *flight_modes = &g.flight_mode1;
|
||||||
|
|
||||||
AP_Baro barometer = AP_Baro::create();
|
AP_Baro barometer = AP_Baro::create();
|
||||||
Compass compass;
|
Compass compass = Compass::create();
|
||||||
|
|
||||||
AP_InertialSensor ins;
|
AP_InertialSensor ins;
|
||||||
|
|
||||||
|
@ -167,7 +167,7 @@ private:
|
|||||||
|
|
||||||
TSYS01 celsius;
|
TSYS01 celsius;
|
||||||
AP_Baro barometer = AP_Baro::create();
|
AP_Baro barometer = AP_Baro::create();
|
||||||
Compass compass;
|
Compass compass = Compass::create();
|
||||||
AP_InertialSensor ins;
|
AP_InertialSensor ins;
|
||||||
|
|
||||||
RangeFinder rangefinder {serial_manager, ROTATION_PITCH_270};
|
RangeFinder rangefinder {serial_manager, ROTATION_PITCH_270};
|
||||||
|
@ -61,7 +61,7 @@ public:
|
|||||||
AP_InertialSensor ins;
|
AP_InertialSensor ins;
|
||||||
AP_Baro barometer = AP_Baro::create();
|
AP_Baro barometer = AP_Baro::create();
|
||||||
AP_GPS gps;
|
AP_GPS gps;
|
||||||
Compass compass;
|
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};
|
||||||
NavEKF2 EKF2{&ahrs, barometer, rng};
|
NavEKF2 EKF2{&ahrs, barometer, rng};
|
||||||
|
@ -16,7 +16,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
|||||||
// INS and Baro declaration
|
// INS and Baro declaration
|
||||||
AP_InertialSensor ins;
|
AP_InertialSensor ins;
|
||||||
|
|
||||||
Compass compass;
|
static Compass compass = Compass::create();
|
||||||
|
|
||||||
AP_GPS gps;
|
AP_GPS gps;
|
||||||
static AP_Baro barometer = AP_Baro::create();
|
static AP_Baro barometer = AP_Baro::create();
|
||||||
|
@ -9,7 +9,7 @@
|
|||||||
|
|
||||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||||
|
|
||||||
static Compass compass;
|
static Compass compass = Compass::create();
|
||||||
|
|
||||||
uint32_t timer;
|
uint32_t timer;
|
||||||
|
|
||||||
|
@ -17,7 +17,7 @@ private:
|
|||||||
AP_InertialSensor ins;
|
AP_InertialSensor ins;
|
||||||
AP_Baro baro = AP_Baro::create();
|
AP_Baro baro = AP_Baro::create();
|
||||||
AP_GPS gps;
|
AP_GPS gps;
|
||||||
Compass compass;
|
Compass compass = Compass::create();
|
||||||
AP_AHRS_DCM ahrs{ins, baro, gps};
|
AP_AHRS_DCM ahrs{ins, baro, gps};
|
||||||
|
|
||||||
// global constants that control how many verify calls must be made for a command before it completes
|
// global constants that control how many verify calls must be made for a command before it completes
|
||||||
|
@ -23,7 +23,7 @@ class DummyVehicle {
|
|||||||
public:
|
public:
|
||||||
AP_GPS gps;
|
AP_GPS gps;
|
||||||
AP_Baro barometer = AP_Baro::create();
|
AP_Baro barometer = AP_Baro::create();
|
||||||
Compass compass;
|
Compass compass = Compass::create();
|
||||||
AP_InertialSensor ins;
|
AP_InertialSensor ins;
|
||||||
AP_SerialManager serial_manager;
|
AP_SerialManager serial_manager;
|
||||||
RangeFinder sonar {serial_manager, ROTATION_PITCH_270};
|
RangeFinder sonar {serial_manager, ROTATION_PITCH_270};
|
||||||
|
Loading…
Reference in New Issue
Block a user