Open3D (C++ API)  0.16.0
ColoredICP.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 <memory>
31
35
36namespace open3d {
37
38namespace geometry {
39class PointCloud;
40}
41
42namespace pipelines {
43namespace registration {
44
45class RegistrationResult;
46
48public:
50
52 const override {
53 return type_;
54 };
56 double lambda_geometric = 0.968,
57 std::shared_ptr<RobustKernel> kernel = std::make_shared<L2Loss>())
58 : lambda_geometric_(lambda_geometric), kernel_(std::move(kernel)) {
59 if (lambda_geometric_ < 0 || lambda_geometric_ > 1.0) {
60 lambda_geometric_ = 0.968;
61 }
62 }
63
64public:
65 double ComputeRMSE(const geometry::PointCloud &source,
66 const geometry::PointCloud &target,
67 const CorrespondenceSet &corres) const override;
68 Eigen::Matrix4d ComputeTransformation(
69 const geometry::PointCloud &source,
70 const geometry::PointCloud &target,
71 const CorrespondenceSet &corres) const override;
72
73public:
74 double lambda_geometric_ = 0.968;
76 std::shared_ptr<RobustKernel> kernel_ = std::make_shared<L2Loss>();
77
78private:
81};
82
100 const geometry::PointCloud &source,
101 const geometry::PointCloud &target,
102 double max_distance,
103 const Eigen::Matrix4d &init = Eigen::Matrix4d::Identity(),
104 const TransformationEstimationForColoredICP &estimation =
107
108} // namespace registration
109} // namespace pipelines
110} // namespace open3d
A point cloud consists of point coordinates, and optionally point colors and point normals.
Definition: PointCloud.h:55
Class that defines the convergence criteria of ICP.
Definition: Registration.h:55
double ComputeRMSE(const geometry::PointCloud &source, const geometry::PointCloud &target, const CorrespondenceSet &corres) const override
Definition: ColoredICP.cpp:200
TransformationEstimationType GetTransformationEstimationType() const override
Definition: ColoredICP.h:51
std::shared_ptr< RobustKernel > kernel_
shared_ptr to an Abstract RobustKernel that could mutate at runtime.
Definition: ColoredICP.h:76
~TransformationEstimationForColoredICP() override
Definition: ColoredICP.h:49
Eigen::Matrix4d ComputeTransformation(const geometry::PointCloud &source, const geometry::PointCloud &target, const CorrespondenceSet &corres) const override
Definition: ColoredICP.cpp:116
TransformationEstimationForColoredICP(double lambda_geometric=0.968, std::shared_ptr< RobustKernel > kernel=std::make_shared< L2Loss >())
Definition: ColoredICP.h:55
Definition: TransformationEstimation.h:61
TransformationEstimationType
Definition: TransformationEstimation.h:48
std::vector< Eigen::Vector2i > CorrespondenceSet
Definition: TransformationEstimation.h:46
RegistrationResult RegistrationColoredICP(const geometry::PointCloud &source, const geometry::PointCloud &target, double max_distance, const Eigen::Matrix4d &init, const TransformationEstimationForColoredICP &estimation, const ICPConvergenceCriteria &criteria)
Function for Colored ICP registration.
Definition: ColoredICP.cpp:233
Definition: PinholeCameraIntrinsic.cpp:35
Definition: Device.h:126