Open3D (C++ API)  0.11.0
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 pipelines {
44 namespace registration {
45 class Feature;
46 
55 public:
63  ICPConvergenceCriteria(double relative_fitness = 1e-6,
64  double relative_rmse = 1e-6,
65  int max_iteration = 30)
66  : relative_fitness_(relative_fitness),
67  relative_rmse_(relative_rmse),
68  max_iteration_(max_iteration) {}
70 
71 public:
80 };
81 
92 public:
98  RANSACConvergenceCriteria(int max_iteration = 1000,
99  int max_validation = 1000)
100  : max_iteration_(max_iteration), max_validation_(max_validation) {}
102 
103 public:
108 };
109 
114 public:
119  const Eigen::Matrix4d &transformation = Eigen::Matrix4d::Identity())
120  : transformation_(transformation), inlier_rmse_(0.0), fitness_(0.0) {}
122 
123 public:
125  Eigen::Matrix4d_u transformation_;
129  double inlier_rmse_;
132  double fitness_;
133 };
134 
144  const geometry::PointCloud &source,
145  const geometry::PointCloud &target,
146  double max_correspondence_distance,
147  const Eigen::Matrix4d &transformation = Eigen::Matrix4d::Identity());
148 
160  const geometry::PointCloud &source,
161  const geometry::PointCloud &target,
162  double max_correspondence_distance,
163  const Eigen::Matrix4d &init = Eigen::Matrix4d::Identity(),
164  const TransformationEstimation &estimation =
166  const ICPConvergenceCriteria &criteria = ICPConvergenceCriteria());
167 
180  const geometry::PointCloud &source,
181  const geometry::PointCloud &target,
182  const CorrespondenceSet &corres,
183  double max_correspondence_distance,
184  const TransformationEstimation &estimation =
186  int ransac_n = 6,
187  const RANSACConvergenceCriteria &criteria =
189 
200  const geometry::PointCloud &source,
201  const geometry::PointCloud &target,
202  const Feature &source_feature,
203  const Feature &target_feature,
204  double max_correspondence_distance,
205  const TransformationEstimation &estimation =
207  int ransac_n = 4,
208  const std::vector<std::reference_wrapper<const CorrespondenceChecker>>
209  &checkers = {},
210  const RANSACConvergenceCriteria &criteria =
212 
219  const geometry::PointCloud &source,
220  const geometry::PointCloud &target,
221  double max_correspondence_distance,
222  const Eigen::Matrix4d &transformation);
223 
224 } // namespace registration
225 } // namespace pipelines
226 } // namespace open3d
Class that defines the convergence criteria of RANSAC.
Definition: Registration.h:91
int max_iteration_
Maximum iteration before iteration stops.
Definition: Registration.h:105
Class that defines the convergence criteria of ICP.
Definition: Registration.h:54
RegistrationResult(const Eigen::Matrix4d &transformation=Eigen::Matrix4d::Identity())
Parameterized Constructor.
Definition: Registration.h:118
A point cloud consists of point coordinates, and optionally point colors and point normals...
Definition: PointCloud.h:54
int max_validation_
Maximum times the validation has been run before the iteration stops.
Definition: Registration.h:107
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:190
std::vector< Eigen::Vector2i > CorrespondenceSet
Definition: TransformationEstimation.h:46
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:120
double relative_fitness_
Definition: Registration.h:74
Class to store featrues for registration.
Definition: Feature.h:47
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:233
Definition: PinholeCameraIntrinsic.cpp:35
int max_iteration_
Maximum iteration before iteration stops.
Definition: Registration.h:79
double inlier_rmse_
RMSE of all inlier correspondences. Lower is better.
Definition: Registration.h:129
~RegistrationResult()
Definition: Registration.h:121
Eigen::Matrix4d_u transformation_
The estimated transformation matrix.
Definition: Registration.h:125
ICPConvergenceCriteria(double relative_fitness=1e-6, double relative_rmse=1e-6, int max_iteration=30)
Parameterized Constructor.
Definition: Registration.h:63
RANSACConvergenceCriteria(int max_iteration=1000, int max_validation=1000)
Parameterized Constructor.
Definition: Registration.h:98
Eigen::Matrix6d GetInformationMatrixFromPointClouds(const geometry::PointCloud &source, const geometry::PointCloud &target, double max_correspondence_distance, const Eigen::Matrix4d &transformation)
Definition: Registration.cpp:345
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:136
~RANSACConvergenceCriteria()
Definition: Registration.h:101
Definition: TransformationEstimation.h:60
double relative_rmse_
Definition: Registration.h:77
~ICPConvergenceCriteria()
Definition: Registration.h:69
double fitness_
Definition: Registration.h:132
CorrespondenceSet correspondence_set_
Correspondence set between source and target point cloud.
Definition: Registration.h:127