Browse Source

AP_NavEKF: Correctly report position timeout when GPS is lost

mission-4.1.18
priseborough 10 years ago committed by Andrew Tridgell
parent
commit
1789dc08a3
  1. 5
      libraries/AP_NavEKF/AP_NavEKF.cpp

5
libraries/AP_NavEKF/AP_NavEKF.cpp

@ -1928,7 +1928,10 @@ void NavEKF::FuseVelPosNED() @@ -1928,7 +1928,10 @@ void NavEKF::FuseVelPosNED()
// use position data if healthy, timed out, or in constant position mode
if (posHealth || posTimeout || constPosMode) {
posHealth = true;
posFailTime = imuSampleTime_ms;
// We don't reset the failed time if we are in constant position mode
if (!constPosMode) {
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 (posTimeout || (maxPosInnov2 > sq(float(_gpsGlitchRadiusMax)))) {
gpsPosGlitchOffsetNE.x += posInnov[0];

Loading…
Cancel
Save