Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

refactor(autoware_tensorrt_common): multi-TensorRT compatibility & tensorrt_common as unified lib for all perception components #9762

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
19 commits
Select commit Hold shift + click to select a range
e5578de
refactor(autoware_tensorrt_common): multi-TensorRT compatibility & te…
amadeuszsz Dec 24, 2024
5063ded
style(pre-commit): autofix
pre-commit-ci[bot] Dec 24, 2024
2941f1f
style(autoware_tensorrt_common): linting
amadeuszsz Dec 25, 2024
b65f646
Merge branch 'main' into refactor/tensorrt_common-API-compat
amadeuszsz Dec 25, 2024
75f82f1
style(autoware_lidar_centerpoint): typo
amadeuszsz Jan 7, 2025
0f19bab
docs(autoware_tensorrt_common): grammar
amadeuszsz Jan 7, 2025
fa498ad
fix(autoware_lidar_transfusion): reuse cast variable
amadeuszsz Jan 7, 2025
76cff71
fix(autoware_tensorrt_common): remove deprecated inference API
amadeuszsz Jan 7, 2025
4112498
style(autoware_tensorrt_common): grammar
amadeuszsz Jan 7, 2025
2f03ff3
style(autoware_tensorrt_common): grammar
amadeuszsz Jan 7, 2025
ec72c65
fix(autoware_tensorrt_common): const pointer
amadeuszsz Jan 8, 2025
45be672
fix(autoware_tensorrt_common): remove unused method declaration
amadeuszsz Jan 8, 2025
e155555
style(pre-commit): autofix
pre-commit-ci[bot] Jan 8, 2025
f9db321
refactor(autoware_tensorrt_common): readability
amadeuszsz Jan 8, 2025
b707837
fix(autoware_tensorrt_common): return if layer not registered
amadeuszsz Jan 8, 2025
e9a9369
refactor(autoware_tensorrt_common): readability
amadeuszsz Jan 8, 2025
7ebc429
fix(autoware_tensorrt_common): rename struct
amadeuszsz Jan 8, 2025
cd234d6
style(pre-commit): autofix
pre-commit-ci[bot] Jan 8, 2025
949119e
Merge branch 'main' into refactor/tensorrt_common-API-compat
amadeuszsz Jan 10, 2025
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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 @@ -176,10 +176,10 @@
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);

Check warning on line 180 in perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp#L180

Added line #L180 was not covered by tests
autoware::tensorrt_common::TrtCommonConfig head_param(
head_onnx_path, trt_precision, head_engine_path);

Check warning on line 182 in perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp#L182

Added line #L182 was not covered by tests
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 @@
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));

Check warning on line 53 in perception/autoware_lidar_apollo_instance_segmentation/src/detector.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_lidar_apollo_instance_segmentation/src/detector.cpp#L53

Added line #L53 was not covered by tests
if (!trt_common_->setup()) {
throw std::runtime_error("Failed to setup TensorRT");

Check warning on line 55 in perception/autoware_lidar_apollo_instance_segmentation/src/detector.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_lidar_apollo_instance_segmentation/src/detector.cpp#L55

Added line #L55 was not covered by tests
}

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

// GPU memory allocation
const auto input_dims = trt_common_->getBindingDimensions(0);
const auto input_dims = trt_common_->getTensorShape(0);

Check warning on line 64 in perception/autoware_lidar_apollo_instance_segmentation/src/detector.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_lidar_apollo_instance_segmentation/src/detector.cpp#L64

Added line #L64 was not covered by tests
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);

Check warning on line 68 in perception/autoware_lidar_apollo_instance_segmentation/src/detector.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_lidar_apollo_instance_segmentation/src/detector.cpp#L68

Added line #L68 was not covered by tests
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 @@
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 @@

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 warning on line 167 in perception/autoware_lidar_apollo_instance_segmentation/src/detector.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_lidar_apollo_instance_segmentation/src/detector.cpp#L167

Added line #L167 was not covered by tests

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
Loading