1 # The frequency, in Hz, at which the filter will output a position estimate. Note that
2 # the filter will not begin computation until it receives at least one message from
3 # one of the inputs. It will then run continuously at the frequency specified here,
4 # regardless of whether it receives more measurements. Defaults to 30 if unspecified.
7 # The period, in seconds, after which we consider a sensor to have timed out. In this event, we
8 # carry out a predict cycle on the EKF without correcting it. This parameter can be thought of
9 # as the minimum frequency with which the filter will generate new output. Defaults to 1 / frequency
13 # If this is set to true, no 3D information will be used in your state estimate. Use this if you
14 # are operating in a planar environment and want to ignore the effect of small variations in the
15 # ground plane that might otherwise be detected by, for example, an IMU. Defaults to false if
19 # REP-105 (http://www.ros.org/reps/rep-0105.html) specifies three principal coordinate frames: map,
20 # odom, and base_link. base_link is the coordinate frame that is affixed to the robot. The robot's
21 # position in the odom frame will drift over time, but is accurate in the short term and should be
22 # continuous. The odom frame is therefore the best frame for executing local motion plans. The map
23 # frame, like the odom frame, is a world-fixed coordinate frame, and while it contains the most
24 # globally accurate position estimate for your robot, it is subject to discrete jumps, e.g., due to
25 # the fusion of GPS data. Here is how to use the following settings:
26 # 1. Set the map_frame, odom_frame, and base_link frames to the appropriate frame names for your system.
27 # * If your system does not have a map_frame, just remove it, and make sure "world_frame" is set
28 # to the value of odom_frame.
29 # 2. If you are fusing continuous position data such as wheel encoder odometry, visual odometry, or IMU data,
30 # set "world_frame" to your odom_frame value. This is the default behavior for robot_localization's state
32 # 3. If you are fusing global absolute position data that is subject to discrete jumps (e.g., GPS or position
33 # updates from landmark observations) then:
34 # 3a. Set your "world_frame" to your map_frame value
35 # 3b. MAKE SURE something else is generating the odom->base_link transform. Note that this can even be
36 # another instance of robot_localization! However, that instance should *not* fuse the global data.
37 # Defaults to "map" if unspecified
39 # Defaults to "odom" if unspecified
41 # Defaults to "base_link" if unspecified
42 base_link_frame: base_footprint
43 # Defaults to the value of "odom_frame" if unspecified
46 # Use this parameter to provide an offset to the transform generated by ekf_localization_node. This
47 # can be used for future dating the transform, which is required for interaction with some other
48 # packages. Defaults to 0.0 if unspecified.
49 #transform_time_offset: 0.0
51 # The filter accepts an arbitrary number of inputs from each input message type (Odometry, PoseStamped,
52 # TwistStamped, Imu). To add a new one, simply append the next number in the sequence to its base name,
53 # e.g., odom0, odom1, twist0, twist1, imu0, imu1, imu2, etc. The value should be the topic name. These
54 # parameters obviously have no default values, and must be specified.
59 # Each sensor reading updates some or all of the filter's state. These options give you greater control over
60 # which values from each measurement are fed to the filter. For example, if you have an odometry message as input,
61 # but only want to use its Z position value, then set the entire vector to false, except for the third entry.
62 # The order of the values is x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Note that not some
63 # message types lack certain variables. For example, a TwistWithCovarianceStamped message has no pose information, so
64 # the first six values would be meaningless in that case. Each vector defaults to all false if unspecified, effectively
65 # making this parameter required for each sensor.
66 # x/y not included because of redundancy with velocities
67 # vyaw not included in odom because too inaccurate
68 odom0_config: [false, false, false,
73 imu0_config: [false, false, false,
79 # The best practice for including new sensors in robot_localization's state estimation nodes is to pass in velocity
80 # measurements and let the nodes integrate them. However, this isn't always feasible, and so the state estimation
81 # nodes support fusion of absolute measurements. If you have more than one sensor providing absolute measurements,
82 # however, you may run into problems if your covariances are not large enough, as the sensors will inevitably
83 # diverge from one another, causing the filter to jump back and forth rapidly. To combat this situation, you can
84 # either increase the covariances for the variables in question, or you can simply set the sensor's differential
85 # parameter to true. When differential mode is enabled, all absolute pose data is converted to velocity data by
86 # differentiating the absolute pose measurements. These velocities are then integrated as usual. NOTE: this only
87 # applies to sensors that provide absolute measurements, so setting differential to true for twit measurements has
90 # Users should take care when setting this to true for orientation variables: if you have only one source of
91 # absolute orientation data, you should not set the differential parameter to true. This is due to the fact that
92 # integration of velocities leads to slowly increasing error in the absolute (pose) variable. For position variables,
93 # this is acceptable. For orientation variables, it can lead to trouble. Users should make sure that all orientation
94 # variables have at least one source of absolute measurement.
95 odom0_differential: false
96 imu0_differential: false
98 # When the node starts, if this parameter is true, then the first measurement is treated as a "zero point" for all
99 # future measurements. While you can achieve the same effect with the differential paremeter, the key difference is
100 # that the relative parameter doesn't cause the measurement to be converted to a velocity before integrating it. If
101 # you simply want your measurements to start at 0 for a given sensor, set this to true.
102 odom0_relative: false
105 # If we're including accelerations in our state estimate, then we'll probably want to remove any acceleration that
106 # is due to gravity for each IMU. If you don't want to, then set this to false. Defaults to false if unspecified.
107 imu0_remove_gravitational_acceleration: true
109 # If you're having trouble, try setting this to true, and then echo the /diagnostics_agg topic to see
110 # if the node is unhappy with any settings or data.
111 print_diagnostics: true
113 # If true, will dynamically scale the process_noise_covariance based on the robot?s velocity. This is useful, e.g., when you want your
114 # robots estimate error covariance to stop growing when the robot is stationary. Defaults to false.
115 dynamic_process_noise_covariance: true