AP_NavEKF3: remove duplicate assignment of posCheckPassed

this assignment is done 4 lines down

../../libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp:823:17: warning: Value stored to 'posCheckPassed' is never read [deadcode.DeadStores]
                posCheckPassed = true;
                ^                ~~~~
This commit is contained in:
Peter Barker 2025-02-24 12:30:31 +11:00 committed by Peter Barker
parent 6a77d56053
commit cfa145940a

View File

@ -820,7 +820,6 @@ void NavEKF3_core::FuseVelPosNED()
// Handle the special case where the glitch radius parameter has been set to a non-positive number.
// The innovation variance is increased to limit the state update to an amount corresponding
// to a test ratio of 1.
posCheckPassed = true;
lastGpsPosPassTime_ms = imuSampleTime_ms;
varInnovVelPos[3] *= posTestRatio;
varInnovVelPos[4] *= posTestRatio;