Skip to content

Commit c8e0040

Browse files
authored
feat(pointpainting_fusion): enable cloud display on image (#9813)
1 parent 869cf4c commit c8e0040

File tree

1 file changed

+48
-42
lines changed
  • perception/autoware_image_projection_based_fusion/src/pointpainting_fusion

1 file changed

+48
-42
lines changed

perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp

+48-42
Original file line numberDiff line numberDiff line change
@@ -316,54 +316,56 @@ dc | dc dc dc dc ||zc|
316316
// iterate points
317317
// Requires 'OMP_NUM_THREADS=N'
318318
omp_set_num_threads(omp_num_threads_);
319-
#pragma omp parallel for
320-
for (int i = 0; i < iterations; i++) {
321-
int stride = p_step * i;
322-
unsigned char * data = &painted_pointcloud_msg.data[0];
323-
unsigned char * output = &painted_pointcloud_msg.data[0];
324-
// cppcheck-suppress-begin invalidPointerCast
325-
float p_x = *reinterpret_cast<const float *>(&data[stride + x_offset]);
326-
float p_y = *reinterpret_cast<const float *>(&data[stride + y_offset]);
327-
float p_z = *reinterpret_cast<const float *>(&data[stride + z_offset]);
328-
// cppcheck-suppress-end invalidPointerCast
329-
point_lidar << p_x, p_y, p_z;
330-
point_camera = lidar2cam_affine * point_lidar;
331-
p_x = point_camera.x();
332-
p_y = point_camera.y();
333-
p_z = point_camera.z();
334-
335-
if (camera_projectors_[image_id].isOutsideHorizontalView(p_x, p_z)) {
336-
continue;
337-
}
319+
std::vector<std::vector<Eigen::Vector2d>> local_vectors(omp_num_threads_);
320+
#pragma omp parallel
321+
{
322+
#pragma omp for
323+
for (int i = 0; i < iterations; i++) {
324+
int stride = p_step * i;
325+
unsigned char * data = &painted_pointcloud_msg.data[0];
326+
unsigned char * output = &painted_pointcloud_msg.data[0];
327+
// cppcheck-suppress-begin invalidPointerCast
328+
float p_x = *reinterpret_cast<const float *>(&data[stride + x_offset]);
329+
float p_y = *reinterpret_cast<const float *>(&data[stride + y_offset]);
330+
float p_z = *reinterpret_cast<const float *>(&data[stride + z_offset]);
331+
// cppcheck-suppress-end invalidPointerCast
332+
point_lidar << p_x, p_y, p_z;
333+
point_camera = lidar2cam_affine * point_lidar;
334+
p_x = point_camera.x();
335+
p_y = point_camera.y();
336+
p_z = point_camera.z();
337+
338+
if (camera_projectors_[image_id].isOutsideHorizontalView(p_x, p_z)) {
339+
continue;
340+
}
338341

339-
// project
340-
Eigen::Vector2d projected_point;
341-
if (camera_projectors_[image_id].calcImageProjectedPoint(
342-
cv::Point3d(p_x, p_y, p_z), projected_point)) {
343-
// iterate 2d bbox
344-
for (const auto & feature_object : objects) {
345-
sensor_msgs::msg::RegionOfInterest roi = feature_object.feature.roi;
346-
// paint current point if it is inside bbox
347-
int label2d = feature_object.object.classification.front().label;
348-
if (
349-
!isUnknown(label2d) && isInsideBbox(projected_point.x(), projected_point.y(), roi, 1.0)) {
350-
// cppcheck-suppress invalidPointerCast
351-
auto p_class = reinterpret_cast<float *>(&output[stride + class_offset]);
352-
for (const auto & cls : isClassTable_) {
353-
// add up the class values if the point belongs to multiple classes
354-
*p_class = cls.second(label2d) ? (class_index_[cls.first] + *p_class) : *p_class;
342+
// project
343+
Eigen::Vector2d projected_point;
344+
if (camera_projectors_[image_id].calcImageProjectedPoint(
345+
cv::Point3d(p_x, p_y, p_z), projected_point)) {
346+
// iterate 2d bbox
347+
for (const auto & feature_object : objects) {
348+
sensor_msgs::msg::RegionOfInterest roi = feature_object.feature.roi;
349+
// paint current point if it is inside bbox
350+
int label2d = feature_object.object.classification.front().label;
351+
if (
352+
!isUnknown(label2d) &&
353+
isInsideBbox(projected_point.x(), projected_point.y(), roi, 1.0)) {
354+
// cppcheck-suppress invalidPointerCast
355+
auto p_class = reinterpret_cast<float *>(&output[stride + class_offset]);
356+
for (const auto & cls : isClassTable_) {
357+
// add up the class values if the point belongs to multiple classes
358+
*p_class = cls.second(label2d) ? (class_index_[cls.first] + *p_class) : *p_class;
359+
}
355360
}
356361
}
362+
if (debugger_) {
363+
int thread_id = omp_get_thread_num();
364+
local_vectors[thread_id].push_back(projected_point);
365+
}
357366
}
358-
#if 0
359-
// Parallelizing loop don't support push_back
360-
if (debugger_) {
361-
debug_image_points.push_back(projected_point);
362-
}
363-
#endif
364367
}
365368
}
366-
367369
if (debugger_) {
368370
std::unique_ptr<ScopedTimeTrack> inner_st_ptr;
369371
if (time_keeper_)
@@ -373,6 +375,10 @@ dc | dc dc dc dc ||zc|
373375
debug_image_rois.push_back(feature_object.feature.roi);
374376
}
375377

378+
for (const auto & local_vec : local_vectors) {
379+
debug_image_points.insert(debug_image_points.end(), local_vec.begin(), local_vec.end());
380+
}
381+
376382
debugger_->image_rois_ = debug_image_rois;
377383
debugger_->obstacle_points_ = debug_image_points;
378384
debugger_->publishImage(image_id, input_roi_msg.header.stamp);

0 commit comments

Comments
 (0)