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

fix(tensorrt_yolox): add run length encoding for sematic segmentation mask #7905

Merged
Show file tree
Hide file tree
Changes from 4 commits
Commits
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
1 change: 1 addition & 0 deletions perception/autoware_tensorrt_yolox/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -143,6 +143,7 @@ rclcpp_components_register_node(yolox_single_image_inference_node
)

ament_auto_add_library(${PROJECT_NAME}_node SHARED
src/utils.cpp
src/tensorrt_yolox_node.cpp
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@
#include <map>
#include <memory>
#include <string>
#include <utility>
#include <vector>

namespace autoware::tensorrt_yolox
Expand Down Expand Up @@ -81,6 +82,7 @@ class TrtYoloXNode : public rclcpp::Node
int mapRoiLabel2SegLabel(const int32_t roi_label_index);
image_transport::Publisher image_pub_;
image_transport::Publisher mask_pub_;

image_transport::Publisher color_mask_pub_;

rclcpp::Publisher<tier4_perception_msgs::msg::DetectedObjectsWithFeature>::SharedPtr objects_pub_;
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
// Copyright 2024 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE__TENSORRT_YOLOX__UTILS_HPP_
#define AUTOWARE__TENSORRT_YOLOX__UTILS_HPP_
#include <opencv2/opencv.hpp>

#include <utility>
#include <vector>

namespace autoware::tensorrt_yolox
{
std::vector<std::pair<uint8_t, int>> runLengthEncoder(const cv::Mat & mask);
cv::Mat runLengthDecoder(const std::vector<uint8_t> & rle_data, const int rows, const int cols);
} // namespace autoware::tensorrt_yolox

#endif // AUTOWARE__TENSORRT_YOLOX__UTILS_HPP_
12 changes: 11 additions & 1 deletion perception/autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2022 TIER IV, Inc.

Check notice on line 1 in perception/autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Overall Code Complexity

The mean cyclomatic complexity increases from 5.43 to 5.57, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -14,6 +14,7 @@

#include "autoware/tensorrt_yolox/tensorrt_yolox_node.hpp"

#include "autoware/tensorrt_yolox/utils.hpp"
#include "object_recognition_utils/object_classification.hpp"

#include <autoware_perception_msgs/msg/object_classification.hpp>
Expand Down Expand Up @@ -176,13 +177,22 @@
if (is_roi_overlap_segment_ && trt_yolox_->getMultitaskNum() > 0) {
overlapSegmentByRoi(yolox_object, mask, width, height);
}
}
// TODO(badai-nguyen): consider to change to 4bits data transfer
if (trt_yolox_->getMultitaskNum() > 0) {
sensor_msgs::msg::Image::SharedPtr out_mask_msg =
cv_bridge::CvImage(std_msgs::msg::Header(), sensor_msgs::image_encodings::MONO8, mask)
.toImageMsg();
out_mask_msg->header = msg->header;

std::vector<std::pair<uint8_t, int>> compressed_data = runLengthEncoder(mask);

Check warning on line 187 in perception/autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp#L187

Added line #L187 was not covered by tests
int step = sizeof(uint8_t) + sizeof(int);
out_mask_msg->data.resize(static_cast<int>(compressed_data.size()) * step);

Check warning on line 189 in perception/autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp#L189

Added line #L189 was not covered by tests
for (size_t i = 0; i < compressed_data.size(); ++i) {
std::memcpy(&out_mask_msg->data[i * step], &compressed_data.at(i).first, sizeof(uint8_t));

Check warning on line 191 in perception/autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp#L191

Added line #L191 was not covered by tests
std::memcpy(
&out_mask_msg->data[i * step + sizeof(uint8_t)], &compressed_data.at(i).second,

Check warning on line 193 in perception/autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp#L193

Added line #L193 was not covered by tests
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

same as #7905 (comment)

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@manato I fixed at 3220095

sizeof(int));
}

Check warning on line 195 in perception/autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

TrtYoloXNode::onImage increases in cyclomatic complexity from 10 to 11, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.

Check warning on line 195 in perception/autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Bumpy Road Ahead

TrtYoloXNode::onImage has 2 blocks with nested conditional logic. Any nesting of 2 or deeper is considered. Threshold is one single, nested block per function. The Bumpy Road code smell is a function that contains multiple chunks of nested conditional logic. The deeper the nesting and the more bumps, the lower the code health.
mask_pub_.publish(out_mask_msg);
}
image_pub_.publish(in_image_ptr->toImageMsg());
Expand Down
64 changes: 64 additions & 0 deletions perception/autoware_tensorrt_yolox/src/utils.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,64 @@
// Copyright 2024 Tier IV, Inc.
badai-nguyen marked this conversation as resolved.
Show resolved Hide resolved
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include "autoware/tensorrt_yolox/utils.hpp"

namespace autoware::tensorrt_yolox
{

std::vector<std::pair<uint8_t, int>> runLengthEncoder(const cv::Mat & image)

Check warning on line 20 in perception/autoware_tensorrt_yolox/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_tensorrt_yolox/src/utils.cpp#L20

Added line #L20 was not covered by tests
{
std::vector<std::pair<uint8_t, int>> compressed_data;
const int rows = image.rows;
const int cols = image.cols;
compressed_data.emplace_back(image.at<uint8_t>(0, 0), 0);

Check warning on line 25 in perception/autoware_tensorrt_yolox/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_tensorrt_yolox/src/utils.cpp#L23-L25

Added lines #L23 - L25 were not covered by tests
for (int i = 0; i < rows; ++i) {
for (int j = 0; j < cols; ++j) {
uint8_t current_value = image.at<uint8_t>(i, j);

Check warning on line 28 in perception/autoware_tensorrt_yolox/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_tensorrt_yolox/src/utils.cpp#L28

Added line #L28 was not covered by tests
if (compressed_data.back().first == current_value) {
++compressed_data.back().second;

Check warning on line 30 in perception/autoware_tensorrt_yolox/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_tensorrt_yolox/src/utils.cpp#L30

Added line #L30 was not covered by tests
} else {
compressed_data.emplace_back(current_value, 1);

Check warning on line 32 in perception/autoware_tensorrt_yolox/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_tensorrt_yolox/src/utils.cpp#L32

Added line #L32 was not covered by tests
}
}
}
return compressed_data;

Check warning on line 36 in perception/autoware_tensorrt_yolox/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_tensorrt_yolox/src/utils.cpp#L36

Added line #L36 was not covered by tests
}

cv::Mat runLengthDecoder(const std::vector<uint8_t> & rle_data, const int rows, const int cols)

Check warning on line 39 in perception/autoware_tensorrt_yolox/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_tensorrt_yolox/src/utils.cpp#L39

Added line #L39 was not covered by tests
{
cv::Mat mask(rows, cols, CV_8UC1, cv::Scalar(0));

Check warning on line 41 in perception/autoware_tensorrt_yolox/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_tensorrt_yolox/src/utils.cpp#L41

Added line #L41 was not covered by tests
int idx = 0;
int step = sizeof(uint8_t) + sizeof(int);
int nb_pixels = 0;
manato marked this conversation as resolved.
Show resolved Hide resolved
for (size_t i = 0; i < rle_data.size(); i += step) {
uint8_t value;
int length;
std::memcpy(&value, &rle_data[i], sizeof(uint8_t));
std::memcpy(&length, &rle_data[i + sizeof(uint8_t)], sizeof(int));

Check warning on line 49 in perception/autoware_tensorrt_yolox/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_tensorrt_yolox/src/utils.cpp#L49

Added line #L49 was not covered by tests
badai-nguyen marked this conversation as resolved.
Show resolved Hide resolved
nb_pixels += length;
for (int j = 0; j < length; ++j) {
int row_idx = static_cast<int>(idx / cols);
int col_idx = static_cast<int>(idx % cols);
mask.at<uint8_t>(row_idx, col_idx) = value;
idx++;

Check warning on line 55 in perception/autoware_tensorrt_yolox/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_tensorrt_yolox/src/utils.cpp#L52-L55

Added lines #L52 - L55 were not covered by tests
if (idx > rows * cols) {
break;
}
}
}
return mask;

Check warning on line 61 in perception/autoware_tensorrt_yolox/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_tensorrt_yolox/src/utils.cpp#L61

Added line #L61 was not covered by tests
}

} // namespace autoware::tensorrt_yolox
Loading