mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_NavEKF3: Fix one frame delay in processing yaw estimator velocity data
This commit is contained in:
parent
ccaa4d6aa9
commit
bcd23e1063
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user