diff --git a/libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp b/libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp index d793cf95cb..07e6c3390e 100644 --- a/libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp +++ b/libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp @@ -25,7 +25,7 @@ void AP_InertialNav_NavEKF::init() void AP_InertialNav_NavEKF::update(float dt) { AP_InertialNav::update(dt); - _ahrs.get_relative_position_NED(_relpos_cm); + _ahrs_ekf.get_NavEKF().getPosNED(_relpos_cm); _relpos_cm *= 100; // convert to cm _haveabspos = _ahrs.get_position(_abspos); diff --git a/libraries/AP_InertialNav/AP_InertialNav_NavEKF.h b/libraries/AP_InertialNav/AP_InertialNav_NavEKF.h index bf954db509..4f2170434b 100644 --- a/libraries/AP_InertialNav/AP_InertialNav_NavEKF.h +++ b/libraries/AP_InertialNav/AP_InertialNav_NavEKF.h @@ -14,9 +14,10 @@ class AP_InertialNav_NavEKF : public AP_InertialNav { public: // Constructor - AP_InertialNav_NavEKF(AP_AHRS &ahrs, AP_Baro &baro, GPS_Glitch& gps_glitch, Baro_Glitch& baro_glitch) : + AP_InertialNav_NavEKF(AP_AHRS_NavEKF &ahrs, AP_Baro &baro, GPS_Glitch& gps_glitch, Baro_Glitch& baro_glitch) : AP_InertialNav(ahrs, baro, gps_glitch, baro_glitch), - _haveabspos(false) + _haveabspos(false), + _ahrs_ekf(ahrs) { } @@ -113,6 +114,7 @@ private: Vector3f _velocity_cm; // NEU struct Location _abspos; bool _haveabspos; + AP_AHRS_NavEKF &_ahrs_ekf; }; #endif // __AP_INERTIALNAV_NAVEKF_H__