AP_NavEKF3: Make target covariance time step larger

The target covariance time step has been increased from 10 to 12 msec to improve conditioning of the covariance prediction calculation.
This commit is contained in:
priseborough 2017-05-21 12:15:06 +10:00 committed by Francisco Ferreira
parent 4c08622a7c
commit 628d140319
2 changed files with 3 additions and 3 deletions

View File

@ -353,7 +353,7 @@ void NavEKF3_core::readIMUData()
* than twice the target time has lapsed. Adjust the target EKF step time threshold to allow for timing jitter in the
* IMU data.
*/
if ((imuDataDownSampledNew.delAngDT >= (EKF_TARGET_DT-(dtIMUavg*0.5)) && startPredictEnabled) ||
if ((imuDataDownSampledNew.delAngDT >= (EKF_TARGET_DT-(dtIMUavg*0.5f)) && startPredictEnabled) ||
(imuDataDownSampledNew.delAngDT >= 2.0f*EKF_TARGET_DT)) {
// convert the accumulated quaternion to an equivalent delta angle

View File

@ -58,8 +58,8 @@
#define ACCEL_BIAS_LIM_SCALER 0.2f
// target update time for the EKF in msec and sec
#define EKF_TARGET_DT_MS 10.0
#define EKF_TARGET_DT 0.01
#define EKF_TARGET_DT_MS 12
#define EKF_TARGET_DT 0.012f
class AP_AHRS;