From 3f3329b34715a239358868351317d27ea17bd423 Mon Sep 17 00:00:00 2001 From: Erik Andresen Date: Fri, 29 Sep 2017 18:24:42 +0200 Subject: [PATCH] robot_localization: Set process noise covariance for absolute x/y (gps pos) to 2.5m --- config/robot_localization.yaml | 4 ++-- launch/wild_thumper.launch | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/config/robot_localization.yaml b/config/robot_localization.yaml index 630e24d..193db56 100644 --- a/config/robot_localization.yaml +++ b/config/robot_localization.yaml @@ -129,8 +129,8 @@ dynamic_process_noise_covariance: true # process_noise_covariance diagonal value for the variable in question, which will cause the filter's predicted error # to be larger, which will cause the filter to trust the incoming measurement more during correction. The values are # ordered as x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. -process_noise_covariance: [0.5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0.5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, +process_noise_covariance: [2.5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 2.5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.06, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, diff --git a/launch/wild_thumper.launch b/launch/wild_thumper.launch index 1d304d8..7c9eece 100644 --- a/launch/wild_thumper.launch +++ b/launch/wild_thumper.launch @@ -22,7 +22,7 @@ - + -- 2.39.5