]> defiant.homedns.org Git - ros_wild_thumper.git/blob - launch/move_base.launch
Added screen-startup file
[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="global_odom" default="false" />
6         <arg name="nomap" default="false" />
7         <arg name="base_local_planner" default="base_local_planner/TrajectoryPlannerROS"/> <!-- base_local_planner/TrajectoryPlannerROS || dwa_local_planner/DWAPlannerROS -->
8
9         <!-- Run AMCL -->
10         <group unless="$(arg nomap)">
11                 <!-- Run the map server -->
12                 <node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)" output="screen" unless="$(arg slam_gmapping)" />
13
14                 <include file="$(find amcl)/examples/amcl_diff.launch" unless="$(arg slam_gmapping)" />
15                 <group ns="amcl">
16                         <param name="base_frame_id" value="base_footprint" />
17                         <param name="odom_model_type" value="diff-corrected" />
18                         <!-- Specifies the expected noise in odometry's rotation estimate from the rotational component of the robot's motion. -->
19                         <param name="odom_alpha1" value="0.001" />
20                         <!-- Specifies the expected noise in odometry's rotation estimate from translational component of the robot's motion. -->
21                         <param name="odom_alpha2" value="0.001" />
22                         <!-- Specifies the expected noise in odometry's translation estimate from the translational component of the robot's motion. -->
23                         <param name="odom_alpha3" value="0.04" />
24                         <!-- Specifies the expected noise in odometry's translation estimate from the rotational component of the robot's motion. -->
25                         <param name="odom_alpha4" value="0.001" />
26                         <!-- How many evenly-spaced beams in each scan to be used when updating the filter. -->
27                         <param name="laser_max_beams" value="50" />
28                         <!-- Exponential decay rate for the slow average weight filter, used in deciding when to recover by adding random poses. -->
29                         <param name="recovery_alpha_slow" value="0.001" />
30                         <!-- Exponential decay rate for the fast average weight filter, used in deciding when to recover by adding random poses. -->
31                         <param name="recovery_alpha_fast" value="0.1" />
32                         <!-- Minimum allowed number of particles. -->
33                         <param name="min_particles" value="100" />
34                 </group>
35         </group>
36
37         <include file="$(find wild_thumper)/launch/gmapping.launch" if="$(arg slam_gmapping)" />
38
39         <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen" clear_params="true">
40                 <param name="base_local_planner" value="$(arg base_local_planner)"/>
41                 <param name="controller_frequency" value="10.0" />
42                 <rosparam file="$(find wild_thumper)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
43                 <rosparam file="$(find wild_thumper)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
44                 <rosparam file="$(find wild_thumper)/config/global_costmap_params.yaml" command="load" />
45                 <rosparam file="$(find wild_thumper)/config/global_costmap_params_odom.yaml" command="load" if="$(arg global_odom)" />
46                 <rosparam file="$(find wild_thumper)/config/local_costmap_params.yaml" command="load" />
47                 <rosparam file="$(find wild_thumper)/config/base_local_planner_params.yaml" command="load" />
48                 <remap from="/cmd_vel" to="move_base/cmd_vel"/>
49         </node>
50 </launch>