Skip to content

Commit d94931f

Browse files
author
Barış Zeren
committed
Merge branch 'feat/add_tensorrt_rtmdet' of https://github.com/StepTurtle/autoware.universe into feat/add_tensorrt_rtmdet
2 parents f7d8088 + 309b53f commit d94931f

File tree

5 files changed

+19
-15
lines changed

5 files changed

+19
-15
lines changed

perception/autoware_tensorrt_rtmdet/include/tensorrt_rtmdet/tensorrt_rtmdet.hpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -20,9 +20,9 @@
2020

2121
#include <autoware/cuda_utils/cuda_unique_ptr.hpp>
2222
#include <autoware/cuda_utils/stream_unique_ptr.hpp>
23+
#include <autoware/tensorrt_common/tensorrt_common.hpp>
2324
#include <opencv2/opencv.hpp>
2425
#include <rclcpp/rclcpp.hpp>
25-
#include <autoware/tensorrt_common/tensorrt_common.hpp>
2626

2727
#include <cv_bridge/cv_bridge.h>
2828

@@ -81,7 +81,8 @@ class TrtRTMDet
8181
const std::string & model_path, const std::string & precision, const ColorMap & color_map,
8282
const float score_threshold = 0.3, const float nms_threshold = 0.7,
8383
const float mask_threshold = 200.0,
84-
const autoware::tensorrt_common::BuildConfig & build_config = autoware::tensorrt_common::BuildConfig(),
84+
const autoware::tensorrt_common::BuildConfig & build_config =
85+
autoware::tensorrt_common::BuildConfig(),
8586
const std::string & calibration_image_list_file_path = std::string(),
8687
const double norm_factor = 1.0, const std::vector<float> & mean = {103.53, 116.28, 123.675},
8788
const std::vector<float> & std = {57.375, 57.12, 58.395},

perception/autoware_tensorrt_rtmdet/package.xml

+3-3
Original file line numberDiff line numberDiff line change
@@ -16,17 +16,17 @@
1616
<buildtool_export_depend>cudnn_cmake_module</buildtool_export_depend>
1717
<buildtool_export_depend>tensorrt_cmake_module</buildtool_export_depend>
1818

19+
<depend>autoware_cuda_utils</depend>
1920
<depend>autoware_internal_msgs</depend>
21+
<depend>autoware_object_recognition_utils</depend>
2022
<depend>autoware_perception_msgs</depend>
21-
<depend>autoware_cuda_utils</depend>
23+
<depend>autoware_tensorrt_common</depend>
2224
<depend>cv_bridge</depend>
2325
<depend>image_transport</depend>
2426
<depend>libopencv-dev</depend>
25-
<depend>autoware_object_recognition_utils</depend>
2627
<depend>rclcpp</depend>
2728
<depend>rclcpp_components</depend>
2829
<depend>sensor_msgs</depend>
29-
<depend>autoware_tensorrt_common</depend>
3030
<depend>tier4_perception_msgs</depend>
3131
<depend>trt_batched_nms</depend>
3232

perception/autoware_tensorrt_rtmdet/src/tensorrt_rtmdet.cpp

+5-4
Original file line numberDiff line numberDiff line change
@@ -62,8 +62,9 @@ TrtRTMDet::TrtRTMDet(
6262
const autoware::tensorrt_common::BuildConfig & build_config,
6363
const std::string & calibration_image_list_file_path, const double norm_factor,
6464
const std::vector<float> & mean, const std::vector<float> & std,
65-
[[maybe_unused]] const std::string & cache_dir, const autoware::tensorrt_common::BatchConfig & batch_config,
66-
const size_t max_workspace_size, const std::vector<std::string> & plugin_paths)
65+
[[maybe_unused]] const std::string & cache_dir,
66+
const autoware::tensorrt_common::BatchConfig & batch_config, const size_t max_workspace_size,
67+
const std::vector<std::string> & plugin_paths)
6768
: score_threshold_{score_threshold},
6869
nms_threshold_{nms_threshold},
6970
mask_threshold_{mask_threshold},
@@ -190,8 +191,8 @@ void TrtRTMDet::preprocess_gpu(const std::vector<cv::Mat> & images)
190191
scale_height_ = input_height / static_cast<float>(image.rows);
191192
image_buf_h_ = autoware::cuda_utils::make_unique_host<unsigned char[]>(
192193
image.cols * image.rows * 3 * batch_size, cudaHostAllocWriteCombined);
193-
image_buf_d_ =
194-
autoware::cuda_utils::make_unique<unsigned char[]>(image.cols * image.rows * 3 * batch_size);
194+
image_buf_d_ = autoware::cuda_utils::make_unique<unsigned char[]>(
195+
image.cols * image.rows * 3 * batch_size);
195196
}
196197
int index = b * image.cols * image.rows * 3;
197198
// Copy into pinned memory

perception/autoware_tensorrt_rtmdet/src/tensorrt_rtmdet_node.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -57,7 +57,7 @@ TrtRTMDetNode::TrtRTMDetNode(const rclcpp::NodeOptions & node_options)
5757

5858
color_map_ = read_color_map_file(color_map_path);
5959

60-
autoware::tensorrt_common::BuildConfig build_config(
60+
autoware::tensorrt_common::BuildConfig build_config(
6161
"Entropy", dla_core_id, quantize_first_layer, quantize_last_layer, profile_per_layer,
6262
clip_value);
6363

@@ -71,8 +71,8 @@ TrtRTMDetNode::TrtRTMDetNode(const rclcpp::NodeOptions & node_options)
7171

7272
trt_rtmdet_ = std::make_unique<tensorrt_rtmdet::TrtRTMDet>(
7373
model_path, precision, color_map_, score_threshold, nms_threshold, mask_threshold, build_config,
74-
calibration_image_list_path, norm_factor, mean_, std_, cache_dir,
75-
batch_config, max_workspace_size, plugin_paths);
74+
calibration_image_list_path, norm_factor, mean_, std_, cache_dir, batch_config,
75+
max_workspace_size, plugin_paths);
7676

7777
timer_ =
7878
rclcpp::create_timer(this, get_clock(), 100ms, std::bind(&TrtRTMDetNode::on_connect, this));

perception/autoware_tensorrt_rtmdet/test/test_rtmdet.cpp

+5-3
Original file line numberDiff line numberDiff line change
@@ -19,8 +19,8 @@
1919

2020
#include <autoware/cuda_utils/cuda_unique_ptr.hpp>
2121
#include <autoware/cuda_utils/stream_unique_ptr.hpp>
22-
#include <opencv2/opencv.hpp>
2322
#include <autoware/tensorrt_common/tensorrt_common.hpp>
23+
#include <opencv2/opencv.hpp>
2424

2525
#include <dlfcn.h>
2626
#include <gtest/gtest.h>
@@ -95,7 +95,8 @@ class TrtRTMDetTest : public ::testing::Test
9595
*
9696
* @return The image buffer on the host.
9797
*/
98-
[[nodiscard]] const autoware::cuda_utils::CudaUniquePtrHost<unsigned char[]> & get_image_buffer_h() const
98+
[[nodiscard]] const autoware::cuda_utils::CudaUniquePtrHost<unsigned char[]> &
99+
get_image_buffer_h() const
99100
{
100101
return trt_rtmdet_->image_buf_h_;
101102
}
@@ -105,7 +106,8 @@ class TrtRTMDetTest : public ::testing::Test
105106
*
106107
* @return The image buffer on the device.
107108
*/
108-
[[nodiscard]] const autoware::cuda_utils::CudaUniquePtr<unsigned char[]> & get_image_buffer_d() const
109+
[[nodiscard]] const autoware::cuda_utils::CudaUniquePtr<unsigned char[]> & get_image_buffer_d()
110+
const
109111
{
110112
return trt_rtmdet_->image_buf_d_;
111113
}

0 commit comments

Comments
 (0)