From 8f33c86d056a6a52af2d157d4b294410e3576d5a Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Thu, 12 Dec 2024 09:38:14 +0000 Subject: [PATCH] style(pre-commit): autofix --- .../src/pointpainting_fusion/node.cpp | 24 ++++++++++--------- .../src/roi_cluster_fusion/node.cpp | 14 ++++++----- 2 files changed, 21 insertions(+), 17 deletions(-) diff --git a/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp index a8e34286d71ad..226f55abd4c10 100644 --- a/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp @@ -334,15 +334,16 @@ dc | dc dc dc dc ||zc| std::vector feature_object_with_roi_info; for (const auto & feature_object : input_roi_msg.feature_objects) { - feature_object_with_roi_info.push_back( - FeatureobjectAndROIInfo{ - &feature_object, feature_object.feature.roi.x_offset+feature_object.feature.roi.width, feature_object.object.classification.front().label - }); + feature_object_with_roi_info.push_back(FeatureobjectAndROIInfo{ + &feature_object, feature_object.feature.roi.x_offset + feature_object.feature.roi.width, + feature_object.object.classification.front().label}); } // sort the ROI by their x-values to search efficiently - std::sort(feature_object_with_roi_info.begin(), feature_object_with_roi_info.end(), - [](const auto &a, const auto &b) { return a.feature_obj->feature.roi.x_offset < b.feature_obj->feature.roi.x_offset; } - ); + std::sort( + feature_object_with_roi_info.begin(), feature_object_with_roi_info.end(), + [](const auto & a, const auto & b) { + return a.feature_obj->feature.roi.x_offset < b.feature_obj->feature.roi.x_offset; + }); int iterations = painted_pointcloud_msg.data.size() / painted_pointcloud_msg.point_step; @@ -389,7 +390,9 @@ dc | dc dc dc dc ||zc| // filter the points in the left side of most left located ROI // if isInsideBbox's zc is not 1.0, this will break the logic // since it is assuming on the image plane (pixel coodinate) - if (feature_object_with_roi_info.size() > 0 && px < feature_object_with_roi_info[0].feature_obj->feature.roi.x_offset) { + if ( + feature_object_with_roi_info.size() > 0 && + px < feature_object_with_roi_info[0].feature_obj->feature.roi.x_offset) { continue; } @@ -398,8 +401,7 @@ dc | dc dc dc dc ||zc| sensor_msgs::msg::RegionOfInterest roi = obj.feature_obj->feature.roi; // paint current point if it is inside bbox int label2d = obj.label; - if ( - !isUnknown(label2d) && isInsideBbox(px, py, roi, 1.0)) { + if (!isUnknown(label2d) && isInsideBbox(px, py, roi, 1.0)) { // cppcheck-suppress invalidPointerCast auto p_class = reinterpret_cast(&output[stride + class_offset]); for (const auto & cls : isClassTable_) { @@ -411,7 +413,7 @@ dc | dc dc dc dc ||zc| // we don't need to search more than this ROI bbox // if isInsideBbox's zc is not 1.0, this will break the logic // since it is assuming on the image plane (pixel coodinate) - if (px > obj.roi_right_side_x){ + if (px > obj.roi_right_side_x) { break; } } diff --git a/perception/autoware_image_projection_based_fusion/src/roi_cluster_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/roi_cluster_fusion/node.cpp index fd6a5ecbe7b7a..efe3695bc89df 100644 --- a/perception/autoware_image_projection_based_fusion/src/roi_cluster_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/roi_cluster_fusion/node.cpp @@ -195,17 +195,17 @@ void RoiClusterFusionNode::fuseOnSingleImage( inner_st_ptr = std::make_unique("compare ROI", *time_keeper_); // sort the clusters by their x-values to search for the max IoU efficiently - std::sort(m_cluster_roi.begin(), m_cluster_roi.end(), - [](const auto &a, const auto &b) { return a.second.x_offset < b.second.x_offset; } - ); + std::sort(m_cluster_roi.begin(), m_cluster_roi.end(), [](const auto & a, const auto & b) { + return a.second.x_offset < b.second.x_offset; + }); for (const auto & feature_obj : input_roi_msg.feature_objects) { int index = -1; bool associated = false; double max_iou = 0.0; auto image_roi = feature_obj.feature.roi; - const unsigned int image_roi_right_side_x = image_roi.x_offset+image_roi.width; - const unsigned int image_roi_bottom_side_y = image_roi.y_offset+image_roi.height; + const unsigned int image_roi_right_side_x = image_roi.x_offset + image_roi.width; + const unsigned int image_roi_bottom_side_y = image_roi.y_offset + image_roi.height; const bool is_roi_label_known = feature_obj.object.classification.front().label != ObjectClassification::UNKNOWN; for (const auto & cluster_map : m_cluster_roi) { @@ -231,7 +231,9 @@ void RoiClusterFusionNode::fuseOnSingleImage( // If the cluster ROI is to the right of the sorted ROIs and below them, // there is no chance of achieving a larger IoU - if (cluster_roi.x_offset > image_roi_right_side_x && cluster_roi.y_offset > image_roi_bottom_side_y){ + if ( + cluster_roi.x_offset > image_roi_right_side_x && + cluster_roi.y_offset > image_roi_bottom_side_y) { break; } }