Skip to content

Commit

Permalink
refactor(autoware_tensorrt_common): multi-TensorRT compatibility & te…
Browse files Browse the repository at this point in the history
…nsorrt_common as unified lib for all perception components

Signed-off-by: Amadeusz Szymko <[email protected]>
  • Loading branch information
amadeuszsz committed Dec 24, 2024
1 parent 57f38b7 commit e5578de
Show file tree
Hide file tree
Showing 47 changed files with 2,372 additions and 2,059 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@

#include <autoware/image_projection_based_fusion/pointpainting_fusion/voxel_generator.hpp>
#include <autoware/lidar_centerpoint/centerpoint_trt.hpp>
#include <autoware/tensorrt_common/utils.hpp>

#include <memory>
#include <string>
Expand All @@ -29,8 +30,8 @@ class PointPaintingTRT : public autoware::lidar_centerpoint::CenterPointTRT
using autoware::lidar_centerpoint::CenterPointTRT::CenterPointTRT;

explicit PointPaintingTRT(
const autoware::lidar_centerpoint::NetworkParam & encoder_param,
const autoware::lidar_centerpoint::NetworkParam & head_param,
const autoware::tensorrt_common::TrtCommonConfig & encoder_param,
const autoware::tensorrt_common::TrtCommonConfig & head_param,
const autoware::lidar_centerpoint::DensificationParam & densification_param,
const autoware::lidar_centerpoint::CenterPointConfig & config);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -172,10 +172,10 @@ PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & opt
iou_bev_nms_.setParameters(p);
}

autoware::lidar_centerpoint::NetworkParam encoder_param(
encoder_onnx_path, encoder_engine_path, trt_precision);
autoware::lidar_centerpoint::NetworkParam head_param(
head_onnx_path, head_engine_path, trt_precision);
autoware::tensorrt_common::TrtCommonConfig encoder_param(
encoder_onnx_path, trt_precision, encoder_engine_path);
autoware::tensorrt_common::TrtCommonConfig head_param(
head_onnx_path, trt_precision, head_engine_path);
autoware::lidar_centerpoint::DensificationParam densification_param(
densification_world_frame_id, densification_num_past_frames);
autoware::lidar_centerpoint::CenterPointConfig config(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,8 @@
namespace autoware::image_projection_based_fusion
{
PointPaintingTRT::PointPaintingTRT(
const autoware::lidar_centerpoint::NetworkParam & encoder_param,
const autoware::lidar_centerpoint::NetworkParam & head_param,
const autoware::tensorrt_common::TrtCommonConfig & encoder_param,
const autoware::tensorrt_common::TrtCommonConfig & head_param,
const autoware::lidar_centerpoint::DensificationParam & densification_param,
const autoware::lidar_centerpoint::CenterPointConfig & config)
: autoware::lidar_centerpoint::CenterPointTRT(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@

#include <sensor_msgs/point_cloud2_iterator.hpp>

#include <NvCaffeParser.h>
#include <NvInfer.h>
#include <pcl_conversions/pcl_conversions.h>

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

trt_common_ = std::make_unique<autoware::tensorrt_common::TrtCommon>(
onnx_file, precision, nullptr, autoware::tensorrt_common::BatchConfig{1, 1, 1}, 1 << 30);
trt_common_->setup();

if (!trt_common_->isInitialized()) {
RCLCPP_ERROR_STREAM(node_->get_logger(), "failed to create tensorrt engine file.");
return;
tensorrt_common::TrtCommonConfig(onnx_file, precision));
if (!trt_common_->setup()) {
throw std::runtime_error("Failed to setup TensorRT");
}

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

// GPU memory allocation
const auto input_dims = trt_common_->getBindingDimensions(0);
const auto input_dims = trt_common_->getTensorShape(0);
const auto input_size =
std::accumulate(input_dims.d + 1, input_dims.d + input_dims.nbDims, 1, std::multiplies<int>());
input_d_ = autoware::cuda_utils::make_unique<float[]>(input_size);
const auto output_dims = trt_common_->getBindingDimensions(1);
const auto output_dims = trt_common_->getTensorShape(1);
output_size_ = std::accumulate(
output_dims.d + 1, output_dims.d + output_dims.nbDims, 1, std::multiplies<int>());
output_d_ = autoware::cuda_utils::make_unique<float[]>(output_size_);
Expand Down Expand Up @@ -127,10 +123,6 @@ bool LidarApolloInstanceSegmentation::detectDynamicObjects(
const sensor_msgs::msg::PointCloud2 & input,
tier4_perception_msgs::msg::DetectedObjectsWithFeature & output)
{
if (!trt_common_->isInitialized()) {
return false;
}

// move up pointcloud z_offset in z axis
sensor_msgs::msg::PointCloud2 transformed_cloud;
transformCloud(input, transformed_cloud, z_offset_);
Expand Down Expand Up @@ -169,7 +161,10 @@ bool LidarApolloInstanceSegmentation::detectDynamicObjects(

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

trt_common_->enqueueV2(buffers.data(), *stream_, nullptr);
if (!trt_common_->setTensorsAddresses(buffers)) {
return false;
}
trt_common_->enqueueV3(*stream_);

CHECK_CUDA_ERROR(cudaMemcpyAsync(
output_h_.get(), output_d_.get(), sizeof(float) * output_size_, cudaMemcpyDeviceToHost,
Expand Down
2 changes: 0 additions & 2 deletions perception/autoware_lidar_centerpoint/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -84,8 +84,6 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL)
lib/detection_class_remapper.cpp
lib/utils.cpp
lib/ros_utils.cpp
lib/network/network_trt.cpp
lib/network/tensorrt_wrapper.cpp
lib/postprocess/non_maximum_suppression.cpp
lib/preprocess/pointcloud_densification.cpp
lib/preprocess/voxel_generator.cpp
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,12 +16,13 @@
#define AUTOWARE__LIDAR_CENTERPOINT__CENTERPOINT_TRT_HPP_

#include "autoware/lidar_centerpoint/cuda_utils.hpp"
#include "autoware/lidar_centerpoint/network/network_trt.hpp"
#include "autoware/lidar_centerpoint/postprocess/postprocess_kernel.hpp"
#include "autoware/lidar_centerpoint/preprocess/voxel_generator.hpp"
#include "pcl/point_cloud.h"
#include "pcl/point_types.h"

#include <autoware/tensorrt_common/tensorrt_common.hpp>

#include "sensor_msgs/msg/point_cloud2.hpp"

#include <memory>
Expand All @@ -31,31 +32,14 @@

namespace autoware::lidar_centerpoint
{
class NetworkParam
{
public:
NetworkParam(std::string onnx_path, std::string engine_path, std::string trt_precision)
: onnx_path_(std::move(onnx_path)),
engine_path_(std::move(engine_path)),
trt_precision_(std::move(trt_precision))
{
}

std::string onnx_path() const { return onnx_path_; }
std::string engine_path() const { return engine_path_; }
std::string trt_precision() const { return trt_precision_; }

private:
std::string onnx_path_;
std::string engine_path_;
std::string trt_precision_;
};
using autoware::tensorrt_common::ProfileDims;
using autoware::tensorrt_common::TrtCommonConfig;

class CenterPointTRT
{
public:
explicit CenterPointTRT(
const NetworkParam & encoder_param, const NetworkParam & head_param,
const TrtCommonConfig & encoder_param, const TrtCommonConfig & head_param,
const DensificationParam & densification_param, const CenterPointConfig & config);

virtual ~CenterPointTRT();
Expand All @@ -66,6 +50,7 @@ class CenterPointTRT

protected:
void initPtr();
void initTrt(const TrtCommonConfig & encoder_param, const TrtCommonConfig & head_param);

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

std::unique_ptr<VoxelGeneratorTemplate> vg_ptr_{nullptr};
std::unique_ptr<VoxelEncoderTRT> encoder_trt_ptr_{nullptr};
std::unique_ptr<HeadTRT> head_trt_ptr_{nullptr};
std::unique_ptr<tensorrt_common::TrtCommon> encoder_trt_ptr_{nullptr};
std::unique_ptr<tensorrt_common::TrtCommon> head_trt_ptr_{nullptr};
std::unique_ptr<PostProcessCUDA> post_proc_ptr_{nullptr};
cudaStream_t stream_{nullptr};

Expand Down

This file was deleted.

This file was deleted.

Loading

0 comments on commit e5578de

Please sign in to comment.