AP_NavEKF: Reduce recovery time after a GPS fusion timeout

This commit is contained in:
Paul Riseborough 2015-04-15 16:07:55 +10:00 committed by Randy Mackay
parent 0852aeab6e
commit 77d3798278

View File

@ -1988,6 +1988,8 @@ void NavEKF::FuseVelPosNED()
decayGpsOffset();
// reset the position to the current GPS position which will include the glitch correction offset
ResetPosition();
// reset the velocity to the GPS velocity
ResetVelocity();
// don't fuse data on this time step
fusePosData = false;
}