3 <arg name="slam_gmapping" default="false" />
4 <arg name="map_file" default="$(find wild_thumper)/data/map.yaml" />
6 <!-- Run the map server -->
7 <node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)" unless="$(arg slam_gmapping)" />
10 <include file="$(find amcl)/examples/amcl_diff.launch" unless="$(arg slam_gmapping)" />
11 <param name="amcl/base_frame_id" value="base_footprint" />
13 <node pkg="gmapping" type="slam_gmapping" name="slap_gmapping" output="screen" if="$(arg slam_gmapping)">
14 <param name="scan" value="scan" />
15 <param name="delta" value="0.01" />
16 <param name="map_update_interval" value="30" />
17 <param name="linearUpdate" value="0.5" />
18 <param name="angularUpdate" value="0.25" />
19 <param name="xmin" value="-1.0"/>
20 <param name="ymin" value="-1.0"/>
21 <param name="xmax" value="1.0"/>
22 <param name="ymax" value="1.0"/>
23 <param name="odom_frame" value="odom"/>
26 <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen" unless="$(arg slam_gmapping)">
27 <rosparam file="$(find wild_thumper)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
28 <rosparam file="$(find wild_thumper)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
29 <rosparam file="$(find wild_thumper)/config/global_costmap_params.yaml" command="load" />
30 <rosparam file="$(find wild_thumper)/config/local_costmap_params.yaml" command="load" />
31 <rosparam file="$(find wild_thumper)/config/base_local_planner_params.yaml" command="load" />