Skip to content

Commit f5f998b

Browse files
authored
feat(lidar_centerpoint): make lidar_centerpoint a shared library (#733)
* refactor: sererate config.hpp Signed-off-by: yukke42 <yusuke.muramatsu@tier4.jp> * feat: set config from ros params Signed-off-by: yukke42 <yusuke.muramatsu@tier4.jp> * refactor: change directory structure Signed-off-by: yukke42 <yusuke.muramatsu@tier4.jp> * feat: make centerpoint shared library Signed-off-by: yukke42 <yusuke.muramatsu@tier4.jp> * feat: to detected objects message Signed-off-by: yukke42 <yusuke.muramatsu@tier4.jp> * refactor: change var name Signed-off-by: yukke42 <yusuke.muramatsu@tier4.jp> * refactor: config Signed-off-by: yukke42 <yusuke.muramatsu@tier4.jp> * chore: remove src directory from target_include_directories Signed-off-by: yukke42 <yusuke.muramatsu@tier4.jp>
1 parent 4832255 commit f5f998b

30 files changed

+576
-377
lines changed

perception/lidar_centerpoint/CMakeLists.txt

+24-17
Original file line numberDiff line numberDiff line change
@@ -110,40 +110,47 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL)
110110
ament_auto_find_build_dependencies()
111111

112112
include_directories(
113-
lib/include
113+
include
114114
${CUDA_INCLUDE_DIRS}
115115
)
116116

117117
### centerpoint ###
118-
ament_auto_add_library(centerpoint SHARED
119-
lib/src/centerpoint_trt.cpp
120-
lib/src/pointcloud_densification.cpp
121-
lib/src/voxel_generator.cpp
122-
lib/src/tensorrt_wrapper.cpp
123-
lib/src/network_trt.cpp
124-
lib/src/utils.cpp
118+
ament_auto_add_library(centerpoint_lib SHARED
119+
lib/centerpoint_trt.cpp
120+
lib/utils.cpp
121+
lib/ros_utils.cpp
122+
lib/network/network_trt.cpp
123+
lib/network/tensorrt_wrapper.cpp
124+
lib/preprocess/pointcloud_densification.cpp
125+
lib/preprocess/voxel_generator.cpp
125126
)
126127

127-
cuda_add_library(centerpoint_cuda_libraries SHARED
128-
lib/src/circle_nms_kernel.cu
129-
lib/src/postprocess_kernel.cu
130-
lib/src/preprocess_kernel.cu
131-
lib/src/scatter_kernel.cu
128+
cuda_add_library(centerpoint_cuda_lib SHARED
129+
lib/postprocess/circle_nms_kernel.cu
130+
lib/postprocess/postprocess_kernel.cu
131+
lib/network/scatter_kernel.cu
132+
lib/preprocess/preprocess_kernel.cu
132133
)
133134

134-
target_link_libraries(centerpoint
135+
target_link_libraries(centerpoint_lib
135136
${NVINFER}
136137
${NVONNXPARSER}
137138
${CUDA_LIBRARIES}
138139
${CUBLAS_LIBRARIES}
139140
${CUDA_curand_LIBRARY}
140141
${CUDNN_LIBRARY}
141-
centerpoint_cuda_libraries
142+
centerpoint_cuda_lib
143+
)
144+
145+
target_include_directories(centerpoint_lib
146+
PUBLIC
147+
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
148+
$<INSTALL_INTERFACE:include>
142149
)
143150

144151
# To suppress unknown-pragmas error. The root-cause is CUB library in CUDA 11.6.
145152
# This issue was fixed by https://github.com/NVIDIA/cub/commit/7d608bf1dc14553e2fb219eabeed80b76621b6fe
146-
target_include_directories(centerpoint
153+
target_include_directories(centerpoint_lib
147154
SYSTEM PUBLIC
148155
${CUDA_INCLUDE_DIRS}
149156
)
@@ -154,7 +161,7 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL)
154161
)
155162

156163
target_link_libraries(lidar_centerpoint_component
157-
centerpoint
164+
centerpoint_lib
158165
)
159166

160167
rclcpp_components_register_node(lidar_centerpoint_component
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,10 @@
11
/**:
22
ros__parameters:
33
class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"]
4+
rename_car_to_truck_and_bus: false
5+
point_feature_size: 4
6+
max_voxel_size: 40000
7+
point_cloud_range: [-89.6, -89.6, -3.0, 89.6, 89.6, 5.0]
8+
voxel_size: [0.32, 0.32, 8.0]
9+
downsample_factor: 2
10+
encoder_in_feature_size: 9

perception/lidar_centerpoint/config/default.param.yaml

+6
Original file line numberDiff line numberDiff line change
@@ -2,3 +2,9 @@
22
ros__parameters:
33
class_names: ["CAR", "PEDESTRIAN", "BICYCLE"]
44
rename_car_to_truck_and_bus: true
5+
point_feature_size: 4
6+
max_voxel_size: 40000
7+
point_cloud_range: [-89.6, -89.6, -3.0, 89.6, 89.6, 5.0]
8+
voxel_size: [0.32, 0.32, 8.0]
9+
downsample_factor: 2
10+
encoder_in_feature_size: 9
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,114 @@
1+
// Copyright 2021 TIER IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef LIDAR_CENTERPOINT__CENTERPOINT_CONFIG_HPP_
16+
#define LIDAR_CENTERPOINT__CENTERPOINT_CONFIG_HPP_
17+
18+
#include <cstddef>
19+
#include <vector>
20+
21+
namespace centerpoint
22+
{
23+
class CenterPointConfig
24+
{
25+
public:
26+
explicit CenterPointConfig(
27+
const std::size_t class_size, const float point_feature_size, const std::size_t max_voxel_size,
28+
const std::vector<double> & point_cloud_range, const std::vector<double> & voxel_size,
29+
const std::size_t downsample_factor, const std::size_t encoder_in_feature_size,
30+
const float score_threshold, const float circle_nms_dist_threshold)
31+
{
32+
class_size_ = class_size;
33+
point_feature_size_ = point_feature_size;
34+
max_voxel_size_ = max_voxel_size;
35+
if (point_cloud_range.size() == 6) {
36+
range_min_x_ = static_cast<float>(point_cloud_range[0]);
37+
range_min_y_ = static_cast<float>(point_cloud_range[1]);
38+
range_min_z_ = static_cast<float>(point_cloud_range[2]);
39+
range_max_x_ = static_cast<float>(point_cloud_range[3]);
40+
range_max_y_ = static_cast<float>(point_cloud_range[4]);
41+
range_max_z_ = static_cast<float>(point_cloud_range[5]);
42+
}
43+
if (voxel_size.size() == 3) {
44+
voxel_size_x_ = static_cast<float>(voxel_size[0]);
45+
voxel_size_y_ = static_cast<float>(voxel_size[1]);
46+
voxel_size_z_ = static_cast<float>(voxel_size[2]);
47+
}
48+
downsample_factor_ = downsample_factor;
49+
encoder_in_feature_size_ = encoder_in_feature_size;
50+
51+
if (score_threshold > 0 && score_threshold < 1) {
52+
score_threshold_ = score_threshold;
53+
}
54+
55+
if (circle_nms_dist_threshold > 0) {
56+
circle_nms_dist_threshold_ = circle_nms_dist_threshold;
57+
}
58+
59+
grid_size_x_ = static_cast<std::size_t>((range_max_x_ - range_min_x_) / voxel_size_x_);
60+
grid_size_y_ = static_cast<std::size_t>((range_max_y_ - range_min_y_) / voxel_size_y_);
61+
grid_size_z_ = static_cast<std::size_t>((range_max_z_ - range_min_z_) / voxel_size_z_);
62+
offset_x_ = range_min_x_ + voxel_size_x_ / 2;
63+
offset_y_ = range_min_y_ + voxel_size_y_ / 2;
64+
offset_z_ = range_min_z_ + voxel_size_z_ / 2;
65+
down_grid_size_x_ = grid_size_x_ / downsample_factor_;
66+
down_grid_size_y_ = grid_size_y_ / downsample_factor_;
67+
};
68+
69+
// input params
70+
std::size_t class_size_{3};
71+
const std::size_t point_dim_size_{3}; // x, y and z
72+
std::size_t point_feature_size_{4}; // x, y, z and timelag
73+
std::size_t max_point_in_voxel_size_{32};
74+
std::size_t max_voxel_size_{40000};
75+
float range_min_x_{-89.6f};
76+
float range_min_y_{-89.6f};
77+
float range_min_z_{-3.0f};
78+
float range_max_x_{89.6f};
79+
float range_max_y_{89.6f};
80+
float range_max_z_{5.0f};
81+
float voxel_size_x_{0.32f};
82+
float voxel_size_y_{0.32f};
83+
float voxel_size_z_{8.0f};
84+
85+
// network params
86+
const std::size_t batch_size_{1};
87+
std::size_t downsample_factor_{2};
88+
std::size_t encoder_in_feature_size_{9};
89+
const std::size_t encoder_out_feature_size_{32};
90+
const std::size_t head_out_size_{6};
91+
const std::size_t head_out_offset_size_{2};
92+
const std::size_t head_out_z_size_{1};
93+
const std::size_t head_out_dim_size_{3};
94+
const std::size_t head_out_rot_size_{2};
95+
const std::size_t head_out_vel_size_{2};
96+
97+
// post-process params
98+
float score_threshold_{0.4f};
99+
float circle_nms_dist_threshold_{1.5f};
100+
101+
// calculated params
102+
std::size_t grid_size_x_ = (range_max_x_ - range_min_x_) / voxel_size_x_;
103+
std::size_t grid_size_y_ = (range_max_y_ - range_min_y_) / voxel_size_y_;
104+
std::size_t grid_size_z_ = (range_max_z_ - range_min_z_) / voxel_size_z_;
105+
float offset_x_ = range_min_x_ + voxel_size_x_ / 2;
106+
float offset_y_ = range_min_y_ + voxel_size_y_ / 2;
107+
float offset_z_ = range_min_z_ + voxel_size_z_ / 2;
108+
std::size_t down_grid_size_x_ = grid_size_x_ / downsample_factor_;
109+
std::size_t down_grid_size_y_ = grid_size_y_ / downsample_factor_;
110+
};
111+
112+
} // namespace centerpoint
113+
114+
#endif // LIDAR_CENTERPOINT__CENTERPOINT_CONFIG_HPP_

perception/lidar_centerpoint/lib/include/centerpoint_trt.hpp perception/lidar_centerpoint/include/lidar_centerpoint/centerpoint_trt.hpp

+11-11
Original file line numberDiff line numberDiff line change
@@ -12,14 +12,13 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef CENTERPOINT_TRT_HPP_
16-
#define CENTERPOINT_TRT_HPP_
15+
#ifndef LIDAR_CENTERPOINT__CENTERPOINT_TRT_HPP_
16+
#define LIDAR_CENTERPOINT__CENTERPOINT_TRT_HPP_
1717

18-
#include <config.hpp>
19-
#include <cuda_utils.hpp>
20-
#include <network_trt.hpp>
21-
#include <postprocess_kernel.hpp>
22-
#include <voxel_generator.hpp>
18+
#include <lidar_centerpoint/cuda_utils.hpp>
19+
#include <lidar_centerpoint/network/network_trt.hpp>
20+
#include <lidar_centerpoint/postprocess/postprocess_kernel.hpp>
21+
#include <lidar_centerpoint/preprocess/voxel_generator.hpp>
2322

2423
#include <sensor_msgs/msg/point_cloud2.hpp>
2524

@@ -57,8 +56,8 @@ class CenterPointTRT
5756
{
5857
public:
5958
explicit CenterPointTRT(
60-
const std::size_t num_class, const float score_threshold, const NetworkParam & encoder_param,
61-
const NetworkParam & head_param, const DensificationParam & densification_param);
59+
const NetworkParam & encoder_param, const NetworkParam & head_param,
60+
const DensificationParam & densification_param, const CenterPointConfig & config);
6261

6362
~CenterPointTRT();
6463

@@ -83,7 +82,8 @@ class CenterPointTRT
8382
cudaStream_t stream_{nullptr};
8483

8584
bool verbose_{false};
86-
std::size_t num_class_{0};
85+
std::size_t class_size_{0};
86+
CenterPointConfig config_;
8787
std::size_t num_voxels_{0};
8888
std::size_t encoder_in_feature_size_{0};
8989
std::size_t spatial_features_size_{0};
@@ -106,4 +106,4 @@ class CenterPointTRT
106106

107107
} // namespace centerpoint
108108

109-
#endif // CENTERPOINT_TRT_HPP_
109+
#endif // LIDAR_CENTERPOINT__CENTERPOINT_TRT_HPP_

perception/lidar_centerpoint/lib/include/cuda_utils.hpp perception/lidar_centerpoint/include/lidar_centerpoint/cuda_utils.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -39,8 +39,8 @@
3939
* https://creativecommons.org/publicdomain/zero/1.0/deed.en
4040
*/
4141

42-
#ifndef CUDA_UTILS_HPP_
43-
#define CUDA_UTILS_HPP_
42+
#ifndef LIDAR_CENTERPOINT__CUDA_UTILS_HPP_
43+
#define LIDAR_CENTERPOINT__CUDA_UTILS_HPP_
4444

4545
#include <cuda_runtime_api.h>
4646

@@ -117,4 +117,4 @@ inline T * get_next_ptr(size_t num_elem, void *& workspace, size_t & workspace_s
117117

118118
} // namespace cuda
119119

120-
#endif // CUDA_UTILS_HPP_
120+
#endif // LIDAR_CENTERPOINT__CUDA_UTILS_HPP_

perception/lidar_centerpoint/lib/include/network_trt.hpp perception/lidar_centerpoint/include/lidar_centerpoint/network/network_trt.hpp

+11-6
Original file line numberDiff line numberDiff line change
@@ -12,10 +12,13 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef NETWORK_TRT_HPP_
16-
#define NETWORK_TRT_HPP_
15+
#ifndef LIDAR_CENTERPOINT__NETWORK__NETWORK_TRT_HPP_
16+
#define LIDAR_CENTERPOINT__NETWORK__NETWORK_TRT_HPP_
1717

18-
#include <tensorrt_wrapper.hpp>
18+
#include <lidar_centerpoint/centerpoint_config.hpp>
19+
#include <lidar_centerpoint/network/tensorrt_wrapper.hpp>
20+
21+
#include <vector>
1922

2023
namespace centerpoint
2124
{
@@ -35,16 +38,18 @@ class HeadTRT : public TensorRTWrapper
3538
public:
3639
using TensorRTWrapper::TensorRTWrapper;
3740

38-
HeadTRT(const std::size_t num_class, const bool verbose);
41+
HeadTRT(
42+
const std::vector<std::size_t> & out_channel_sizes, const CenterPointConfig & config,
43+
const bool verbose);
3944

4045
protected:
4146
bool setProfile(
4247
nvinfer1::IBuilder & builder, nvinfer1::INetworkDefinition & network,
4348
nvinfer1::IBuilderConfig & config) override;
4449

45-
std::size_t num_class_{0};
50+
std::vector<std::size_t> out_channel_sizes_;
4651
};
4752

4853
} // namespace centerpoint
4954

50-
#endif // NETWORK_TRT_HPP_
55+
#endif // LIDAR_CENTERPOINT__NETWORK__NETWORK_TRT_HPP_

perception/lidar_centerpoint/lib/include/scatter_kernel.hpp perception/lidar_centerpoint/include/lidar_centerpoint/network/scatter_kernel.hpp

+6-4
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef SCATTER_KERNEL_HPP_
16-
#define SCATTER_KERNEL_HPP_
15+
#ifndef LIDAR_CENTERPOINT__NETWORK__SCATTER_KERNEL_HPP_
16+
#define LIDAR_CENTERPOINT__NETWORK__SCATTER_KERNEL_HPP_
1717

1818
#include <cuda.h>
1919
#include <cuda_runtime_api.h>
@@ -22,8 +22,10 @@ namespace centerpoint
2222
{
2323
cudaError_t scatterFeatures_launch(
2424
const float * pillar_features, const int * coords, const std::size_t num_pillars,
25-
float * scattered_features, cudaStream_t stream);
25+
const std::size_t max_voxel_size, const std::size_t encoder_out_feature_size,
26+
const std::size_t grid_size_x, const std::size_t grid_size_y, float * scattered_features,
27+
cudaStream_t stream);
2628

2729
} // namespace centerpoint
2830

29-
#endif // SCATTER_KERNEL_HPP_
31+
#endif // LIDAR_CENTERPOINT__NETWORK__SCATTER_KERNEL_HPP_

perception/lidar_centerpoint/lib/include/tensorrt_wrapper.hpp perception/lidar_centerpoint/include/lidar_centerpoint/network/tensorrt_wrapper.hpp

+7-4
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,10 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef TENSORRT_WRAPPER_HPP_
16-
#define TENSORRT_WRAPPER_HPP_
15+
#ifndef LIDAR_CENTERPOINT__NETWORK__TENSORRT_WRAPPER_HPP_
16+
#define LIDAR_CENTERPOINT__NETWORK__TENSORRT_WRAPPER_HPP_
17+
18+
#include <lidar_centerpoint/centerpoint_config.hpp>
1719

1820
#include <NvInfer.h>
1921

@@ -56,7 +58,7 @@ class Logger : public nvinfer1::ILogger
5658
class TensorRTWrapper
5759
{
5860
public:
59-
explicit TensorRTWrapper(bool verbose);
61+
explicit TensorRTWrapper(const CenterPointConfig & config, const bool verbose);
6062

6163
bool init(
6264
const std::string & onnx_path, const std::string & engine_path, const std::string & precision);
@@ -68,6 +70,7 @@ class TensorRTWrapper
6870
nvinfer1::IBuilder & builder, nvinfer1::INetworkDefinition & network,
6971
nvinfer1::IBuilderConfig & config) = 0;
7072

73+
CenterPointConfig config_;
7174
Logger logger_;
7275

7376
private:
@@ -88,4 +91,4 @@ class TensorRTWrapper
8891

8992
} // namespace centerpoint
9093

91-
#endif // TENSORRT_WRAPPER_HPP_
94+
#endif // LIDAR_CENTERPOINT__NETWORK__TENSORRT_WRAPPER_HPP_

0 commit comments

Comments
 (0)