Open3D (C++ API)  0.18.0
Loading...
Searching...
No Matches
ColoredICP.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 <memory>
12
16
17namespace open3d {
18
19namespace geometry {
20class PointCloud;
21}
22
23namespace pipelines {
24namespace registration {
25
26class RegistrationResult;
27
29public:
31
33 const override {
34 return type_;
35 };
37 double lambda_geometric = 0.968,
38 std::shared_ptr<RobustKernel> kernel = std::make_shared<L2Loss>())
39 : lambda_geometric_(lambda_geometric), kernel_(std::move(kernel)) {
40 if (lambda_geometric_ < 0 || lambda_geometric_ > 1.0) {
41 lambda_geometric_ = 0.968;
42 }
43 }
44
45public:
46 double ComputeRMSE(const geometry::PointCloud &source,
47 const geometry::PointCloud &target,
48 const CorrespondenceSet &corres) const override;
49 Eigen::Matrix4d ComputeTransformation(
50 const geometry::PointCloud &source,
51 const geometry::PointCloud &target,
52 const CorrespondenceSet &corres) const override;
53
54public:
55 double lambda_geometric_ = 0.968;
57 std::shared_ptr<RobustKernel> kernel_ = std::make_shared<L2Loss>();
58
59private:
62};
63
81 const geometry::PointCloud &source,
82 const geometry::PointCloud &target,
83 double max_distance,
84 const Eigen::Matrix4d &init = Eigen::Matrix4d::Identity(),
88
89} // namespace registration
90} // namespace pipelines
91} // 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 ComputeRMSE(const geometry::PointCloud &source, const geometry::PointCloud &target, const CorrespondenceSet &corres) const override
Definition ColoredICP.cpp:181
TransformationEstimationType GetTransformationEstimationType() const override
Definition ColoredICP.h:32
std::shared_ptr< RobustKernel > kernel_
shared_ptr to an Abstract RobustKernel that could mutate at runtime.
Definition ColoredICP.h:57
~TransformationEstimationForColoredICP() override
Definition ColoredICP.h:30
Eigen::Matrix4d ComputeTransformation(const geometry::PointCloud &source, const geometry::PointCloud &target, const CorrespondenceSet &corres) const override
Definition ColoredICP.cpp:97
TransformationEstimationForColoredICP(double lambda_geometric=0.968, std::shared_ptr< RobustKernel > kernel=std::make_shared< L2Loss >())
Definition ColoredICP.h:36
Definition TransformationEstimation.h:42
std::vector< Eigen::Vector2i > CorrespondenceSet
Definition Feature.h:25
TransformationEstimationType
Definition TransformationEstimation.h:29
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:214
Definition PinholeCameraIntrinsic.cpp:16
Definition Device.h:107