diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index eaa1490415..9976199b88 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -165,7 +165,7 @@ private: #if AP_AHRS_NAVEKF_AVAILABLE NavEKF2 EKF2{&ahrs, barometer, rangefinder}; NavEKF3 EKF3{&ahrs, barometer, rangefinder}; - AP_AHRS_NavEKF ahrs {ins, barometer, gps, rangefinder, EKF2, EKF3}; + AP_AHRS_NavEKF ahrs {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 a19322668b..1e580facef 100644 --- a/AntennaTracker/Tracker.h +++ b/AntennaTracker/Tracker.h @@ -118,7 +118,7 @@ private: #if AP_AHRS_NAVEKF_AVAILABLE NavEKF2 EKF2{&ahrs, barometer, rng}; NavEKF3 EKF3{&ahrs, barometer, rng}; - AP_AHRS_NavEKF ahrs{ins, barometer, gps, rng, EKF2, EKF3}; + AP_AHRS_NavEKF ahrs{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 c3ea3f6ee9..c068e8f415 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -216,7 +216,7 @@ private: // Inertial Navigation EKF NavEKF2 EKF2{&ahrs, barometer, rangefinder}; NavEKF3 EKF3{&ahrs, barometer, rangefinder}; - AP_AHRS_NavEKF ahrs{ins, barometer, gps, rangefinder, EKF2, EKF3, AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF}; + AP_AHRS_NavEKF ahrs{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 37a6c6f12a..1b65d5fa06 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -210,12 +210,12 @@ private: AP_Vehicle::FixedWing::Rangefinder_State rangefinder_state; AP_RPM rpm_sensor; - + // Inertial Navigation EKF #if AP_AHRS_NAVEKF_AVAILABLE NavEKF2 EKF2{&ahrs, barometer, rangefinder}; NavEKF3 EKF3{&ahrs, barometer, rangefinder}; - AP_AHRS_NavEKF ahrs {ins, barometer, gps, rangefinder, EKF2, EKF3}; + AP_AHRS_NavEKF ahrs {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 b8d53358e3..85dca5f9e4 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -186,7 +186,7 @@ private: // Inertial Navigation EKF NavEKF2 EKF2 {&ahrs, barometer, rangefinder}; NavEKF3 EKF3 {&ahrs, barometer, rangefinder}; - AP_AHRS_NavEKF ahrs {ins, barometer, gps, rangefinder, EKF2, EKF3, AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF}; + AP_AHRS_NavEKF ahrs {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 ceaf5aa1b3..858e642b6c 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{&ahrs, barometer, rng}; NavEKF3 EKF3{&ahrs, barometer, rng}; - AP_AHRS_NavEKF ahrs {ins, barometer, gps, rng, EKF2, EKF3}; + AP_AHRS_NavEKF ahrs {ins, barometer, gps, EKF2, EKF3}; AP_InertialNav_NavEKF inertial_nav{ahrs}; AP_Vehicle::FixedWing aparm; AP_Airspeed airspeed; diff --git a/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp b/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp index 847eed1772..245275d734 100644 --- a/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp +++ b/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp @@ -30,7 +30,7 @@ extern const AP_HAL::HAL& hal; // constructor -AP_AHRS_NavEKF::AP_AHRS_NavEKF(AP_InertialSensor &ins, AP_Baro &baro, AP_GPS &gps, RangeFinder &rng, NavEKF2 &_EKF2, NavEKF3 &_EKF3, Flags flags) : +AP_AHRS_NavEKF::AP_AHRS_NavEKF(AP_InertialSensor &ins, AP_Baro &baro, AP_GPS &gps, NavEKF2 &_EKF2, NavEKF3 &_EKF3, Flags flags) : AP_AHRS_DCM(ins, baro, gps), EKF2(_EKF2), EKF3(_EKF3), diff --git a/libraries/AP_AHRS/AP_AHRS_NavEKF.h b/libraries/AP_AHRS/AP_AHRS_NavEKF.h index 2a6dff960c..c2c5c52a6c 100644 --- a/libraries/AP_AHRS/AP_AHRS_NavEKF.h +++ b/libraries/AP_AHRS/AP_AHRS_NavEKF.h @@ -45,7 +45,7 @@ public: }; // Constructor - AP_AHRS_NavEKF(AP_InertialSensor &ins, AP_Baro &baro, AP_GPS &gps, RangeFinder &rng, + AP_AHRS_NavEKF(AP_InertialSensor &ins, AP_Baro &baro, AP_GPS &gps, NavEKF2 &_EKF2, NavEKF3 &_EKF3, Flags flags = FLAG_NONE); // return the smoothed gyro vector corrected for drift diff --git a/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp b/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp index de3ac3d1b8..a70b163a9f 100644 --- a/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp +++ b/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp @@ -24,10 +24,10 @@ AP_SerialManager serial_manager; class DummyVehicle { public: RangeFinder sonar = RangeFinder::create(serial_manager, ROTATION_PITCH_270); - AP_AHRS_NavEKF ahrs{ins, barometer, gps, sonar, EKF2, EKF3, - AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF}; NavEKF2 EKF2{&ahrs, barometer, sonar}; NavEKF3 EKF3{&ahrs, barometer, sonar}; + AP_AHRS_NavEKF ahrs{ins, barometer, gps, EKF2, EKF3, + AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF}; }; static DummyVehicle vehicle; 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 94298f84b6..e24872b772 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,7 +27,7 @@ public: AP_InertialSensor ins = AP_InertialSensor::create(); AP_SerialManager serial_manager; RangeFinder sonar = RangeFinder::create(serial_manager, ROTATION_PITCH_270); - AP_AHRS_NavEKF ahrs{ins, barometer, gps, sonar, EKF2, EKF3, + AP_AHRS_NavEKF ahrs{ins, barometer, gps, EKF2, EKF3, AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF}; NavEKF2 EKF2{&ahrs, barometer, sonar}; NavEKF3 EKF3{&ahrs, barometer, sonar};