Point cloud pre-processing design#
Overview#
Point cloud pre-processing is a collection of modules that apply some primitive pre-processing to the raw sensor data.
This pipeline covers the flow of data from drivers to the perception stack.
Recommended processing pipeline#
graph TD
Driver["Lidar Driver"] -->|"Cloud XYZIRCADT"| FilterPR["Polygon Remover Filter / CropBox Filter"]
subgraph "sensing"
FilterPR -->|"Cloud XYZIRCADT"| FilterDC["Motion Distortion Corrector Filter"]
FilterDC -->|"Cloud XYZIRCAD"| 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"]
List of modules#
The modules used here are from pointcloud_preprocessor package.
For details about the modules, see the following table.
It is recommended that these modules are used in a single container as components. For details see ROS 2 Composition
Point cloud fields#
In the ideal case, the driver is expected to output a point cloud with the PointXYZIRCADT
point type.
name | datatype | derived | description |
---|---|---|---|
X |
FLOAT32 |
false |
X position |
Y |
FLOAT32 |
false |
Y position |
Z |
FLOAT32 |
false |
Z position |
I (intensity) |
FLOAT32 |
false |
Measured reflectivity, intensity of the point |
R (return type) |
UINT8 |
false |
Laser return type for dual return lidars |
C (channel) |
UINT16 |
false |
Vertical channel id of the laser that measured the point |
A (azimuth) |
FLOAT32 |
true |
atan2(Y, X) , Horizontal angle from the front of the lidar to the point |
D (distance) |
FLOAT32 |
true |
hypot(X, Y, Z) , Euclidean distance of the point to lidar |
T (time stamp) |
FLOAT64 |
false |
Seconds passed since the time of the header when this point was measured |
Note
A (azimuth)
and D (distance)
fields are derived fields.
They are provided by the driver to reduce the computational load on some parts of the perception stack.
Note
If the Motion Distortion Corrector Filter
won't be used, the T (time)
field can be omitted, PointXYZIRCAD
point type can be used.
Warning
Autoware will support conversion from PointXYZI
to PointXYZIRC
or PointXYZIRCAD
(with channel and return is set to 0) for prototyping purposes.
However, this conversion is not recommended for production use since it's not efficient.
Intensity#
We will use following ranges for intensity, compatible with the VLP16 User Manual:
Quoting from the VLP-16 User Manual:
For each laser measurement, a reflectivity byte is returned in addition to distance. Reflectivity byte values are segmented into two ranges, allowing software to distinguish diffuse reflectors (e.g. tree trunks, clothing) in the low range from retroreflectors (e.g. road signs, license plates) in the high range. A retroreflector reflects light back to its source with a minimum of scattering. The VLP-16 provides its own light, with negligible separation between transmitting laser and receiving detector, so retroreflecting surfaces pop with reflected IR light compared to diffuse reflectors that tend to scatter reflected energy.
- Diffuse reflectors report values from 0 to 100 for reflectivities from 0% to 100%.
- Retroreflectors report values from 101 to 255, where 255 represents an ideal reflection.
In a typical point cloud without retroreflectors, all intensity points will be between 0 and 100.
Retroreflective Gradient road sign, Image Source
But in a point cloud with retroreflectors, the intensity points will be between 0 and 255.
Intensity mapping for other lidar brands#
Hesai PandarXT16#
This lidar has 2 modes for reporting reflectivity:
- Linear mapping
- Non-linear mapping
If you are using linear mapping mode, you should map from [0, 255] to [0, 100] when constructing the point cloud.
If you are using non-linear mapping mode, you should map (hesai to autoware)
- [0, 251] to [0, 100] and
- [252, 254] to [101, 255]
when constructing the point cloud.
Livox Mid-70#
This lidar has 2 modes for reporting reflectivity similar to Velodyne VLP-16, only the ranges are slightly different.
You should map (livox to autoware)
- [0, 150] to [0, 100] and
- [151, 255] to [101, 255]
when constructing the point cloud.
RoboSense RS-LiDAR-16#
RoboSense RS-LiDAR-16 User Manual
No mapping required, same as Velodyne VLP-16.
Ouster OS-1-64#
Software User Manual v2.0.0 for all Ouster sensors
In the manual it is stated:
Reflectivity [16 bit unsigned int] - sensor Signal Photons measurements are scaled based on measured range and sensor sensitivity at that range, providing an indication of target reflectivity. Calibration of this measurement has not currently been rigorously implemented, but this will be updated in a future firmware release.
So it is advised to map the 16 bit reflectivity to [0, 100] range.
Leishen CH64W#
I couldn't get the english user manual, link of website
In a user manual I was able to find it says:
Byte 7 represents echo strength, and the value range is 0-255. (Echo strength can reflect the energy reflection characteristics of the measured object in the actual measurement environment. Therefore, the echo strength can be used to distinguish objects with different reflection characteristics.)
So it is advised to map the [0, 255] to [0, 100] range.
Return type#
Various lidars support multiple return modes. Velodyne lidars support Strongest and Last return modes.
In the PointXYZIRCT
and PointXYZIRC
types, R
field represents return mode with an UINT8
.
R (return type) | Description |
---|---|
0 |
Unknown / Not Marked |
1 |
Strongest |
2 |
Last |
Channel#
The channel field is used to identify the vertical channel of the laser that measured the point. In various lidar manuals or literature, it can also be called laser id, ring, laser line.
For Velodyne VLP-16, there are 16 channels. Default order of channels in drivers are generally in firing order.
In the PointXYZIRCT
and PointXYZIRC
types, C
field represents the vertical channel id with an UINT16
.
Solid state and petal pattern lidars#
Warning
This section is subject to change. Following are suggestions and open for discussion.
For solid state lidars that have lines, assign row number as the channel id.
For petal pattern lidars, you can keep channel 0.
Time stamp#
In lidar point clouds, each point measurement can have its individual time stamp. This information can be used to eliminate the motion blur that is caused by the movement of the lidar during the scan.
Point cloud header time#
The header contains a Time field. The time field has 2 components:
Field | Type | Description |
---|---|---|
sec |
int32 |
Unix time (seconds elapsed since January 1, 1970) |
nanosec |
uint32 |
Nanoseconds elapsed since the sec field |
The header of the point cloud message is expected to have the time of the earliest point it has.
Note
The sec
field is int32
in ROS 2 humble. The largest value it can represent is 2^31 seconds, it is subject to
year 2038 problems. We will wait for actions on ROS 2 community side.
More info at: https://github.com/ros2/rcl_interfaces/issues/85
Individual point time stamp#
Each PointXYZIRCT
point type has the T
field for representing the seconds passed since the first-shot point of the point cloud.
To calculate exact time each point was shot, the T
seconds are added to the header time.