mirror of https://github.com/ArduPilot/ardupilot
global: use static method to construct AP_NavEKF3
This commit is contained in:
parent
bd6145af6d
commit
c9fbf7b722
|
@ -164,7 +164,7 @@ private:
|
|||
// Inertial Navigation EKF
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, rangefinder);
|
||||
NavEKF3 EKF3{&ahrs, barometer, rangefinder};
|
||||
NavEKF3 EKF3 = NavEKF3::create(&ahrs, barometer, rangefinder);
|
||||
AP_AHRS_NavEKF ahrs {ins, barometer, gps, EKF2, EKF3};
|
||||
#else
|
||||
AP_AHRS_DCM ahrs {ins, barometer, gps};
|
||||
|
|
|
@ -117,7 +117,7 @@ private:
|
|||
// Inertial Navigation EKF
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, rng);
|
||||
NavEKF3 EKF3{&ahrs, barometer, rng};
|
||||
NavEKF3 EKF3 = NavEKF3::create(&ahrs, barometer, rng);
|
||||
AP_AHRS_NavEKF ahrs{ins, barometer, gps, EKF2, EKF3};
|
||||
#else
|
||||
AP_AHRS_DCM ahrs{ins, barometer, gps};
|
||||
|
|
|
@ -215,7 +215,7 @@ private:
|
|||
|
||||
// Inertial Navigation EKF
|
||||
NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, rangefinder);
|
||||
NavEKF3 EKF3{&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};
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
|
|
|
@ -214,7 +214,7 @@ private:
|
|||
// Inertial Navigation EKF
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, rangefinder);
|
||||
NavEKF3 EKF3{&ahrs, barometer, rangefinder};
|
||||
NavEKF3 EKF3 = NavEKF3::create(&ahrs, barometer, rangefinder);
|
||||
AP_AHRS_NavEKF ahrs {ins, barometer, gps, EKF2, EKF3};
|
||||
#else
|
||||
AP_AHRS_DCM ahrs {ins, barometer, gps};
|
||||
|
|
|
@ -185,7 +185,7 @@ private:
|
|||
|
||||
// Inertial Navigation EKF
|
||||
NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, rangefinder);
|
||||
NavEKF3 EKF3 {&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};
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
|
|
|
@ -65,7 +65,7 @@ public:
|
|||
AP_SerialManager serial_manager = AP_SerialManager::create();
|
||||
RangeFinder rng = RangeFinder::create(serial_manager, ROTATION_PITCH_270);
|
||||
NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, rng);
|
||||
NavEKF3 EKF3{&ahrs, barometer, rng};
|
||||
NavEKF3 EKF3 = NavEKF3::create(&ahrs, barometer, rng);
|
||||
AP_AHRS_NavEKF ahrs {ins, barometer, gps, EKF2, EKF3};
|
||||
AP_InertialNav_NavEKF inertial_nav{ahrs};
|
||||
AP_Vehicle::FixedWing aparm;
|
||||
|
|
|
@ -27,7 +27,7 @@ class DummyVehicle {
|
|||
public:
|
||||
RangeFinder sonar = RangeFinder::create(serial_manager, ROTATION_PITCH_270);
|
||||
NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, sonar);
|
||||
NavEKF3 EKF3{&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};
|
||||
};
|
||||
|
|
|
@ -30,7 +30,7 @@ public:
|
|||
AP_AHRS_NavEKF ahrs{ins, barometer, gps, EKF2, EKF3,
|
||||
AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF};
|
||||
NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, sonar);
|
||||
NavEKF3 EKF3{&ahrs, barometer, sonar};
|
||||
NavEKF3 EKF3 = NavEKF3::create(&ahrs, barometer, sonar);
|
||||
};
|
||||
|
||||
static DummyVehicle vehicle;
|
||||
|
|
Loading…
Reference in New Issue