mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: Fix bug preventing reset to GPS
This fixes a bug that prevented the reset to the GPS position occurring if GPS velocity observations were still passing innovation consistency checks.
This commit is contained in:
parent
b7c4945000
commit
7a8783f35e
|
@ -252,8 +252,7 @@ void NavEKF3_core::setAidingMode()
|
||||||
maxLossTime_ms = frontend->posRetryTimeUseVel_ms;
|
maxLossTime_ms = frontend->posRetryTimeUseVel_ms;
|
||||||
}
|
}
|
||||||
posAidLossCritical = (imuSampleTime_ms - lastRngBcnPassTime_ms > maxLossTime_ms) &&
|
posAidLossCritical = (imuSampleTime_ms - lastRngBcnPassTime_ms > maxLossTime_ms) &&
|
||||||
(imuSampleTime_ms - lastPosPassTime_ms > maxLossTime_ms) &&
|
(imuSampleTime_ms - lastPosPassTime_ms > maxLossTime_ms);
|
||||||
(imuSampleTime_ms - lastVelPassTime_ms > maxLossTime_ms);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
if (attAidLossCritical) {
|
if (attAidLossCritical) {
|
||||||
|
|
Loading…
Reference in New Issue