Skip to content

Commit 5f309f8

Browse files
committed
fix: move rle into utils
Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp>
1 parent 10bfceb commit 5f309f8

File tree

5 files changed

+95
-21
lines changed

5 files changed

+95
-21
lines changed

perception/autoware_tensorrt_yolox/CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -143,6 +143,7 @@ rclcpp_components_register_node(yolox_single_image_inference_node
143143
)
144144

145145
ament_auto_add_library(${PROJECT_NAME}_node SHARED
146+
src/utils.cpp
146147
src/tensorrt_yolox_node.cpp
147148
)
148149

perception/autoware_tensorrt_yolox/include/autoware/tensorrt_yolox/tensorrt_yolox_node.hpp

-1
Original file line numberDiff line numberDiff line change
@@ -71,7 +71,6 @@ class TrtYoloXNode : public rclcpp::Node
7171

7272
public:
7373
explicit TrtYoloXNode(const rclcpp::NodeOptions & node_options);
74-
std::vector<std::pair<uint8_t, int>> rle_compress(const cv::Mat & mask);
7574

7675
private:
7776
void onConnect();
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,26 @@
1+
// Copyright 2024 TIER IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef AUTOWARE_TENSORRT_YOLOX__UTILS_HPP_
16+
#define AUTOWARE_TENSORRT_YOLOX__UTILS_HPP_
17+
#include <opencv2/opencv.hpp>
18+
19+
20+
namespace autoware::tensorrt_yolox
21+
{
22+
std::vector<std::pair<uint8_t, int>> runLengthEncoder(const cv::Mat & mask);
23+
cv::Mat runLengthDecoder(const std::vector<uint8_t> & rle_data, const int rows, const int cols);
24+
} // namespace autoware::tensorrt_yolox
25+
26+
#endif //AUTOWARE_TENSORRT_YOLOX__UTILS_HPP_

perception/autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp

+2-20
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
#include "autoware/tensorrt_yolox/tensorrt_yolox_node.hpp"
1616

1717
#include "object_recognition_utils/object_classification.hpp"
18+
#include "autoware/tensorrt_yolox/utils.hpp"
1819

1920
#include <autoware_perception_msgs/msg/object_classification.hpp>
2021

@@ -126,25 +127,6 @@ void TrtYoloXNode::onConnect()
126127
}
127128
}
128129

129-
std::vector<std::pair<uint8_t, int>> TrtYoloXNode::rle_compress(const cv::Mat & image)
130-
{
131-
std::vector<std::pair<uint8_t, int>> compressed_data;
132-
const int rows = image.rows;
133-
const int cols = image.cols;
134-
compressed_data.emplace_back(image.at<uint8_t>(0, 0), 0);
135-
for (int i = 0; i < rows; ++i) {
136-
for (int j = 0; j < cols; ++j) {
137-
uint8_t current_value = image.at<uint8_t>(i, j);
138-
if (compressed_data.back().first == current_value) {
139-
++compressed_data.back().second;
140-
} else {
141-
compressed_data.emplace_back(current_value, 1);
142-
}
143-
}
144-
}
145-
return compressed_data;
146-
}
147-
148130
void TrtYoloXNode::onImage(const sensor_msgs::msg::Image::ConstSharedPtr msg)
149131
{
150132
stop_watch_ptr_->toc("processing_time", true);
@@ -203,7 +185,7 @@ void TrtYoloXNode::onImage(const sensor_msgs::msg::Image::ConstSharedPtr msg)
203185
.toImageMsg();
204186
out_mask_msg->header = msg->header;
205187

206-
std::vector<std::pair<uint8_t, int>> compressed_data = TrtYoloXNode::rle_compress(mask);
188+
std::vector<std::pair<uint8_t, int>> compressed_data = runLengthEncoder(mask);
207189
int step = sizeof(uint8_t) + sizeof(int);
208190
out_mask_msg->data.resize(static_cast<int>(compressed_data.size()) * step);
209191
for (size_t i = 0; i < compressed_data.size(); ++i) {
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,66 @@
1+
// Copyright 2024 Tier IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include "autoware/tensorrt_yolox/utils.hpp"
16+
17+
namespace autoware::tensorrt_yolox
18+
{
19+
20+
std::vector<std::pair<uint8_t, int>> runLengthEncoder(const cv::Mat & image)
21+
{
22+
std::vector<std::pair<uint8_t, int>> compressed_data;
23+
const int rows = image.rows;
24+
const int cols = image.cols;
25+
compressed_data.emplace_back(image.at<uint8_t>(0, 0), 0);
26+
for (int i = 0; i < rows; ++i) {
27+
for (int j = 0; j < cols; ++j) {
28+
uint8_t current_value = image.at<uint8_t>(i, j);
29+
if (compressed_data.back().first == current_value) {
30+
++compressed_data.back().second;
31+
} else {
32+
compressed_data.emplace_back(current_value, 1);
33+
}
34+
}
35+
}
36+
return compressed_data;
37+
}
38+
39+
40+
cv::Mat runLengthDecoder(
41+
const std::vector<uint8_t> & rle_data, const int rows, const int cols)
42+
{
43+
cv::Mat mask(rows, cols, CV_8UC1, cv::Scalar(0));
44+
int idx = 0;
45+
int step = sizeof(uint8_t) + sizeof(int);
46+
int nb_pixels = 0;
47+
for (size_t i = 0; i < rle_data.size(); i += step) {
48+
uint8_t value;
49+
int length;
50+
std::memcpy(&value, &rle_data[i], sizeof(uint8_t));
51+
std::memcpy(&length, &rle_data[i + sizeof(uint8_t)], sizeof(int));
52+
nb_pixels += length;
53+
for (int j = 0; j < length; ++j) {
54+
int row_idx = static_cast<int>(idx / cols);
55+
int col_idx = static_cast<int>(idx % cols);
56+
mask.at<uint8_t>(row_idx, col_idx) = value;
57+
idx++;
58+
if (idx > rows * cols) {
59+
break;
60+
}
61+
}
62+
}
63+
return mask;
64+
}
65+
66+
} // namespace tensorrt_yolox

0 commit comments

Comments
 (0)