From ccaa4d6aa9aa70f41fe93e613073553e74fcef51 Mon Sep 17 00:00:00 2001 From: Paul Riseborough Date: Sat, 25 Apr 2020 07:52:45 +1000 Subject: [PATCH] AP_NavEKF2: Fix one frame delay in processing yaw estimator velocity data --- libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp index 4412a2f4a8..8aae61fd4f 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp @@ -565,7 +565,7 @@ void NavEKF2_core::runYawEstimatorCorrection() if (gpsDataToFuse) { Vector2f gpsVelNE = Vector2f(gpsDataDelayed.vel.x, gpsDataDelayed.vel.y); float gpsVelAcc = fmaxf(gpsSpdAccuracy, frontend->_gpsHorizVelNoise); - yawEstimator->pushVelData(gpsVelNE, gpsVelAcc); + yawEstimator->fuseVelData(gpsVelNE, gpsVelAcc); } // action an external reset request