Skip to content

Commit f7d8088

Browse files
author
Barış Zeren
committed
fix: spellings
Signed-off-by: Barış Zeren <baris@leodrive.ai>
1 parent feb9792 commit f7d8088

File tree

3 files changed

+14
-14
lines changed

3 files changed

+14
-14
lines changed

perception/autoware_tensorrt_rtmdet/README.md

+1-1
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@
33
## Purpose
44

55
RTMDet is a real-time instance segmentation model which can be used for detecting objects like cars, pedestrians,
6-
bicycles, etc. in a scene. This package provides a ROS2 interface for RTMDet using TensorRT.
6+
bicycles, etc. in a scene. This package provides a ROS 2 interface for RTMDet using TensorRT.
77

88
## Inner-workings / Algorithms
99

perception/autoware_tensorrt_rtmdet/include/tensorrt_rtmdet/tensorrt_rtmdet.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -171,12 +171,12 @@ class TrtRTMDet
171171
CudaUniquePtr<float[]> input_d_;
172172

173173
// Device pointer for outputs
174-
CudaUniquePtr<float[]> out_dets_d_;
174+
CudaUniquePtr<float[]> out_detections_d_;
175175
CudaUniquePtr<int32_t[]> out_labels_d_;
176176
CudaUniquePtr<float[]> out_masks_d_;
177177

178178
// Host pointer for outputs
179-
std::unique_ptr<float[]> out_dets_h_;
179+
std::unique_ptr<float[]> out_detections_h_;
180180
std::unique_ptr<int32_t[]> out_labels_h_;
181181
std::unique_ptr<float[]> out_masks_h_;
182182

perception/autoware_tensorrt_rtmdet/src/tensorrt_rtmdet.cpp

+11-11
Original file line numberDiff line numberDiff line change
@@ -120,19 +120,19 @@ TrtRTMDet::TrtRTMDet(
120120

121121
input_d_ = autoware::cuda_utils::make_unique<float[]>(
122122
batch_size_ * input_dims.d[1] * input_dims.d[2] * input_dims.d[3]);
123-
out_dets_d_ = autoware::cuda_utils::make_unique<float[]>(batch_size_ * max_detections_ * 5);
123+
out_detections_d_ = autoware::cuda_utils::make_unique<float[]>(batch_size_ * max_detections_ * 5);
124124
out_labels_d_ = autoware::cuda_utils::make_unique<int32_t[]>(batch_size_ * max_detections_);
125125
out_masks_d_ = autoware::cuda_utils::make_unique<float[]>(
126126
batch_size_ * max_detections_ * model_input_width_ * model_input_height_);
127127

128-
out_dets_h_ = std::make_unique<float[]>(batch_size_ * max_detections_ * 5);
128+
out_detections_h_ = std::make_unique<float[]>(batch_size_ * max_detections_ * 5);
129129
out_labels_h_ = std::make_unique<int32_t[]>(batch_size_ * max_detections_);
130130
out_masks_h_ = std::make_unique<float[]>(
131131
batch_size_ * max_detections_ * model_input_width_ * model_input_height_);
132132

133133
#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8050
134134
std::vector<void *> buffers = {
135-
input_d_.get(), out_dets_d_.get(), out_labels_d_.get(), out_masks_d_.get()};
135+
input_d_.get(), out_detections_d_.get(), out_labels_d_.get(), out_masks_d_.get()};
136136
trt_common_->setupBindings(buffers);
137137
#endif
138138
}
@@ -238,12 +238,12 @@ bool TrtRTMDet::feedforward(
238238
#endif
239239

240240
const auto batch_size = images.size();
241-
out_dets_h_.reset(new float[batch_size_ * max_detections_ * 5]);
241+
out_detections_h_.reset(new float[batch_size_ * max_detections_ * 5]);
242242
out_labels_h_.reset(new int32_t[batch_size_ * max_detections_]);
243243
out_masks_h_.reset(new float[batch_size_ * 20 * model_input_width_ * model_input_height_]);
244244

245245
CHECK_CUDA_ERROR(cudaMemcpyAsync(
246-
out_dets_h_.get(), out_dets_d_.get(), sizeof(float) * batch_size_ * max_detections_ * 5,
246+
out_detections_h_.get(), out_detections_d_.get(), sizeof(float) * batch_size_ * max_detections_ * 5,
247247
cudaMemcpyDeviceToHost, *stream_));
248248
CHECK_CUDA_ERROR(cudaMemcpyAsync(
249249
out_labels_h_.get(), out_labels_d_.get(), sizeof(int32_t) * batch_size_ * max_detections_,
@@ -260,22 +260,22 @@ bool TrtRTMDet::feedforward(
260260
for (size_t batch = 0; batch < batch_size; ++batch) {
261261
ObjectArray object_array;
262262
for (uint32_t index = 0; index < max_detections_; ++index) {
263-
if (out_dets_h_[(batch * max_detections_ * 5) + ((5 * index) + 4)] < score_threshold_) {
263+
if (out_detections_h_[(batch * max_detections_ * 5) + ((5 * index) + 4)] < score_threshold_) {
264264
break;
265265
}
266266

267267
Object object{};
268268
object.mask_index = index;
269269
object.class_id = out_labels_h_[(batch * max_detections_) + index];
270270
object.x1 = static_cast<uint32_t>(
271-
out_dets_h_[(batch * max_detections_ * 5) + ((5 * index) + 0)] / scale_width_);
271+
out_detections_h_[(batch * max_detections_ * 5) + ((5 * index) + 0)] / scale_width_);
272272
object.y1 = static_cast<uint32_t>(
273-
out_dets_h_[(batch * max_detections_ * 5) + ((5 * index) + 1)] / scale_height_);
273+
out_detections_h_[(batch * max_detections_ * 5) + ((5 * index) + 1)] / scale_height_);
274274
object.x2 = static_cast<uint32_t>(
275-
out_dets_h_[(batch * max_detections_ * 5) + ((5 * index) + 2)] / scale_width_);
275+
out_detections_h_[(batch * max_detections_ * 5) + ((5 * index) + 2)] / scale_width_);
276276
object.y2 = static_cast<uint32_t>(
277-
out_dets_h_[(batch * max_detections_ * 5) + ((5 * index) + 3)] / scale_height_);
278-
object.score = out_dets_h_[(batch * max_detections_ * 5) + ((5 * index) + 4)];
277+
out_detections_h_[(batch * max_detections_ * 5) + ((5 * index) + 3)] / scale_height_);
278+
object.score = out_detections_h_[(batch * max_detections_ * 5) + ((5 * index) + 4)];
279279
object_array.push_back(object);
280280
}
281281
ObjectArray nms_objects;

0 commit comments

Comments
 (0)