# Use this parameter to provide an offset to the transform generated by ekf_localization_node. This
# can be used for future dating the transform, which is required for interaction with some other
# packages. Defaults to 0.0 if unspecified.
-#transform_time_offset: 0.0
+#transform_time_offset: 0.05
# The filter accepts an arbitrary number of inputs from each input message type (Odometry, PoseStamped,
# TwistStamped, Imu). To add a new one, simply append the next number in the sequence to its base name,
# e.g., odom0, odom1, twist0, twist1, imu0, imu1, imu2, etc. The value should be the topic name. These
# parameters obviously have no default values, and must be specified.
odom0: odom
+odom1: gps
imu0: imu
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,
- false, false, false,
+ false, false, false,
true, true, true,
false, false, true,
false, false, false]
+# gps
+odom1_config: [true, true, false,
+ false, false, false,
+ false, false, false,
+ false, false, false,
+ false, false, false]
imu0_config: [false, false, false,
true, true, true,
false, false, false,
# either increase the covariances for the variables in question, or you can simply set the sensor's differential
# parameter to true. When differential mode is enabled, all absolute pose data is converted to velocity data by
# differentiating the absolute pose measurements. These velocities are then integrated as usual. NOTE: this only
-# applies to sensors that provide absolute measurements, so setting differential to true for twit measurements has
+# applies to sensors that provide absolute measurements, so setting differential to true for twist measurements has
# no effect.
-#
+#
# Users should take care when setting this to true for orientation variables: if you have only one source of
# absolute orientation data, you should not set the differential parameter to true. This is due to the fact that
# integration of velocities leads to slowly increasing error in the absolute (pose) variable. For position variables,
# this is acceptable. For orientation variables, it can lead to trouble. Users should make sure that all orientation
# variables have at least one source of absolute measurement.
odom0_differential: false
+odom1_differential: false
imu0_differential: false
# When the node starts, if this parameter is true, then the first measurement is treated as a "zero point" for all
# that the relative parameter doesn't cause the measurement to be converted to a velocity before integrating it. If
# you simply want your measurements to start at 0 for a given sensor, set this to true.
odom0_relative: false
+odom1_relative: false
imu0_relative: false
# If we're including accelerations in our state estimate, then we'll probably want to remove any acceleration that
# If true, will dynamically scale the process_noise_covariance based on the robot?s velocity. This is useful, e.g., when you want your
# robots estimate error covariance to stop growing when the robot is stationary. Defaults to false.
dynamic_process_noise_covariance: true
+
+# The process noise covariance matrix can be difficult to tune, and can vary for each application, so it is
+# exposed as a configuration parameter. This matrix represents the noise we add to the total error after each
+# prediction step. The better the omnidirectional motion model matches your system, the smaller these values can be.
+# However, if users find that a given variable is slow to converge, one approach is to increase the
+# 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: [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,
+ 0, 0, 0, 0, 0, 0.06, 0, 0, 0, 0, 0, 0, 0, 0, 0,
+ 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, 0,
+ 0, 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0,
+ 0, 0, 0, 0, 0, 0, 0, 0, 0.04, 0, 0, 0, 0, 0, 0,
+ 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0,
+ 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0,
+ 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.02, 0, 0, 0,
+ 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0,
+ 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0,
+ 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.015]