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