mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_NavEKF: Bypass GPS glitch logic when not aiding
When we are not using GPS measurements, we should not be allowing the GPS glitch logic to reset position states as this can interfere with operation of non GPS modes.
This commit is contained in:
parent
5c8e71a8d1
commit
12c3368c4d
@ -1939,7 +1939,6 @@ void NavEKF::FuseVelPosNED()
|
|||||||
// only reset the failed time and do glitch timeout checks if we are doing full aiding
|
// only reset the failed time and do glitch timeout checks if we are doing full aiding
|
||||||
if (PV_AidingMode == AID_ABSOLUTE) {
|
if (PV_AidingMode == AID_ABSOLUTE) {
|
||||||
posFailTime = imuSampleTime_ms;
|
posFailTime = imuSampleTime_ms;
|
||||||
}
|
|
||||||
// if timed out or outside the specified glitch radius, increment the offset applied to GPS data to compensate for large GPS position jumps
|
// if timed out or outside the specified glitch radius, increment the offset applied to GPS data to compensate for large GPS position jumps
|
||||||
if (posTimeout || (maxPosInnov2 > sq(float(_gpsGlitchRadiusMax)))) {
|
if (posTimeout || (maxPosInnov2 > sq(float(_gpsGlitchRadiusMax)))) {
|
||||||
gpsPosGlitchOffsetNE.x += posInnov[0];
|
gpsPosGlitchOffsetNE.x += posInnov[0];
|
||||||
@ -1951,6 +1950,7 @@ void NavEKF::FuseVelPosNED()
|
|||||||
// don't fuse data on this time step
|
// don't fuse data on this time step
|
||||||
fusePosData = false;
|
fusePosData = false;
|
||||||
}
|
}
|
||||||
|
}
|
||||||
} else {
|
} else {
|
||||||
posHealth = false;
|
posHealth = false;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user