diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp index c2e579133f..b9df57602e 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp @@ -664,10 +664,6 @@ void NavEKF3_core::readGpsData() hal.util->snprintf(prearm_fail_string, sizeof(prearm_fail_string), "Waiting for 3D fix"); } } - - // get data that has now fallen behind the fusion time horizon - gpsDataToFuse = storedGPS.recall(gpsDataDelayed,imuDataDelayed.time_ms); - } // read the delta angle and corresponding time interval from the IMU diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp index 9d6d327e3a..5bd3897a9d 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp @@ -284,6 +284,12 @@ void NavEKF3_core::SelectVelPosFusion() posVelFusionDelayed = false; } + // Read GPS data from the sensor + readGpsData(); + + // get data that has now fallen behind the fusion time horizon + gpsDataToFuse = storedGPS.recall(gpsDataDelayed,imuDataDelayed.time_ms); + // Determine if we need to fuse position and velocity data on this time step if (gpsDataToFuse && PV_AidingMode == AID_ABSOLUTE) { diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp index 2fcdb05689..3c092bc0df 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp @@ -631,20 +631,21 @@ void NavEKF3_core::UpdateFilter(bool predict) // Predict the covariance growth CovariancePrediction(); - // Read GPS data from the sensor - // This is required by multiple processes so needs to be done before other fusion steps - readGpsData(); - - // Generate an alternative yaw estimate used for inflight recovery from bad compass data - // requires horizontal GPS velocity - runYawEstimator(); - // Update states using magnetometer or external yaw sensor data SelectMagFusion(); // Update states using GPS and altimeter data SelectVelPosFusion(); + // Generate an alternative yaw estimate used for inflight + // recovery from bad compass data requires horizontal GPS + // velocity. We only do this when posVelFusionDelayed is false + // as otherwise there will be no new GPS data, as the + // sttoredGPS recall will have been skipped + if (!posVelFusionDelayed) { + runYawEstimator(); + } + // Update states using range beacon data SelectRngBcnFusion();