AP_NavEKF: Ensure Covariance initialisation uses correct IMU time step

This commit is contained in:
Paul Riseborough 2015-04-20 21:34:25 +10:00 committed by Randy Mackay
parent 5dc29699ab
commit c4c0f819b5
1 changed files with 6 additions and 6 deletions

View File

@ -575,15 +575,15 @@ bool NavEKF::InitialiseFilterDynamic(void)
// set to true now that states have be initialised
statesInitialised = true;
// initialise the covariance matrix
CovarianceInit();
// define Earth rotation vector in the NED navigation frame
calcEarthRateNED(earthRateNED, _ahrs->get_home().lat);
// initialise IMU pre-processing states
readIMUData();
// initialise the covariance matrix
CovarianceInit();
return true;
}
@ -662,15 +662,15 @@ bool NavEKF::InitialiseFilterBootstrap(void)
// set to true now we have intialised the states
statesInitialised = true;
// initialise the covariance matrix
CovarianceInit();
// define Earth rotation vector in the NED navigation frame
calcEarthRateNED(earthRateNED, _ahrs->get_home().lat);
// initialise IMU pre-processing states
readIMUData();
// initialise the covariance matrix
CovarianceInit();
return true;
}