<launch>
<arg name="slam_gmapping" default="false" />
<arg name="map_file" default="$(find wild_thumper)/data/map.yaml" />
+ <arg name="global_odom" default="false" />
<arg name="nomap" default="false" />
<arg name="base_local_planner" default="base_local_planner/TrajectoryPlannerROS"/> <!-- base_local_planner/TrajectoryPlannerROS || dwa_local_planner/DWAPlannerROS -->
<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.01" />
+ <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.03" />
+ <param name="odom_alpha4" value="0.001" />
<!-- How many evenly-spaced beams in each scan to be used when updating the filter. -->
<param name="laser_max_beams" value="50" />
<!-- Exponential decay rate for the slow average weight filter, used in deciding when to recover by adding random poses. -->
- <param name="recovery_alpha_slow" value="0.01" />
+ <param name="recovery_alpha_slow" value="0.001" />
<!-- Exponential decay rate for the fast average weight filter, used in deciding when to recover by adding random poses. -->
- <param name="recovery_alpha_fast" value="0.2" />
+ <param name="recovery_alpha_fast" value="0.1" />
<!-- Minimum allowed number of particles. -->
<param name="min_particles" value="100" />
</group>
<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" />
<rosparam file="$(find wild_thumper)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
- <rosparam file="$(find wild_thumper)/config/global_costmap_params.yaml" command="load" unless="$(arg nomap)" />
- <rosparam file="$(find wild_thumper)/config/global_costmap_params_odom.yaml" command="load" if="$(arg nomap)" />
+ <rosparam file="$(find wild_thumper)/config/global_costmap_params.yaml" command="load" />
+ <rosparam file="$(find wild_thumper)/config/global_costmap_params_odom.yaml" command="load" if="$(arg global_odom)" />
<rosparam file="$(find wild_thumper)/config/local_costmap_params.yaml" command="load" />
<rosparam file="$(find wild_thumper)/config/base_local_planner_params.yaml" command="load" />
<remap from="/cmd_vel" to="move_base/cmd_vel"/>