English | 简体中文
High performance version of 3D object detection network -PointPillars, which can achieve the real-time processing (less than 1 ms / head)
- The inference part of PointPillars(pfe , backbone(multihead)) is optimized by tensorrt
- The pre- and post- processing are optimized by CUDA / C + recode.
-
Easy to train
- this repo directly uses mmlab/OpenPCdet for training. Therefore, as long as you follow the steps of the official tutorial, it is very easy to train your own data. In addition, you can directly use official weight(PointPillar-MultiHead) for deployment. Due to the need to use Tensorrt, the official mmlab/OpenPCdet still needs to be customized. I will upload my modified version to hova88/OpenPCdet.
-
Easy to deploy
- On the basis of Autoware.ai/core_perception/lidar_point_pillars and Apollo/modules/perception/lidar/lib/detection/lidar_point_pillars, this repo improves the way of information transmission, removes redundant things and adds MultiHead feature in postprocess.
- Linux Ubuntu 18.04
- OpenPCdet
- ONNX IR version: 0.0.6
- onnx2trt
- Linux Ubuntu 18.04
- CMake 3.17
- CUDA 10.2
- TensorRT 7.1.3
- yaml-cpp
- google-test (not necessary)
-
clone thest two repositories, and make sure the dependences is complete
mkdir workspace && cd workspace git clone https://github.com/hova88/PointPillars_MultiHead_40FPS.git --recursive && cd .. git clone https://github.com/hova88/OpenPCDet.git
-
generate engine file
-
1.1 Pytorch model --> ONNX model : The specific conversion tutorial, i have put in the change log of hova88/OpenPCdet.
-
1.2 ONNX model --> TensorRT model : after install the onnx2trt, things become very simple. Note that if you want to further improve the the inference speed, you must use half precision or mixed precision(like ,-d 16)
onnx2trt cbgs_pp_multihead_pfe.onnx -o cbgs_pp_multihead_pfe.trt -b 1 -d 16 onnx2trt cbgs_pp_multihead_backbone.onnx -o cbgs_pp_multihead_backbone.trt -b 1 -d 16
-
1.3 engine file --> algorithm : Specified the path of engine files(*.onnx , *.trt) in
bootstrap.yaml
. -
1.4 Download the test pointcloud nuscenes_10sweeps_points.txt, and specified the path in
bootstrap.yaml
.
-
-
Compiler
cd PointPillars_MultiHead_40FPS mkdir build && cd build cmake .. && make -j8 && ./test/test_model
-
Visualization
cd PointPillars_MultiHead_40FPS/tools python viewer.py
Left figure shows the results of this repo, Right figure shows the official result of mmlab/OpenPCdet.
with the ScoreThreshold = 0.1
| ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄>
| ../model/cbgs_pp_multihead_pfe.trt >
|_____________________>
(\__/) ||
(•ㅅ•) ||
/ づ
| ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄>
| ../model/cbgs_pp_multihead_backbone.trt >
|_____________________>
(\__/) || ****
(•ㅅ•) ||
/ づ
------------------------------------
Module Time
------------------------------------
Preprocess 0.571069 ms
Pfe 3.26203 ms
Scatter 0.384075 ms
Backbone 2.92882 ms
Postprocess 8.82032 ms
Summary 15.9707 ms
------------------------------------
with the ScoreThreshold = 0.4
| ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄>
| ../model/cbgs_pp_multihead_pfe.trt >
|_____________________>
(\__/) ||
(•ㅅ•) ||
/ づ
| ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄ ̄>
| ../model/cbgs_pp_multihead_backbone.trt >
|_____________________>
(\__/) || ****
(•ㅅ•) ||
/ づ
------------------------------------
Module Time
------------------------------------
Preprocess 0.337111 ms
Pfe 2.81834 ms
Scatter 0.161953 ms
Backbone 3.64112 ms
Postprocess 4.34731 ms
Summary 11.3101 ms
------------------------------------
GNU General Public License v3.0 or later
See COPYING
to see the full text.