-
Notifications
You must be signed in to change notification settings - Fork 309
/
hdl_localization.launch
45 lines (42 loc) · 2.37 KB
/
hdl_localization.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
<?xml version="1.0"?>
<launch>
<!-- arguments -->
<arg name="nodelet_manager" default="velodyne_nodelet_manager" />
<arg name="points_topic" default="/velodyne_points" />
<arg name="imu_topic" default="/gpsimu_driver/imu_data" />
<arg name="odom_child_frame_id" default="velodyne" />
<!-- in case you use velodyne_driver, comment out the following line -->
<node pkg="nodelet" type="nodelet" name="$(arg nodelet_manager)" args="manager" output="screen"/>
<!-- globalmap_server_nodelet -->
<node pkg="nodelet" type="nodelet" name="globalmap_server_nodelet" args="load hdl_localization/GlobalmapServerNodelet $(arg nodelet_manager)">
<param name="globalmap_pcd" value="$(find hdl_localization)/data/map.pcd" />
<param name="downsample_resolution" value="0.1" />
</node>
<!-- hdl_localization_nodelet -->
<node pkg="nodelet" type="nodelet" name="hdl_localization_nodelet" args="load hdl_localization/HdlLocalizationNodelet $(arg nodelet_manager)">
<remap from="/velodyne_points" to="$(arg points_topic)" />
<remap from="/gpsimu_driver/imu_data" to="$(arg imu_topic)" />
<!-- odometry frame_id -->
<param name="odom_child_frame_id" value="$(arg odom_child_frame_id)" />
<!-- imu settings -->
<!-- during "cool_time", imu inputs are ignored -->
<param name="use_imu" value="true" />
<param name="invert_imu" value="true" />
<param name="cool_time_duration" value="2.0" />
<!-- ndt settings -->
<!-- if NDT is slow for your PC, try DIRECT1 serach method, which is a bit unstable but extremely fast -->
<param name="ndt_neighbor_search_method" value="DIRECT7" />
<param name="ndt_resolution" value="1.0" />
<param name="downsample_resolution" value="0.1" />
<!-- if "specify_init_pose" is true, pose estimator will be initialized with the following params -->
<!-- otherwise, you need to input an initial pose with "2D Pose Estimate" on rviz" -->
<param name="specify_init_pose" value="true" />
<param name="init_pos_x" value="0.0" />
<param name="init_pos_y" value="0.0" />
<param name="init_pos_z" value="0.0" />
<param name="init_ori_w" value="1.0" />
<param name="init_ori_x" value="0.0" />
<param name="init_ori_y" value="0.0" />
<param name="init_ori_z" value="0.0" />
</node>
</launch>