AP_NavEKF: Always check for new GPS data

This fixes a bug that meant that once the EKF had started up in a non-GPS mode, it would no longer read the GPS and therefore would never be able to use GPS again until reset.
This commit is contained in:
priseborough 2015-01-28 15:24:10 +11:00 committed by Randy Mackay
parent 00758a3e91
commit 2c012c2763

View File

@ -737,11 +737,11 @@ void NavEKF::UpdateFilter()
// select fusion of velocity, position and height measurements
void NavEKF::SelectVelPosFusion()
{
// check for new data, specify which measurements should be used and check data for freshness
if (PV_AidingMode == AID_ABSOLUTE) {
// check for and read new GPS data
readGpsData();
// check for and read new GPS data
readGpsData();
// Specify which measurements should be used and check data for freshness
if (PV_AidingMode == AID_ABSOLUTE) {
// check if we can use opticalflow as a backup
bool optFlowBackup = (flowDataValid && !hgtTimeout);