mirror of https://github.com/ArduPilot/ardupilot
global: remove rangefinder from AP_AHRS_NavEKF
AP_AHRS_NavEKF doesn't use the rangefinder, it just delegates the calls to the right estimator. For libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp the initialization order has also been modified to match the order on vehicles. It's more correct since it passes a reference when EKF2/EKF3 are already constructed, while thos constructors use a pointer. Ideally these should be moved to an init() method though, or use a get_instance().
This commit is contained in:
parent
9027a55696
commit
40fd1b346c
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -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),
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -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};
|
||||
|
|
Loading…
Reference in New Issue