<launch>
<arg name="slam_gmapping" default="false" />
<arg name="map_file" default="$(find wild_thumper)/data/map.yaml" />
- <arg name="global_utm" default="false" />
<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 -->
<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" />
- <rosparam file="$(find wild_thumper)/config/global_costmap_params_odom.yaml" command="load" if="$(arg global_odm)" />
- <rosparam file="$(find wild_thumper)/config/global_costmap_params_utm.yaml" command="load" if="$(arg global_utm)" />
+ <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"/>