Loading [MathJax]/extensions/TeX/AMSsymbols.js
Open3D (C++ API)  0.16.0
All Data Structures Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros
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-2021 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"
37 
38 namespace open3d {
39 
40 namespace geometry {
41 class PointCloud;
42 }
43 
44 namespace pipelines {
45 namespace registration {
46 class Feature;
47 
56 public:
64  ICPConvergenceCriteria(double relative_fitness = 1e-6,
65  double relative_rmse = 1e-6,
66  int max_iteration = 30)
67  : relative_fitness_(relative_fitness),
68  relative_rmse_(relative_rmse),
69  max_iteration_(max_iteration) {}
71 
72 public:
81 };
82 
94 public:
100  RANSACConvergenceCriteria(int max_iteration = 100000,
101  double confidence = 0.999)
102  : max_iteration_(max_iteration),
103  confidence_(std::max(std::min(confidence, 1.0), 0.0)) {}
104 
106 
107 public:
111  double confidence_;
112 };
113 
118 public:
123  const Eigen::Matrix4d &transformation = Eigen::Matrix4d::Identity())
124  : transformation_(transformation), inlier_rmse_(0.0), fitness_(0.0) {}
126  bool IsBetterRANSACThan(const RegistrationResult &other) const {
127  return fitness_ > other.fitness_ || (fitness_ == other.fitness_ &&
128  inlier_rmse_ < other.inlier_rmse_);
129  }
130 
131 public:
133  Eigen::Matrix4d_u transformation_;
137  double inlier_rmse_;
142  double fitness_;
143 };
144 
154  const geometry::PointCloud &source,
155  const geometry::PointCloud &target,
156  double max_correspondence_distance,
157  const Eigen::Matrix4d &transformation = Eigen::Matrix4d::Identity());
158 
170  const geometry::PointCloud &source,
171  const geometry::PointCloud &target,
172  double max_correspondence_distance,
173  const Eigen::Matrix4d &init = Eigen::Matrix4d::Identity(),
174  const TransformationEstimation &estimation =
176  const ICPConvergenceCriteria &criteria = ICPConvergenceCriteria());
177 
191  const geometry::PointCloud &source,
192  const geometry::PointCloud &target,
193  const CorrespondenceSet &corres,
194  double max_correspondence_distance,
195  const TransformationEstimation &estimation =
197  int ransac_n = 3,
198  const std::vector<std::reference_wrapper<const CorrespondenceChecker>>
199  &checkers = {},
200  const RANSACConvergenceCriteria &criteria =
202 
217  const geometry::PointCloud &source,
218  const geometry::PointCloud &target,
219  const Feature &source_feature,
220  const Feature &target_feature,
221  bool mutual_filter,
222  double max_correspondence_distance,
223  const TransformationEstimation &estimation =
225  int ransac_n = 3,
226  const std::vector<std::reference_wrapper<const CorrespondenceChecker>>
227  &checkers = {},
228  const RANSACConvergenceCriteria &criteria =
230 
237  const geometry::PointCloud &source,
238  const geometry::PointCloud &target,
239  double max_correspondence_distance,
240  const Eigen::Matrix4d &transformation);
241 
242 } // namespace registration
243 } // namespace pipelines
244 } // namespace open3d
Class that defines the convergence criteria of RANSAC.
Definition: Registration.h:93
int max_iteration_
Maximum iteration before iteration stops.
Definition: Registration.h:109
Class that defines the convergence criteria of ICP.
Definition: Registration.h:55
RegistrationResult RegistrationRANSACBasedOnCorrespondence(const geometry::PointCloud &source, const geometry::PointCloud &target, const CorrespondenceSet &corres, 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 a given set of correspondences.
Definition: Registration.cpp:189
Definition: Device.h:126
bool IsBetterRANSACThan(const RegistrationResult &other) const
Definition: Registration.h:126
RegistrationResult(const Eigen::Matrix4d &transformation=Eigen::Matrix4d::Identity())
Parameterized Constructor.
Definition: Registration.h:122
A point cloud consists of point coordinates, and optionally point colors and point normals...
Definition: PointCloud.h:55
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:111
double relative_fitness_
Definition: Registration.h:75
Class to store featrues for registration.
Definition: Feature.h:47
RANSACConvergenceCriteria(int max_iteration=100000, double confidence=0.999)
Parameterized Constructor.
Definition: Registration.h:100
Definition: PinholeCameraIntrinsic.cpp:35
int max_iteration_
Maximum iteration before iteration stops.
Definition: Registration.h:80
double inlier_rmse_
RMSE of all inlier correspondences. Lower is better.
Definition: Registration.h:137
RegistrationResult RegistrationRANSACBasedOnFeatureMatching(const geometry::PointCloud &source, const geometry::PointCloud &target, const Feature &source_feature, const Feature &target_feature, bool mutual_filter, 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:299
~RegistrationResult()
Definition: Registration.h:125
Eigen::Matrix4d_u transformation_
The estimated transformation matrix.
Definition: Registration.h:133
ICPConvergenceCriteria(double relative_fitness=1e-6, double relative_rmse=1e-6, int max_iteration=30)
Parameterized Constructor.
Definition: Registration.h:64
Eigen::Matrix6d GetInformationMatrixFromPointClouds(const geometry::PointCloud &source, const geometry::PointCloud &target, double max_correspondence_distance, const Eigen::Matrix4d &transformation)
Definition: Registration.cpp:376
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:127
~RANSACConvergenceCriteria()
Definition: Registration.h:105
Definition: TransformationEstimation.h:61
double confidence_
Desired probability of success.
Definition: Registration.h:111
double relative_rmse_
Definition: Registration.h:78
~ICPConvergenceCriteria()
Definition: Registration.h:70
double fitness_
Definition: Registration.h:142
CorrespondenceSet correspondence_set_
Correspondence set between source and target point cloud.
Definition: Registration.h:135