AP_NavEKF: changes to support to 20Hz flow fusion rate

This commit is contained in:
priseborough 2014-11-07 21:58:11 +11:00 committed by Andrew Tridgell
parent 715d64dce9
commit 5f941655a8

View File

@ -331,7 +331,7 @@ const AP_Param::GroupInfo NavEKF::var_info[] PROGMEM = {
// @Range: 0 - 500
// @Increment: 10
// @User: advanced
AP_GROUPINFO("FLOW_DELAY", 28, NavEKF, _msecFLowDelay, 20),
AP_GROUPINFO("FLOW_DELAY", 28, NavEKF, _msecFLowDelay, 10),
// @Param: RNG_GATE
// @DisplayName: Range finder measurement gate size
@ -397,7 +397,7 @@ NavEKF::NavEKF(const AP_AHRS *ahrs, AP_Baro &baro) :
_msecMagAvg = 100; // average number of msec between magnetometer measurements
_msecBetaAvg = 100; // average number of msec between synthetic sideslip measurements
_msecBetaMax = 200; // maximum number of msec between synthetic sideslip measurements
_msecFlowAvg = 100; // average number of msec between optical flow measurements
_msecFlowAvg = 50; // average number of msec between optical flow measurements
dtVelPos = 0.02; // number of seconds between position and velocity corrections. This should be a multiple of the imu update interval.
// Misc initial conditions