AP_NavEKF2: 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
7f11cf3ca6
commit
b7c4945000
@ -238,8 +238,7 @@ void NavEKF2_core::setAidingMode()
|
||||
maxLossTime_ms = frontend->posRetryTimeUseVel_ms;
|
||||
}
|
||||
posAidLossCritical = (imuSampleTime_ms - lastRngBcnPassTime_ms > maxLossTime_ms) &&
|
||||
(imuSampleTime_ms - lastPosPassTime_ms > maxLossTime_ms) &&
|
||||
(imuSampleTime_ms - lastVelPassTime_ms > maxLossTime_ms);
|
||||
(imuSampleTime_ms - lastPosPassTime_ms > maxLossTime_ms);
|
||||
}
|
||||
|
||||
if (attAidLossCritical) {
|
||||
|
Loading…
Reference in New Issue
Block a user