<launch>
<node pkg="gpsd_client" type="gpsd_client" name="gpsd_client" output="screen">
<param name="use_gps_time" value="false"/>
- <param name="frame_id" value="gps"/>
+ <param name="frame_id" value="base_footprint"/>
</node>
<node pkg="robot_localization" type="navsat_transform_node" name="navsat_transform_node" output="screen">
<remap from="/odometry/gps" to="gps"/>
</node>
- <node pkg="robot_localization" type="ekf_localization_node" name="ekf_localization_gps" clear_params="true" output="screen">
+ <node pkg="robot_localization" type="ekf_localization_node" name="ekf_gps" clear_params="true" output="screen">
<!-- The frequency, in Hz, at which the filter will output a position estimate. Note that
the filter will not begin computation until it receives at least one message from
one of the inputs. It will then run continuously at the frequency specified here,
regardless of whether it receives more measurements. Defaults to 30 if unspecified. -->
- <param name="frequency" value="20"/>
+ <param name="frequency" value="10"/>
<!-- The period, in seconds, after which we consider a sensor to have timed out. In this event, we
carry out a predict cycle on the EKF without correcting it. This parameter can be thought of
as the minimum frequency with which the filter will generate new output. Defaults to 1 / frequency
if not specified. -->
- <param name="sensor_timeout" value="0.1"/>
+ <param name="sensor_timeout" value="2.0"/>
<!-- If this is set to true, no 3D information will be used in your state estimate. Use this if you
are operating in a planar environment and want to ignore the effect of small variations in the
<!-- Defaults to the value of "odom_frame" if unspecified -->
<param name="world_frame" value="gps"/>
+ <!-- We already have a publisher for odom->base transform -->
+ <param name="publish_tf" value="true"/>
+
<!-- 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. -->
making this parameter required for each sensor. -->
<!-- x/y not included because of redundancy with velocities -->
<!-- vyaw not included in odom because too inaccurate -->
- <rosparam param="odom0_config">[false, false, false, false, false, false, true, true, false, false, false, true, false, false, false]</rosparam>
- <rosparam param="odom1_config">[true, true, false, false, false, false, false, false, false, false, false, false, false, false, false]</rosparam>
- <rosparam param="imu0_config">[false, false, false, false, false, true, false, false, false, false, false, false, false, false, false]</rosparam>
+ <rosparam param="odom0_config">[false, false, false,
+ false, false, false,
+ true, true, false,
+ false, false, true,
+ false, false, false]</rosparam>
+ <rosparam param="odom1_config">[true, true, false,
+ false, false, false,
+ false, false, false,
+ false, false, false,
+ false, false, false]</rosparam>
+ <rosparam param="imu0_config">[false, false, false,
+ false, false, true,
+ false, false, false,
+ false, false, false,
+ false, false, false]</rosparam>
<!-- The best practice for including new sensors in robot_localization's state estimation nodes is to pass in velocity
measurements and let the nodes integrate them. However, this isn't always feasible, and so the state estimation
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
<param name="print_diagnostics" value="true"/>
<remap from="odometry/filtered" to="gps_combined"/>
+
+ <rosparam param="process_noise_covariance">
+ [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.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]
+ </rosparam>
</node>
</launch>