Apollo 10.0
自动驾驶开放平台
lslidar16_conf.pb.txt
浏览该文件的文档.
2 scan_channel: "/apollo/sensor/lslidar16/Scan"
3 point_cloud_channel: "/apollo/sensor/lslidar16/PointCloud2"
4 frame_id: "lslidar16"
5
6 # sample ONLINE_LIDAR, RAW_PACKET
7 source_type: ONLINE_LIDAR
8}
9
10model: LSLIDAR16P
11device_ip: "192.168.1.201"
12msop_port: 2370
13difop_port: 2371
14return_mode: 1
15degree_mode: 2 #2: 均匀2度校准两列 1://均匀1.33度校准两列
16distance_unit: 0.25
17packet_size: 1206
18time_synchronization: false
19add_multicast: false
20group_ip: "224.1.1.2"
21rpm: 600 #雷达转速 10hz:600rpm, 20hz:1200rpm, 5hz:300rpm
22frame_id: "lslidar16"
23min_range: 0.15
24max_range: 150.0
25config_vert: true
26scan_start_angle: 0.0
27scan_end_angle: 36000.0
28#要屏蔽的矩形区域参数
29bottom_left_x: 0.0 #左下 x值
30bottom_left_y: 0.0 #左下 y值
31top_right_x: 0.0 #右上 x值
32top_right_y: 0.0 #右上 y值
33
34calibration: false
35calibration_file: "modules/drivers/lidar/lslidar/params/LS16_calibration.yaml"
36pcap_path: "" #读取pcap包,测试时使用,连接雷达的时候,将此值设置为空
37
std::string frame_id
Point cloud frame id