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="2.0"/>
+ <!-- <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
<!-- 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. -->
- <param name="transform_time_offset" value="0.0"/>
+ <!-- <param name="transform_time_offset" value="0.0"/> -->
<!-- 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,
parameters obviously have no default values, and must be specified. -->
<param name="odom0" value="odom"/>
<param name="imu0" value="imu"/>
- <param name="odom1" value="gps"/>
+ <rosparam param="imu0_queue_size">10</rosparam>
<!-- Each sensor reading updates some or all of the filter's state. These options give you greater control over
which values from each measurement are fed to the filter. For example, if you have an odometry message as input,
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. -->
- <rosparam param="odom0_config">[true, true, false, false, false, true, true, true, false, false, false, true, true, true, false]</rosparam>
- <rosparam param="imu0_config">[false, false, false, true, true, true, false, false, false, true, true, true, true, true, true]</rosparam>
- <rosparam param="odom1_config">[true, true, true, false, false, false, true, true, true, false, false, false, true, true, true]</rosparam>
-
+ <!-- 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, true, false, false, true, false, false, false]</rosparam>
+ <rosparam param="imu0_config">[false, false, false, true, true, 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
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. -->
- <param name="odom0_differential" value="true"/>
+ <param name="odom0_differential" value="false"/>
<param name="imu0_differential" value="false"/>
- <param name="odom1_differential" value="true"/>
<!-- When the node starts, if this parameter is true, then the first measurement is treated as a "zero point" for all
future measurements. While you can achieve the same effect with the differential paremeter, the key difference is
you simply want your measurements to start at 0 for a given sensor, set this to true. -->
<param name="odom0_relative" value="false"/>
<param name="imu0_relative" value="false"/>
- <param name="odom1_relative" value="false"/>
<!-- If we're including accelerations in our state estimate, then we'll probably want to remove any acceleration that
is due to gravity for each IMU. If you don't want to, then set this to false. Defaults to false if unspecified. -->
if the node is unhappy with any settings or data. -->
<param name="print_diagnostics" value="true"/>
- <remap from="odometry/filtered" to="odom_combined"/>
+ <!-- If true, will dynamically scale the process_noise_covariance based on the robot?s velocity. This is useful, e.g., when you want your
+ robot?s estimate error covariance to stop growing when the robot is stationary. Defaults to false. -->
+ <param name="dynamic_process_noise_covariance" value="true"/>
+ <remap from="odometry/filtered" to="odom_combined"/>
</node>
-
</launch>