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

feat: unrecify image projection based fusion #7030

Conversation

yukkysaito
Copy link
Contributor

@yukkysaito yukkysaito commented May 15, 2024

Description

Fixed this PR

In image_projection_based_fusion, only the internal parameters of the camera were considered, and no distortion correction was applied. As a result, when projecting onto images with significant distortion, misalignments occurred. This Pull Request has been modified to account for distortion.

Related links

Tests performed

In roi_cluster_fusion, operation has been confirmed on the actual machine.
before
image

after
image

Notes for reviewers

Interface changes

Effects on system behavior

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.

  • The PR follows the pull request guidelines.
  • The PR has been properly tested.
  • The PR has been reviewed by the code owners.

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.
  • The PR is ready for merge.

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

@yukkysaito yukkysaito marked this pull request as ready for review May 15, 2024 14:14
@github-actions github-actions bot added the component:perception Advanced sensor data processing and environment understanding. (auto-assigned) label May 15, 2024
Copy link
Contributor

@kminoda kminoda left a comment

Choose a reason for hiding this comment

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

Thank you for the PR 🙏


cv::Point2d raw_image_point = rectified_image_point;

try {
Copy link
Contributor

Choose a reason for hiding this comment

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

What is this try sentence for?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

The code for determining whether to unrectify in the library of image_geometry seems to change occasionally. If it can't be done, it is thrown, so I want to be able to catch it.

Copy link
Contributor

Choose a reason for hiding this comment

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

Hmm, understood. It is a difficult decision, but IMHO we should avoid catching this error and just logging warning without killing the node, since it will be difficult for developers to be aware of a breaking change or a bug in image_geometry library, increasing a risk of a potential degradation of Autoware. What do you think?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

@kminoda So, what exactly do you want to do?

Copy link
Contributor

Choose a reason for hiding this comment

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

Please see here #7030 (comment)

Copy link
Contributor Author

Choose a reason for hiding this comment

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

@kminoda This time, when d is 0 in the image_geometry class, it is determined that the image is not calibrated, and thus there is no need to unrectify, resulting in an exception being thrown. This determination of being uncalibrated seems to change frequently in the code. Even if an exception is thrown, there is no need to terminate the process since it only means that unrectifying is not possible. Wouldn't it be better to skip this with a try-catch block?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

I will close this PR as there seems to have been a misunderstanding on my part.

Comment on lines +26 to +36
try {
const bool need_unrectify = std::any_of(
pinhole_camera_model.cameraInfo().d.begin(), pinhole_camera_model.cameraInfo().d.end(),
[](double distortion) { return distortion != 0.0; });

if (need_unrectify) {
raw_image_point = pinhole_camera_model.unrectifyPoint(rectified_image_point);
}
} catch (cv::Exception & e) {
RCLCPP_WARN_STREAM(rclcpp::get_logger("image_projection_based_fusion"), e.what());
}
Copy link
Contributor

Choose a reason for hiding this comment

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

Suggested change
try {
const bool need_unrectify = std::any_of(
pinhole_camera_model.cameraInfo().d.begin(), pinhole_camera_model.cameraInfo().d.end(),
[](double distortion) { return distortion != 0.0; });
if (need_unrectify) {
raw_image_point = pinhole_camera_model.unrectifyPoint(rectified_image_point);
}
} catch (cv::Exception & e) {
RCLCPP_WARN_STREAM(rclcpp::get_logger("image_projection_based_fusion"), e.what());
}
const bool need_unrectify = std::any_of(
pinhole_camera_model.cameraInfo().d.begin(), pinhole_camera_model.cameraInfo().d.end(),
[](double distortion) { return distortion != 0.0; });
if (need_unrectify) {
raw_image_point = pinhole_camera_model.unrectifyPoint(rectified_image_point);
}

Regarding https://github.com/autowarefoundation/autoware.universe/pull/7030/files#r1604255216, here's my proposal.

@yukkysaito yukkysaito closed this May 17, 2024
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)
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants