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

Nacho/generalized icp #3181

Merged
merged 104 commits into from
Jul 22, 2021
Merged

Nacho/generalized icp #3181

merged 104 commits into from
Jul 22, 2021

Conversation

nachovizzo
Copy link
Contributor

@nachovizzo nachovizzo commented Mar 17, 2021

Generalized ICP

This PR brings the power of gicp to Open3D.

Experiments

KITTI benchmark, Sequence 00

  • AVG runtime multicore: 14fps
  • Other open-source implementations like fast_gicp achieve no more than 7/8 fps on the same computer.

Sequence 00

experiment

Method Implementation avg. translational error avg. rotational error
gicp Open3D 1.16 0.561
gicp KAIST/fast-gicp 1.26 0.595
PointToPoint ICP Open3D 3.18 1.24
PointToPlane ICP Open3D 5.74 1.74

I also did some other experiments on different sequences that I will omit to
save space on this PR description.

Footnote

I'd like to create a more precise tutorial. The problem is I ran out of time and I can't contribute any more to this implementation(although I wish I had more time!).

I'm more than happy to review and comment if anyone from the Open3D community or wants to extend this Pull Request.

From my point of view, some stuff that needs to be addressed in future changes are:

  • Add propper unit-tests (the transformation used in PointCloud.Transform test is not even in homogenous coordinates)
  • Implement the 4 DISABLED unit tests, related to GeneralizedICP and EstimateCovariances
  • Extend the PointCloud examples showing the use case of the new data member pcd.covariances_
  • Improve the tutorial on generalized ICP. So far, it's now a toy example but not even the underlying math of the method is explained in the tutorial.

I'm sorry but this is the best I can do with my available free time.

Old PR

I have created a deprecated PR: #2521 but there was some discussion in there


This change is Reviewable

Ideally one could also add a robust kernel in this step.
This extends PR isl-org#2425
After changing how we compute the Jacbonians API
This finally works!
No time to deal with API changes, will fix this later
@review-notebook-app
Copy link

Check out this pull request on  ReviewNB

See visual diffs & provide feedback on Jupyter Notebooks.


Powered by ReviewNB

@theNded theNded self-requested a review March 26, 2021 15:20
Copy link
Contributor

@theNded theNded left a comment

Choose a reason for hiding this comment

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

Reviewed 20 of 22 files at r1, 2 of 2 files at r2.
Reviewable status: all files reviewed, 2 unresolved discussions (waiting on @nachovizzo)


cpp/open3d/geometry/PointCloud.h, line 99 at r2 (raw file):

    /// Returns 'true' if the point cloud contains per-point covariance matrix.
    bool HasCovariances() const {
        return !points_.empty() && covariances_.size() == points_.size();

One potential change could be inheriting PointCloud in a specific context in the pipelines: https://github.com/intel-isl/Open3D/blob/master/cpp/open3d/pipelines/registration/ColoredICP.cpp#L45
The same applies to other extensions.
The current implementation looks fine though, as it couples with normal estimation.


cpp/open3d/pipelines/registration/GeneralizedICP.cpp, line 134 at r2 (raw file):

                const Eigen::Matrix3d &Ct = target.covariances_[corres[i][1]];
                const Eigen::Vector3d d = vs - vt;
                const Eigen::Matrix3d M = Ct + Cs;

You have mentioned that Ct + T @ Cs @ T.T was not implemented. Is it still the case? If so, please add a TODO line and leave it as a future work.

Copy link
Contributor Author

@nachovizzo nachovizzo left a comment

Choose a reason for hiding this comment

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

Reviewable status: all files reviewed, 2 unresolved discussions (waiting on @theNded)


cpp/open3d/geometry/PointCloud.h, line 99 at r2 (raw file):

Previously, theNded (Wei Dong) wrote…

One potential change could be inheriting PointCloud in a specific context in the pipelines: https://github.com/intel-isl/Open3D/blob/master/cpp/open3d/pipelines/registration/ColoredICP.cpp#L45
The same applies to other extensions.
The current implementation looks fine though, as it couples with normal estimation.

That was the original implementation on PR #2521. But without changing the whole registration pipeline to use Geometry3D instead of PointCloud it's sort of "impossible" to efficiently implement G-ICP. The main reasons could be (just for the records)

Overall I still feel "unsafe" of adding a 4th private member to the PointCloud class, but this might also bring more flexibility for different applications.


cpp/open3d/pipelines/registration/GeneralizedICP.cpp, line 134 at r2 (raw file):

Previously, theNded (Wei Dong) wrote…

You have mentioned that Ct + T @ Cs @ T.T was not implemented. Is it still the case? If so, please add a TODO line and leave it as a future work.

It used to be like that, but since now the covariance is a private member of the PointCloud when you hit this line https://github.com/intel-isl/Open3D/blob/784cb5ef4b6ba68f39c00aca4e887d13d8be1c96/cpp/open3d/pipelines/registration/Registration.cpp#L162 then the Cs matrix will also get transformed here: https://github.com/nachovizzo/Open3D/blob/nacho/generalized_icp/cpp/open3d/geometry/Geometry3D.cpp#L164. Which is a nice outcome of the "new" implementation. That also might explain why when re-running the experiments there was a small improvement on the G-ICP approach.

PR #2521

Method Implementation avg. translational error avg. rotational error
gicp Open3D 1.18 0.568

PR #3181

Method Implementation avg. translational error avg. rotational error
gicp Open3D 1.16 0.561

Is not a big deal, but, it's better :)

Copy link
Contributor

@theNded theNded left a comment

Choose a reason for hiding this comment

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

Reviewable status: :shipit: complete! all files reviewed, all discussions resolved (waiting on @nachovizzo)

@nachovizzo
Copy link
Contributor Author

nachovizzo commented Apr 6, 2021

Reviewable status: :shipit: complete! all files reviewed, all discussions resolved (waiting on @nachovizzo)

@theNded Should I do something? It looks good to me so far.

@theNded
Copy link
Contributor

theNded commented Apr 6, 2021

Reviewable status: :shipit: complete! all files reviewed, all discussions resolved (waiting on @nachovizzo)

@theNded Should I do something? It looks good to me so far.

Looks fine for me -- I will take some time to test the entire reconstruction system before merging just in case. Thanks!

@nachovizzo
Copy link
Contributor Author

@theNded @ssheorey shall we merge this sometime? I didn't manage to find some time to improve the notebook example. One option would be to delete the notebook and move it to a ToDO list

@nachovizzo nachovizzo closed this Jul 22, 2021
@nachovizzo nachovizzo reopened this Jul 22, 2021
@theNded
Copy link
Contributor

theNded commented Jul 22, 2021

@nachovizzo Sorry I forgot about this... Let me fix it today.

@theNded theNded merged commit 7c62640 into isl-org:master Jul 22, 2021
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants