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:
priseborough 2017-03-04 21:44:19 +11:00 committed by Randy Mackay
parent b7c4945000
commit 7a8783f35e
1 changed files with 1 additions and 2 deletions

View File

@ -252,8 +252,7 @@ void NavEKF3_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) {