<param name="base_frame_id" value="base_footprint" />
<param name="odom_model_type" value="diff-corrected" />
<!-- Specifies the expected noise in odometry's rotation estimate from the rotational component of the robot's motion. -->
- <param name="odom_alpha1" value="0.00001" />
+ <param name="odom_alpha1" value="0.001" />
<!-- Specifies the expected noise in odometry's rotation estimate from translational component of the robot's motion. -->
- <param name="odom_alpha2" value="0.00001" />
+ <param name="odom_alpha2" value="0.001" />
<!-- Specifies the expected noise in odometry's translation estimate from the translational component of the robot's motion. -->
- <param name="odom_alpha3" value="0.03" />
+ <param name="odom_alpha3" value="0.04" />
<!-- Specifies the expected noise in odometry's translation estimate from the rotational component of the robot's motion. -->
<param name="odom_alpha4" value="0.001" />
<!-- How many evenly-spaced beams in each scan to be used when updating the filter. -->
<include file="$(find wild_thumper)/launch/gmapping.launch" if="$(arg slam_gmapping)" />
- <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
+ <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen" clear_params="true">
<param name="base_local_planner" value="$(arg base_local_planner)"/>
<param name="controller_frequency" value="10.0" />
<rosparam file="$(find wild_thumper)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />