]> defiant.homedns.org Git - ros_wild_thumper.git/blob - launch/move_base.launch
tune slam gmapping
[ros_wild_thumper.git] / launch / move_base.launch
1 <?xml version="1.0"?>
2 <launch>
3         <arg name="slam_gmapping" default="false" />
4         <arg name="map_file" default="$(find wild_thumper)/data/map.yaml" />
5         <arg name="nomap" default="false" />
6         <arg name="base_local_planner" default="base_local_planner/TrajectoryPlannerROS"/> <!-- base_local_planner/TrajectoryPlannerROS || dwa_local_planner/DWAPlannerROS -->
7
8         <!-- Run AMCL -->
9         <group unless="$(arg nomap)">
10                 <!-- Run the map server -->
11                 <node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)" output="screen" unless="$(arg slam_gmapping)" />
12
13                 <include file="$(find amcl)/examples/amcl_diff.launch" unless="$(arg slam_gmapping)" />
14                 <param name="amcl/base_frame_id" value="base_footprint" />
15         </group>
16
17         <include file="$(find wild_thumper)/launch/gmapping.launch" if="$(arg slam_gmapping)" />
18
19         <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
20                 <param name="base_local_planner" value="$(arg base_local_planner)"/>
21                 <param name="controller_frequency" value="10.0" />
22                 <rosparam file="$(find wild_thumper)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
23                 <rosparam file="$(find wild_thumper)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
24                 <rosparam file="$(find wild_thumper)/config/global_costmap_params.yaml" command="load" unless="$(arg nomap)" />
25                 <rosparam file="$(find wild_thumper)/config/global_costmap_params_odom.yaml" command="load" if="$(arg nomap)" />
26                 <rosparam file="$(find wild_thumper)/config/local_costmap_params.yaml" command="load" />
27                 <rosparam file="$(find wild_thumper)/config/base_local_planner_params.yaml" command="load" />
28                 <remap from="/cmd_vel" to="move_base/cmd_vel"/>
29         </node>
30 </launch>