diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index d9f6d344a8..e84cfceda2 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -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; diff --git a/AntennaTracker/Tracker.h b/AntennaTracker/Tracker.h index d8a4fb8d19..9763e84f25 100644 --- a/AntennaTracker/Tracker.h +++ b/AntennaTracker/Tracker.h @@ -108,7 +108,7 @@ private: AP_Baro barometer = AP_Baro::create(); - Compass compass; + Compass compass = Compass::create(); AP_InertialSensor ins; diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 3378ff0349..3ab2593e6b 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -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}; diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index b35f1b031e..5dc5691efa 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -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; diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 3871b1adff..436ae13151 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -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}; diff --git a/Tools/Replay/Replay.h b/Tools/Replay/Replay.h index 0ee3e7984d..4579c31e96 100644 --- a/Tools/Replay/Replay.h +++ b/Tools/Replay/Replay.h @@ -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}; diff --git a/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp b/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp index 4dcd2f35e5..4c0f961007 100644 --- a/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp +++ b/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp @@ -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(); diff --git a/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.cpp b/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.cpp index 63683961d5..cca63d595f 100644 --- a/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.cpp +++ b/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.cpp @@ -9,7 +9,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); -static Compass compass; +static Compass compass = Compass::create(); uint32_t timer; diff --git a/libraries/AP_Mission/examples/AP_Mission_test/AP_Mission_test.cpp b/libraries/AP_Mission/examples/AP_Mission_test/AP_Mission_test.cpp index 32a6bec421..d832e8270e 100644 --- a/libraries/AP_Mission/examples/AP_Mission_test/AP_Mission_test.cpp +++ b/libraries/AP_Mission/examples/AP_Mission_test/AP_Mission_test.cpp @@ -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 diff --git a/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.cpp b/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.cpp index 74af4e4f6a..74d8e4386a 100644 --- a/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.cpp +++ b/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.cpp @@ -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};