ekf2: Update tuning parameters

Remove unused gyro scale factor parameter
Change gyro and accelerometer bias noise parameters to more intuitive units
Updated tuning defaults
This commit is contained in:
Paul Riseborough
2016-05-09 09:38:10 +10:00
committed by Lorenz Meier
parent 7f1632d65b
commit 2c6b7a008f
2 changed files with 23 additions and 35 deletions
-2
View File
@@ -176,7 +176,6 @@ private:
// process noise
control::BlockParamFloat _gyro_bias_p_noise;
control::BlockParamFloat _accel_bias_p_noise;
control::BlockParamFloat _gyro_scale_p_noise;
control::BlockParamFloat _mage_p_noise;
control::BlockParamFloat _magb_p_noise;
control::BlockParamFloat _wind_vel_p_noise;
@@ -275,7 +274,6 @@ Ekf2::Ekf2():
_accel_noise(this, "EKF2_ACC_NOISE", false, &_params->accel_noise),
_gyro_bias_p_noise(this, "EKF2_GYR_B_NOISE", false, &_params->gyro_bias_p_noise),
_accel_bias_p_noise(this, "EKF2_ACC_B_NOISE", false, &_params->accel_bias_p_noise),
_gyro_scale_p_noise(this, "EKF2_GYR_S_NOISE", false, &_params->gyro_scale_p_noise),
_mage_p_noise(this, "EKF2_MAG_E_NOISE", false, &_params->mage_p_noise),
_magb_p_noise(this, "EKF2_MAG_B_NOISE", false, &_params->magb_p_noise),
_wind_vel_p_noise(this, "EKF2_WIND_NOISE", false, &_params->wind_vel_p_noise),
+23 -33
View File
@@ -211,7 +211,7 @@ PARAM_DEFINE_FLOAT(EKF2_REQ_VDRIFT, 0.5f);
* @unit rad/s
* @decimal 4
*/
PARAM_DEFINE_FLOAT(EKF2_GYR_NOISE, 6.0e-2f);
PARAM_DEFINE_FLOAT(EKF2_GYR_NOISE, 1.5e-2f);
/**
* Accelerometer noise for covariance prediction.
@@ -222,39 +222,29 @@ PARAM_DEFINE_FLOAT(EKF2_GYR_NOISE, 6.0e-2f);
* @unit m/s/s
* @decimal 2
*/
PARAM_DEFINE_FLOAT(EKF2_ACC_NOISE, 0.25f);
PARAM_DEFINE_FLOAT(EKF2_ACC_NOISE, 3.5e-1f);
/**
* Process noise for delta angle bias prediction.
*
* @group EKF2
* @min 0.0
* @max 0.0001
* @unit rad/s
* @decimal 8
*/
PARAM_DEFINE_FLOAT(EKF2_GYR_B_NOISE, 2.5e-6f);
/**
* Process noise for delta velocity z bias prediction.
*
* @group EKF2
* @min 0.0
* @max 0.01
* @unit m/s/s
* @decimal 7
*/
PARAM_DEFINE_FLOAT(EKF2_ACC_B_NOISE, 3.0e-5f);
/**
* Process noise for delta angle scale factor prediction.
* Process noise for IMU rate gyro bias prediction.
*
* @group EKF2
* @min 0.0
* @max 0.01
* @unit rad/s**2
* @decimal 6
*/
PARAM_DEFINE_FLOAT(EKF2_GYR_S_NOISE, 3.0e-4f);
PARAM_DEFINE_FLOAT(EKF2_GYR_B_NOISE, 1.0e-3f);
/**
* Process noise for IMU accelerometer bias prediction.
*
* @group EKF2
* @min 0.0
* @max 0.01
* @unit m/s**3
* @decimal 6
*/
PARAM_DEFINE_FLOAT(EKF2_ACC_B_NOISE, 3.0e-3f);
/**
* Process noise for body magnetic field prediction.
@@ -265,7 +255,7 @@ PARAM_DEFINE_FLOAT(EKF2_GYR_S_NOISE, 3.0e-4f);
* @unit Gauss/s
* @decimal 6
*/
PARAM_DEFINE_FLOAT(EKF2_MAG_B_NOISE, 5.0e-4f);
PARAM_DEFINE_FLOAT(EKF2_MAG_B_NOISE, 1.0e-4f);
/**
* Process noise for earth magnetic field prediction.
@@ -276,7 +266,7 @@ PARAM_DEFINE_FLOAT(EKF2_MAG_B_NOISE, 5.0e-4f);
* @unit Gauss/s
* @decimal 6
*/
PARAM_DEFINE_FLOAT(EKF2_MAG_E_NOISE, 2.5e-3f);
PARAM_DEFINE_FLOAT(EKF2_MAG_E_NOISE, 1.0e-3f);
/**
* Process noise for wind velocity prediction.
@@ -331,7 +321,7 @@ PARAM_DEFINE_FLOAT(EKF2_NOAID_NOISE, 10.0f);
* @unit m
* @decimal 2
*/
PARAM_DEFINE_FLOAT(EKF2_BARO_NOISE, 3.0f);
PARAM_DEFINE_FLOAT(EKF2_BARO_NOISE, 2.0f);
/**
* Measurement noise for magnetic heading fusion.
@@ -419,8 +409,7 @@ PARAM_DEFINE_INT32(EKF2_DECL_TYPE, 7);
* @value 0 Automatic
* @value 1 Magnetic heading
* @value 2 3-axis fusion
* @value 3 2-D projection
* @value 4 None
* @value 3 None
*/
PARAM_DEFINE_INT32(EKF2_MAG_TYPE, 0);
@@ -466,15 +455,16 @@ PARAM_DEFINE_FLOAT(EKF2_GPS_V_GATE, 5.0f);
PARAM_DEFINE_INT32(EKF2_REC_RPL, 0);
/**
* Integer bitmask controlling which external aiding sources will be used.
* Integer bitmask controlling data fusion and aiding methods.
*
* Set bits in the following positions to enable:
* 0 : Set to true to use GPS data if available
* 1 : Set to true to use optical flow data if available
* 2 : Set to true to inhibit IMU bias estimation
*
* @group EKF2
* @min 0
* @max 3
* @max 15
*/
PARAM_DEFINE_INT32(EKF2_AID_MASK, 1);