From 31c256bdd8e8236613a817f627dd573aafe75f59 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 9 Oct 2014 16:43:24 +0900 Subject: [PATCH] AP_InertialNav: fixed use of ahrs.get_velocity with EKF disabled --- libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp b/libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp index 07e6c3390e..585c82f873 100644 --- a/libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp +++ b/libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp @@ -30,7 +30,7 @@ void AP_InertialNav_NavEKF::update(float dt) _haveabspos = _ahrs.get_position(_abspos); - _ahrs.get_velocity_NED(_velocity_cm); + _ahrs_ekf.get_NavEKF().getVelNED(_velocity_cm); _velocity_cm *= 100; // convert to cm/s // InertialNav is NEU