-
Notifications
You must be signed in to change notification settings - Fork 17
/
Copy pathlidar.launch.xml
57 lines (51 loc) · 2.51 KB
/
lidar.launch.xml
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
<launch>
<arg name="launch_driver" default="true" />
<arg name="host_ip" default="127.0.0.1"/>
<arg name="use_concat_filter" default="true" />
<arg name="vehicle_id" default="$(env VEHICLE_ID default)" />
<arg name="vehicle_mirror_param_file" />
<arg name="pointcloud_container_name" default="pointcloud_container"/>
<arg name="enable_blockage_diag" default="false"/>
<group>
<push-ros-namespace namespace="lidar"/>
<group>
<push-ros-namespace namespace="top"/>
<include file="$(find-pkg-share common_sensor_launch)/launch/velodyne_VLP16.launch.xml">
<arg name="sensor_frame" value="velodyne_top" />
<arg name="device_ip" value="192.168.1.20"/>
<arg name="host_ip" value="$(var host_ip)"/>
<arg name="data_port" value="2368"/>
<arg name="scan_phase" value="180.0" />
<arg name="launch_driver" value="$(var launch_driver)" />
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)" />
<arg name="container_name" value="pointcloud_container"/>
<arg name="enable_blockage_diag" value="$(var enable_blockage_diag)"/>
</include>
</group>
<group>
<push-ros-namespace namespace="front_center" />
<include file="$(find-pkg-share common_sensor_launch)/launch/hesai_XT32.launch.xml">
<arg name="sensor_frame" value="pandar_xt32_front_center" />
<arg name="sensor_ip" value="192.168.3.201" />
<arg name="data_port" value="2321" />
<arg name="gnss_port" value="10121" />
<arg name="scan_phase" value="0.0" />
<arg name="cloud_min_angle" value="0"/>
<arg name="cloud_max_angle" value="360"/>
<arg name="min_range" value="0.05"/>
<arg name="max_range" value="200.0"/>
<arg name="return_mode" value="Strongest" />
<arg name="config_file" value="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x1/xt32.csv" />
<arg name="launch_driver" value="$(var launch_driver)" />
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)" />
<arg name="container_name" value="pointcloud_container"/>
</include>
</group>
<include file="$(find-pkg-share aip_x1_launch)/launch/pointcloud_preprocessor.launch.py">
<arg name="base_frame" value="base_link" />
<arg name="use_intra_process" value="true" />
<arg name="use_multithread" value="false" />
<arg name="container_name" value="$(var pointcloud_container_name)"/>
</include>
</group>
</launch>