]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - config/robot_localization.yaml
base_local_planner: Reduce acc_lim_x for less shaky acceleration
[ros_wild_thumper.git] / config / robot_localization.yaml
index 630e24d2822f96dc2f687b31710232a1722c4026..82d5fff34d9f547cfc3d0a57e069803e1242ec56 100644 (file)
@@ -64,6 +64,7 @@ imu0_queue_size: 10
 #  message types lack certain variables. For example, a TwistWithCovarianceStamped message has no pose information, so
 #  the first six values would be meaningless in that case. Each vector defaults to all false if unspecified, effectively
 #  making this parameter required for each sensor.
+# odom
 # x/y not included because of redundancy with velocities
 # vyaw not included in odom because too inaccurate
 odom0_config: [false, false, false,
@@ -71,6 +72,7 @@ odom0_config: [false, false, false,
                true,  true,  true,
                false, false, true,
                false, false, false]
+# gps
 odom1_config: [true,  true,  false,
                false, false, false,
                false, false, false,
@@ -129,8 +131,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,