Skip to content

Commit 301e36b

Browse files
authored
fix(autoware_image_projection_based_fusion): resolve issue with segmentation pointcloud fusion node failing with multiple mask inputs (#8769)
1 parent 6e31ed8 commit 301e36b

File tree

2 files changed

+30
-25
lines changed
  • perception/autoware_image_projection_based_fusion
    • include/autoware/image_projection_based_fusion/segmentation_pointcloud_fusion
    • src/segmentation_pointcloud_fusion

2 files changed

+30
-25
lines changed

perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121
#include <image_transport/image_transport.hpp>
2222

2323
#include <string>
24+
#include <unordered_set>
2425
#include <utility>
2526
#include <vector>
2627

@@ -47,6 +48,7 @@ class SegmentPointCloudFusionNode : public FusionNode<PointCloud2, PointCloud2,
4748

4849
image_transport::Publisher pub_debug_mask_ptr_;
4950
bool is_publish_debug_mask_;
51+
std::unordered_set<size_t> filter_global_offset_set_;
5052

5153
public:
5254
explicit SegmentPointCloudFusionNode(const rclcpp::NodeOptions & options);

perception/autoware_image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp

+28-25
Original file line numberDiff line numberDiff line change
@@ -49,10 +49,31 @@ void SegmentPointCloudFusionNode::preprocess(__attribute__((unused)) PointCloud2
4949
return;
5050
}
5151

52-
void SegmentPointCloudFusionNode::postprocess(__attribute__((unused)) PointCloud2 & pointcloud_msg)
52+
void SegmentPointCloudFusionNode::postprocess(PointCloud2 & pointcloud_msg)
5353
{
54+
auto original_cloud = std::make_shared<PointCloud2>(pointcloud_msg);
55+
56+
int point_step = original_cloud->point_step;
57+
size_t output_pointcloud_size = 0;
58+
pointcloud_msg.data.clear();
59+
pointcloud_msg.data.resize(original_cloud->data.size());
60+
61+
for (size_t global_offset = 0; global_offset < original_cloud->data.size();
62+
global_offset += point_step) {
63+
if (filter_global_offset_set_.find(global_offset) == filter_global_offset_set_.end()) {
64+
copyPointCloud(
65+
*original_cloud, point_step, global_offset, pointcloud_msg, output_pointcloud_size);
66+
}
67+
}
68+
69+
pointcloud_msg.data.resize(output_pointcloud_size);
70+
pointcloud_msg.row_step = output_pointcloud_size / pointcloud_msg.height;
71+
pointcloud_msg.width = output_pointcloud_size / pointcloud_msg.point_step / pointcloud_msg.height;
72+
73+
filter_global_offset_set_.clear();
5474
return;
5575
}
76+
5677
void SegmentPointCloudFusionNode::fuseOnSingleImage(
5778
const PointCloud2 & input_pointcloud_msg, __attribute__((unused)) const std::size_t image_id,
5879
[[maybe_unused]] const Image & input_mask, __attribute__((unused)) const CameraInfo & camera_info,
@@ -101,15 +122,7 @@ void SegmentPointCloudFusionNode::fuseOnSingleImage(
101122
int x_offset = input_pointcloud_msg.fields[pcl::getFieldIndex(input_pointcloud_msg, "x")].offset;
102123
int y_offset = input_pointcloud_msg.fields[pcl::getFieldIndex(input_pointcloud_msg, "y")].offset;
103124
int z_offset = input_pointcloud_msg.fields[pcl::getFieldIndex(input_pointcloud_msg, "z")].offset;
104-
size_t output_pointcloud_size = 0;
105-
output_cloud.data.clear();
106-
output_cloud.data.resize(input_pointcloud_msg.data.size());
107-
output_cloud.fields = input_pointcloud_msg.fields;
108-
output_cloud.header = input_pointcloud_msg.header;
109-
output_cloud.height = input_pointcloud_msg.height;
110-
output_cloud.point_step = input_pointcloud_msg.point_step;
111-
output_cloud.is_bigendian = input_pointcloud_msg.is_bigendian;
112-
output_cloud.is_dense = input_pointcloud_msg.is_dense;
125+
113126
for (size_t global_offset = 0; global_offset < transformed_cloud.data.size();
114127
global_offset += point_step) {
115128
float transformed_x =
@@ -120,8 +133,6 @@ void SegmentPointCloudFusionNode::fuseOnSingleImage(
120133
*reinterpret_cast<float *>(&transformed_cloud.data[global_offset + z_offset]);
121134
// skip filtering pointcloud behind the camera or too far from camera
122135
if (transformed_z <= 0.0 || transformed_z > filter_distance_threshold_) {
123-
copyPointCloud(
124-
input_pointcloud_msg, point_step, global_offset, output_cloud, output_pointcloud_size);
125136
continue;
126137
}
127138

@@ -131,28 +142,20 @@ void SegmentPointCloudFusionNode::fuseOnSingleImage(
131142
bool is_inside_image = projected_point.x() > 0 && projected_point.x() < camera_info.width &&
132143
projected_point.y() > 0 && projected_point.y() < camera_info.height;
133144
if (!is_inside_image) {
134-
copyPointCloud(
135-
input_pointcloud_msg, point_step, global_offset, output_cloud, output_pointcloud_size);
136145
continue;
137146
}
138147

139148
// skip filtering pointcloud where semantic id out of the defined list
140149
uint8_t semantic_id = mask.at<uint8_t>(
141150
static_cast<uint16_t>(projected_point.y()), static_cast<uint16_t>(projected_point.x()));
142-
if (static_cast<size_t>(semantic_id) >= filter_semantic_label_target_list_.size()) {
143-
copyPointCloud(
144-
input_pointcloud_msg, point_step, global_offset, output_cloud, output_pointcloud_size);
151+
if (
152+
static_cast<size_t>(semantic_id) >= filter_semantic_label_target_list_.size() ||
153+
!filter_semantic_label_target_list_.at(semantic_id).second) {
145154
continue;
146155
}
147-
if (!filter_semantic_label_target_list_.at(semantic_id).second) {
148-
copyPointCloud(
149-
input_pointcloud_msg, point_step, global_offset, output_cloud, output_pointcloud_size);
150-
}
151-
}
152156

153-
output_cloud.data.resize(output_pointcloud_size);
154-
output_cloud.row_step = output_pointcloud_size / output_cloud.height;
155-
output_cloud.width = output_pointcloud_size / output_cloud.point_step / output_cloud.height;
157+
filter_global_offset_set_.insert(global_offset);
158+
}
156159
}
157160

158161
bool SegmentPointCloudFusionNode::out_of_scope(__attribute__((unused))

0 commit comments

Comments
 (0)