]> defiant.homedns.org Git - ros_wild_thumper.git/blob - launch/move_base.launch
urdf: Rotate manipulator by 180°
[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="close_to_obstacles" default="false" />
7         <arg name="nomap" default="false" />
8         <arg name="base_global_planner" default="navfn/NavfnROS"/> <!-- navfn/NavfnROS || carrot_planner/CarrotPlanner -->
9         <arg name="base_local_planner" default="base_local_planner/TrajectoryPlannerROS"/> <!-- base_local_planner/TrajectoryPlannerROS || dwa_local_planner/DWAPlannerROS || pose_follower/PoseFollower -->
10         <!-- default: [{name: conservative_reset, type: clear_costmap_recovery/ClearCostmapRecovery}, {name: rotate_recovery, type: rotate_recovery/RotateRecovery}, {name: aggressive_reset, type: clear_costmap_recovery/ClearCostmapRecovery}]" -->
11         <arg name="recovery_behaviors" default="[{name: conservative_reset, type: clear_costmap_recovery/ClearCostmapRecovery}, {name: aggressive_reset, type: clear_costmap_recovery/ClearCostmapRecovery}]"/>
12
13         <!-- Run AMCL -->
14         <group unless="$(arg nomap)">
15                 <!-- Run the map server -->
16                 <node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)" output="screen" unless="$(arg slam_gmapping)" />
17
18                 <include file="$(find amcl)/examples/amcl_diff.launch" unless="$(arg slam_gmapping)" />
19                 <group ns="amcl">
20                         <param name="base_frame_id" value="base_footprint" />
21                         <param name="odom_model_type" value="diff-corrected" />
22                         <!-- Specifies the expected noise in odometry's rotation estimate from the rotational component of the robot's motion. -->
23                         <param name="odom_alpha1" value="0.001" />
24                         <!-- Specifies the expected noise in odometry's rotation estimate from translational component of the robot's motion. -->
25                         <param name="odom_alpha2" value="0.001" />
26                         <!-- Specifies the expected noise in odometry's translation estimate from the translational component of the robot's motion. -->
27                         <param name="odom_alpha3" value="0.04" />
28                         <!-- Specifies the expected noise in odometry's translation estimate from the rotational component of the robot's motion. -->
29                         <param name="odom_alpha4" value="0.001" />
30                         <!-- How many evenly-spaced beams in each scan to be used when updating the filter. -->
31                         <param name="laser_max_beams" value="50" />
32                         <!-- Exponential decay rate for the slow average weight filter, used in deciding when to recover by adding random poses. -->
33                         <param name="recovery_alpha_slow" value="0.001" />
34                         <!-- Exponential decay rate for the fast average weight filter, used in deciding when to recover by adding random poses. -->
35                         <param name="recovery_alpha_fast" value="0.1" />
36                         <!-- Minimum allowed number of particles. -->
37                         <param name="min_particles" value="100" />
38                 </group>
39         </group>
40
41         <include file="$(find wild_thumper)/launch/gmapping.launch" if="$(arg slam_gmapping)" />
42
43         <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen" clear_params="true">
44                 <param name="base_local_planner" value="$(arg base_local_planner)"/>
45                 <param name="base_global_planner" value="$(arg base_global_planner)"/>
46                 <param name="controller_frequency" value="10.0" />
47                 <param name="max_planning_retries" value="3" />
48                 <param name="clearing_rotation_allowed" value="false" />
49                 <param name="GlobalPlanner/default_tolerance" value="0.2" />
50                 <param name="conservative_reset/affected_maps" value="local" />
51                 <param name="make_plan_clear_costmap" value="false" />
52                 <param name="make_plan_add_unreachable_goal" value="false" />
53                 <rosparam param="recovery_behaviors" subst_value="True">$(arg recovery_behaviors)</rosparam>
54                 <rosparam file="$(find wild_thumper)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
55                 <rosparam file="$(find wild_thumper)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
56                 <rosparam file="$(find wild_thumper)/config/global_costmap_params.yaml" command="load" />
57                 <rosparam file="$(find wild_thumper)/config/global_costmap_params_odom.yaml" command="load" if="$(arg global_odom)" />
58                 <rosparam file="$(find wild_thumper)/config/local_costmap_params.yaml" command="load" />
59                 <rosparam file="$(find wild_thumper)/config/base_local_planner_params.yaml" command="load" />
60                 <rosparam file="$(find wild_thumper)/config/nav_close_to_obstacles.yaml" command="load" if="$(arg close_to_obstacles)" />
61                 <remap from="/cmd_vel" to="move_base/cmd_vel"/>
62         </node>
63 </launch>