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(autoware_image_projection_based_fusion): fix bug of fov checker in pointpainting #9637

Open
wants to merge 5 commits into
base: main
Choose a base branch
from

Conversation

technolojin
Copy link
Contributor

@technolojin technolojin commented Dec 12, 2024

Description

When the point is projected to the image space, the point is checked if the point is in the filed-of-view of corresponding camera.
It may cut unnecessary calculation of later roi matching.

However, @a-maumau found that the current implementation of loading camera parameter is done at the initialization and do not get the camera info.

    auto fx = camera_info_map_[roi_i].k.at(0); // fx = 0
    auto x0 = camera_info_map_[roi_i].k.at(2); // x0 = 0
    tan_h_[roi_i] = x0 / fx;                   // tan_h_[0] == NaN
    if (p_z <= 0.0 || p_x > (tan_h_.at(image_id) * p_z) || p_x < (-tan_h_.at(image_id) * p_z)) {
      continue;
    }
    // p_x > (tan_h_.at(image_id) * p_z) == false
    // p_x < (-tan_h_.at(image_id) * p_z) == false

Therefore the checker of the FoV was not done correctly.

This PR will not induce any logic difference.

Special thanks to @a-maumau

Related links

Parent Issue:

  • Link

How was this PR tested?

Visually confirmed that the given roi and the pointcloud class is corresponding.

Screenshot from 2024-12-12 18-19-47

Notes for reviewers

None.

Interface changes

None.

Effects on system behavior

None.

@technolojin technolojin self-assigned this Dec 12, 2024
@github-actions github-actions bot added component:perception Advanced sensor data processing and environment understanding. (auto-assigned) tag:require-cuda-build-and-test labels Dec 12, 2024
Copy link

github-actions bot commented Dec 12, 2024

Thank you for contributing to the Autoware project!

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

Please ensure:

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

codecov bot commented Dec 13, 2024

Codecov Report

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

Project coverage is 29.61%. Comparing base (2127ca8) to head (355c183).
Report is 12 commits behind head on main.

Files with missing lines Patch % Lines
...ion_based_fusion/src/pointpainting_fusion/node.cpp 0.00% 10 Missing ⚠️
Additional details and impacted files
@@            Coverage Diff             @@
##             main    #9637      +/-   ##
==========================================
+ Coverage   29.57%   29.61%   +0.03%     
==========================================
  Files        1440     1441       +1     
  Lines      108348   108370      +22     
  Branches    41384    41389       +5     
==========================================
+ Hits        32049    32089      +40     
+ Misses      73190    73169      -21     
- Partials     3109     3112       +3     
Flag Coverage Δ *Carryforward flag
differential 2.62% <0.00%> (?)
total 29.61% <ø> (+0.03%) ⬆️ Carriedforward from 849e529

*This pull request uses carry forward flags. Click here to find out more.

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

@technolojin technolojin force-pushed the fix/image-proj-fusion/out-of-camera-fov-checker branch from acd27c5 to 849e529 Compare December 13, 2024 02:52
@technolojin technolojin marked this pull request as ready for review December 13, 2024 04:50
@technolojin technolojin requested a review from a-maumau December 16, 2024 05:24
Comment on lines 355 to 356
if (projected_point.x() < fov_left_.at(image_id)) continue;
if (projected_point.x() > fov_right_.at(image_id)) continue;
Copy link
Contributor

@badai-nguyen badai-nguyen Dec 16, 2024

Choose a reason for hiding this comment

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

@technolojin Could you make some change to check fov before calcRawImageProjectedPoint function to avoid unnecessary projection calculation for points out of FOV?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

@badai-nguyen
We do not know until the lens distortion is corrected.
In the case the lens warps the view inside, the more points will be inside of FoV.
In another word, if it comes before the correction, it may miss some points on the edges.

In the case the camera model is the pinhole camera and do not have lens distortion, the previous process p_x > (tan_h_.at(image_id) * p_z) will be done in the calcRawImageProjectedPoint and it means it doubles the same process anyway.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

well... If the lens distortion is considered when the boundary is set, we may can cut some inefficient process.. let me consider it.

Copy link
Contributor Author

@technolojin technolojin Dec 16, 2024

Choose a reason for hiding this comment

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

resolved by 355c183

to check distortion effect, additional process is needed and will be implemented by following PRs

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:require-cuda-build-and-test tag:run-build-and-test-differential Mark to enable build-and-test-differential workflow. (used-by-ci)
Projects
Status: To Triage
Development

Successfully merging this pull request may close these issues.

3 participants