AP_NavEKF3: Fix one frame delay in processing yaw estimator velocity data

This commit is contained in:
Paul Riseborough 2020-04-25 07:52:52 +10:00 committed by Peter Barker
parent ccaa4d6aa9
commit bcd23e1063
1 changed files with 1 additions and 1 deletions

View File

@ -632,7 +632,7 @@ void NavEKF3_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