mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AP_NavEKF2: Fix one frame delay in processing yaw estimator velocity data
This commit is contained in:
parent
0ce4dd457d
commit
ccaa4d6aa9
@ -565,7 +565,7 @@ void NavEKF2_core::runYawEstimatorCorrection()
|
|||||||
if (gpsDataToFuse) {
|
if (gpsDataToFuse) {
|
||||||
Vector2f gpsVelNE = Vector2f(gpsDataDelayed.vel.x, gpsDataDelayed.vel.y);
|
Vector2f gpsVelNE = Vector2f(gpsDataDelayed.vel.x, gpsDataDelayed.vel.y);
|
||||||
float gpsVelAcc = fmaxf(gpsSpdAccuracy, frontend->_gpsHorizVelNoise);
|
float gpsVelAcc = fmaxf(gpsSpdAccuracy, frontend->_gpsHorizVelNoise);
|
||||||
yawEstimator->pushVelData(gpsVelNE, gpsVelAcc);
|
yawEstimator->fuseVelData(gpsVelNE, gpsVelAcc);
|
||||||
}
|
}
|
||||||
|
|
||||||
// action an external reset request
|
// action an external reset request
|
||||||
|
Loading…
Reference in New Issue
Block a user