AP_NavEKF2: Improve timing accuracy

This parameter is a compromise between numerical accuracy of the covariance prediction and sensor timing jitter
Further testing has shown that doing covariance prediction and sensor fusion every 10msec has no observable effect on fusion health and reduces timing hitter noise on magnetometer observations during high rate maneovures
This commit is contained in:
Paul Riseborough 2015-10-19 09:09:13 +11:00 committed by Andrew Tridgell
parent e0ed2dab63
commit a1d6c7ae1e
1 changed files with 1 additions and 1 deletions

View File

@ -402,7 +402,7 @@ NavEKF2::NavEKF2(const AP_AHRS *ahrs, AP_Baro &baro, const RangeFinder &rng) :
gndEffectTimeout_ms(1000), // time in msec that baro ground effect compensation will timeout after initiation
gndEffectBaroScaler(4.0f), // scaler applied to the barometer observation variance when operating in ground effect
gndGradientSigma(2), // RMS terrain gradient percentage assumed by the terrain height estimation
fusionTimeStep_ms(20) // The nominal number of msec between covariance prediction and fusion operations
fusionTimeStep_ms(10) // The nominal number of msec between covariance prediction and fusion operations
{
AP_Param::setup_object_defaults(this, var_info);
}