EKF2 output predictor update (#4606)

* ekf2: Update tuning parameter documentation

* ecl: update submodule reference

Enables selection of a new output predictor method
This commit is contained in:
Paul Riseborough
2016-05-27 16:36:37 +10:00
committed by Lorenz Meier
parent c08eec0a23
commit d4262bce2a
2 changed files with 3 additions and 4 deletions

View File

@@ -701,10 +701,9 @@ PARAM_DEFINE_FLOAT(EKF2_OF_POS_Y, 0.0f);
PARAM_DEFINE_FLOAT(EKF2_OF_POS_Z, 0.0f);
/**
* Time constant of the velocity output prediction and smoothing filter
* Time constant of the velocity output prediction and smoothing filter. Controls how tightly the velocity output tracks the EKF states. Set to a negative number to disable the EKF velocity state tracking. This will cause the output velocity to track the output position time derivative.
*
* @group EKF2
* @min 0.1
* @max 1.0
* @unit s
* @decimal 2
@@ -712,7 +711,7 @@ PARAM_DEFINE_FLOAT(EKF2_OF_POS_Z, 0.0f);
PARAM_DEFINE_FLOAT(EKF2_TAU_VEL, 0.5f);
/**
* Time constant of the position output prediction and smoothing filter
* Time constant of the position output prediction and smoothing filter. Controls how tightly the output track the EKF states.
*
* @group EKF2
* @min 0.1