Open3D (C++ API)
Registration.h
Go to the documentation of this file.
1 // ----------------------------------------------------------------------------
2 // - Open3D: www.open3d.org -
3 // ----------------------------------------------------------------------------
4 // The MIT License (MIT)
5 //
6 // Copyright (c) 2018 www.open3d.org
7 //
8 // Permission is hereby granted, free of charge, to any person obtaining a copy
9 // of this software and associated documentation files (the "Software"), to deal
10 // in the Software without restriction, including without limitation the rights
11 // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
12 // copies of the Software, and to permit persons to whom the Software is
13 // furnished to do so, subject to the following conditions:
14 //
15 // The above copyright notice and this permission notice shall be included in
16 // all copies or substantial portions of the Software.
17 //
18 // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
19 // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
20 // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
21 // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
22 // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
23 // FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
24 // IN THE SOFTWARE.
25 // ----------------------------------------------------------------------------
26 
27 #pragma once
28 
29 #include <Eigen/Core>
30 #include <tuple>
31 #include <vector>
32 
35 #include "Open3D/Utility/Eigen.h"
36 
37 namespace open3d {
38 
39 namespace geometry {
40 class PointCloud;
41 }
42 
43 namespace registration {
44 class Feature;
45 
54 public:
62  ICPConvergenceCriteria(double relative_fitness = 1e-6,
63  double relative_rmse = 1e-6,
64  int max_iteration = 30)
65  : relative_fitness_(relative_fitness),
66  relative_rmse_(relative_rmse),
67  max_iteration_(max_iteration) {}
69 
70 public:
79 };
80 
91 public:
97  RANSACConvergenceCriteria(int max_iteration = 1000,
98  int max_validation = 1000)
99  : max_iteration_(max_iteration), max_validation_(max_validation) {}
101 
102 public:
107 };
108 
113 public:
118  const Eigen::Matrix4d &transformation = Eigen::Matrix4d::Identity())
119  : transformation_(transformation), inlier_rmse_(0.0), fitness_(0.0) {}
121 
122 public:
128  double inlier_rmse_;
131  double fitness_;
132 };
133 
143  const geometry::PointCloud &source,
144  const geometry::PointCloud &target,
145  double max_correspondence_distance,
146  const Eigen::Matrix4d &transformation = Eigen::Matrix4d::Identity());
147 
159  const geometry::PointCloud &source,
160  const geometry::PointCloud &target,
161  double max_correspondence_distance,
162  const Eigen::Matrix4d &init = Eigen::Matrix4d::Identity(),
163  const TransformationEstimation &estimation =
165  const ICPConvergenceCriteria &criteria = ICPConvergenceCriteria());
166 
179  const geometry::PointCloud &source,
180  const geometry::PointCloud &target,
181  const CorrespondenceSet &corres,
182  double max_correspondence_distance,
183  const TransformationEstimation &estimation =
185  int ransac_n = 6,
186  const RANSACConvergenceCriteria &criteria =
188 
199  const geometry::PointCloud &source,
200  const geometry::PointCloud &target,
201  const Feature &source_feature,
202  const Feature &target_feature,
203  double max_correspondence_distance,
204  const TransformationEstimation &estimation =
206  int ransac_n = 4,
207  const std::vector<std::reference_wrapper<const CorrespondenceChecker>>
208  &checkers = {},
209  const RANSACConvergenceCriteria &criteria =
211 
218  const geometry::PointCloud &source,
219  const geometry::PointCloud &target,
220  double max_correspondence_distance,
221  const Eigen::Matrix4d &transformation);
222 
223 } // namespace registration
224 } // namespace open3d
double inlier_rmse_
RMSE of all inlier correspondences. Lower is better.
Definition: Registration.h:128
int max_validation_
Maximum times the validation has been run before the iteration stops.
Definition: Registration.h:106
RegistrationResult RegistrationICP(const geometry::PointCloud &source, const geometry::PointCloud &target, double max_correspondence_distance, const Eigen::Matrix4d &init, const TransformationEstimation &estimation, const ICPConvergenceCriteria &criteria)
Functions for ICP registration.
Definition: Registration.cpp:148
int max_iteration_
Maximum iteration before iteration stops.
Definition: Registration.h:104
Eigen::Matrix6d GetInformationMatrixFromPointClouds(const geometry::PointCloud &source, const geometry::PointCloud &target, double max_correspondence_distance, const Eigen::Matrix4d &transformation)
Definition: Registration.cpp:369
RegistrationResult EvaluateRegistration(const geometry::PointCloud &source, const geometry::PointCloud &target, double max_correspondence_distance, const Eigen::Matrix4d &transformation)
Function for evaluating registration between point clouds.
Definition: Registration.cpp:132
std::vector< Eigen::Vector2i > CorrespondenceSet
Definition: TransformationEstimation.h:42
RegistrationResult RegistrationRANSACBasedOnCorrespondence(const geometry::PointCloud &source, const geometry::PointCloud &target, const CorrespondenceSet &corres, double max_correspondence_distance, const TransformationEstimation &estimation, int ransac_n, const RANSACConvergenceCriteria &criteria)
Function for global RANSAC registration based on a given set of correspondences.
Definition: Registration.cpp:202
A point cloud consists of point coordinates, and optionally point colors and point normals...
Definition: PointCloud.h:54
CorrespondenceSet correspondence_set_
Correspondence set between source and target point cloud.
Definition: Registration.h:126
~ICPConvergenceCriteria()
Definition: Registration.h:68
RegistrationResult RegistrationRANSACBasedOnFeatureMatching(const geometry::PointCloud &source, const geometry::PointCloud &target, const Feature &source_feature, const Feature &target_feature, double max_correspondence_distance, const TransformationEstimation &estimation, int ransac_n, const std::vector< std::reference_wrapper< const CorrespondenceChecker >> &checkers, const RANSACConvergenceCriteria &criteria)
Function for global RANSAC registration based on feature matching.
Definition: Registration.cpp:245
Definition: TransformationEstimation.h:56
~RegistrationResult()
Definition: Registration.h:120
Definition: Registration.h:112
RegistrationResult(const Eigen::Matrix4d &transformation=Eigen::Matrix4d::Identity())
Parameterized Constructor.
Definition: Registration.h:117
Class that defines the convergence criteria of RANSAC.
Definition: Registration.h:90
Definition: Open3DViewer.h:29
double fitness_
Definition: Registration.h:131
double relative_rmse_
Definition: Registration.h:76
Eigen::Matrix4d_u transformation_
The estimated transformation matrix.
Definition: Registration.h:124
ICPConvergenceCriteria(double relative_fitness=1e-6, double relative_rmse=1e-6, int max_iteration=30)
Parameterized Constructor.
Definition: Registration.h:62
RANSACConvergenceCriteria(int max_iteration=1000, int max_validation=1000)
Parameterized Constructor.
Definition: Registration.h:97
~RANSACConvergenceCriteria()
Definition: Registration.h:100
Eigen::Matrix< double, 4, 4, Eigen::DontAlign > Matrix4d_u
Definition: Eigen.h:43
double relative_fitness_
Definition: Registration.h:73
int max_iteration_
Maximum iteration before iteration stops.
Definition: Registration.h:78
Definition: TransformationEstimation.h:89
Class to store featrues for registration.
Definition: Feature.h:46
Class that defines the convergence criteria of ICP.
Definition: Registration.h:53
Eigen::Matrix< double, 6, 6 > Matrix6d
Extending Eigen namespace by adding frequently used matrix type.
Definition: Eigen.h:37