点云预处理设计#
概述#
点云预处理是一组模块,用于将一些原始预处理应用于原始传感器数据.
此管道涵盖从驱动程序到感知堆栈的数据流.
推荐的处理管道#
graph TD
Driver["Lidar Driver"] -->|"Cloud XYZIRCAEDT"| FilterPR["Polygon Remover Filter / CropBox Filter"]
subgraph "sensing"
FilterPR -->|"Cloud XYZIRCAEDT"| FilterDC["Motion Distortion Corrector Filter"]
FilterDC -->|"Cloud XYZIRCAEDT"| FilterOF["Outlier Remover Filter"]
FilterOF -->|"Cloud XYZIRC"| FilterDS["Downsampler Filter"]
FilterDS -->|"Cloud XYZIRC"| FilterTrans["Cloud Transformer"]
FilterTrans -->|"Cloud XYZIRC"| FilterC
FilterX["..."] -->|"Cloud XYZIRC (i)"| FilterC["Cloud Concatenator"]
end
FilterC -->|"Cloud XYZIRC"| SegGr["Ground Segmentation"]
模块列表#
这里使用的模块来自 pointcloud_preprocessor package.
有关模块的详细信息,请参见 下表.
建议在单个容器中将这些模块用作组件.有关详细信息,请参见 ROS 2 组成
点云字段#
激光雷达驱动程序应输出具有 PointXYZIRCAEDT 点类型的点云.
| 字段名称 | 数据类型 | 派生 | 描述 |
|---|---|---|---|
X |
FLOAT32 |
false |
X 位置 |
Y |
FLOAT32 |
false |
Y 位置 |
Z |
FLOAT32 |
false |
Z 位置 |
I (intensity) |
UINT8 |
false |
测得的反射率、点的强度 |
R (return type) |
UINT8 |
false |
用于双回波激光雷达的激光回波型 |
C (channel) |
UINT16 |
false |
测量点的激光器的通道 ID |
A (azimuth) |
FLOAT32 |
true |
atan2(Y, X), 从激光雷达原点到点的水平角度 |
E (elevation) |
FLOAT32 |
true |
atan2(Z, D), 从激光雷达原点到点的垂直角 |
D (distance) |
FLOAT32 |
true |
hypot(X, Y, Z), 从激光雷达原点到点的欧氏距离 |
T (time) |
UINT32 |
false |
自测量此点时标头时间以来经过的纳秒 |
注意
A (azimuth)、E (elevation) 和 D (distance) 字段是派生字段.
它们由驱动程序提供,以减少感知堆栈某些部分的计算负载.
警告
Autoware 支持从 PointXYZI 到 PointXYZIRC 的转换(通道和返回类型设置为 0),以便进行原型设计.
但是,不建议将此转换用于生产用途,因为它效率低下.
强度#
我们将使用以下强度范围,与 VLP16 用户手册 兼容:
引用 VLP-16 用户手册:
对于每个激光测量,除了距离之外,还会返回一个反射率字节. 反射率字节值分为两个范围,允许软件区分漫反射体 (例如树干、衣服)与高范围内的角锥反射器(例如路标、车牌)处于低范围. 角锥反射器以最小的散射将光反射回其光源. VLP-16 提供自己的光,发射激光器和接收探测器之间的间隔可以忽略不计,因此 逆向反射表面与倾向于散射反射能量的漫反射器相比,反射红外光会显得突出.
- 漫反射器报告从 0% 到 100% 的反射率从 0 到 100 的值.
- 角锥反射器报告的值从 101 到 255,其中 255 表示理想反射.
在没有角锥反射器的典型点云中,所有强度点都将介于 0 和 100 之间.

但在带有角锥反射器的点云中,强度点将介于 0 和 255 之间.
其他激光雷达品牌的强度映射#
禾赛 PandarXT16#
该激光雷达有 2 种报告反射率的模式:
- 线性映射
- 非线性映射
如果使用线性映射模式,则在构造点云时应从 [0, 255] 映射到 [0, 100].
如果你正在使用非线性映射模式,你应该映射 (hesai to autoware)
- [0, 251] 到 [0, 100] 和
- [252, 254] 至 [101, 255]
在构建点云时.
Livox Mid-70#
该激光雷达有 2 种报告反射率的模式,类似于 Velodyne VLP-16,只是范围略有不同.
您应该映射 (livox 到 autoware)
- [0, 150] 到 [0, 100] 和
- [151, 255] 至 [101, 255]
在构建点云时.
RoboSense RS-LiDAR-16#
无需映射,与 Velodyne VLP-16 相同.
Ouster OS-1-64#
软件用户手册 v2.0.0 适用于所有 Ouster 传感器
手册中写道:
反射率 [16 位无符号整数] - 传感器信号光子测量值根据测量范围和该范围内的传感器灵敏度进行缩放,从而提供目标反射率的指示.此测量的校准目前尚未严格实施,但将在未来的固件版本中更新.
因此,建议将 16 位反射率映射到 [0, 100] 范围.
雷神 CH64W#
在用户手册中,我能够找到它说:
Byte 7 表示回声强度,取值范围是 0 到 255.(回声强度可以反射 实际测量中被测物体的能量反射特性 环境.因此,可以使用回声强度来区分具有 不同的反射特性.
因此,建议将 [0, 255] 映射到 [0, 100] 范围.
返回类型#
各种激光雷达支持多种返回模式.Velodyne 激光雷达支持 Strongest 和 Last 返回模式.
在 PointXYZIRC 和 PointXYZIRCAEDT 类型中,R 字段表示具有 UINT8 的返回类型.
返回类型特定于供应商.下表提供了返回类型定义的示例.
| R (return type) | 描述 |
|---|---|
0 |
Unknown / Not Marked |
1 |
Strongest |
2 |
Last |
频道#
通道字段用于标识测量该点的激光的垂直通道. 在各种激光雷达手册或文献中,它也可以称为 laser id、ring laser line.
对于 Velodyne VLP-16,有 16 个通道.驱动程序中通道的默认顺序通常按触发顺序排列.
在 PointXYZIRC 和 PointXYZIRCAEDT 类型中,C 字段表示带有 UINT16 的垂直通道 ID.
方位角#
方位角场给出了激光雷达的光学原点与点之间的水平角. 许多激光雷达在激光发射时用旋转编码器的角度来测量这个值,驾驶员通常根据校准数据校正该值.
在 PointXYZIRCAEDT 类型中,A 字段表示以弧度(顺时针)为单位的方位角,并带有 FLOAT32.
海拔#
高程字段给出了激光雷达的光学原点与点之间的垂直角.
在 PointXYZIRCAEDT 类型中,E 字段表示以弧度(顺时针)为单位的仰角,带有 FLOAT32.
固态和花瓣图案激光雷达#
警告
本节可能会发生更改.以下是建议,可供讨论.
对于具有线条的固态激光雷达,将行号指定为通道 ID.
对于花瓣图案激光雷达,您可以保留通道 0.
时间戳#
在激光雷达点云中,每个点测量值都可以有其单独的时间戳. 此信息可用于消除扫描期间激光雷达移动引起的运动模糊.
点云头球时间#
标头包含一个 Time field. time 字段有 2 个组成部分:
| 田 | 类型 | 描述 |
|---|---|---|
sec |
int32 |
Unix 时间(自 1970 年 1 月 1 日以来经过的秒数) |
nanosec |
uint32 |
自 sec 字段以来经过的纳秒 |
点云消息的标头应具有其最早点的时间.
注意
sec 字段在 ROS 2 humble 中是 int32.它可以表示的最大值是 2^31 秒,它受
2038 年问题.我们将等待 ROS 2 社区方面的行动.
更多信息请访问: https://github.com/ros2/rcl_interfaces/issues/85
单个时间点时间戳#
每个 PointXYZIRCAEDT 点类型都有 T 字段,用于表示自点云的第一个发射点以来经过的纳秒.
为了计算每个点的准确拍摄时间,将 T 纳秒添加到标头时间中.
注意
T 字段是 uint32 类型.它可以表示的最大值是 2^32 纳秒,大约相当于
4.29 秒.通常的点云在整个周期内持续时间不会超过 100 毫秒.所以这个字段应该就足够了.