]> defiant.homedns.org Git - arm_ros_conn.git/blobdiff - move_base.launch
-added arm_ros_conn
[arm_ros_conn.git] / move_base.launch
index 8d46da1af9245e6c5ae965ddb4c1808f69db840e..cd1ef67c6869446f9ce8426a283926688ab2b214 100644 (file)
@@ -1,13 +1,15 @@
 <?xml version="1.0"?>
 <launch>
+       <node pkg="arm" type="arm_ros_conn.py" name="arm_ros_conn" output="screen" />
+
        <!-- Run the map server -->
-       <node name="map_server" pkg="map_server" type="map_server" args="$(find arm)/config/map.pgm 0.05"/>
+       <node name="map_server" pkg="map_server" type="map_server" args="$(find arm)/config/map.png 0.01" />
 
        <!-- Run AMCL -->
        <include file="$(find amcl)/examples/amcl_diff.launch" />
 
        <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
-               <param name="controller_frequency" value="2.0" />
+               <param name="controller_frequency" value="10.0" />
                <rosparam file="$(find arm)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
                <rosparam file="$(find arm)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
                <rosparam file="$(find arm)/config/global_costmap_params.yaml" command="load" />