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(euclidean_cluster): fix euclidean cluster params #7662

Conversation

beginningfan
Copy link
Contributor

Description

Fix bug 2 about max_cluster_size_ related in here
The bug about min_cluster_size is a mistake and it should not to be changed

Tests performed

use a large max_cluster_size_ will not take too much CPU and memory

Effects on system behavior

Not applicable.

Interface changes

Pre-review checklist for the PR author

The PR author must check the checkboxes below when creating the PR.

In-review checklist for the PR reviewers

The PR reviewers must check the checkboxes below before approval.

Post-review checklist for the PR author

The PR author must check the checkboxes below before merging.

  • There are no open discussions or they are tracked via tickets.

After all checkboxes are checked, anyone who has write access can merge the PR.

@github-actions github-actions bot added the component:perception Advanced sensor data processing and environment understanding. (auto-assigned) label Jun 24, 2024
@beginningfan beginningfan changed the title Fix euclidean cluster params fix(euclidean_cluster): fix euclidean cluster params Jun 24, 2024
@yukkysaito
Copy link
Contributor

@badai-nguyen Can I ask you to review this?

@badai-nguyen
Copy link
Contributor

badai-nguyen commented Jun 24, 2024

@beginningfan Thank you for your PR and raising issue.

  • Related to min_cluster_size I commented here Bugs about euclidean_cluster #7587 (comment)
  • Related to max_cluster_size, since the voxel_grid_filter was applied to downsized input pointcloud before applying euclidean_cluster filter so that the actual output cluster size after reversing the voxel_grid_filter could be bigger than cluster.indices.size(). It means that applying your proposal might over_filtering out some clusters which has actual cluster_size < max_cluster_size_. That is also the reason why min_cluster_size for pcl_euclidean_cluster_filter is set as 1 and rechecked at later stage.

Could you check the issue that you raised again, and let me known if you have further comment.

@beginningfan
Copy link
Contributor Author

@badai-nguyen thanks for your reply.
Related to min_cluster_size, I misunderstood this, so I did not modify min_cluster_size in this PR.
Related to max_cluster_size, I understand your approach. I first allocate space according to the downsized cluster size, and then resize it if there is insufficient space when push_back. Because mostly we cannot determine the maximum value of clusters, so we set a larger number to ensure that clusters are not lost. However, using the maximum value to allocate space will cause excessive CPU and memory usage.This method will not cause problems in previous versions.

@@ -124,6 +124,10 @@ bool VoxelGridBasedEuclideanCluster::cluster(
&temporary_clusters.at(map[index]).data[cluster_data_size],
&pointcloud_msg->data[i * point_step], point_step);
cluster_data_size += point_step;
if (cluster_data_size == temporary_clusters.at(map[index]).data.size()) {
temporary_clusters.at(map[index])
.data.resize(temporary_clusters.at(map[index]).data.size() * 2);
Copy link
Contributor

@badai-nguyen badai-nguyen Jun 26, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

using the maximum value to allocate space will cause excessive CPU and memory usage.

@beginningfan I agree with you.
However, I think decide that the max size of output cluster (cluster_data_size) to be doubled of temporary_cluster is not reasonable. (runtime_error might be occurred here for some high dense pointcloud)

Suggested change
.data.resize(temporary_clusters.at(map[index]).data.size() * 2);
.data.resize(max_cluster_size_ * point_step);

Or we can increment cluster_data_size and check it repeatedly.

    if (cluster_data_size >= temporary_clusters.at(map[index]).data.size()) {
        temporary_clusters.at(map[index]).data.resize(cluster_data_size + point_step * 10);
      }
      std::memcpy(
        &temporary_clusters.at(map[index]).data[cluster_data_size],
        &pointcloud_msg->data[i * point_step], point_step);
      cluster_data_size += point_step;
    }

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Here is a for loop that reallocates twice the space every time the space is full. When the space is full, it will twice the space again.I have tested using a ouster64, and the dense pointcloud is sometimes 50 times larger than the downsampled one. Even so, enough space can be allocated quickly.
If you use max_cluster_size_, it might as well just use the original code. If we add 10 points each time, this will result in multiple copies of the vector data.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@beginningfan I understood. I have checked and it worked well. Thank you for your improvement.

@beginningfan beginningfan added the tag:run-build-and-test-differential Mark to enable build-and-test-differential workflow. (used-by-ci) label Jun 27, 2024
Copy link

codecov bot commented Jun 27, 2024

Codecov Report

Attention: Patch coverage is 0% with 4 lines in your changes missing coverage. Please review.

Project coverage is 2.56%. Comparing base (3d849e9) to head (69483aa).
Report is 548 commits behind head on main.

Files Patch % Lines
...cluster/lib/voxel_grid_based_euclidean_cluster.cpp 0.00% 4 Missing ⚠️
Additional details and impacted files
@@            Coverage Diff             @@
##             main   #7662       +/-   ##
==========================================
- Coverage   15.09%   2.56%   -12.54%     
==========================================
  Files        1967     201     -1766     
  Lines      135941   10420   -125521     
  Branches    42122    1744    -40378     
==========================================
- Hits        20520     267    -20253     
+ Misses      92700   10097    -82603     
+ Partials    22721      56    -22665     
Flag Coverage Δ
differential 2.56% <0.00%> (?)
total ?

☔ View full report in Codecov by Sentry.
📢 Have feedback on the report? Share it here.

Copy link
Contributor

@badai-nguyen badai-nguyen left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

LGTM

Copy link

github-actions bot commented Jun 28, 2024

Thank you for contributing to the Autoware project!

🚧 If your pull request is in progress, switch it to draft mode.

Please ensure:

@beginningfan
Copy link
Contributor Author

@mitsudome-r The reviewer of this PR has approved it. Can it be merged now?

@badai-nguyen badai-nguyen merged commit 9df90bc into autowarefoundation:main Jul 1, 2024
27 of 30 checks passed
mitukou1109 pushed a commit to mitukou1109/autoware.universe that referenced this pull request Jul 2, 2024
…ion#7662)

* fix(euclidean_cluster): fix max and min cluster size

Signed-off-by: beginningfan <[email protected]>

* fix(gnss_poser): fix a typo

Signed-off-by: beginningfan <[email protected]>

* fix(euclidean_cluster): fix min cluster size

Signed-off-by: beginningfan <[email protected]>

* style(pre-commit): autofix

---------

Signed-off-by: beginningfan <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
badai-nguyen pushed a commit to tier4/autoware.universe that referenced this pull request Jul 3, 2024
…ion#7662)

* fix(euclidean_cluster): fix max and min cluster size

Signed-off-by: beginningfan <[email protected]>

* fix(gnss_poser): fix a typo

Signed-off-by: beginningfan <[email protected]>

* fix(euclidean_cluster): fix min cluster size

Signed-off-by: beginningfan <[email protected]>

* style(pre-commit): autofix

---------

Signed-off-by: beginningfan <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
badai-nguyen added a commit to tier4/autoware.universe that referenced this pull request Jul 4, 2024
…1378)

* fix(euclidean_cluster): fix euclidean cluster params (autowarefoundation#7662)

* fix(euclidean_cluster): fix max and min cluster size

Signed-off-by: beginningfan <[email protected]>

* fix(gnss_poser): fix a typo

Signed-off-by: beginningfan <[email protected]>

* fix(euclidean_cluster): fix min cluster size

Signed-off-by: beginningfan <[email protected]>

* style(pre-commit): autofix

---------

Signed-off-by: beginningfan <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>

* fix(euclidean_cluster): fix max_cluster_size bug (autowarefoundation#7734)

Signed-off-by: badai-nguyen <[email protected]>

* fix(ground_segmentation): fix bug  (autowarefoundation#7771)

---------

Signed-off-by: beginningfan <[email protected]>
Signed-off-by: badai-nguyen <[email protected]>
Co-authored-by: beginningfan <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
Co-authored-by: Shunsuke Miura <[email protected]>
palas21 pushed a commit to palas21/autoware.universe that referenced this pull request Jul 12, 2024
…ion#7662)

* fix(euclidean_cluster): fix max and min cluster size

Signed-off-by: beginningfan <[email protected]>

* fix(gnss_poser): fix a typo

Signed-off-by: beginningfan <[email protected]>

* fix(euclidean_cluster): fix min cluster size

Signed-off-by: beginningfan <[email protected]>

* style(pre-commit): autofix

---------

Signed-off-by: beginningfan <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
Signed-off-by: palas21 <[email protected]>
tby-udel pushed a commit to tby-udel/autoware.universe that referenced this pull request Jul 14, 2024
…ion#7662)

* fix(euclidean_cluster): fix max and min cluster size

Signed-off-by: beginningfan <[email protected]>

* fix(gnss_poser): fix a typo

Signed-off-by: beginningfan <[email protected]>

* fix(euclidean_cluster): fix min cluster size

Signed-off-by: beginningfan <[email protected]>

* style(pre-commit): autofix

---------

Signed-off-by: beginningfan <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
KhalilSelyan pushed a commit that referenced this pull request Jul 22, 2024
* fix(euclidean_cluster): fix max and min cluster size

Signed-off-by: beginningfan <[email protected]>

* fix(gnss_poser): fix a typo

Signed-off-by: beginningfan <[email protected]>

* fix(euclidean_cluster): fix min cluster size

Signed-off-by: beginningfan <[email protected]>

* style(pre-commit): autofix

---------

Signed-off-by: beginningfan <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
component:perception Advanced sensor data processing and environment understanding. (auto-assigned) tag:run-build-and-test-differential Mark to enable build-and-test-differential workflow. (used-by-ci)
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants