mirror of https://github.com/ArduPilot/ardupilot
global: use static method to construct AP_NavEKF2
This commit is contained in:
parent
3c04f4e4d1
commit
e2fe36357a
|
@ -163,7 +163,7 @@ private:
|
|||
|
||||
// Inertial Navigation EKF
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
NavEKF2 EKF2{&ahrs, barometer, rangefinder};
|
||||
NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, rangefinder);
|
||||
NavEKF3 EKF3{&ahrs, barometer, rangefinder};
|
||||
AP_AHRS_NavEKF ahrs {ins, barometer, gps, EKF2, EKF3};
|
||||
#else
|
||||
|
|
|
@ -116,7 +116,7 @@ private:
|
|||
|
||||
// Inertial Navigation EKF
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
NavEKF2 EKF2{&ahrs, barometer, rng};
|
||||
NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, rng);
|
||||
NavEKF3 EKF3{&ahrs, barometer, rng};
|
||||
AP_AHRS_NavEKF ahrs{ins, barometer, gps, EKF2, EKF3};
|
||||
#else
|
||||
|
|
|
@ -214,7 +214,7 @@ private:
|
|||
AP_RPM rpm_sensor = AP_RPM::create();
|
||||
|
||||
// Inertial Navigation EKF
|
||||
NavEKF2 EKF2{&ahrs, barometer, rangefinder};
|
||||
NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, rangefinder);
|
||||
NavEKF3 EKF3{&ahrs, barometer, rangefinder};
|
||||
AP_AHRS_NavEKF ahrs{ins, barometer, gps, EKF2, EKF3, AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF};
|
||||
|
||||
|
|
|
@ -213,7 +213,7 @@ private:
|
|||
|
||||
// Inertial Navigation EKF
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
NavEKF2 EKF2{&ahrs, barometer, rangefinder};
|
||||
NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, rangefinder);
|
||||
NavEKF3 EKF3{&ahrs, barometer, rangefinder};
|
||||
AP_AHRS_NavEKF ahrs {ins, barometer, gps, EKF2, EKF3};
|
||||
#else
|
||||
|
|
|
@ -184,7 +184,7 @@ private:
|
|||
#endif
|
||||
|
||||
// Inertial Navigation EKF
|
||||
NavEKF2 EKF2 {&ahrs, barometer, rangefinder};
|
||||
NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, rangefinder);
|
||||
NavEKF3 EKF3 {&ahrs, barometer, rangefinder};
|
||||
AP_AHRS_NavEKF ahrs {ins, barometer, gps, EKF2, EKF3, AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF};
|
||||
|
||||
|
|
|
@ -64,7 +64,7 @@ public:
|
|||
Compass compass = Compass::create();
|
||||
AP_SerialManager serial_manager = AP_SerialManager::create();
|
||||
RangeFinder rng = RangeFinder::create(serial_manager, ROTATION_PITCH_270);
|
||||
NavEKF2 EKF2{&ahrs, barometer, rng};
|
||||
NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, rng);
|
||||
NavEKF3 EKF3{&ahrs, barometer, rng};
|
||||
AP_AHRS_NavEKF ahrs {ins, barometer, gps, EKF2, EKF3};
|
||||
AP_InertialNav_NavEKF inertial_nav{ahrs};
|
||||
|
|
|
@ -26,7 +26,7 @@ static AP_SerialManager serial_manager = AP_SerialManager::create();
|
|||
class DummyVehicle {
|
||||
public:
|
||||
RangeFinder sonar = RangeFinder::create(serial_manager, ROTATION_PITCH_270);
|
||||
NavEKF2 EKF2{&ahrs, barometer, sonar};
|
||||
NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, sonar);
|
||||
NavEKF3 EKF3{&ahrs, barometer, sonar};
|
||||
AP_AHRS_NavEKF ahrs{ins, barometer, gps, EKF2, EKF3,
|
||||
AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF};
|
||||
|
|
|
@ -29,7 +29,7 @@ public:
|
|||
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};
|
||||
NavEKF2 EKF2{&ahrs, barometer, sonar};
|
||||
NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, sonar);
|
||||
NavEKF3 EKF3{&ahrs, barometer, sonar};
|
||||
};
|
||||
|
||||
|
|
Loading…
Reference in New Issue