mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_NavEKF: Ensure Covariance initialisation uses correct IMU time step
This commit is contained in:
parent
5dc29699ab
commit
c4c0f819b5
@ -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;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user