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(image_projection_based_fusion): add run length decoding for segmentation_pointcloud_fusion #7909

Merged
Show file tree
Hide file tree
Changes from 12 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
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
<depend>image_transport</depend>
<depend>message_filters</depend>
<depend>object_recognition_utils</depend>
<depend>perception_utils</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>sensor_msgs</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@

#include "autoware/image_projection_based_fusion/utils/geometry.hpp"
#include "autoware/image_projection_based_fusion/utils/utils.hpp"
#include "perception_utils/run_length_encoder.hpp"

#ifdef ROS_DISTRO_GALACTIC
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
Expand Down Expand Up @@ -58,20 +59,12 @@
return;
}
if (!checkCameraInfo(camera_info)) return;

cv_bridge::CvImagePtr in_image_ptr;
try {
in_image_ptr = cv_bridge::toCvCopy(
std::make_shared<sensor_msgs::msg::Image>(input_mask), input_mask.encoding);
} catch (const std::exception & e) {
RCLCPP_ERROR(this->get_logger(), "cv_bridge exception:%s", e.what());
if (input_mask.height == 0 || input_mask.width == 0) {
return;
}
std::vector<uint8_t> mask_data(input_mask.data.begin(), input_mask.data.end());

Check warning on line 65 in perception/autoware_image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp#L65

Added line #L65 was not covered by tests
cv::Mat mask = perception_utils::runLengthDecoder(mask_data, input_mask.height, input_mask.width);

cv::Mat mask = in_image_ptr->image;
if (mask.cols == 0 || mask.rows == 0) {
return;
}
const int orig_width = camera_info.width;
const int orig_height = camera_info.height;
// resize mask to the same size as the camera image
Expand Down
Loading