]> defiant.homedns.org Git - ros_wild_thumper.git/blob - launch/move_base.launch
wild_thumper.launch: make wt_node required
[ros_wild_thumper.git] / launch / move_base.launch
1 <?xml version="1.0"?>
2 <launch>
3         <arg name="slam_gmapping" default="false" />
4         <arg name="map_file" default="$(find wild_thumper)/data/map.yaml" />
5         <arg name="nomap" default="false" />
6
7         <!-- Run AMCL -->
8         <group unless="$(arg nomap)">
9                 <!-- Run the map server -->
10                 <node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)" unless="$(arg slam_gmapping)" />
11
12                 <include file="$(find amcl)/examples/amcl_diff.launch" unless="$(arg slam_gmapping)" />
13                 <param name="amcl/base_frame_id" value="base_footprint" />
14         </group>
15
16         <node pkg="gmapping" type="slam_gmapping" name="slap_gmapping" output="screen" if="$(arg slam_gmapping)">
17                 <param name="scan" value="scan" />
18                 <param name="delta" value="0.01" />
19                 <param name="map_update_interval" value="30" />
20                 <param name="linearUpdate" value="0.5" />
21                 <param name="angularUpdate" value="0.25" />
22                 <param name="xmin" value="-1.0"/>
23                 <param name="ymin" value="-1.0"/>
24                 <param name="xmax" value="1.0"/>
25                 <param name="ymax" value="1.0"/>
26                 <param name="odom_frame" value="odom"/>
27         </node>
28
29         <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
30                 <rosparam file="$(find wild_thumper)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
31                 <rosparam file="$(find wild_thumper)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
32                 <rosparam file="$(find wild_thumper)/config/global_costmap_params.yaml" command="load" unless="$(arg nomap)" />
33                 <rosparam file="$(find wild_thumper)/config/global_costmap_params_odom.yaml" command="load" if="$(arg nomap)" />
34                 <rosparam file="$(find wild_thumper)/config/local_costmap_params.yaml" command="load" />
35                 <rosparam file="$(find wild_thumper)/config/base_local_planner_params.yaml" command="load" />
36                 <remap from="/cmd_vel" to="move_base/cmd_vel"/>
37         </node>
38 </launch>