Browse Source

global: use static method to construct AP_AHRS_NavEKF

mission-4.1.18
Lucas De Marchi 8 years ago committed by Francisco Ferreira
parent
commit
beabae6a98
  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. 6
      libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp
  8. 4
      libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.cpp

2
APMrover2/Rover.h

@ -165,7 +165,7 @@ private:
#if AP_AHRS_NAVEKF_AVAILABLE #if AP_AHRS_NAVEKF_AVAILABLE
NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, rangefinder); NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, rangefinder);
NavEKF3 EKF3 = NavEKF3::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 #else
AP_AHRS_DCM ahrs {ins, barometer, gps}; AP_AHRS_DCM ahrs {ins, barometer, gps};
#endif #endif

2
AntennaTracker/Tracker.h

@ -118,7 +118,7 @@ private:
#if AP_AHRS_NAVEKF_AVAILABLE #if AP_AHRS_NAVEKF_AVAILABLE
NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, rng); NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, rng);
NavEKF3 EKF3 = NavEKF3::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 #else
AP_AHRS_DCM ahrs{ins, barometer, gps}; AP_AHRS_DCM ahrs{ins, barometer, gps};
#endif #endif

2
ArduCopter/Copter.h

@ -216,7 +216,7 @@ private:
// Inertial Navigation EKF // Inertial Navigation EKF
NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, rangefinder); NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, rangefinder);
NavEKF3 EKF3 = NavEKF3::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 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
SITL::SITL sitl; SITL::SITL sitl;

2
ArduPlane/Plane.h

@ -215,7 +215,7 @@ private:
#if AP_AHRS_NAVEKF_AVAILABLE #if AP_AHRS_NAVEKF_AVAILABLE
NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, rangefinder); NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, rangefinder);
NavEKF3 EKF3 = NavEKF3::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 #else
AP_AHRS_DCM ahrs {ins, barometer, gps}; AP_AHRS_DCM ahrs {ins, barometer, gps};
#endif #endif

2
ArduSub/Sub.h

@ -186,7 +186,7 @@ private:
// Inertial Navigation EKF // Inertial Navigation EKF
NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, rangefinder); NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, rangefinder);
NavEKF3 EKF3 = NavEKF3::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 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
SITL::SITL sitl; SITL::SITL sitl;

2
Tools/Replay/Replay.h

@ -66,7 +66,7 @@ public:
RangeFinder rng = RangeFinder::create(serial_manager, ROTATION_PITCH_270); RangeFinder rng = RangeFinder::create(serial_manager, ROTATION_PITCH_270);
NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, rng); NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, rng);
NavEKF3 EKF3 = NavEKF3::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_InertialNav_NavEKF inertial_nav{ahrs};
AP_Vehicle::FixedWing aparm; AP_Vehicle::FixedWing aparm;
AP_Airspeed airspeed; AP_Airspeed airspeed;

6
libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp

@ -28,15 +28,15 @@ public:
RangeFinder sonar = RangeFinder::create(serial_manager, ROTATION_PITCH_270); RangeFinder sonar = RangeFinder::create(serial_manager, ROTATION_PITCH_270);
NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, sonar); NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, sonar);
NavEKF3 EKF3 = NavEKF3::create(&ahrs, barometer, sonar); NavEKF3 EKF3 = NavEKF3::create(&ahrs, barometer, sonar);
AP_AHRS_NavEKF ahrs{ins, barometer, gps, EKF2, EKF3, AP_AHRS_NavEKF ahrs = AP_AHRS_NavEKF::create(ins, barometer, gps, EKF2, EKF3,
AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF}; AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF);
}; };
static DummyVehicle vehicle; static DummyVehicle vehicle;
// choose which AHRS system to use // choose which AHRS system to use
// AP_AHRS_DCM ahrs(ins, baro, gps); // AP_AHRS_DCM ahrs(ins, baro, gps);
AP_AHRS_NavEKF ahrs(vehicle.ahrs); AP_AHRS_NavEKF &ahrs = vehicle.ahrs;
void setup(void) void setup(void)
{ {

4
libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.cpp

@ -27,8 +27,8 @@ public:
AP_InertialSensor ins = AP_InertialSensor::create(); AP_InertialSensor ins = AP_InertialSensor::create();
AP_SerialManager serial_manager = AP_SerialManager::create(); AP_SerialManager serial_manager = AP_SerialManager::create();
RangeFinder sonar = RangeFinder::create(serial_manager, ROTATION_PITCH_270); RangeFinder sonar = RangeFinder::create(serial_manager, ROTATION_PITCH_270);
AP_AHRS_NavEKF ahrs{ins, barometer, gps, EKF2, EKF3, AP_AHRS_NavEKF ahrs = AP_AHRS_NavEKF::create(ins, barometer, gps, EKF2, EKF3,
AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF}; AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF);
NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, sonar); NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, sonar);
NavEKF3 EKF3 = NavEKF3::create(&ahrs, barometer, sonar); NavEKF3 EKF3 = NavEKF3::create(&ahrs, barometer, sonar);
}; };

Loading…
Cancel
Save