]> defiant.homedns.org Git - arm_ros_conn.git/blob - move_base.launch
8d46da1af9245e6c5ae965ddb4c1808f69db840e
[arm_ros_conn.git] / move_base.launch
1 <?xml version="1.0"?>
2 <launch>
3         <!-- Run the map server -->
4         <node name="map_server" pkg="map_server" type="map_server" args="$(find arm)/config/map.pgm 0.05"/>
5
6         <!-- Run AMCL -->
7         <include file="$(find amcl)/examples/amcl_diff.launch" />
8
9         <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
10                 <param name="controller_frequency" value="2.0" />
11                 <rosparam file="$(find arm)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
12                 <rosparam file="$(find arm)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
13                 <rosparam file="$(find arm)/config/global_costmap_params.yaml" command="load" />
14                 <rosparam file="$(find arm)/config/local_costmap_params.yaml" command="load" />
15                 <rosparam file="$(find arm)/config/base_local_planner_params.yaml" command="load" />
16         </node>
17
18         <param name="robot_description" command="$(find xacro)/xacro.py $(find arm)/urdf/arm.urdf.xacro" />
19         <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
20 </launch>