mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: Update output filter tuning
Updated tuning to take advantage of corrected time delta dtEkfAvg
This commit is contained in:
parent
55dee347e0
commit
a49c16d63c
|
@ -455,10 +455,10 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = {
|
|||
// @Param: TAU_OUTPUT
|
||||
// @DisplayName: Output complementary filter time constant (centi-sec)
|
||||
// @Description: Sets the time constant of the output complementary filter/predictor in centi-seconds.
|
||||
// @Range: 5 30
|
||||
// @Range: 10 50
|
||||
// @Increment: 5
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("TAU_OUTPUT", 39, NavEKF2, _tauVelPosOutput, 20),
|
||||
AP_GROUPINFO("TAU_OUTPUT", 39, NavEKF2, _tauVelPosOutput, 25),
|
||||
|
||||
// @Param: MAGE_P_NSE
|
||||
// @DisplayName: Earth magnetic field process noise (gauss/s)
|
||||
|
|
|
@ -652,8 +652,8 @@ void NavEKF2_core::calcOutputStates()
|
|||
float velPosGain = dtEkfAvg / constrain_float(tauPosVel, dtEkfAvg, 10.0f);
|
||||
|
||||
// use a PI feedback to calculate a correction that will be applied to the output state history
|
||||
posCorrection += posDelta * velPosGain; // I term
|
||||
velCorrection += velDelta * velPosGain; // I term
|
||||
posCorrection += posDelta * velPosGain * 0.9f; // I term
|
||||
velCorrection += velDelta * velPosGain * 0.9f; // I term
|
||||
velDelta *= velPosGain; // P term
|
||||
posDelta *= velPosGain; // P term
|
||||
|
||||
|
|
Loading…
Reference in New Issue