mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-20 12:09:06 +08:00
ekf2: Enable tuning of initial tilt alignment uncertainty
This commit is contained in:
parent
71db04c02c
commit
83cc9ef496
@ -251,6 +251,7 @@ private:
|
||||
// IMU switch on bias paameters
|
||||
control::BlockParamFloat _gyr_bias_init; // 1-sigma gyro bias uncertainty at switch-on (rad/sec)
|
||||
control::BlockParamFloat _acc_bias_init; // 1-sigma accelerometer bias uncertainty at switch-on (m/s**2)
|
||||
control::BlockParamFloat _ang_err_init; // 1-sigma uncertainty in tilt angle after gravity vector alignment (rad)
|
||||
|
||||
int update_subscriptions();
|
||||
|
||||
@ -338,7 +339,8 @@ Ekf2::Ekf2():
|
||||
_tau_vel(this, "EKF2_TAU_VEL", false, &_params->vel_Tau),
|
||||
_tau_pos(this, "EKF2_TAU_POS", false, &_params->pos_Tau),
|
||||
_gyr_bias_init(this, "EKF2_GBIAS_INIT", false, &_params->switch_on_gyro_bias),
|
||||
_acc_bias_init(this, "EKF2_ABIAS_INIT", false, &_params->switch_on_accel_bias)
|
||||
_acc_bias_init(this, "EKF2_ABIAS_INIT", false, &_params->switch_on_accel_bias),
|
||||
_ang_err_init(this, "EKF2_ANGERR_INIT", false, &_params->initial_tilt_err)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
@ -743,3 +743,14 @@ PARAM_DEFINE_FLOAT(EKF2_GBIAS_INIT, 0.1f);
|
||||
* @decimal 2
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(EKF2_ABIAS_INIT, 0.2f);
|
||||
|
||||
/**
|
||||
* 1-sigma tilt angle uncertainty after gravity vector alignment
|
||||
*
|
||||
* @group EKF2
|
||||
* @min 0.0
|
||||
* @max 0.5
|
||||
* @unit rad
|
||||
* @decimal 3
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(EKF2_ANGERR_INIT, 0.1f);
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user