From 6cbb9d635abf03324b00e7c255dcde74712f60af Mon Sep 17 00:00:00 2001 From: priseborough Date: Fri, 3 Oct 2014 05:51:24 +1000 Subject: [PATCH] AP_NavEKF : Fix bug in reset of GPS glitch offset The GPS glitch offset was being zeroed during position resets. This caused the filter to reject subsequent GPS measurements if the GPS error persisted long enough to invoke a timeout and a position reset. --- libraries/AP_NavEKF/AP_NavEKF.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/libraries/AP_NavEKF/AP_NavEKF.cpp b/libraries/AP_NavEKF/AP_NavEKF.cpp index 4274316926..26b303b1cd 100644 --- a/libraries/AP_NavEKF/AP_NavEKF.cpp +++ b/libraries/AP_NavEKF/AP_NavEKF.cpp @@ -411,8 +411,6 @@ void NavEKF::ResetPosition(void) state.position.x = gpsPosNE.x + gpsPosGlitchOffsetNE.x + 0.001f*velNED.x*float(_msecPosDelay); state.position.y = gpsPosNE.y + gpsPosGlitchOffsetNE.y + 0.001f*velNED.y*float(_msecPosDelay); } - // reset the glitch ofset correction states - gpsPosGlitchOffsetNE.zero(); // stored horizontal position states to prevent subsequent GPS measurements from being rejected for (uint8_t i=0; i<=49; i++){ storedStates[i].position[0] = state.position[0];