From 28fb5e364b95e8b9c8243687c328dea3a6598d26 Mon Sep 17 00:00:00 2001 From: Paul Riseborough Date: Fri, 24 Jan 2014 16:04:42 +1100 Subject: [PATCH] AP_NavEKF: Fixed bug in pos/vel/hgt reset on timout --- libraries/AP_NavEKF/AP_NavEKF.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/AP_NavEKF/AP_NavEKF.cpp b/libraries/AP_NavEKF/AP_NavEKF.cpp index a10eb5a55b..be6ac0580d 100644 --- a/libraries/AP_NavEKF/AP_NavEKF.cpp +++ b/libraries/AP_NavEKF/AP_NavEKF.cpp @@ -1584,6 +1584,7 @@ void NavEKF::FuseVelPosNED() if (velTimeout) { ResetVelocity(); + fuseVelData = false; } } @@ -1609,6 +1610,7 @@ void NavEKF::FuseVelPosNED() if (posTimeout) { ResetPosition(); + fusePosData = false; } } else @@ -1636,6 +1638,7 @@ void NavEKF::FuseVelPosNED() if (hgtTimeout) { ResetHeight(); + fuseHgtData = false; } } else