From c6584635674d7f0ee5183949df0d9652f17f5cfd Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 16 Dec 2015 17:07:45 +0000 Subject: [PATCH] EKF: Set better value for accel process noise --- .../ekf_att_pos_estimator/ekf_att_pos_estimator_params.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_params.c b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_params.c index 45e2f24939..208449790b 100644 --- a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_params.c +++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_params.c @@ -202,7 +202,7 @@ PARAM_DEFINE_FLOAT(PE_GYRO_PNOISE, 0.015f); * @max 1.0 * @group Position Estimator */ -PARAM_DEFINE_FLOAT(PE_ACC_PNOISE, 0.25f); +PARAM_DEFINE_FLOAT(PE_ACC_PNOISE, 0.125f); /** * Gyro bias estimate process noise