-
Notifications
You must be signed in to change notification settings - Fork 1
/
amcl.launch
67 lines (57 loc) · 3.24 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
59
60
61
62
63
64
65
66
67
<launch>
<!-- Parameter -->
<arg name="x_init_value" default="15"/>
<arg name="y_init_value" default="5"/>
<arg name="a_init_value" default="-1.5708"/>
<arg name="scan_topic" default="scan"/>
<!-- Map Server Node -->
<arg name="map_file" default="$(find whereami)/maps/map.yaml"/>
<node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)" />
<!-- AMCL Node -->
<node name="amcl" pkg="amcl" type="amcl" output="screen">
<!-- will use the remap tag to remap the topic name scan to the actual topic name -->
<!-- <remap from="scan" to="whereami/laser/scan"/> -->
<param name="min_particles" value="500"/>
<param name="max_particles" value="3000"/>
<param name="kld_err" value="0.02"/>
<param name="update_min_d" value="0.20"/>
<param name="update_min_a" value="0.20"/>
<param name="resample_interval" value="1"/>
<param name="transform_tolerance" value="0.5"/>
<remap from="scan" to="$(arg scan_topic)"/>
<param name="laser_max_range" value="5.5"/>
<param name="laser_max_beams" value="200"/>
<param name="laser_z_hit" value="0.5"/>
<param name="laser_z_short" value="0.05"/>
<param name="laser_z_max" value="0.09"/>
<param name="laser_z_rand" value="0.8"/>
<param name="laser_sigma_hit" value="0.2"/>
<param name="laser_lambda_short" value="0.1"/>
<param name="laser_likelihood_max_dist" value="3.0"/>
<param name="laser_model_type" value="likelihood_field"/>
<param name="odom_frame_id" value="odom"/>
<param name="odom_alpha4" value="0.3"/>
<param name="odom_model_type" value="diff-corrected"/> <!--can choose "diff", "omni", "diff-corrected" or "omni-corrected".-->
<param name="base_frame_id" value="robot_footprint"/>
<param name="global_frame_id" value="map"/>
<param name="transform_tolerance" value="0.4"/>
<!-- If you choose to define initial pose here -->
<!-- <param name="initial_pose_x" value="0"/> -->
<!-- <param name="initial_pose_y" value="0"/> -->
<param name="initial_pose_x" value="$(arg x_init_value)"/>
<param name="initial_pose_y" value="$(arg y_init_value)"/>
<param name="initial_pose_a" value="$(arg a_init_value)"/>
</node>
<!-- Move Base -->
<node name="move_base" pkg="move_base" type="move_base" respawn="false" output="screen">
<!-- <remap from="scan" to="whereami/laser/scan"/> -->
<param name="base_global_planner" value="navfn/NavfnROS" />
<param name="base_local_planner" value="base_local_planner/TrajectoryPlannerROS"/>
<rosparam file="$(find whereami)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find whereami)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find whereami)/config/local_costmap_params.yaml" command="load" />
<rosparam file="$(find whereami)/config/global_costmap_params.yaml" command="load" />
<rosparam file="$(find whereami)/config/base_local_planner_params.yaml" command="load" />
<remap from="scan" to="$(arg scan_topic)"/>
</node>
</launch>