From ed25c85d21c38cd18bd5282d172150a1969002e4 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 23 Sep 2015 10:35:02 +1000 Subject: [PATCH] AP_AHRS: added NavEKF2 to constructor --- libraries/AP_AHRS/AP_AHRS_NavEKF.h | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/libraries/AP_AHRS/AP_AHRS_NavEKF.h b/libraries/AP_AHRS/AP_AHRS_NavEKF.h index 497e08af25..395f242656 100644 --- a/libraries/AP_AHRS/AP_AHRS_NavEKF.h +++ b/libraries/AP_AHRS/AP_AHRS_NavEKF.h @@ -26,6 +26,7 @@ #if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 #include +#include #define AP_AHRS_NAVEKF_AVAILABLE 1 #define AP_AHRS_NAVEKF_SETTLE_TIME_MS 20000 // time in milliseconds the ekf needs to settle after being started @@ -34,9 +35,11 @@ class AP_AHRS_NavEKF : public AP_AHRS_DCM { public: // Constructor -AP_AHRS_NavEKF(AP_InertialSensor &ins, AP_Baro &baro, AP_GPS &gps, RangeFinder &rng, NavEKF &_EKF) : +AP_AHRS_NavEKF(AP_InertialSensor &ins, AP_Baro &baro, AP_GPS &gps, RangeFinder &rng, + NavEKF &_EKF, NavEKF2 &_EKF2) : AP_AHRS_DCM(ins, baro, gps), EKF(_EKF), + EKF2(_EKF2), ekf_started(false), startup_delay_ms(1000), start_time_ms(0) @@ -131,6 +134,7 @@ private: bool using_EKF(void) const; NavEKF &EKF; + NavEKF2 &EKF2; bool ekf_started; Matrix3f _dcm_matrix; Vector3f _dcm_attitude;