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 
51 public:
52  ICPConvergenceCriteria(double relative_fitness = 1e-6,
53  double relative_rmse = 1e-6,
54  int max_iteration = 30)
55  : relative_fitness_(relative_fitness),
56  relative_rmse_(relative_rmse),
57  max_iteration_(max_iteration) {}
59 
60 public:
64 };
65 
73 public:
74  RANSACConvergenceCriteria(int max_iteration = 1000,
75  int max_validation = 1000)
76  : max_iteration_(max_iteration), max_validation_(max_validation) {}
78 
79 public:
82 };
83 
86 public:
88  const Eigen::Matrix4d &transformation = Eigen::Matrix4d::Identity())
89  : transformation_(transformation), inlier_rmse_(0.0), fitness_(0.0) {}
91 
92 public:
95  double inlier_rmse_;
96  double fitness_;
97 };
98 
101  const geometry::PointCloud &source,
102  const geometry::PointCloud &target,
103  double max_correspondence_distance,
104  const Eigen::Matrix4d &transformation = Eigen::Matrix4d::Identity());
105 
108  const geometry::PointCloud &source,
109  const geometry::PointCloud &target,
110  double max_correspondence_distance,
111  const Eigen::Matrix4d &init = Eigen::Matrix4d::Identity(),
112  const TransformationEstimation &estimation =
114  const ICPConvergenceCriteria &criteria = ICPConvergenceCriteria());
115 
119  const geometry::PointCloud &source,
120  const geometry::PointCloud &target,
121  const CorrespondenceSet &corres,
122  double max_correspondence_distance,
123  const TransformationEstimation &estimation =
125  int ransac_n = 6,
126  const RANSACConvergenceCriteria &criteria =
128 
131  const geometry::PointCloud &source,
132  const geometry::PointCloud &target,
133  const Feature &source_feature,
134  const Feature &target_feature,
135  double max_correspondence_distance,
136  const TransformationEstimation &estimation =
138  int ransac_n = 4,
139  const std::vector<std::reference_wrapper<const CorrespondenceChecker>>
140  &checkers = {},
141  const RANSACConvergenceCriteria &criteria =
143 
146  const geometry::PointCloud &source,
147  const geometry::PointCloud &target,
148  double max_correspondence_distance,
149  const Eigen::Matrix4d &transformation);
150 
151 } // namespace registration
152 } // namespace open3d
double inlier_rmse_
Definition: Registration.h:95
int max_validation_
Definition: Registration.h:81
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:147
int max_iteration_
Definition: Registration.h:80
Eigen::Matrix6d GetInformationMatrixFromPointClouds(const geometry::PointCloud &source, const geometry::PointCloud &target, double max_correspondence_distance, const Eigen::Matrix4d &transformation)
Function for computing information matrix from transformation matrix.
Definition: Registration.cpp:374
RegistrationResult EvaluateRegistration(const geometry::PointCloud &source, const geometry::PointCloud &target, double max_correspondence_distance, const Eigen::Matrix4d &transformation)
Function for evaluation.
Definition: Registration.cpp:131
std::vector< Eigen::Vector2i > CorrespondenceSet
Definition: TransformationEstimation.h:42
Definition: PointCloud.h:49
CorrespondenceSet correspondence_set_
Definition: Registration.h:94
~ICPConvergenceCriteria()
Definition: Registration.h:58
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:242
Definition: TransformationEstimation.h:54
~RegistrationResult()
Definition: Registration.h:90
Class that contains the registration results.
Definition: Registration.h:85
RegistrationResult(const Eigen::Matrix4d &transformation=Eigen::Matrix4d::Identity())
Definition: Registration.h:87
Definition: PinholeCameraIntrinsic.cpp:34
double fitness_
Definition: Registration.h:96
double relative_rmse_
Definition: Registration.h:62
Eigen::Matrix4d_u transformation_
Definition: Registration.h:93
ICPConvergenceCriteria(double relative_fitness=1e-6, double relative_rmse=1e-6, int max_iteration=30)
Definition: Registration.h:52
RANSACConvergenceCriteria(int max_iteration=1000, int max_validation=1000)
Definition: Registration.h:74
~RANSACConvergenceCriteria()
Definition: Registration.h:77
Eigen::Matrix< double, 4, 4, Eigen::DontAlign > Matrix4d_u
Definition: Eigen.h:43
double relative_fitness_
Definition: Registration.h:61
int max_iteration_
Definition: Registration.h:63
Estimate a transformation for point to point distance.
Definition: TransformationEstimation.h:72
Definition: Feature.h:43
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)
Definition: Registration.cpp:200
Eigen::Matrix< double, 6, 6 > Matrix6d
Extending Eigen namespace by adding frequently used matrix type.
Definition: Eigen.h:37