mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
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.
This commit is contained in:
parent
400dd94ec5
commit
6cbb9d635a
@ -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];
|
||||
|
Loading…
Reference in New Issue
Block a user