From 4b88b2ccec71a22d47603d7824b9988c2c87ef6d Mon Sep 17 00:00:00 2001 From: Paul Riseborough Date: Thu, 17 Jun 2021 19:35:32 +1000 Subject: [PATCH] AP_NavEKF3: Remove unwanted line --- libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp index b153010a84..0e9d06e824 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp @@ -711,7 +711,6 @@ void NavEKF3_core::FuseVelPosNED() // Always fuse data if bad IMU to prevent aliasing and clipping pulling the state estimate away // from the measurement un-opposed if test threshold is exceeded. if (posCheckPassed || posTimeout || badIMUdata) { - posCheckPassed = true; lastPosPassTime_ms = imuSampleTime_ms; // if timed out or outside the specified uncertainty radius, reset to the external sensor if (posTimeout || ((P[8][8] + P[7][7]) > sq(float(frontend->_gpsGlitchRadiusMax)))) {