Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
df600e3e
A
apollo
项目概览
Pinoxchio
/
apollo
与 Fork 源项目一致
从无法访问的项目Fork
通知
2
Star
0
Fork
0
代码
文件
提交
分支
Tags
贡献者
分支图
Diff
Issue
0
列表
看板
标记
里程碑
合并请求
0
Wiki
0
Wiki
分析
仓库
DevOps
项目成员
Pages
A
apollo
项目概览
项目概览
详情
发布
仓库
仓库
文件
提交
分支
标签
贡献者
分支图
比较
Issue
0
Issue
0
列表
看板
标记
里程碑
合并请求
0
合并请求
0
Pages
分析
分析
仓库分析
DevOps
Wiki
0
Wiki
成员
成员
收起侧边栏
关闭侧边栏
动态
分支图
创建新Issue
提交
Issue看板
体验新版 GitCode,发现更多精彩内容 >>
提交
df600e3e
编写于
4月 12, 2019
作者:
P
pengronggui
提交者:
Ronggui Peng
4月 14, 2019
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
Drivers: add support velodyne-vlp32c
上级
c39b8965
变更
8
隐藏空白更改
内联
并排
Showing
8 changed file
with
399 addition
and
6 deletion
+399
-6
modules/drivers/velodyne/conf/velodyne_vlp32c_conf.pb.txt
modules/drivers/velodyne/conf/velodyne_vlp32c_conf.pb.txt
+16
-0
modules/drivers/velodyne/driver/driver.cc
modules/drivers/velodyne/driver/driver.cc
+5
-0
modules/drivers/velodyne/driver/driver.h
modules/drivers/velodyne/driver/driver.h
+1
-0
modules/drivers/velodyne/params/VLP32C_calibration_example.yaml
...s/drivers/velodyne/params/VLP32C_calibration_example.yaml
+225
-0
modules/drivers/velodyne/parser/const_variables.h
modules/drivers/velodyne/parser/const_variables.h
+58
-0
modules/drivers/velodyne/parser/velodyne32_parser.cc
modules/drivers/velodyne/parser/velodyne32_parser.cc
+92
-5
modules/drivers/velodyne/parser/velodyne_parser.cc
modules/drivers/velodyne/parser/velodyne_parser.cc
+1
-1
modules/drivers/velodyne/parser/velodyne_parser.h
modules/drivers/velodyne/parser/velodyne_parser.h
+1
-0
未找到文件。
modules/drivers/velodyne/conf/velodyne_vlp32c_conf.pb.txt
0 → 100644
浏览文件 @
df600e3e
frame_id: "velodyne32"
scan_channel: "/apollo/sensor/velodyne32/VelodyneScan"
rpm: 600.0
model: VLP32C
mode: STRONGEST
firing_data_port: 8308
use_sensor_sync: false
max_range: 200
min_range: 0.4
use_gps_time: true
calibration_online: false
calibration_file: "/apollo/modules/drivers/velodyne/params/VLP32C_calibration_example.yaml"
organized: false
convert_channel_name: "/apollo/sensor/velodyne32/PointCloud2"
use_poll_sync: true
is_main_frame: true
modules/drivers/velodyne/driver/driver.cc
浏览文件 @
df600e3e
...
...
@@ -254,6 +254,11 @@ VelodyneDriver* VelodyneDriverFactory::CreateDriver(const Config& config) {
driver
->
SetPacketRate
(
PACKET_RATE_HDL32E
);
break
;
}
case
VLP32C
:
{
driver
=
new
VelodyneDriver
(
config
);
driver
->
SetPacketRate
(
PACKET_RATE_VLP32C
);
break
;
}
case
VLP16
:
{
driver
=
new
VelodyneDriver
(
config
);
driver
->
SetPacketRate
(
PACKET_RATE_VLP16
);
...
...
modules/drivers/velodyne/driver/driver.h
浏览文件 @
df600e3e
...
...
@@ -36,6 +36,7 @@ constexpr double PACKET_RATE_HDL64E_S2 = 3472.17;
constexpr
double
PACKET_RATE_HDL64E_S3S
=
3472.17
;
constexpr
double
PACKET_RATE_HDL64E_S3D
=
5789
;
constexpr
double
PACKET_RATE_VLS128
=
6250.0
;
constexpr
double
PACKET_RATE_VLP32C
=
1507.0
;
class
VelodyneDriver
{
public:
...
...
modules/drivers/velodyne/params/VLP32C_calibration_example.yaml
0 → 100644
浏览文件 @
df600e3e
lasers
:
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
0
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
-0.024434609527920613
,
vert_correction
:
-0.4363323129985824
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
1
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.07330382858376185
,
vert_correction
:
-0.017453292519943295
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
2
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
-0.024434609527920613
,
vert_correction
:
-0.029094638630745476
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
3
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.024434609527920613
,
vert_correction
:
-0.2729520417193932
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
4
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
-0.024434609527920613
,
vert_correction
:
-0.19739673840055869
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
5
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.024434609527920613
,
vert_correction
:
0.0
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
6
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
-0.07330382858376185
,
vert_correction
:
-0.011641346110802179
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
7
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.024434609527920613
,
vert_correction
:
-0.15433946575385857
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
8
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
-0.024434609527920613
,
vert_correction
:
-0.12660618393966866
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
9
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.07330382858376185
,
vert_correction
:
0.005811946409141118
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
10
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
-0.024434609527920613
,
vert_correction
:
-0.005811946409141118
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
11
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.024434609527920613
,
vert_correction
:
-0.10730284241261137
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
12
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
-0.07330382858376185
,
vert_correction
:
-0.0930784090088576
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
13
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.024434609527920613
,
vert_correction
:
0.02326523892908441
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
14
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
-0.07330382858376185
,
vert_correction
:
0.011641346110802179
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
15
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.024434609527920613
,
vert_correction
:
-0.06981317007977318
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
16
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
-0.024434609527920613
,
vert_correction
:
-0.08145451619057535
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
17
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.07330382858376185
,
vert_correction
:
0.029094638630745476
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
18
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
-0.024434609527920613
,
vert_correction
:
0.017453292519943295
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
19
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.07330382858376185
,
vert_correction
:
-0.06400122367063206
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
20
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
-0.07330382858376185
,
vert_correction
:
-0.058171823968971005
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
21
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.024434609527920613
,
vert_correction
:
0.058171823968971005
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
22
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
-0.024434609527920613
,
vert_correction
:
0.04071853144902771
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
23
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.024434609527920613
,
vert_correction
:
-0.04654793115068877
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
24
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
-0.024434609527920613
,
vert_correction
:
-0.05235987755982989
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
25
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.024434609527920613
,
vert_correction
:
0.12217304763960307
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
26
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
-0.024434609527920613
,
vert_correction
:
0.08145451619057535
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
27
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.07330382858376185
,
vert_correction
:
-0.04071853144902771
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
28
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
-0.07330382858376185
,
vert_correction
:
-0.03490658503988659
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
29
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.024434609527920613
,
vert_correction
:
0.2617993877991494
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
30
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
-0.024434609527920613
,
vert_correction
:
0.18034487160857407
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
31
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.024434609527920613
,
vert_correction
:
-0.02326523892908441
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
32
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.0
,
vert_correction
:
0.0
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
33
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.0
,
vert_correction
:
0.0
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
34
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.0
,
vert_correction
:
0.0
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
35
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.0
,
vert_correction
:
0.0
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
36
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.0
,
vert_correction
:
0.0
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
37
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.0
,
vert_correction
:
0.0
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
38
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.0
,
vert_correction
:
0.0
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
39
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.0
,
vert_correction
:
0.0
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
40
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.0
,
vert_correction
:
0.0
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
41
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.0
,
vert_correction
:
0.0
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
42
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.0
,
vert_correction
:
0.0
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
43
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.0
,
vert_correction
:
0.0
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
44
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.0
,
vert_correction
:
0.0
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
45
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.0
,
vert_correction
:
0.0
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
46
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.0
,
vert_correction
:
0.0
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
47
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.0
,
vert_correction
:
0.0
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
48
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.0
,
vert_correction
:
0.0
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
49
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.0
,
vert_correction
:
0.0
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
50
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.0
,
vert_correction
:
0.0
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
51
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.0
,
vert_correction
:
0.0
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
52
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.0
,
vert_correction
:
0.0
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
53
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.0
,
vert_correction
:
0.0
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
54
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.0
,
vert_correction
:
0.0
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
55
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.0
,
vert_correction
:
0.0
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
56
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.0
,
vert_correction
:
0.0
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
57
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.0
,
vert_correction
:
0.0
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
58
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.0
,
vert_correction
:
0.0
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
59
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.0
,
vert_correction
:
0.0
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
60
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.0
,
vert_correction
:
0.0
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
61
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.0
,
vert_correction
:
0.0
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
62
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.0
,
vert_correction
:
0.0
,
vert_offset_correction
:
0.0
}
-
{
dist_correction
:
0.0
,
dist_correction_x
:
0.0
,
dist_correction_y
:
0.0
,
focal_distance
:
0.0
,
focal_slope
:
0.0
,
horiz_offset_correction
:
0.0
,
laser_id
:
63
,
max_intensity
:
255
,
min_intensity
:
0
,
rot_correction
:
0.0
,
vert_correction
:
0.0
,
vert_offset_correction
:
0.0
}
num_lasers
:
64
modules/drivers/velodyne/parser/const_variables.h
浏览文件 @
df600e3e
...
...
@@ -303,6 +303,64 @@ const float INNER_TIME_128[12][32] = {
137.9
f
,
137.9
f
,
137.9
f
,
137.9
f
,
137.9
f
,
137.9
f
,
137.9
f
,
137.9
f
,
140.5
f
,
140.5
f
,
140.5
f
,
140.5
f
,
140.5
f
,
140.5
f
,
140.5
f
,
140.5
f
}};
const
float
INNER_TIME_VLP32C
[
12
][
32
]
=
{
{
0.000
f
,
0.000
f
,
2.304
f
,
2.304
f
,
4.608
f
,
4.608
f
,
6.912
f
,
6.912
f
,
9.216
f
,
9.216
f
,
11.520
f
,
11.520
f
,
13.824
f
,
13.824
f
,
16.128
f
,
16.128
f
,
18.432
f
,
18.432
f
,
20.736
f
,
20.736
f
,
23.040
f
,
23.040
f
,
25.344
f
,
25.344
f
,
27.648
f
,
27.648
f
,
29.952
f
,
29.952
f
,
32.256
f
,
32.256
f
,
34.560
f
,
34.560
f
},
{
0.000
f
,
0.000
f
,
2.304
f
,
2.304
f
,
4.608
f
,
4.608
f
,
6.912
f
,
6.912
f
,
9.216
f
,
9.216
f
,
11.520
f
,
11.520
f
,
13.824
f
,
13.824
f
,
16.128
f
,
16.128
f
,
18.432
f
,
18.432
f
,
20.736
f
,
20.736
f
,
23.040
f
,
23.040
f
,
25.344
f
,
25.344
f
,
27.648
f
,
27.648
f
,
29.952
f
,
29.952
f
,
32.256
f
,
32.256
f
,
34.560
f
,
34.560
f
},
{
55.296
f
,
55.296
f
,
57.600
f
,
57.600
f
,
59.904
f
,
59.904
f
,
62.208
f
,
62.208
f
,
64.512
f
,
64.512
f
,
66.816
f
,
66.816
f
,
69.120
f
,
69.120
f
,
71.424
f
,
71.424
f
,
73.728
f
,
73.728
f
,
76.032
f
,
76.032
f
,
78.336
f
,
78.336
f
,
80.640
f
,
80.640
f
,
82.944
f
,
82.944
f
,
85.248
f
,
85.248
f
,
87.552
f
,
87.552
f
,
89.856
f
,
89.856
f
},
{
55.296
f
,
55.296
f
,
57.600
f
,
57.600
f
,
59.904
f
,
59.904
f
,
62.208
f
,
62.208
f
,
64.512
f
,
64.512
f
,
66.816
f
,
66.816
f
,
69.120
f
,
69.120
f
,
71.424
f
,
71.424
f
,
73.728
f
,
73.728
f
,
76.032
f
,
76.032
f
,
78.336
f
,
78.336
f
,
80.640
f
,
80.640
f
,
82.944
f
,
82.944
f
,
85.248
f
,
85.248
f
,
87.552
f
,
87.552
f
,
89.856
f
,
89.856
f
},
{
110.592
f
,
110.592
f
,
112.896
f
,
112.896
f
,
115.200
f
,
115.200
f
,
117.504
f
,
117.504
f
,
119.808
f
,
119.808
f
,
122.112
f
,
122.112
f
,
124.416
f
,
124.416
f
,
126.720
f
,
126.720
f
,
129.024
f
,
129.024
f
,
131.328
f
,
131.328
f
,
133.632
f
,
133.632
f
,
135.936
f
,
135.936
f
,
138.240
f
,
138.240
f
,
140.544
f
,
140.544
f
,
142.848
f
,
142.848
f
,
145.152
f
,
145.152
f
},
{
110.592
f
,
110.592
f
,
112.896
f
,
112.896
f
,
115.200
f
,
115.200
f
,
117.504
f
,
117.504
f
,
119.808
f
,
119.808
f
,
122.112
f
,
122.112
f
,
124.416
f
,
124.416
f
,
126.720
f
,
126.720
f
,
129.024
f
,
129.024
f
,
131.328
f
,
131.328
f
,
133.632
f
,
133.632
f
,
135.936
f
,
135.936
f
,
138.240
f
,
138.240
f
,
140.544
f
,
140.544
f
,
142.848
f
,
142.848
f
,
145.152
f
,
145.152
f
},
{
165.888
f
,
165.888
f
,
168.192
f
,
168.192
f
,
170.496
f
,
170.496
f
,
172.800
f
,
172.800
f
,
175.104
f
,
175.104
f
,
177.408
f
,
177.408
f
,
179.712
f
,
179.712
f
,
182.016
f
,
182.016
f
,
184.320
f
,
184.320
f
,
186.624
f
,
186.624
f
,
188.928
f
,
188.928
f
,
191.232
f
,
191.232
f
,
193.536
f
,
193.536
f
,
195.840
f
,
195.840
f
,
198.144
f
,
198.144
f
,
200.448
f
,
200.448
f
},
{
165.888
f
,
165.888
f
,
168.192
f
,
168.192
f
,
170.496
f
,
170.496
f
,
172.800
f
,
172.800
f
,
175.104
f
,
175.104
f
,
177.408
f
,
177.408
f
,
179.712
f
,
179.712
f
,
182.016
f
,
182.016
f
,
184.320
f
,
184.320
f
,
186.624
f
,
186.624
f
,
188.928
f
,
188.928
f
,
191.232
f
,
191.232
f
,
193.536
f
,
193.536
f
,
195.840
f
,
195.840
f
,
198.144
f
,
198.144
f
,
200.448
f
,
200.448
f
},
{
221.184
f
,
221.184
f
,
223.488
f
,
223.488
f
,
225.792
f
,
225.792
f
,
228.096
f
,
228.096
f
,
230.400
f
,
230.400
f
,
232.704
f
,
232.704
f
,
235.008
f
,
235.008
f
,
237.312
f
,
237.312
f
,
239.616
f
,
239.616
f
,
241.920
f
,
241.920
f
,
244.224
f
,
244.224
f
,
246.528
f
,
246.528
f
,
248.832
f
,
248.832
f
,
251.136
f
,
251.136
f
,
253.440
f
,
253.440
f
,
255.744
f
,
255.744
f
},
{
221.184
f
,
221.184
f
,
223.488
f
,
223.488
f
,
225.792
f
,
225.792
f
,
228.096
f
,
228.096
f
,
230.400
f
,
230.400
f
,
232.704
f
,
232.704
f
,
235.008
f
,
235.008
f
,
237.312
f
,
237.312
f
,
239.616
f
,
239.616
f
,
241.920
f
,
241.920
f
,
244.224
f
,
244.224
f
,
246.528
f
,
246.528
f
,
248.832
f
,
248.832
f
,
251.136
f
,
251.136
f
,
253.440
f
,
253.440
f
,
255.744
f
,
255.744
f
},
{
276.480
f
,
276.480
f
,
278.784
f
,
278.784
f
,
281.088
f
,
281.088
f
,
283.392
f
,
283.392
f
,
285.696
f
,
285.696
f
,
288.000
f
,
288.000
f
,
290.304
f
,
290.304
f
,
292.608
f
,
292.608
f
,
294.912
f
,
294.912
f
,
297.216
f
,
297.216
f
,
299.520
f
,
299.520
f
,
301.824
f
,
301.824
f
,
304.128
f
,
304.128
f
,
306.432
f
,
306.432
f
,
308.736
f
,
308.736
f
,
311.040
f
,
311.040
f
},
{
276.480
f
,
276.480
f
,
278.784
f
,
278.784
f
,
281.088
f
,
281.088
f
,
283.392
f
,
283.392
f
,
285.696
f
,
285.696
f
,
288.000
f
,
288.000
f
,
290.304
f
,
290.304
f
,
292.608
f
,
292.608
f
,
294.912
f
,
294.912
f
,
297.216
f
,
297.216
f
,
299.520
f
,
299.520
f
,
301.824
f
,
301.824
f
,
304.128
f
,
304.128
f
,
306.432
f
,
306.432
f
,
308.736
f
,
308.736
f
,
311.040
f
,
311.040
f
}};
}
// namespace velodyne
}
// namespace drivers
}
// namespace apollo
modules/drivers/velodyne/parser/velodyne32_parser.cc
浏览文件 @
df600e3e
...
...
@@ -24,6 +24,9 @@ Velodyne32Parser::Velodyne32Parser(const Config& config)
:
VelodyneParser
(
config
),
previous_packet_stamp_
(
0
),
gps_base_usec_
(
0
)
{
inner_time_
=
&
velodyne
::
INNER_TIME_HDL32E
;
need_two_pt_correction_
=
false
;
if
(
config_
.
model
()
==
VLP32C
)
{
inner_time_
=
&
velodyne
::
INNER_TIME_VLP32C
;
}
}
void
Velodyne32Parser
::
GeneratePointcloud
(
...
...
@@ -37,12 +40,18 @@ void Velodyne32Parser::GeneratePointcloud(
gps_base_usec_
=
scan_msg
->
basetime
();
size_t
packets_size
=
scan_msg
->
firing_pkts_size
();
for
(
size_t
i
=
0
;
i
<
packets_size
;
++
i
)
{
Unpack
(
scan_msg
->
firing_pkts
(
static_cast
<
int
>
(
i
)),
out_msg
);
last_time_stamp_
=
out_msg
->
measurement_time
();
ADEBUG
<<
"stamp: "
<<
std
::
fixed
<<
last_time_stamp_
;
if
(
config_
.
model
()
==
VLP32C
)
{
for
(
size_t
i
=
0
;
i
<
packets_size
;
++
i
)
{
UnpackVLP32C
(
scan_msg
->
firing_pkts
(
static_cast
<
int
>
(
i
)),
out_msg
);
last_time_stamp_
=
out_msg
->
measurement_time
();
}
}
else
{
for
(
size_t
i
=
0
;
i
<
packets_size
;
++
i
)
{
Unpack
(
scan_msg
->
firing_pkts
(
static_cast
<
int
>
(
i
)),
out_msg
);
last_time_stamp_
=
out_msg
->
measurement_time
();
ADEBUG
<<
"stamp: "
<<
std
::
fixed
<<
last_time_stamp_
;
}
}
if
(
out_msg
->
point_size
()
==
0
)
{
// we discard this pointcloud if empty
AERROR
<<
"All points is NAN!Please check velodyne:"
<<
config_
.
model
();
...
...
@@ -54,10 +63,85 @@ void Velodyne32Parser::GeneratePointcloud(
uint64_t
Velodyne32Parser
::
GetTimestamp
(
double
base_time
,
float
time_offset
,
uint16_t
block_id
)
{
double
t
=
base_time
-
time_offset
;
if
(
config_
.
model
()
==
VLP32C
)
{
t
=
base_time
+
time_offset
;
}
uint64_t
timestamp
=
GetGpsStamp
(
t
,
&
previous_packet_stamp_
,
&
gps_base_usec_
);
return
timestamp
;
}
void
Velodyne32Parser
::
UnpackVLP32C
(
const
VelodynePacket
&
pkt
,
std
::
shared_ptr
<
PointCloud
>
pc
)
{
const
RawPacket
*
raw
=
(
const
RawPacket
*
)
pkt
.
data
().
c_str
();
double
basetime
=
raw
->
gps_timestamp
;
// usec
float
azimuth
=
0.0
f
;
float
azimuth_diff
=
0.0
f
;
float
last_azimuth_diff
=
0.0
f
;
float
azimuth_corrected_f
=
0.0
f
;
int
azimuth_corrected
=
0
;
for
(
int
i
=
0
;
i
<
BLOCKS_PER_PACKET
;
i
++
)
{
// 12
azimuth
=
static_cast
<
float
>
(
raw
->
blocks
[
i
].
rotation
);
if
(
i
<
(
BLOCKS_PER_PACKET
-
1
))
{
azimuth_diff
=
static_cast
<
float
>
(
(
36000
+
raw
->
blocks
[
i
+
1
].
rotation
-
raw
->
blocks
[
i
].
rotation
)
%
36000
);
last_azimuth_diff
=
azimuth_diff
;
}
else
{
azimuth_diff
=
last_azimuth_diff
;
}
for
(
int
laser_id
=
0
,
k
=
0
;
laser_id
<
SCANS_PER_BLOCK
;
++
laser_id
,
k
+=
RAW_SCAN_SIZE
)
{
// 32, 3
LaserCorrection
&
corrections
=
calibration_
.
laser_corrections_
[
laser_id
];
union
RawDistance
raw_distance
;
raw_distance
.
bytes
[
0
]
=
raw
->
blocks
[
i
].
data
[
k
];
raw_distance
.
bytes
[
1
]
=
raw
->
blocks
[
i
].
data
[
k
+
1
];
// compute time
uint64_t
timestamp
=
static_cast
<
uint64_t
>
(
GetTimestamp
(
basetime
,
(
*
inner_time_
)[
i
][
laser_id
],
static_cast
<
uint16_t
>
(
i
)));
if
(
laser_id
==
SCANS_PER_BLOCK
-
1
)
{
// set header stamp before organize the point cloud
pc
->
set_measurement_time
(
static_cast
<
double
>
(
timestamp
)
/
1e9
);
}
azimuth_corrected_f
=
azimuth
+
(
azimuth_diff
*
(
static_cast
<
float
>
(
laser_id
)
/
2.0
f
)
*
CHANNEL_TDURATION
/
SEQ_TDURATION
);
azimuth_corrected
=
static_cast
<
int
>
(
round
(
fmod
(
azimuth_corrected_f
,
36000.0
)));
float
real_distance
=
raw_distance
.
raw_distance
*
VLP32_DISTANCE_RESOLUTION
;
float
distance
=
real_distance
+
corrections
.
dist_correction
;
// AINFO << "raw_distance:" << raw_distance.raw_distance << ", distance:"
// << distance;
if
(
raw_distance
.
raw_distance
==
0
||
!
is_scan_valid
(
azimuth_corrected
,
distance
))
{
if
(
config_
.
organized
())
{
apollo
::
drivers
::
PointXYZIT
*
point_new
=
pc
->
add_point
();
point_new
->
set_x
(
nan
);
point_new
->
set_y
(
nan
);
point_new
->
set_z
(
nan
);
point_new
->
set_timestamp
(
timestamp
);
point_new
->
set_intensity
(
0
);
}
continue
;
}
apollo
::
drivers
::
PointXYZIT
*
point
=
pc
->
add_point
();
point
->
set_timestamp
(
timestamp
);
// Position Calculation, append this point to the cloud
ComputeCoords
(
real_distance
,
corrections
,
static_cast
<
uint16_t
>
(
azimuth_corrected
),
point
);
point
->
set_intensity
(
raw
->
blocks
[
i
].
data
[
k
+
2
]);
}
}
}
void
Velodyne32Parser
::
Unpack
(
const
VelodynePacket
&
pkt
,
std
::
shared_ptr
<
PointCloud
>
pc
)
{
// const RawPacket* raw = (const RawPacket*)&pkt.data[0];
...
...
@@ -112,6 +196,9 @@ void Velodyne32Parser::Unpack(const VelodynePacket& pkt,
}
void
Velodyne32Parser
::
Order
(
std
::
shared_ptr
<
PointCloud
>
cloud
)
{
if
(
config_
.
model
()
==
VLP32C
)
{
return
;
}
int
width
=
32
;
cloud
->
set_width
(
width
);
int
height
=
cloud
->
point_size
()
/
cloud
->
width
();
...
...
modules/drivers/velodyne/parser/velodyne_parser.cc
浏览文件 @
df600e3e
...
...
@@ -205,7 +205,7 @@ VelodyneParser *VelodyneParserFactory::CreateParser(Config source_config) {
if
(
config
.
model
()
==
VLP16
)
{
config
.
set_calibration_online
(
false
);
return
new
Velodyne16Parser
(
config
);
}
else
if
(
config
.
model
()
==
HDL32E
)
{
}
else
if
(
config
.
model
()
==
HDL32E
||
config
.
model
()
==
VLP32C
)
{
config
.
set_calibration_online
(
false
);
return
new
Velodyne32Parser
(
config
);
}
else
if
(
config
.
model
()
==
HDL64E_S3S
||
config
.
model
()
==
HDL64E_S3D
||
...
...
modules/drivers/velodyne/parser/velodyne_parser.h
浏览文件 @
df600e3e
...
...
@@ -327,6 +327,7 @@ class Velodyne32Parser : public VelodyneParser {
uint64_t
GetTimestamp
(
double
base_time
,
float
time_offset
,
uint16_t
laser_block_id
);
void
Unpack
(
const
VelodynePacket
&
pkt
,
std
::
shared_ptr
<
PointCloud
>
pc
);
void
UnpackVLP32C
(
const
VelodynePacket
&
pkt
,
std
::
shared_ptr
<
PointCloud
>
pc
);
// Previous Velodyne packet time stamp. (offset to the top hour)
double
previous_packet_stamp_
;
uint64_t
gps_base_usec_
;
// full time
...
...
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录