diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index ec095b0756..5bf182001c 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -167,7 +167,7 @@ private: NavEKF3 EKF3 = NavEKF3::create(&ahrs, barometer, rangefinder); AP_AHRS_NavEKF ahrs = AP_AHRS_NavEKF::create(ins, barometer, gps, EKF2, EKF3); #else - AP_AHRS_DCM ahrs {ins, barometer, gps}; + AP_AHRS_DCM ahrs = AP_AHRS_DCM::create(ins, barometer, gps); #endif // Arming/Disarming management class diff --git a/AntennaTracker/Tracker.h b/AntennaTracker/Tracker.h index 2b4a34a20a..a21fb04cf1 100644 --- a/AntennaTracker/Tracker.h +++ b/AntennaTracker/Tracker.h @@ -120,7 +120,7 @@ private: NavEKF3 EKF3 = NavEKF3::create(&ahrs, barometer, rng); AP_AHRS_NavEKF ahrs = AP_AHRS_NavEKF::create(ins, barometer, gps, EKF2, EKF3); #else - AP_AHRS_DCM ahrs{ins, barometer, gps}; + AP_AHRS_DCM ahrs = AP_AHRS_DCM::create(ins, barometer, gps); #endif #if CONFIG_HAL_BOARD == HAL_BOARD_SITL diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index afd9625ca2..86ad712339 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -217,7 +217,7 @@ private: NavEKF3 EKF3 = NavEKF3::create(&ahrs, barometer, rangefinder); AP_AHRS_NavEKF ahrs = AP_AHRS_NavEKF::create(ins, barometer, gps, EKF2, EKF3); #else - AP_AHRS_DCM ahrs {ins, barometer, gps}; + AP_AHRS_DCM ahrs = AP_AHRS_DCM::create(ins, barometer, gps); #endif AP_TECS TECS_controller {ahrs, aparm, landing, g2.soaring_controller}; diff --git a/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp b/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp index fbde2f848c..6cd66af3da 100644 --- a/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp +++ b/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp @@ -35,7 +35,7 @@ public: static DummyVehicle vehicle; // choose which AHRS system to use -// AP_AHRS_DCM ahrs(ins, baro, gps); +// AP_AHRS_DCM ahrs = AP_AHRS_DCM::create(ins, barometer, gps); AP_AHRS_NavEKF &ahrs = vehicle.ahrs; void setup(void) 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 4544b128fc..12e6a3e3b4 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 @@ -18,7 +18,7 @@ private: AP_Baro baro = AP_Baro::create(); AP_GPS gps = AP_GPS::create(); Compass compass = Compass::create(); - AP_AHRS_DCM ahrs{ins, baro, gps}; + AP_AHRS_DCM ahrs = AP_AHRS_DCM::create(ins, baro, gps); // global constants that control how many verify calls must be made for a command before it completes uint8_t verify_nav_cmd_iterations_to_complete = 3; diff --git a/libraries/AP_Module/examples/ModuleTest/ModuleTest.cpp b/libraries/AP_Module/examples/ModuleTest/ModuleTest.cpp index 66916fcaeb..8fca7e6b8c 100644 --- a/libraries/AP_Module/examples/ModuleTest/ModuleTest.cpp +++ b/libraries/AP_Module/examples/ModuleTest/ModuleTest.cpp @@ -19,7 +19,7 @@ static AP_Baro baro = AP_Baro::create(); static AP_SerialManager serial_manager = AP_SerialManager::create(); // choose which AHRS system to use -AP_AHRS_DCM ahrs(ins, baro, gps); +static AP_AHRS_DCM ahrs = AP_AHRS_DCM::create(ins, baro, gps); void setup(void) {