Skip to content

Commit

Permalink
style(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] committed Dec 12, 2024
1 parent 6b4e247 commit 8f33c86
Show file tree
Hide file tree
Showing 2 changed files with 21 additions and 17 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -334,15 +334,16 @@ dc | dc dc dc dc ||zc|

std::vector<FeatureobjectAndROIInfo> 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;

Expand Down Expand Up @@ -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;
}

Expand All @@ -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<float *>(&output[stride + class_offset]);
for (const auto & cls : isClassTable_) {
Expand All @@ -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;
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -195,17 +195,17 @@ void RoiClusterFusionNode::fuseOnSingleImage(
inner_st_ptr = std::make_unique<ScopedTimeTrack>("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) {
Expand All @@ -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;
}
}
Expand Down

0 comments on commit 8f33c86

Please sign in to comment.