Browse Source

global: use static method to construct AP_NavEKF3

master
Lucas De Marchi 8 years ago committed by Francisco Ferreira
parent
commit
c9fbf7b722
  1. 2
      APMrover2/Rover.h
  2. 2
      AntennaTracker/Tracker.h
  3. 2
      ArduCopter/Copter.h
  4. 2
      ArduPlane/Plane.h
  5. 2
      ArduSub/Sub.h
  6. 2
      Tools/Replay/Replay.h
  7. 2
      libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp
  8. 2
      libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.cpp

2
APMrover2/Rover.h

@ -164,7 +164,7 @@ private: @@ -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};

2
AntennaTracker/Tracker.h

@ -117,7 +117,7 @@ private: @@ -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};

2
ArduCopter/Copter.h

@ -215,7 +215,7 @@ private: @@ -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

2
ArduPlane/Plane.h

@ -214,7 +214,7 @@ private: @@ -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};

2
ArduSub/Sub.h

@ -185,7 +185,7 @@ private: @@ -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

2
Tools/Replay/Replay.h

@ -65,7 +65,7 @@ public: @@ -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;

2
libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp

@ -27,7 +27,7 @@ class DummyVehicle { @@ -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};
};

2
libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.cpp

@ -30,7 +30,7 @@ public: @@ -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…
Cancel
Save