]> defiant.homedns.org Git - ros_roboint.git/blobdiff - launch/move_base.launch
remove amcl and use odom as global frame
[ros_roboint.git] / launch / move_base.launch
diff --git a/launch/move_base.launch b/launch/move_base.launch
new file mode 100644 (file)
index 0000000..378dd07
--- /dev/null
@@ -0,0 +1,17 @@
+<?xml version="1.0"?>
+<launch>
+       <!-- Run the map server -->
+       <arg name="map_file" default="$(find roboint)/config/map.png" />
+       <node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file) 0.01" >
+               <param name="frame_id" value="odom" />
+       </node>
+
+       <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
+               <param name="controller_frequency" value="4.0" />
+               <rosparam file="$(find roboint)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
+               <rosparam file="$(find roboint)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
+               <rosparam file="$(find roboint)/config/global_costmap_params.yaml" command="load" />
+               <rosparam file="$(find roboint)/config/local_costmap_params.yaml" command="load" />
+               <rosparam file="$(find roboint)/config/base_local_planner_params.yaml" command="load" />
+       </node>
+</launch>