]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - launch/move_base.launch
frontier exploration fixes
[ros_wild_thumper.git] / launch / move_base.launch
index 441dbeaf5d13efb5af6b02609ef01a4fc533b56c..30f7ff1118caaa7e93aa8b51df49f12c7630f3f9 100644 (file)
@@ -3,12 +3,13 @@
        <arg name="slam_gmapping" default="false" />
        <arg name="map_file" default="$(find wild_thumper)/data/map.yaml" />
        <arg name="nomap" default="false" />
-
-       <!-- Run the map server -->
-       <node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)" unless="$(arg slam_gmapping)" />
+       <arg name="base_local_planner" default="base_local_planner/TrajectoryPlannerROS"/> <!-- base_local_planner/TrajectoryPlannerROS || dwa_local_planner/DWAPlannerROS -->
 
        <!-- Run AMCL -->
        <group unless="$(arg nomap)">
+               <!-- Run the map server -->
+               <node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)" unless="$(arg slam_gmapping)" />
+
                <include file="$(find amcl)/examples/amcl_diff.launch" unless="$(arg slam_gmapping)" />
                <param name="amcl/base_frame_id" value="base_footprint" />
        </group>
                <param name="map_update_interval" value="30" />
                <param name="linearUpdate" value="0.5" />
                <param name="angularUpdate" value="0.25" />
-               <param name="xmin" value="-1.0"/>
-               <param name="ymin" value="-1.0"/>
-               <param name="xmax" value="1.0"/>
-               <param name="ymax" value="1.0"/>
+               <param name="xmin" value="-5.0"/>
+               <param name="ymin" value="-5.0"/>
+               <param name="xmax" value="5.0"/>
+               <param name="ymax" value="5.0"/>
                <param name="odom_frame" value="odom"/>
        </node>
 
        <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
+               <param name="base_local_planner" value="$(arg base_local_planner)"/>
+               <param name="controller_frequency" value="10.0" />
                <rosparam file="$(find wild_thumper)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
                <rosparam file="$(find wild_thumper)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
                <rosparam file="$(find wild_thumper)/config/global_costmap_params.yaml" command="load" unless="$(arg nomap)" />
                <rosparam file="$(find wild_thumper)/config/global_costmap_params_odom.yaml" command="load" if="$(arg nomap)" />
                <rosparam file="$(find wild_thumper)/config/local_costmap_params.yaml" command="load" />
                <rosparam file="$(find wild_thumper)/config/base_local_planner_params.yaml" command="load" />
+               <remap from="/cmd_vel" to="move_base/cmd_vel"/>
        </node>
 </launch>