Skip to content

Commit a3c851f

Browse files
authored
Merge pull request #15042 from Lslidar/apollo_lslidar_230714
Add lslidar driver for Apollo platform,230714
2 parents d5f88cb + cf81fa2 commit a3c851f

File tree

114 files changed

+10420
-0
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

114 files changed

+10420
-0
lines changed

modules/drivers/lidar/BUILD

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@ install(
1818
"//modules/drivers/lidar/hesai:install",
1919
"//modules/drivers/lidar/robosense:install",
2020
"//modules/drivers/lidar/velodyne:install",
21+
"//modules/drivers/lidar/lslidar:install",
2122
]
2223
)
2324

Lines changed: 27 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,27 @@
1+
load("//tools/install:install.bzl", "install")
2+
3+
package(default_visibility = ["//visibility:public"])
4+
5+
install(
6+
name = "install",
7+
data_dest = "drivers/addition_data/lidar/lslidar",
8+
library_dest = "drivers/lib/lidar/lslidar",
9+
data = [
10+
":runtime_data",
11+
],
12+
targets = [
13+
"//modules/drivers/lidar/lslidar/driver:liblslidar_driver_component.so",
14+
"//modules/drivers/lidar/lslidar/parser:liblslidar_convert_component.so",
15+
],
16+
)
17+
18+
filegroup(
19+
name = "runtime_data",
20+
srcs = glob([
21+
"conf/*.txt",
22+
"conf/*.conf",
23+
"dag/*.dag",
24+
"launch/*.launch",
25+
"params/*.yaml",
26+
]),
27+
)
Lines changed: 140 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,140 @@
1+
# **Lslidar LiDAR Driver**
2+
3+
4+
5+
## 1、 工程简介
6+
7+
**lslidar** 为镭神在Apollo 8.0平台的雷达驱动集成包。 目前支持*C16,C32,CH16,CH32,CH64,CH64w,CH120,CH128,CH128X1*等型号的雷达。
8+
9+
10+
11+
## 2、 驱动运行示例
12+
13+
#### 2.1 C16
14+
15+
cyber_launch start /apollo/modules/drivers/lidar/lslidar/launch/lslidar16.launch
16+
17+
mainboard -d /apollo/modules/drivers/lidar/lslidar/dag/lslidar16.dag
18+
19+
默认话题名:
20+
21+
- 原始点云 -- /apollo/sensor/lslidar16/PointCloud2
22+
- Scan--/apollo/sensor/lslidar16/Scan
23+
- 运动补偿后点云 -- /apollo/sensor/lslidar16/compensator/PointCloud2
24+
25+
26+
#### 2.2 C32
27+
28+
cyber_launch start /apollo/modules/drivers/lidar/lslidar/launch/lslidar32.launch
29+
30+
mainboard -d /apollo/modules/drivers/lidar/lslidar/dag/lslidar32.dag
31+
32+
默认话题名:
33+
34+
- 原始点云 -- /apollo/sensor/lslidar32/PointCloud2
35+
- Scan--/apollo/sensor/lslidar32/Scan
36+
- 运动补偿后点云 -- /apollo/sensor/lslidar32/compensator/PointCloud2
37+
38+
39+
#### 2.3 N401(删除)
40+
41+
cyber_launch start /apollo/modules/drivers/lidar/lslidar/launch/lslidar401.launch
42+
43+
mainboard -d /apollo/modules/drivers/lidar/lslidar/dag/lslidar401.dag
44+
45+
默认话题名:
46+
47+
- 原始点云 -- /apollo/sensor/lslidar401/PointCloud2
48+
- Scan--/apollo/sensor/lslidar401/Scan
49+
50+
#### 2.4 CH16
51+
52+
cyber_launch start /apollo/modules/drivers/lidar/lslidar/launch/lslidarCH16.launch
53+
54+
mainboard -d /apollo/modules/drivers/lidar/lslidar/dag/lslidarCH16.dag
55+
56+
默认话题名:
57+
58+
- 原始点云 -- /apollo/sensor/lslidarCH16/PointCloud2
59+
- Scan--/apollo/sensor/lslidarCH16/Scan
60+
- 运动补偿后点云 -- /apollo/sensor/lslidarCH16/compensator/PointCloud2
61+
62+
#### 2.5 CH32
63+
64+
cyber_launch start /apollo/modules/drivers/lidar/lslidar/launch/lslidarCH32.launch
65+
66+
mainboard -d /apollo/modules/drivers/lidar/lslidar/dag/lslidarCH32.dag
67+
68+
默认话题名:
69+
70+
- 原始点云 -- /apollo/sensor/lslidarCH32/PointCloud2
71+
- Scan--/apollo/sensor/lslidarCH32/Scan
72+
- 运动补偿后点云 -- /apollo/sensor/lslidarCH32/compensator/PointCloud2
73+
74+
#### 2.6 CH64
75+
76+
cyber_launch start /apollo/modules/drivers/lidar/lslidar/launch/lslidarCH64.launch
77+
78+
mainboard -d /apollo/modules/drivers/lidar/lslidar/dag/lslidarCH64.dag
79+
80+
默认话题名:
81+
82+
- 原始点云 -- /apollo/sensor/lslidarCH64/PointCloud2
83+
- Scan--/apollo/sensor/lslidarCH64/Scan
84+
- 运动补偿后点云 -- /apollo/sensor/lslidarCH64/compensator/PointCloud2
85+
86+
#### 2.7 CH64w
87+
88+
cyber_launch start /apollo/modules/drivers/lidar/lslidar/launch/lslidarCH64w.launch
89+
90+
mainboard -d /apollo/modules/drivers/lidar/lslidar/dag/lslidarCH64w.dag
91+
92+
默认话题名:
93+
94+
- 原始点云 -- /apollo/sensor/lslidarCH64w/PointCloud2
95+
- Scan--/apollo/sensor/lslidarCH64w/Scan
96+
- 运动补偿后点云 -- /apollo/sensor/lslidarCH64w/compensator/PointCloud2
97+
98+
#### 2.8 CH120
99+
100+
cyber_launch start /apollo/modules/drivers/lidar/lslidar/launch/lslidarCH120.launch
101+
102+
mainboard -d /apollo/modules/drivers/lidar/lslidar/dag/lslidarCH120.dag
103+
104+
默认话题名:
105+
106+
- 原始点云 -- /apollo/sensor/lslidarCH120/PointCloud2
107+
- Scan--/apollo/sensor/lslidarCH120/Scan
108+
- 运动补偿后点云 -- /apollo/sensor/lslidarCH120/compensator/PointCloud2
109+
110+
#### 2.9 CH128
111+
112+
cyber_launch start /apollo/modules/drivers/lidar/lslidar/launch/lslidarCH128.launch
113+
114+
mainboard -d /apollo/modules/drivers/lidar/lslidar/dag/lslidarCH128.dag
115+
116+
默认话题名:
117+
118+
- 原始点云 -- /apollo/sensor/lslidarCH128/PointCloud2
119+
- Scan--/apollo/sensor/lslidarCH128/Scan
120+
- 运动补偿后点云 -- /apollo/sensor/lslidarCH128/compensator/PointCloud2
121+
122+
#### 2.10 CH128X1
123+
124+
cyber_launch start /apollo/modules/drivers/lidar/lslidar/launch/lslidarCH128X1.launch
125+
126+
mainboard -d /apollo/modules/drivers/lidar/lslidar/dag/lslidarCH128X1.dag
127+
128+
默认话题名:
129+
130+
- 原始点云 -- /apollo/sensor/lslidarCH128X1/PointCloud2
131+
- Scan--/apollo/sensor/lslidarCH128X1/Scan
132+
- 运动补偿后点云 -- /apollo/sensor/lslidarCH128X1/compensator/PointCloud2
133+
134+
135+
136+
### 常见问题
137+
138+
- 打印“[lslidar]lslidar poll() timeout, port: 2368‘’ 表示计算平台与雷达网络不通。
139+
140+
可用wireshark查看是否有雷达数据;以及雷达ip和端口号参数设置是否正确。
Lines changed: 142 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,142 @@
1+
# **Lslidar LiDAR Driver**
2+
3+
4+
5+
## 1. Overview
6+
7+
**lslidar** is a lidar driver integration package from LenShen Intelligent System Co. Ltd. for the Apollo 8.0 platform. Currently the *C16, C32, CH16, CH32, CH64, CH64w, CH120, CH128,CH128X1* lidar models are supported.
8+
9+
10+
11+
## 2. Example of driver running
12+
13+
#### 2.1 C16
14+
15+
cyber_launch start /apollo/modules/drivers/lidar/lslidar/launch/lslidar16.launch
16+
or
17+
mainboard -d /apollo/modules/drivers/lidar/lslidar/dag/lslidar16.dag
18+
19+
Default topic name:
20+
21+
- Raw point cloud -- /apollo/sensor/lslidar16/PointCloud2
22+
- Scan--/apollo/sensor/lslidar16/Scan
23+
- Point cloud after motion compensation -- /apollo/sensor/lslidar16/compensator/PointCloud2
24+
25+
26+
#### 2.2 C32
27+
28+
cyber_launch start /apollo/modules/drivers/lidar/lslidar/launch/lslidar32.launch
29+
or
30+
mainboard -d /apollo/modules/drivers/lidar/lslidar/dag/lslidar32.dag
31+
32+
Default topic name:
33+
34+
- Raw point cloud -- /apollo/sensor/lslidar32/PointCloud2
35+
- Scan--/apollo/sensor/lslidar32/Scan
36+
- Point cloud after motion compensation -- /apollo/sensor/lslidar32/compensator/PointCloud2
37+
38+
39+
#### 2.3 N401(delete)
40+
41+
cyber_launch start /apollo/modules/drivers/lidar/lslidar/launch/lslidar401.launch
42+
or
43+
mainboard -d /apollo/modules/drivers/lidar/lslidar/dag/lslidar401.dag
44+
45+
Default topic name:
46+
47+
- Raw point cloud -- /apollo/sensor/lslidar401/PointCloud2
48+
- Scan--/apollo/sensor/lslidar401/Scan
49+
50+
#### 2.4 CH16
51+
52+
cyber_launch start /apollo/modules/drivers/lidar/lslidar/launch/lslidarCH16.launch
53+
or
54+
mainboard -d /apollo/modules/drivers/lidar/lslidar/dag/lslidarCH16.dag
55+
56+
Default topic name:
57+
58+
- Raw point cloud -- /apollo/sensor/lslidarCH16/PointCloud2
59+
- Scan--/apollo/sensor/lslidarCH16/Scan
60+
- Point cloud after motion compensation -- /apollo/sensor/lslidarCH16/compensator/PointCloud2
61+
62+
#### 2.5 CH32
63+
64+
cyber_launch start /apollo/modules/drivers/lidar/lslidar/launch/lslidarCH32.launch
65+
or
66+
mainboard -d /apollo/modules/drivers/lidar/lslidar/dag/lslidarCH32.dag
67+
68+
Default topic name:
69+
70+
- Raw point cloud -- /apollo/sensor/lslidarCH32/PointCloud2
71+
- Scan--/apollo/sensor/lslidarCH32/Scan
72+
- Point cloud after motion compensation -- /apollo/sensor/lslidarCH32/compensator/PointCloud2
73+
74+
#### 2.6 CH64
75+
76+
cyber_launch start /apollo/modules/drivers/lidar/lslidar/launch/lslidarCH64.launch
77+
or
78+
mainboard -d /apollo/modules/drivers/lidar/lslidar/dag/lslidarCH64.dag
79+
80+
Default topic name:
81+
82+
- Raw point cloud -- /apollo/sensor/lslidarCH64/PointCloud2
83+
- Scan--/apollo/sensor/lslidarCH64/Scan
84+
- Point cloud after motion compensation -- /apollo/sensor/lslidarCH64/compensator/PointCloud2
85+
86+
#### 2.7 CH64w
87+
88+
cyber_launch start /apollo/modules/drivers/lidar/lslidar/launch/lslidarCH64w.launch
89+
or
90+
mainboard -d /apollo/modules/drivers/lidar/lslidar/dag/lslidarCH64w.dag
91+
92+
Default topic name:
93+
94+
- Raw point cloud -- /apollo/sensor/lslidarCH64w/PointCloud2
95+
- Scan--/apollo/sensor/lslidarCH64w/Scan
96+
- Point cloud after motion compensation -- /apollo/sensor/lslidarCH64w/compensator/PointCloud2
97+
98+
#### 2.8 CH120
99+
100+
cyber_launch start /apollo/modules/drivers/lidar/lslidar/launch/lslidarCH120.launch
101+
or
102+
mainboard -d /apollo/modules/drivers/lidar/lslidar/dag/lslidarCH120.dag
103+
104+
Default topic name:
105+
106+
- Raw point cloud -- /apollo/sensor/lslidarCH120/PointCloud2
107+
- Scan--/apollo/sensor/lslidarCH120/Scan
108+
- Point cloud after motion compensation -- /apollo/sensor/lslidarCH120/compensator/PointCloud2
109+
110+
#### 2.9 CH128
111+
112+
cyber_launch start /apollo/modules/drivers/lidar/lslidar/launch/lslidarCH128.launch
113+
or
114+
mainboard -d /apollo/modules/drivers/lidar/lslidar/dag/lslidarCH128.dag
115+
116+
Default topic name:
117+
118+
- Raw point cloud -- /apollo/sensor/lslidarCH128/PointCloud2
119+
- Scan--/apollo/sensor/lslidarCH128/Scan
120+
- Point cloud after motion compensation -- /apollo/sensor/lslidarCH128/compensator/PointCloud2
121+
122+
#### 2.10 CH128X1
123+
124+
cyber_launch start /apollo/modules/drivers/lidar/lslidar/launch/lslidarCH128X1.launch
125+
or
126+
mainboard -d /apollo/modules/drivers/lidar/lslidar/dag/lslidarCH128X1.dag
127+
128+
Default topic name:
129+
130+
- Raw point cloud -- /apollo/sensor/lslidarCH128X1/PointCloud2
131+
- Scan--/apollo/sensor/lslidarCH128X1/Scan
132+
- Point cloud after motion compensation -- /apollo/sensor/lslidarCH128X1/compensator/PointCloud2
133+
134+
135+
136+
### Frequently asked questions
137+
138+
- The printout "[lslidar]lslidar poll() timeout, port: 2368" indicates that the computing platform is not connected to the lidar network.
139+
140+
You can use Wireshark to see if lidar data is available; and if the lidar IP and port number parameters are set correctly.
141+
142+
Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,3 @@
1+
world_frame_id: "world"
2+
transform_query_timeout: 0.02
3+
output_channel: "/apollo/sensor/lslidar16/compensator/PointCloud2"
Lines changed: 30 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,30 @@
1+
model: LSLIDAR16P
2+
device_ip: "192.168.1.201"
3+
msop_port: 2370
4+
difop_port: 2371
5+
return_mode: 1
6+
degree_mode: 2 #2: 均匀2度校准两列 1://均匀1.33度校准两列
7+
distance_unit: 0.25
8+
packet_size: 1206
9+
time_synchronization: false
10+
add_multicast: false
11+
group_ip: "224.1.1.2"
12+
rpm: 600 #雷达转速 10hz:600rpm, 20hz:1200rpm, 5hz:300rpm
13+
convert_channel_name: "/apollo/sensor/lslidar16/PointCloud2"
14+
frame_id: "lslidar16"
15+
scan_channel: "/apollo/sensor/lslidar16/Scan"
16+
min_range: 0.15
17+
max_range: 150.0
18+
config_vert: true
19+
scan_start_angle: 0.0
20+
scan_end_angle: 36000.0
21+
#要屏蔽的矩形区域参数
22+
bottom_left_x: 0.0 #左下 x值
23+
bottom_left_y: 0.0 #左下 y值
24+
top_right_x: 0.0 #右上 x值
25+
top_right_y: 0.0 #右上 y值
26+
27+
calibration: false
28+
calibration_file: "/apollo/modules/drivers/lidar/lslidar/params/LS16_calibration.yaml"
29+
pcap_path: "" #读取pcap包,测试时使用,连接雷达的时候,将此值设置为空
30+
Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,3 @@
1+
world_frame_id: "world"
2+
transform_query_timeout: 0.02
3+
output_channel: "/apollo/sensor/lslidar16v4/compensator/PointCloud2"
Lines changed: 26 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,26 @@
1+
model: LSLIDAR_C16_V4
2+
device_ip: "192.168.1.200"
3+
msop_port: 2368
4+
difop_port: 2369
5+
return_mode: 1
6+
degree_mode: 2 #2: 均匀1度校准两列 1://均匀0.33度校准两列
7+
distance_unit: 0.4
8+
packet_size: 1212
9+
time_synchronization: false
10+
add_multicast: false
11+
group_ip: "224.1.1.2"
12+
rpm: 600
13+
convert_channel_name: "/apollo/sensor/lslidar16v4/PointCloud2"
14+
frame_id: "lslidar16v4"
15+
scan_channel: "/apollo/sensor/lslidar16v4/Scan"
16+
min_range: 0.15
17+
max_range: 150.0
18+
config_vert: true
19+
scan_start_angle: 0.0
20+
scan_end_angle: 36000.0
21+
#要屏蔽的矩形区域参数
22+
bottom_left_x: 0.0 #左下 x值
23+
bottom_left_y: 0.0 #左下 y值
24+
top_right_x: 0.0 #右上 x值
25+
top_right_y: 0.0 #右上 y值
26+
pcap_path: "" #读取pcap包,测试时使用,连接雷达的时候,将此值设置为空
Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,3 @@
1+
world_frame_id: "world"
2+
transform_query_timeout: 0.02
3+
output_channel: "/apollo/sensor/lslidar1v4/compensator/PointCloud2"

0 commit comments

Comments
 (0)