-
-
Notifications
You must be signed in to change notification settings - Fork 95
/
Copy pathamcl.launch
58 lines (53 loc) · 3.07 KB
/
amcl.launch
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
<launch>
<!-- Arguments -->
<!--arg name="model" default="$(env DIFFBOT_MODEL)" doc="model type [diffbot, remo]"/-->
<arg name="model" default="diffbot" doc="model type [diffbot, remo]"/>
<arg name="scan_topic" default="diffbot/scan"/>
<arg name="initial_pose_x" default="0.0"/>
<arg name="initial_pose_y" default="0.0"/>
<arg name="initial_pose_a" default="0.0"/>
<arg name="use_map_topic" default="true"/>
<arg name="odom_frame_id" default="/odom"/>
<arg name="base_frame_id" default="/base_footprint"/>
<arg name="global_frame_id" default="/map"/>
<!-- AMCL -->
<node pkg="amcl" type="amcl" name="amcl">
<param name="use_map_topic" value="$(arg use_map_topic)"/>
<param name="min_particles" value="500"/>
<param name="max_particles" value="5000"/>
<param name="kld_err" value="0.02"/>
<param name="kld_z" value="0.99"/>
<param name="update_min_d" value="0.15"/>
<param name="update_min_a" value="0.15"/>
<param name="resample_interval" value="1"/>
<param name="transform_tolerance" value="0.1"/>
<param name="recovery_alpha_slow" value="0.00"/>
<param name="recovery_alpha_fast" value="0.00"/>
<param name="initial_pose_x" value="$(arg initial_pose_x)"/>
<param name="initial_pose_y" value="$(arg initial_pose_y)"/>
<param name="initial_pose_a" value="$(arg initial_pose_a)"/>
<param name="gui_publish_rate" value="50.0"/>
<remap from="scan" to="$(arg scan_topic)"/>
<param name="laser_max_range" value="-1"/>
<param name="laser_max_beams" value="30"/>
<param name="laser_z_hit" value="0.95"/>
<param name="laser_z_short" value="0.1"/>
<param name="laser_z_max" value="0.05"/>
<param name="laser_z_rand" value="0.05"/>
<param name="laser_sigma_hit" value="0.2"/>
<param name="laser_lambda_short" value="0.1"/>
<param name="laser_likelihood_max_dist" value="2.0"/>
<param name="laser_model_type" value="likelihood_field"/>
<!-- Which model to use, either "diff", "omni", "diff-corrected" or "omni-corrected". -->
<!-- diff-corrected was introduced to fix a bug and keep tuned robot's using the old modle (diff) working. -->
<!-- For the bug see http://wiki.ros.org/amcl#Parameters and https://github.com/ros-planning/navigation/issues/20 -->
<param name="odom_model_type" value="diff-corrected"/>
<param name="odom_alpha1" value="0.1"/>
<param name="odom_alpha2" value="0.1"/>
<param name="odom_alpha3" value="0.1"/>
<param name="odom_alpha4" value="0.1"/>
<param name="odom_frame_id" value="$(arg odom_frame_id)"/>
<param name="base_frame_id" value="$(arg base_frame_id)"/>
<param name="global_frame_id" value="$(arg global_frame_id)"/>
</node>
</launch>