diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index 75e1353a4f..ec095b0756 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -165,7 +165,7 @@ private: #if AP_AHRS_NAVEKF_AVAILABLE NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, rangefinder); NavEKF3 EKF3 = NavEKF3::create(&ahrs, barometer, rangefinder); - AP_AHRS_NavEKF ahrs {ins, barometer, gps, EKF2, EKF3}; + AP_AHRS_NavEKF ahrs = AP_AHRS_NavEKF::create(ins, barometer, gps, EKF2, EKF3); #else AP_AHRS_DCM ahrs {ins, barometer, gps}; #endif diff --git a/AntennaTracker/Tracker.h b/AntennaTracker/Tracker.h index a20cbfdf3d..2b4a34a20a 100644 --- a/AntennaTracker/Tracker.h +++ b/AntennaTracker/Tracker.h @@ -118,7 +118,7 @@ private: #if AP_AHRS_NAVEKF_AVAILABLE NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, rng); NavEKF3 EKF3 = NavEKF3::create(&ahrs, barometer, rng); - AP_AHRS_NavEKF ahrs{ins, barometer, gps, EKF2, EKF3}; + AP_AHRS_NavEKF ahrs = AP_AHRS_NavEKF::create(ins, barometer, gps, EKF2, EKF3); #else AP_AHRS_DCM ahrs{ins, barometer, gps}; #endif diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 28a40547fe..431c87545f 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -216,7 +216,7 @@ private: // Inertial Navigation EKF NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, rangefinder); NavEKF3 EKF3 = NavEKF3::create(&ahrs, barometer, rangefinder); - AP_AHRS_NavEKF ahrs{ins, barometer, gps, EKF2, EKF3, AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF}; + AP_AHRS_NavEKF ahrs = AP_AHRS_NavEKF::create(ins, barometer, gps, EKF2, EKF3, AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF); #if CONFIG_HAL_BOARD == HAL_BOARD_SITL SITL::SITL sitl; diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 19bf2f7e7f..afd9625ca2 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -215,7 +215,7 @@ private: #if AP_AHRS_NAVEKF_AVAILABLE NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, rangefinder); NavEKF3 EKF3 = NavEKF3::create(&ahrs, barometer, rangefinder); - AP_AHRS_NavEKF ahrs {ins, barometer, gps, EKF2, EKF3}; + AP_AHRS_NavEKF ahrs = AP_AHRS_NavEKF::create(ins, barometer, gps, EKF2, EKF3); #else AP_AHRS_DCM ahrs {ins, barometer, gps}; #endif diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 7bcb03a276..3994062d47 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -186,7 +186,7 @@ private: // Inertial Navigation EKF NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, rangefinder); NavEKF3 EKF3 = NavEKF3::create(&ahrs, barometer, rangefinder); - AP_AHRS_NavEKF ahrs {ins, barometer, gps, EKF2, EKF3, AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF}; + AP_AHRS_NavEKF ahrs = AP_AHRS_NavEKF::create(ins, barometer, gps, EKF2, EKF3, AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF); #if CONFIG_HAL_BOARD == HAL_BOARD_SITL SITL::SITL sitl; diff --git a/Tools/Replay/Replay.h b/Tools/Replay/Replay.h index 29f1965b53..927ae9ed2b 100644 --- a/Tools/Replay/Replay.h +++ b/Tools/Replay/Replay.h @@ -66,7 +66,7 @@ public: RangeFinder rng = RangeFinder::create(serial_manager, ROTATION_PITCH_270); NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, rng); NavEKF3 EKF3 = NavEKF3::create(&ahrs, barometer, rng); - AP_AHRS_NavEKF ahrs {ins, barometer, gps, EKF2, EKF3}; + AP_AHRS_NavEKF ahrs = AP_AHRS_NavEKF::create(ins, barometer, gps, EKF2, EKF3); AP_InertialNav_NavEKF inertial_nav{ahrs}; AP_Vehicle::FixedWing aparm; AP_Airspeed airspeed; diff --git a/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp b/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp index e6efa1916e..fbde2f848c 100644 --- a/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp +++ b/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp @@ -28,15 +28,15 @@ public: RangeFinder sonar = RangeFinder::create(serial_manager, ROTATION_PITCH_270); NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, sonar); NavEKF3 EKF3 = NavEKF3::create(&ahrs, barometer, sonar); - AP_AHRS_NavEKF ahrs{ins, barometer, gps, EKF2, EKF3, - AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF}; + AP_AHRS_NavEKF ahrs = AP_AHRS_NavEKF::create(ins, barometer, gps, EKF2, EKF3, + AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF); }; static DummyVehicle vehicle; // choose which AHRS system to use // AP_AHRS_DCM ahrs(ins, baro, gps); -AP_AHRS_NavEKF ahrs(vehicle.ahrs); +AP_AHRS_NavEKF &ahrs = vehicle.ahrs; void setup(void) { 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 0240c68d3a..660b5eda73 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 @@ -27,8 +27,8 @@ public: AP_InertialSensor ins = AP_InertialSensor::create(); AP_SerialManager serial_manager = AP_SerialManager::create(); RangeFinder sonar = RangeFinder::create(serial_manager, ROTATION_PITCH_270); - AP_AHRS_NavEKF ahrs{ins, barometer, gps, EKF2, EKF3, - AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF}; + AP_AHRS_NavEKF ahrs = AP_AHRS_NavEKF::create(ins, barometer, gps, EKF2, EKF3, + AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF); NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, sonar); NavEKF3 EKF3 = NavEKF3::create(&ahrs, barometer, sonar); };