3 <node pkg="gpsd_client" type="gpsd_client" name="gpsd_client" output="screen">
4 <param name="use_gps_time" value="false"/>
5 <param name="frame_id" value="base_footprint"/>
8 <node pkg="robot_localization" type="navsat_transform_node" name="navsat_transform_node" output="screen">
9 <param name="magnetic_declination_radians" value="0.047"/>
10 <param name="yaw_offset" value="0.0"/>
11 <param name="zero_altitude" value="true"/>
12 <param name="broadcast_utm_transform" value="true"/>
14 <remap from="/imu/data" to="imu"/>
15 <remap from="/gps/fix" to="fix" />
16 <remap from="/odometry/filtered" to="odom_combined"/>
17 <remap from="/odometry/gps" to="gps"/>
20 <node pkg="robot_localization" type="ekf_localization_node" name="ekf_gps" clear_params="true" output="screen">
21 <!-- The frequency, in Hz, at which the filter will output a position estimate. Note that
22 the filter will not begin computation until it receives at least one message from
23 one of the inputs. It will then run continuously at the frequency specified here,
24 regardless of whether it receives more measurements. Defaults to 30 if unspecified. -->
25 <param name="frequency" value="10"/>
27 <!-- The period, in seconds, after which we consider a sensor to have timed out. In this event, we
28 carry out a predict cycle on the EKF without correcting it. This parameter can be thought of
29 as the minimum frequency with which the filter will generate new output. Defaults to 1 / frequency
31 <param name="sensor_timeout" value="2.0"/>
33 <!-- If this is set to true, no 3D information will be used in your state estimate. Use this if you
34 are operating in a planar environment and want to ignore the effect of small variations in the
35 ground plane that might otherwise be detected by, for example, an IMU. Defaults to false if
37 <param name="two_d_mode" value="true"/>
39 <!-- REP-105 (http://www.ros.org/reps/rep-0105.html) specifies three principal coordinate frames: map,
40 odom, and base_link. base_link is the coordinate frame that is affixed to the robot. The robot's
41 position in the odom frame will drift over time, but is accurate in the short term and should be
42 continuous. The odom frame is therefore the best frame for executing local motion plans. The map
43 frame, like the odom frame, is a world-fixed coordinate frame, and while it contains the most
44 globally accurate position estimate for your robot, it is subject to discrete jumps, e.g., due to
45 the fusion of GPS data. Here is how to use the following settings:
46 1. Set the map_frame, odom_frame, and base_link frames to the appropriate frame names for your system.
47 * If your system does not have a map_frame, just remove it, and make sure "world_frame" is set
48 to the value of odom_frame.
49 2. If you are fusing continuous position data such as wheel encoder odometry, visual odometry, or IMU data,
50 set "world_frame" to your odom_frame value. This is the default behavior for robot_localization's state
52 3. If you are fusing global absolute position data that is subject to discrete jumps (e.g., GPS or position
53 updates from landmark observations) then:
54 3a. Set your "world_frame" to your map_frame value
55 3b. MAKE SURE something else is generating the odom->base_link transform. Note that this can even be
56 another instance of robot_localization! However, that instance should *not* fuse the global data. -->
57 <!-- Defaults to "map" if unspecified -->
58 <param name="map_frame" value="gps"/>
59 <!-- Defaults to "odom" if unspecified -->
60 <param name="odom_frame" value="odom"/>
61 <!-- Defaults to "base_link" if unspecified -->
62 <param name="base_link_frame" value="base_footprint"/>
63 <!-- Defaults to the value of "odom_frame" if unspecified -->
64 <param name="world_frame" value="gps"/>
66 <!-- We already have a publisher for odom->base transform -->
67 <param name="publish_tf" value="true"/>
69 <!-- Use this parameter to provide an offset to the transform generated by ekf_localization_node. This
70 can be used for future dating the transform, which is required for interaction with some other
71 packages. Defaults to 0.0 if unspecified. -->
72 <!-- <param name="transform_time_offset" value="0.0"/> -->
74 <!-- The filter accepts an arbitrary number of inputs from each input message type (Odometry, PoseStamped,
75 TwistStamped, Imu). To add a new one, simply append the next number in the sequence to its base name,
76 e.g., odom0, odom1, twist0, twist1, imu0, imu1, imu2, etc. The value should be the topic name. These
77 parameters obviously have no default values, and must be specified. -->
78 <param name="odom0" value="odom"/>
79 <param name="odom1" value="gps"/>
80 <param name="imu0" value="imu"/>
81 <rosparam param="imu0_queue_size">10</rosparam>
83 <!-- Each sensor reading updates some or all of the filter's state. These options give you greater control over
84 which values from each measurement are fed to the filter. For example, if you have an odometry message as input,
85 but only want to use its Z position value, then set the entire vector to false, except for the third entry.
86 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
87 message types lack certain variables. For example, a TwistWithCovarianceStamped message has no pose information, so
88 the first six values would be meaningless in that case. Each vector defaults to all false if unspecified, effectively
89 making this parameter required for each sensor. -->
90 <!-- x/y not included because of redundancy with velocities -->
91 <!-- vyaw not included in odom because too inaccurate -->
92 <rosparam param="odom0_config">[false, false, false,
96 false, false, false]</rosparam>
97 <rosparam param="odom1_config">[true, true, false,
101 false, false, false]</rosparam>
102 <rosparam param="imu0_config">[false, false, false,
106 false, false, false]</rosparam>
108 <!-- The best practice for including new sensors in robot_localization's state estimation nodes is to pass in velocity
109 measurements and let the nodes integrate them. However, this isn't always feasible, and so the state estimation
110 nodes support fusion of absolute measurements. If you have more than one sensor providing absolute measurements,
111 however, you may run into problems if your covariances are not large enough, as the sensors will inevitably
112 diverge from one another, causing the filter to jump back and forth rapidly. To combat this situation, you can
113 either increase the covariances for the variables in question, or you can simply set the sensor's differential
114 parameter to true. When differential mode is enabled, all absolute pose data is converted to velocity data by
115 differentiating the absolute pose measurements. These velocities are then integrated as usual. NOTE: this only
116 applies to sensors that provide absolute measurements, so setting differential to true for twist measurements has
119 Users should take care when setting this to true for orientation variables: if you have only one source of
120 absolute orientation data, you should not set the differential parameter to true. This is due to the fact that
121 integration of velocities leads to slowly increasing error in the absolute (pose) variable. For position variables,
122 this is acceptable. For orientation variables, it can lead to trouble. Users should make sure that all orientation
123 variables have at least one source of absolute measurement. -->
124 <param name="odom0_differential" value="false"/>
125 <param name="odom1_differential" value="false"/>
126 <param name="imu0_differential" value="false"/>
128 <!-- When the node starts, if this parameter is true, then the first measurement is treated as a "zero point" for all
129 future measurements. While you can achieve the same effect with the differential paremeter, the key difference is
130 that the relative parameter doesn't cause the measurement to be converted to a velocity before integrating it. If
131 you simply want your measurements to start at 0 for a given sensor, set this to true. -->
132 <param name="odom0_relative" value="false"/>
133 <param name="odom1_relative" value="false"/>
134 <param name="imu0_relative" value="false"/>
136 <!-- If we're including accelerations in our state estimate, then we'll probably want to remove any acceleration that
137 is due to gravity for each IMU. If you don't want to, then set this to false. Defaults to false if unspecified. -->
138 <param name="imu0_remove_gravitational_acceleration" value="true"/>
140 <!-- If you're having trouble, try setting this to true, and then echo the /diagnostics_agg topic to see
141 if the node is unhappy with any settings or data. -->
142 <param name="print_diagnostics" value="true"/>
144 <remap from="odometry/filtered" to="gps_combined"/>
146 <rosparam param="process_noise_covariance">
147 [0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
148 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
149 0, 0, 0.06, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
150 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
151 0, 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
152 0, 0, 0, 0, 0, 0.06, 0, 0, 0, 0, 0, 0, 0, 0, 0,
153 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, 0,
154 0, 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0,
155 0, 0, 0, 0, 0, 0, 0, 0, 0.04, 0, 0, 0, 0, 0, 0,
156 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0,
157 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0,
158 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.02, 0, 0, 0,
159 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0,
160 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0,
161 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.015]