Skip to content

Commit 51f7a6b

Browse files
feat(lidar_centerpoint): remove libtorch from centerpoint (#480)
* feat: remove libtorch Signed-off-by: yukke42 <yusuke.muramatsu@tier4.jp> * feat: postprocess cuda Signed-off-by: yukke42 <yusuke.muramatsu@tier4.jp> * refactor: remove densificated pointcloud publisher Signed-off-by: yukke42 <yusuke.muramatsu@tier4.jp> * refactor: orgainze code Signed-off-by: yukke42 <yusuke.muramatsu@tier4.jp> * docs: change ros params and references Signed-off-by: yukke42 <yusuke.muramatsu@tier4.jp> * docs: circleNMS description * feat: warn log when no detected boxes Signed-off-by: yukke42 <yusuke.muramatsu@tier4.jp> * chore: update trained model links Signed-off-by: yukke42 <yusuke.muramatsu@tier4.jp> * refactor: not memcopy empty voxels Signed-off-by: yukke42 <yusuke.muramatsu@tier4.jp> * fix: disable to check downloaded files to pass ci Signed-off-by: yukke42 <yusuke.muramatsu@tier4.jp> * chore: change the name of Copyright Signed-off-by: yukke42 <yusuke.muramatsu@tier4.jp> * refactor: rename nms_kernel to circle_nms_kernel Signed-off-by: yukke42 <yusuke.muramatsu@tier4.jp> * ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent fa2eda0 commit 51f7a6b

28 files changed

+1163
-675
lines changed

perception/lidar_centerpoint/CMakeLists.txt

+43-29
Original file line numberDiff line numberDiff line change
@@ -52,23 +52,27 @@ else()
5252
set(TRT_AVAIL OFF)
5353
endif()
5454

55-
option(TORCH_AVAIL "Torch available" OFF)
56-
if(CUDA_FOUND)
57-
set(Torch_DIR /usr/local/libtorch/share/cmake/Torch)
58-
find_package(Torch)
59-
if(TORCH_FOUND)
60-
if(CUDA_VERBOSE)
61-
message(STATUS "TORCH_INCLUDE_DIRS: ${TORCH_INCLUDE_DIRS}")
62-
message(STATUS "TORCH_LIBRARIES: ${TORCH_LIBRARIES}")
63-
endif()
64-
set(TORCH_AVAIL ON)
65-
else()
66-
message("Torch NOT FOUND")
67-
set(TORCH_AVAIL OFF)
55+
# set flags for CUDNN availability
56+
option(CUDNN_AVAIL "CUDNN available" OFF)
57+
# try to find the CUDNN module
58+
find_library(CUDNN_LIBRARY
59+
NAMES libcudnn.so${__cudnn_ver_suffix} libcudnn${__cudnn_ver_suffix}.dylib ${__cudnn_lib_win_name}
60+
PATHS $ENV{LD_LIBRARY_PATH} ${__libpath_cudart} ${CUDNN_ROOT_DIR} ${PC_CUDNN_LIBRARY_DIRS} ${CMAKE_INSTALL_PREFIX}
61+
PATH_SUFFIXES lib lib64 bin
62+
DOC "CUDNN library."
63+
)
64+
if(CUDNN_LIBRARY)
65+
if(CUDA_VERBOSE)
66+
message(STATUS "CUDNN is available!")
67+
message(STATUS "CUDNN_LIBRARY: ${CUDNN_LIBRARY}")
6868
endif()
69+
set(CUDNN_AVAIL ON)
70+
else()
71+
message("CUDNN is NOT Available")
72+
set(CUDNN_AVAIL OFF)
6973
endif()
7074

71-
if(TRT_AVAIL AND CUDA_AVAIL AND TORCH_AVAIL)
75+
if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL)
7276
# Download trained models
7377
find_program(GDOWN_AVAIL "gdown")
7478
if(NOT GDOWN_AVAIL)
@@ -84,53 +88,63 @@ if(TRT_AVAIL AND CUDA_AVAIL AND TORCH_AVAIL)
8488
set(FILE_PATH ${DATA_PATH}/${FILE_NAME})
8589
if(EXISTS ${FILE_PATH})
8690
file(MD5 ${FILE_PATH} EXISTING_FILE_HASH)
87-
if(NOT ${FILE_HASH} EQUAL ${EXISTING_FILE_HASH})
88-
message(STATUS "... file hash changes. Downloading now ...")
91+
if(${FILE_HASH} EQUAL ${EXISTING_FILE_HASH})
92+
message(STATUS "File already exists.")
93+
else()
94+
message(STATUS "File hash changes. Downloading now ...")
8995
execute_process(COMMAND gdown --quiet https://drive.google.com//uc?id=${GFILE_ID} -O ${FILE_PATH})
96+
# file(MD5 ${FILE_PATH} DOWNLOADED_FILE_HASH) # disable to pass ci
97+
message(STATUS "Downloaded file hash: ${DOWNLOADED_FILE_HASH}")
9098
endif()
9199
else()
92-
message(STATUS "... file doesn't exists. Downloading now ...")
100+
message(STATUS "File doesn't exists. Downloading now ...")
93101
execute_process(COMMAND gdown --quiet https://drive.google.com//uc?id=${GFILE_ID} -O ${FILE_PATH})
102+
# file(MD5 ${FILE_PATH} DOWNLOADED_FILE_HASH) # disable to pass ci
103+
message(STATUS "Downloaded file hash: ${DOWNLOADED_FILE_HASH}")
94104
endif()
95105
endfunction()
96106

97107
# default model
98-
download(pts_voxel_encoder_default.onnx 1_8OCQmrPm_R4ZVh70QsS9HZo6uGrlbgz 01b860612e497591c4375d90dff61ef7)
99-
download(pts_voxel_encoder_default.pt 1RZ7cuDnI-RBrDiWe-2vEs16mR_z0e9Uo 33136caa97e3bcef2cf3e04bbc93d1e4)
100-
download(pts_backbone_neck_head_default.onnx 1UxDyt8T-TMJS7Ujx-1vbbqGRfDbMUZg2 e23a8ad4ea440f923e44dbe072b070da)
101-
download(pts_backbone_neck_head_default.pt 1toAhmOriX8bwVI-ohuas9_2EBZnltoXh eb0df29b30acf9c1082ac4490af0bbc5)
108+
download(pts_voxel_encoder_default.onnx 1KFhmA4oFT6CtZx5806QeMzn5H2tKa3oD 410f730c537968cb27fbd70c941849a8)
109+
download(pts_backbone_neck_head_default.onnx 1iyk5VoQ4uNBGPZwypVZIMjSuSYAI1RxP e97c165c7877222c0e27e44409a07517)
102110

103111
# aip_x2 model
104-
download(pts_voxel_encoder_aip_x2.onnx 1x-NAHQ3W0lbLmjJlrL6Nhvdq8yz6Ux0n 65eeb95c5e48ebfe6894146cdb48c160)
105-
download(pts_voxel_encoder_aip_x2.pt 1jzKopAhXWjnEgo_v8rtYy0hQIayUE-oL 4db81ce8edc6571aa0afb1ae43ee72e9)
106-
download(pts_backbone_neck_head_aip_x2.onnx 1l2fdIQcBWr3-6stVoNkudnL4OZaPqmNT a33c8910fd9c9c910b10904d3cd96717)
107-
download(pts_backbone_neck_head_aip_x2.pt 18iOAlRsjvcWoUG9KiL1PlD7OY5mi9BSw 274fdf1580dd899e36c050c1366f1883)
112+
download(pts_voxel_encoder_aip_x2.onnx 13aYPRHx17Ge4BqxzW9drAUSWTppjtUV5 3ae5e9efd7b2ed12115e6f0b28cac58d)
113+
download(pts_backbone_neck_head_aip_x2.onnx 14PJ_L3Jpz6Yi8GzoctVOEbGWcaCLArGp 6a406a19e05660677c162486ab332de8)
108114

109115
find_package(ament_cmake_auto REQUIRED)
110116
ament_auto_find_build_dependencies()
111117

112118
include_directories(
113119
lib/include
114120
${CUDA_INCLUDE_DIRS}
115-
${TORCH_INCLUDE_DIRS}
116121
)
117122

118123
### centerpoint ###
119124
ament_auto_add_library(centerpoint SHARED
125+
lib/src/centerpoint_trt.cpp
120126
lib/src/pointcloud_densification.cpp
121127
lib/src/voxel_generator.cpp
122-
lib/src/centerpoint_trt.cpp
123128
lib/src/tensorrt_wrapper.cpp
124129
lib/src/network_trt.cpp
130+
lib/src/utils.cpp
131+
)
132+
133+
cuda_add_library(centerpoint_cuda_libraries SHARED
134+
lib/src/circle_nms_kernel.cu
135+
lib/src/postprocess_kernel.cu
136+
lib/src/preprocess_kernel.cu
137+
lib/src/scatter_kernel.cu
125138
)
126139

127140
target_link_libraries(centerpoint
128141
${NVINFER}
129142
${NVONNXPARSER}
130-
${NVINFER_PLUGIN}
131143
${CUDA_LIBRARIES}
132144
${CUBLAS_LIBRARIES}
133-
${TORCH_LIBRARIES}
145+
${CUDA_curand_LIBRARY}
146+
${CUDNN_LIBRARY}
147+
centerpoint_cuda_libraries
134148
)
135149

136150
## node ##

perception/lidar_centerpoint/README.md

+5-26
Original file line numberDiff line numberDiff line change
@@ -20,10 +20,9 @@ We trained the models using <https://github.com/open-mmlab/mmdetection3d>.
2020

2121
### Output
2222

23-
| Name | Type | Description |
24-
| ---------------------------------- | ----------------------------------------------------- | ------------------------ |
25-
| `~/output/objects` | `autoware_auto_perception_msgs::msg::DetectedObjects` | detected objects |
26-
| `~/debug/pointcloud_densification` | `sensor_msgs::msg::PointCloud2` | densification pointcloud |
23+
| Name | Type | Description |
24+
| ------------------ | ----------------------------------------------------- | ---------------- |
25+
| `~/output/objects` | `autoware_auto_perception_msgs::msg::DetectedObjects` | detected objects |
2726

2827
## Parameters
2928

@@ -34,30 +33,16 @@ We trained the models using <https://github.com/open-mmlab/mmdetection3d>.
3433
| `score_threshold` | float | `0.4` | detected objects with score less than threshold are ignored |
3534
| `densification_world_frame_id` | string | `map` | the world frame id to fuse multi-frame pointcloud |
3635
| `densification_num_past_frames` | int | `1` | the number of past frames to fuse with the current frame |
37-
| `use_encoder_trt` | bool | `false` | use TensorRT VoxelFeatureEncoder |
38-
| `use_head_trt` | bool | `true` | use TensorRT DetectionHead |
3936
| `trt_precision` | string | `fp16` | TensorRT inference precision: `fp32` or `fp16` |
4037
| `encoder_onnx_path` | string | `""` | path to VoxelFeatureEncoder ONNX file |
4138
| `encoder_engine_path` | string | `""` | path to VoxelFeatureEncoder TensorRT Engine file |
42-
| `encoder_pt_path` | string | `""` | path to VoxelFeatureEncoder TorchScript file |
4339
| `head_onnx_path` | string | `""` | path to DetectionHead ONNX file |
4440
| `head_engine_path` | string | `""` | path to DetectionHead TensorRT Engine file |
45-
| `head_pt_path` | string | `""` | path to DetectionHead TorchScript file |
4641

4742
## Assumptions / Known limits
4843

4944
- The `object.existence_probability` is stored the value of classification confidence of a DNN, not probability.
5045

51-
- If you have an error like `'GOMP_4.5' not found`, replace the OpenMP library in libtorch.
52-
53-
```bash
54-
sudo apt install libgomp1 -y
55-
sudo rm /usr/local/libtorch/lib/libgomp-75eea7e8.so.1
56-
sudo ln -s /usr/lib/x86_64-linux-gnu/libgomp.so.1 /usr/local/libtorch/lib/libgomp-75eea7e8.so.1
57-
```
58-
59-
- if `use_encoder_trt` is set `use_encoder_trt`, more GPU memory is allocated.
60-
6146
## (Optional) Error detection and handling
6247

6348
<!-- Write how to detect errors and how to recover from them.
@@ -92,15 +77,9 @@ Example:
9277

9378
[5] <https://github.com/open-mmlab/OpenPCDet>
9479

95-
[6] <https://github.com/poodarchu/Det3D>
96-
97-
[7] <https://github.com/xingyizhou/CenterNet>
98-
99-
[8] <https://github.com/lzccccc/SMOKE>
100-
101-
[9] <https://github.com/yukkysaito/autoware_perception>
80+
[6] <https://github.com/yukkysaito/autoware_perception>
10281

103-
[10] <https://github.com/pytorch/pytorch>
82+
[7] <https://github.com/NVIDIA-AI-IOT/CUDA-PointPillars>
10483

10584
## (Optional) Future extensions / Unimplemented parts
10685

perception/lidar_centerpoint/include/lidar_centerpoint/node.hpp

+3-14
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright 2021 Tier IV, Inc.
1+
// Copyright 2021 TIER IV, Inc.
22
//
33
// Licensed under the Apache License, Version 2.0 (the "License");
44
// you may not use this file except in compliance with the License.
@@ -40,7 +40,8 @@ class LidarCenterPointNode : public rclcpp::Node
4040

4141
private:
4242
void pointCloudCallback(const sensor_msgs::msg::PointCloud2::ConstSharedPtr input_pointcloud_msg);
43-
43+
void box3DToDetectedObject(
44+
const Box3D & box3d, autoware_auto_perception_msgs::msg::DetectedObject & obj);
4445
static uint8_t getSemanticType(const std::string & class_name);
4546
static bool isCarLikeVehicleLabel(const uint8_t label);
4647

@@ -49,20 +50,8 @@ class LidarCenterPointNode : public rclcpp::Node
4950

5051
rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr pointcloud_sub_;
5152
rclcpp::Publisher<autoware_auto_perception_msgs::msg::DetectedObjects>::SharedPtr objects_pub_;
52-
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr pointcloud_pub_;
5353

5454
float score_threshold_{0.0};
55-
bool use_encoder_trt_{false};
56-
bool use_head_trt_{false};
57-
std::string trt_precision_;
58-
59-
std::string encoder_onnx_path_;
60-
std::string encoder_engine_path_;
61-
std::string encoder_pt_path_;
62-
std::string head_onnx_path_;
63-
std::string head_engine_path_;
64-
std::string head_pt_path_;
65-
6655
std::vector<std::string> class_names_;
6756
bool rename_car_to_truck_and_bus_{false};
6857

perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml

+2-2
Original file line numberDiff line numberDiff line change
@@ -13,9 +13,9 @@
1313
<param name="score_threshold" value="0.45"/>
1414
<param name="densification_world_frame_id" value="map"/>
1515
<param name="densification_num_past_frames" value="1"/>
16-
<param name="use_head_trt" value="true"/>
1716
<param name="trt_precision" value="fp16"/>
18-
<param name="encoder_pt_path" value="$(var model_path)/pts_voxel_encoder_$(var model_name).pt"/>
17+
<param name="encoder_onnx_path" value="$(var model_path)/pts_voxel_encoder_$(var model_name).onnx"/>
18+
<param name="encoder_engine_path" value="$(var model_path)/pts_voxel_encoder_$(var model_name).engine"/>
1919
<param name="head_onnx_path" value="$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"/>
2020
<param name="head_engine_path" value="$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"/>
2121
<param from="$(var model_param_path)"/>

perception/lidar_centerpoint/lib/include/centerpoint_trt.hpp

+44-48
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright 2021 Tier IV, Inc.
1+
// Copyright 2021 TIER IV, Inc.
22
//
33
// Licensed under the Apache License, Version 2.0 (the "License");
44
// you may not use this file except in compliance with the License.
@@ -18,14 +18,13 @@
1818
#include <config.hpp>
1919
#include <cuda_utils.hpp>
2020
#include <network_trt.hpp>
21-
#include <tier4_autoware_utils/math/constants.hpp>
21+
#include <postprocess_kernel.hpp>
2222
#include <voxel_generator.hpp>
2323

2424
#include <sensor_msgs/msg/point_cloud2.hpp>
2525

2626
#include <pcl/point_cloud.h>
2727
#include <pcl/point_types.h>
28-
#include <torch/script.h>
2928

3029
#include <memory>
3130
#include <string>
@@ -37,75 +36,72 @@ namespace centerpoint
3736
class NetworkParam
3837
{
3938
public:
40-
NetworkParam(
41-
std::string onnx_path, std::string engine_path, std::string pt_path, std::string trt_precision,
42-
const bool use_trt)
39+
NetworkParam(std::string onnx_path, std::string engine_path, std::string trt_precision)
4340
: onnx_path_(std::move(onnx_path)),
4441
engine_path_(std::move(engine_path)),
45-
pt_path_(std::move(pt_path)),
46-
trt_precision_(std::move(trt_precision)),
47-
use_trt_(use_trt)
42+
trt_precision_(std::move(trt_precision))
4843
{
4944
}
5045

5146
std::string onnx_path() const { return onnx_path_; }
5247
std::string engine_path() const { return engine_path_; }
53-
std::string pt_path() const { return pt_path_; }
5448
std::string trt_precision() const { return trt_precision_; }
55-
bool use_trt() const { return use_trt_; }
5649

5750
private:
5851
std::string onnx_path_;
5952
std::string engine_path_;
60-
std::string pt_path_;
6153
std::string trt_precision_;
62-
bool use_trt_;
6354
};
6455

6556
class CenterPointTRT
6657
{
6758
public:
6859
explicit CenterPointTRT(
69-
const int num_class, const NetworkParam & encoder_param, const NetworkParam & head_param,
70-
const DensificationParam & densification_param);
60+
const std::size_t num_class, const float score_threshold, const NetworkParam & encoder_param,
61+
const NetworkParam & head_param, const DensificationParam & densification_param);
7162

7263
~CenterPointTRT();
7364

74-
std::vector<float> detect(
75-
const sensor_msgs::msg::PointCloud2 &, const tf2_ros::Buffer & tf_buffer);
65+
bool detect(
66+
const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const tf2_ros::Buffer & tf_buffer,
67+
std::vector<Box3D> & det_boxes3d);
7668

7769
private:
78-
bool initPtr(bool use_encoder_trt, bool use_head_trt);
79-
80-
bool loadTorchScript(torch::jit::script::Module & module, const std::string & model_path);
81-
82-
static at::Tensor createInputFeatures(
83-
const at::Tensor & voxels, const at::Tensor & coords, const at::Tensor & voxel_num_points);
84-
85-
static at::Tensor scatterPillarFeatures(
86-
const at::Tensor & pillar_features, const at::Tensor & coordinates);
87-
88-
at::Tensor generatePredictedBoxes();
89-
90-
std::unique_ptr<VoxelGeneratorTemplate> vg_ptr_ = nullptr;
91-
torch::jit::script::Module encoder_pt_;
92-
torch::jit::script::Module head_pt_;
93-
std::unique_ptr<VoxelEncoderTRT> encoder_trt_ptr_ = nullptr;
94-
std::unique_ptr<HeadTRT> head_trt_ptr_ = nullptr;
95-
c10::Device device_ = torch::kCUDA;
96-
cudaStream_t stream_ = nullptr;
97-
98-
int num_class_{0};
99-
at::Tensor voxels_t_;
100-
at::Tensor coordinates_t_;
101-
at::Tensor num_points_per_voxel_t_;
102-
at::Tensor output_pillar_feature_t_;
103-
at::Tensor output_heatmap_t_;
104-
at::Tensor output_offset_t_;
105-
at::Tensor output_z_t_;
106-
at::Tensor output_dim_t_;
107-
at::Tensor output_rot_t_;
108-
at::Tensor output_vel_t_;
70+
void initPtr();
71+
72+
bool preprocess(
73+
const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const tf2_ros::Buffer & tf_buffer);
74+
75+
void inference();
76+
77+
void postProcess(std::vector<Box3D> & det_boxes3d);
78+
79+
std::unique_ptr<VoxelGeneratorTemplate> vg_ptr_{nullptr};
80+
std::unique_ptr<VoxelEncoderTRT> encoder_trt_ptr_{nullptr};
81+
std::unique_ptr<HeadTRT> head_trt_ptr_{nullptr};
82+
std::unique_ptr<PostProcessCUDA> post_proc_ptr_{nullptr};
83+
cudaStream_t stream_{nullptr};
84+
85+
bool verbose_{false};
86+
std::size_t num_class_{0};
87+
std::size_t num_voxels_{0};
88+
std::size_t encoder_in_feature_size_{0};
89+
std::size_t spatial_features_size_{0};
90+
std::vector<float> voxels_;
91+
std::vector<int> coordinates_;
92+
std::vector<float> num_points_per_voxel_;
93+
cuda::unique_ptr<float[]> voxels_d_{nullptr};
94+
cuda::unique_ptr<int[]> coordinates_d_{nullptr};
95+
cuda::unique_ptr<float[]> num_points_per_voxel_d_{nullptr};
96+
cuda::unique_ptr<float[]> encoder_in_features_d_{nullptr};
97+
cuda::unique_ptr<float[]> pillar_features_d_{nullptr};
98+
cuda::unique_ptr<float[]> spatial_features_d_{nullptr};
99+
cuda::unique_ptr<float[]> head_out_heatmap_d_{nullptr};
100+
cuda::unique_ptr<float[]> head_out_offset_d_{nullptr};
101+
cuda::unique_ptr<float[]> head_out_z_d_{nullptr};
102+
cuda::unique_ptr<float[]> head_out_dim_d_{nullptr};
103+
cuda::unique_ptr<float[]> head_out_rot_d_{nullptr};
104+
cuda::unique_ptr<float[]> head_out_vel_d_{nullptr};
109105
};
110106

111107
} // namespace centerpoint

0 commit comments

Comments
 (0)