mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
AP_NavEKF: changes to support to 20Hz flow fusion rate
This commit is contained in:
parent
715d64dce9
commit
5f941655a8
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user