AP_NavEKF: Fixed bug in pos/vel/hgt reset on timout

This commit is contained in:
Paul Riseborough 2014-01-24 16:04:42 +11:00 committed by Andrew Tridgell
parent f74cce8b4e
commit 28fb5e364b
1 changed files with 3 additions and 0 deletions

View File

@ -1584,6 +1584,7 @@ void NavEKF::FuseVelPosNED()
if (velTimeout) if (velTimeout)
{ {
ResetVelocity(); ResetVelocity();
fuseVelData = false;
} }
} }
@ -1609,6 +1610,7 @@ void NavEKF::FuseVelPosNED()
if (posTimeout) if (posTimeout)
{ {
ResetPosition(); ResetPosition();
fusePosData = false;
} }
} }
else else
@ -1636,6 +1638,7 @@ void NavEKF::FuseVelPosNED()
if (hgtTimeout) if (hgtTimeout)
{ {
ResetHeight(); ResetHeight();
fuseHgtData = false;
} }
} }
else else