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