Skip to content

Commit e5578de

Browse files
committed
refactor(autoware_tensorrt_common): multi-TensorRT compatibility & tensorrt_common as unified lib for all perception components
Signed-off-by: Amadeusz Szymko <amadeusz.szymko.2@tier4.jp>
1 parent 57f38b7 commit e5578de

File tree

47 files changed

+2372
-2059
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

47 files changed

+2372
-2059
lines changed

perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/pointpainting_fusion/pointpainting_trt.hpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717

1818
#include <autoware/image_projection_based_fusion/pointpainting_fusion/voxel_generator.hpp>
1919
#include <autoware/lidar_centerpoint/centerpoint_trt.hpp>
20+
#include <autoware/tensorrt_common/utils.hpp>
2021

2122
#include <memory>
2223
#include <string>
@@ -29,8 +30,8 @@ class PointPaintingTRT : public autoware::lidar_centerpoint::CenterPointTRT
2930
using autoware::lidar_centerpoint::CenterPointTRT::CenterPointTRT;
3031

3132
explicit PointPaintingTRT(
32-
const autoware::lidar_centerpoint::NetworkParam & encoder_param,
33-
const autoware::lidar_centerpoint::NetworkParam & head_param,
33+
const autoware::tensorrt_common::TrtCommonConfig & encoder_param,
34+
const autoware::tensorrt_common::TrtCommonConfig & head_param,
3435
const autoware::lidar_centerpoint::DensificationParam & densification_param,
3536
const autoware::lidar_centerpoint::CenterPointConfig & config);
3637

perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -172,10 +172,10 @@ PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & opt
172172
iou_bev_nms_.setParameters(p);
173173
}
174174

175-
autoware::lidar_centerpoint::NetworkParam encoder_param(
176-
encoder_onnx_path, encoder_engine_path, trt_precision);
177-
autoware::lidar_centerpoint::NetworkParam head_param(
178-
head_onnx_path, head_engine_path, trt_precision);
175+
autoware::tensorrt_common::TrtCommonConfig encoder_param(
176+
encoder_onnx_path, trt_precision, encoder_engine_path);
177+
autoware::tensorrt_common::TrtCommonConfig head_param(
178+
head_onnx_path, trt_precision, head_engine_path);
179179
autoware::lidar_centerpoint::DensificationParam densification_param(
180180
densification_world_frame_id, densification_num_past_frames);
181181
autoware::lidar_centerpoint::CenterPointConfig config(

perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/pointpainting_trt.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -27,8 +27,8 @@
2727
namespace autoware::image_projection_based_fusion
2828
{
2929
PointPaintingTRT::PointPaintingTRT(
30-
const autoware::lidar_centerpoint::NetworkParam & encoder_param,
31-
const autoware::lidar_centerpoint::NetworkParam & head_param,
30+
const autoware::tensorrt_common::TrtCommonConfig & encoder_param,
31+
const autoware::tensorrt_common::TrtCommonConfig & head_param,
3232
const autoware::lidar_centerpoint::DensificationParam & densification_param,
3333
const autoware::lidar_centerpoint::CenterPointConfig & config)
3434
: autoware::lidar_centerpoint::CenterPointTRT(

perception/autoware_lidar_apollo_instance_segmentation/src/detector.cpp

+9-14
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,6 @@
1818

1919
#include <sensor_msgs/point_cloud2_iterator.hpp>
2020

21-
#include <NvCaffeParser.h>
2221
#include <NvInfer.h>
2322
#include <pcl_conversions/pcl_conversions.h>
2423

@@ -51,12 +50,9 @@ LidarApolloInstanceSegmentation::LidarApolloInstanceSegmentation(rclcpp::Node *
5150
const auto precision = node_->declare_parameter("precision", "fp32");
5251

5352
trt_common_ = std::make_unique<autoware::tensorrt_common::TrtCommon>(
54-
onnx_file, precision, nullptr, autoware::tensorrt_common::BatchConfig{1, 1, 1}, 1 << 30);
55-
trt_common_->setup();
56-
57-
if (!trt_common_->isInitialized()) {
58-
RCLCPP_ERROR_STREAM(node_->get_logger(), "failed to create tensorrt engine file.");
59-
return;
53+
tensorrt_common::TrtCommonConfig(onnx_file, precision));
54+
if (!trt_common_->setup()) {
55+
throw std::runtime_error("Failed to setup TensorRT");
6056
}
6157

6258
if (node_->declare_parameter("build_only", false)) {
@@ -65,11 +61,11 @@ LidarApolloInstanceSegmentation::LidarApolloInstanceSegmentation(rclcpp::Node *
6561
}
6662

6763
// GPU memory allocation
68-
const auto input_dims = trt_common_->getBindingDimensions(0);
64+
const auto input_dims = trt_common_->getTensorShape(0);
6965
const auto input_size =
7066
std::accumulate(input_dims.d + 1, input_dims.d + input_dims.nbDims, 1, std::multiplies<int>());
7167
input_d_ = autoware::cuda_utils::make_unique<float[]>(input_size);
72-
const auto output_dims = trt_common_->getBindingDimensions(1);
68+
const auto output_dims = trt_common_->getTensorShape(1);
7369
output_size_ = std::accumulate(
7470
output_dims.d + 1, output_dims.d + output_dims.nbDims, 1, std::multiplies<int>());
7571
output_d_ = autoware::cuda_utils::make_unique<float[]>(output_size_);
@@ -127,10 +123,6 @@ bool LidarApolloInstanceSegmentation::detectDynamicObjects(
127123
const sensor_msgs::msg::PointCloud2 & input,
128124
tier4_perception_msgs::msg::DetectedObjectsWithFeature & output)
129125
{
130-
if (!trt_common_->isInitialized()) {
131-
return false;
132-
}
133-
134126
// move up pointcloud z_offset in z axis
135127
sensor_msgs::msg::PointCloud2 transformed_cloud;
136128
transformCloud(input, transformed_cloud, z_offset_);
@@ -169,7 +161,10 @@ bool LidarApolloInstanceSegmentation::detectDynamicObjects(
169161

170162
std::vector<void *> buffers = {input_d_.get(), output_d_.get()};
171163

172-
trt_common_->enqueueV2(buffers.data(), *stream_, nullptr);
164+
if (!trt_common_->setTensorsAddresses(buffers)) {
165+
return false;
166+
}
167+
trt_common_->enqueueV3(*stream_);
173168

174169
CHECK_CUDA_ERROR(cudaMemcpyAsync(
175170
output_h_.get(), output_d_.get(), sizeof(float) * output_size_, cudaMemcpyDeviceToHost,

perception/autoware_lidar_centerpoint/CMakeLists.txt

-2
Original file line numberDiff line numberDiff line change
@@ -84,8 +84,6 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL)
8484
lib/detection_class_remapper.cpp
8585
lib/utils.cpp
8686
lib/ros_utils.cpp
87-
lib/network/network_trt.cpp
88-
lib/network/tensorrt_wrapper.cpp
8987
lib/postprocess/non_maximum_suppression.cpp
9088
lib/preprocess/pointcloud_densification.cpp
9189
lib/preprocess/voxel_generator.cpp

perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/centerpoint_trt.hpp

+8-23
Original file line numberDiff line numberDiff line change
@@ -16,12 +16,13 @@
1616
#define AUTOWARE__LIDAR_CENTERPOINT__CENTERPOINT_TRT_HPP_
1717

1818
#include "autoware/lidar_centerpoint/cuda_utils.hpp"
19-
#include "autoware/lidar_centerpoint/network/network_trt.hpp"
2019
#include "autoware/lidar_centerpoint/postprocess/postprocess_kernel.hpp"
2120
#include "autoware/lidar_centerpoint/preprocess/voxel_generator.hpp"
2221
#include "pcl/point_cloud.h"
2322
#include "pcl/point_types.h"
2423

24+
#include <autoware/tensorrt_common/tensorrt_common.hpp>
25+
2526
#include "sensor_msgs/msg/point_cloud2.hpp"
2627

2728
#include <memory>
@@ -31,31 +32,14 @@
3132

3233
namespace autoware::lidar_centerpoint
3334
{
34-
class NetworkParam
35-
{
36-
public:
37-
NetworkParam(std::string onnx_path, std::string engine_path, std::string trt_precision)
38-
: onnx_path_(std::move(onnx_path)),
39-
engine_path_(std::move(engine_path)),
40-
trt_precision_(std::move(trt_precision))
41-
{
42-
}
43-
44-
std::string onnx_path() const { return onnx_path_; }
45-
std::string engine_path() const { return engine_path_; }
46-
std::string trt_precision() const { return trt_precision_; }
47-
48-
private:
49-
std::string onnx_path_;
50-
std::string engine_path_;
51-
std::string trt_precision_;
52-
};
35+
using autoware::tensorrt_common::ProfileDims;
36+
using autoware::tensorrt_common::TrtCommonConfig;
5337

5438
class CenterPointTRT
5539
{
5640
public:
5741
explicit CenterPointTRT(
58-
const NetworkParam & encoder_param, const NetworkParam & head_param,
42+
const TrtCommonConfig & encoder_param, const TrtCommonConfig & head_param,
5943
const DensificationParam & densification_param, const CenterPointConfig & config);
6044

6145
virtual ~CenterPointTRT();
@@ -66,6 +50,7 @@ class CenterPointTRT
6650

6751
protected:
6852
void initPtr();
53+
void initTrt(const TrtCommonConfig & encoder_param, const TrtCommonConfig & head_param);
6954

7055
virtual bool preprocess(
7156
const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const tf2_ros::Buffer & tf_buffer);
@@ -75,8 +60,8 @@ class CenterPointTRT
7560
void postProcess(std::vector<Box3D> & det_boxes3d);
7661

7762
std::unique_ptr<VoxelGeneratorTemplate> vg_ptr_{nullptr};
78-
std::unique_ptr<VoxelEncoderTRT> encoder_trt_ptr_{nullptr};
79-
std::unique_ptr<HeadTRT> head_trt_ptr_{nullptr};
63+
std::unique_ptr<tensorrt_common::TrtCommon> encoder_trt_ptr_{nullptr};
64+
std::unique_ptr<tensorrt_common::TrtCommon> head_trt_ptr_{nullptr};
8065
std::unique_ptr<PostProcessCUDA> post_proc_ptr_{nullptr};
8166
cudaStream_t stream_{nullptr};
8267

perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/network/network_trt.hpp

-53
This file was deleted.

perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/network/tensorrt_wrapper.hpp

-67
This file was deleted.

0 commit comments

Comments
 (0)