]> defiant.homedns.org Git - ros_wild_thumper.git/blob - launch/robot_localization.launch
Merge branch 'master' of ssh://vontaene/home/erik_alt/git/ros_wild_thumper
[ros_wild_thumper.git] / launch / robot_localization.launch
1 <?xml version="1.0"?>
2
3 <!-- Launch file for ekf_localization_node -->
4 <launch>
5
6         <!-- This node will take in measurements from odometry, IMU, stamped pose, and stamped twist messages. It tracks
7          the state of the robot, with the state vector being defined as X position, Y position, Z position,
8          roll, pitch, yaw, their respective velocites, and linear acceleration. Units for all measurements are assumed
9          to conform to the SI standard as specified in REP-103. -->
10         <node pkg="robot_localization" type="ekf_localization_node" name="ekf_localization" clear_params="true" output="screen">
11
12                 <!-- ======== STANDARD PARAMETERS ======== -->
13
14                 <!-- The frequency, in Hz, at which the filter will output a position estimate. Note that
15                 the filter will not begin computation until it receives at least one message from
16                 one of the inputs. It will then run continuously at the frequency specified here,
17                 regardless of whether it receives more measurements. Defaults to 30 if unspecified. -->
18                 <param name="frequency" value="20"/>
19
20                 <!-- The period, in seconds, after which we consider a sensor to have timed out. In this event, we
21                    carry out a predict cycle on the EKF without correcting it. This parameter can be thought of
22                    as the minimum frequency with which the filter will generate new output. Defaults to 1 / frequency
23                    if not specified. -->
24                 <param name="sensor_timeout" value="2.0"/>
25
26                 <!-- If this is set to true, no 3D information will be used in your state estimate. Use this if you
27                    are operating in a planar environment and want to ignore the effect of small variations in the
28                    ground plane that might otherwise be detected by, for example, an IMU. Defaults to false if
29                    unspecified. -->
30                 <param name="two_d_mode" value="true"/>
31
32                 <!-- REP-105 (http://www.ros.org/reps/rep-0105.html) specifies three principal coordinate frames: map,
33                    odom, and base_link. base_link is the coordinate frame that is affixed to the robot. The robot's
34                    position in the odom frame will drift over time, but is accurate in the short term and should be
35                    continuous. The odom frame is therefore the best frame for executing local motion plans. The map
36                    frame, like the odom frame, is a world-fixed coordinate frame, and while it contains the most
37                    globally accurate position estimate for your robot, it is subject to discrete jumps, e.g., due to
38                    the fusion of GPS data. Here is how to use the following settings:
39                      1. Set the map_frame, odom_frame, and base_link frames to the appropriate frame names for your system.
40                           * If your system does not have a map_frame, just remove it, and make sure "world_frame" is set
41                             to the value of odom_frame.
42                      2. If you are fusing continuous position data such as wheel encoder odometry, visual odometry, or IMU data,
43                         set "world_frame" to your odom_frame value. This is the default behavior for robot_localization's state
44                         estimation nodes.
45                      3. If you are fusing global absolute position data that is subject to discrete jumps (e.g., GPS or position
46                         updates from landmark observations) then:
47                           3a. Set your "world_frame" to your map_frame value
48                           3b. MAKE SURE something else is generating the odom->base_link transform. Note that this can even be
49                               another instance of robot_localization! However, that instance should *not* fuse the global data. -->
50                 <!-- Defaults to "map" if unspecified -->
51                 <param name="map_frame" value="map"/>
52                 <!-- Defaults to "odom" if unspecified -->
53                 <param name="odom_frame" value="odom"/>
54                 <!-- Defaults to "base_link" if unspecified -->
55                 <param name="base_link_frame" value="base_footprint"/>
56                 <!-- Defaults to the value of "odom_frame" if unspecified -->
57                 <param name="world_frame" value="odom"/>
58
59                 <!-- Use this parameter to provide an offset to the transform generated by ekf_localization_node. This
60                    can be used for future dating the transform, which is required for interaction with some other
61                    packages. Defaults to 0.0 if unspecified. -->
62                 <param name="transform_time_offset" value="0.0"/>
63
64                 <!-- The filter accepts an arbitrary number of inputs from each input message type (Odometry, PoseStamped,
65                    TwistStamped, Imu). To add a new one, simply append the next number in the sequence to its base name,
66                    e.g., odom0, odom1, twist0, twist1, imu0, imu1, imu2, etc. The value should be the topic name. These
67                    parameters obviously have no default values, and must be specified. -->
68                 <param name="odom0" value="odom"/>
69                 <param name="imu0" value="imu"/>
70                 <param name="odom1" value="gps"/>
71
72                 <!-- Each sensor reading updates some or all of the filter's state. These options give you greater control over
73                    which values from each measurement are fed to the filter. For example, if you have an odometry message as input,
74                    but only want to use its Z position value, then set the entire vector to false, except for the third entry.
75                    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
76                    message types lack certain variables. For example, a TwistWithCovarianceStamped message has no pose information, so
77                    the first six values would be meaningless in that case. Each vector defaults to all false if unspecified, effectively
78                    making this parameter required for each sensor. -->
79                 <rosparam param="odom0_config">[true, true, false, false, false, true, true, true, false, false, false, true, true, true, false]</rosparam>
80                 <rosparam param="imu0_config">[false, false, false, true, true, true, false, false, false, true, true, true, true, true, true]</rosparam>
81                 <rosparam param="odom1_config">[true, true, true, false, false, false, false, false, false, false, false, false, false, false, false]</rosparam>
82
83
84                 <!-- The best practice for including new sensors in robot_localization's state estimation nodes is to pass in velocity
85                    measurements and let the nodes integrate them. However, this isn't always feasible, and so the state estimation
86                    nodes support fusion of absolute measurements. If you have more than one sensor providing absolute measurements,
87                    however, you may run into problems if your covariances are not large enough, as the sensors will inevitably
88                    diverge from one another, causing the filter to jump back and forth rapidly. To combat this situation, you can
89                    either increase the covariances for the variables in question, or you can simply set the sensor's differential
90                    parameter to true. When differential mode is enabled, all absolute pose data is converted to velocity data by
91                    differentiating the absolute pose measurements. These velocities are then integrated as usual. NOTE: this only
92                    applies to sensors that provide absolute measurements, so setting differential to true for twit measurements has
93                    no effect.
94
95                    Users should take care when setting this to true for orientation variables: if you have only one source of
96                    absolute orientation data, you should not set the differential parameter to true. This is due to the fact that
97                    integration of velocities leads to slowly increasing error in the absolute (pose) variable. For position variables,
98                    this is acceptable. For orientation variables, it can lead to trouble. Users should make sure that all orientation
99                    variables have at least one source of absolute measurement. -->
100                 <param name="odom0_differential" value="true"/>
101                 <param name="imu0_differential" value="false"/>
102                 <param name="odom1_differential" value="false"/>
103
104                 <!-- When the node starts, if this parameter is true, then the first measurement is treated as a "zero point" for all
105                    future measurements. While you can achieve the same effect with the differential paremeter, the key difference is
106                    that the relative parameter doesn't cause the measurement to be converted to a velocity before integrating it. If
107                    you simply want your measurements to start at 0 for a given sensor, set this to true. -->
108                 <param name="odom0_relative" value="false"/>
109                 <param name="imu0_relative" value="false"/>
110                 <param name="odom1_relative" value="true"/>
111
112                 <!-- If we're including accelerations in our state estimate, then we'll probably want to remove any acceleration that
113                    is due to gravity for each IMU. If you don't want to, then set this to false. Defaults to false if unspecified. -->
114                 <param name="imu0_remove_gravitational_acceleration" value="true"/>
115
116                 <!-- If you're having trouble, try setting this to true, and then echo the /diagnostics_agg topic to see
117                    if the node is unhappy with any settings or data. -->
118                 <param name="print_diagnostics" value="true"/>
119
120                 <remap from="odometry/filtered" to="odom_combined"/>
121
122         </node>
123
124 </launch>