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