Open3D (C++ API)  0.17.0
Loading...
Searching...
No Matches
Registration.h
Go to the documentation of this file.
1// ----------------------------------------------------------------------------
2// - Open3D: www.open3d.org -
3// ----------------------------------------------------------------------------
4// Copyright (c) 2018-2023 www.open3d.org
5// SPDX-License-Identifier: MIT
6// ----------------------------------------------------------------------------
7
8#pragma once
9
10#include <Eigen/Core>
11#include <tuple>
12#include <vector>
13
18
19namespace open3d {
20
21namespace geometry {
22class PointCloud;
23}
24
25namespace pipelines {
26namespace registration {
27class Feature;
28
37public:
45 ICPConvergenceCriteria(double relative_fitness = 1e-6,
46 double relative_rmse = 1e-6,
47 int max_iteration = 30)
48 : relative_fitness_(relative_fitness),
49 relative_rmse_(relative_rmse),
50 max_iteration_(max_iteration) {}
52
53public:
62};
63
75public:
81 RANSACConvergenceCriteria(int max_iteration = 100000,
82 double confidence = 0.999)
83 : max_iteration_(max_iteration),
84 confidence_(std::max(std::min(confidence, 1.0), 0.0)) {}
85
87
88public:
93};
94
99public:
104 const Eigen::Matrix4d &transformation = Eigen::Matrix4d::Identity())
105 : transformation_(transformation), inlier_rmse_(0.0), fitness_(0.0) {}
107 bool IsBetterRANSACThan(const RegistrationResult &other) const {
108 return fitness_ > other.fitness_ || (fitness_ == other.fitness_ &&
109 inlier_rmse_ < other.inlier_rmse_);
110 }
111
112public:
114 Eigen::Matrix4d_u transformation_;
123 double fitness_;
124};
125
135 const geometry::PointCloud &source,
136 const geometry::PointCloud &target,
137 double max_correspondence_distance,
138 const Eigen::Matrix4d &transformation = Eigen::Matrix4d::Identity());
139
151 const geometry::PointCloud &source,
152 const geometry::PointCloud &target,
153 double max_correspondence_distance,
154 const Eigen::Matrix4d &init = Eigen::Matrix4d::Identity(),
155 const TransformationEstimation &estimation =
158
172 const geometry::PointCloud &source,
173 const geometry::PointCloud &target,
174 const CorrespondenceSet &corres,
175 double max_correspondence_distance,
176 const TransformationEstimation &estimation =
178 int ransac_n = 3,
179 const std::vector<std::reference_wrapper<const CorrespondenceChecker>>
180 &checkers = {},
181 const RANSACConvergenceCriteria &criteria =
182 RANSACConvergenceCriteria());
183
198 const geometry::PointCloud &source,
199 const geometry::PointCloud &target,
200 const Feature &source_feature,
201 const Feature &target_feature,
202 bool mutual_filter,
203 double max_correspondence_distance,
204 const TransformationEstimation &estimation =
205 TransformationEstimationPointToPoint(false),
206 int ransac_n = 3,
207 const std::vector<std::reference_wrapper<const CorrespondenceChecker>>
208 &checkers = {},
209 const RANSACConvergenceCriteria &criteria =
210 RANSACConvergenceCriteria());
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 pipelines
225} // namespace open3d
A point cloud consists of point coordinates, and optionally point colors and point normals.
Definition PointCloud.h:36
Class that defines the convergence criteria of ICP.
Definition Registration.h:36
double relative_rmse_
Definition Registration.h:59
ICPConvergenceCriteria(double relative_fitness=1e-6, double relative_rmse=1e-6, int max_iteration=30)
Parameterized Constructor.
Definition Registration.h:45
int max_iteration_
Maximum iteration before iteration stops.
Definition Registration.h:61
double relative_fitness_
Definition Registration.h:56
Class that defines the convergence criteria of RANSAC.
Definition Registration.h:74
double confidence_
Desired probability of success.
Definition Registration.h:92
RANSACConvergenceCriteria(int max_iteration=100000, double confidence=0.999)
Parameterized Constructor.
Definition Registration.h:81
int max_iteration_
Maximum iteration before iteration stops.
Definition Registration.h:90
bool IsBetterRANSACThan(const RegistrationResult &other) const
Definition Registration.h:107
RegistrationResult(const Eigen::Matrix4d &transformation=Eigen::Matrix4d::Identity())
Parameterized Constructor.
Definition Registration.h:103
CorrespondenceSet correspondence_set_
Correspondence set between source and target point cloud.
Definition Registration.h:116
~RegistrationResult()
Definition Registration.h:106
double fitness_
Definition Registration.h:123
Eigen::Matrix4d_u transformation_
The estimated transformation matrix.
Definition Registration.h:114
double inlier_rmse_
RMSE of all inlier correspondences. Lower is better.
Definition Registration.h:118
Definition TransformationEstimation.h:42
Eigen::Matrix6d GetInformationMatrixFromPointClouds(const geometry::PointCloud &source, const geometry::PointCloud &target, double max_correspondence_distance, const Eigen::Matrix4d &transformation)
Definition Registration.cpp:357
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:92
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:108
std::vector< Eigen::Vector2i > CorrespondenceSet
Definition TransformationEstimation.h:27
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:170
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:280
Definition PinholeCameraIntrinsic.cpp:16
Definition Device.h:107