]> defiant.homedns.org Git - ros_roboint.git/blob - launch/move_base.launch
remove amcl and use odom as global frame
[ros_roboint.git] / launch / move_base.launch
1 <?xml version="1.0"?>
2 <launch>
3         <!-- Run the map server -->
4         <arg name="map_file" default="$(find roboint)/config/map.png" />
5         <node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file) 0.01" >
6                 <param name="frame_id" value="odom" />
7         </node>
8
9         <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
10                 <param name="controller_frequency" value="4.0" />
11                 <rosparam file="$(find roboint)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
12                 <rosparam file="$(find roboint)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
13                 <rosparam file="$(find roboint)/config/global_costmap_params.yaml" command="load" />
14                 <rosparam file="$(find roboint)/config/local_costmap_params.yaml" command="load" />
15                 <rosparam file="$(find roboint)/config/base_local_planner_params.yaml" command="load" />
16         </node>
17 </launch>