small_gicp
registration_result.hpp
Go to the documentation of this file.
1 // SPDX-FileCopyrightText: Copyright 2024 Kenji Koide
2 // SPDX-License-Identifier: MIT
3 #pragma once
4 
5 #include <Eigen/Core>
6 #include <Eigen/Geometry>
7 
8 namespace small_gicp {
9 
12  RegistrationResult(const Eigen::Isometry3d& T = Eigen::Isometry3d::Identity())
13  : T_target_source(T),
14  converged(false),
15  iterations(0),
16  num_inliers(0),
17  H(Eigen::Matrix<double, 6, 6>::Zero()),
18  b(Eigen::Matrix<double, 6, 1>::Zero()),
19  error(0.0) {}
20 
21  Eigen::Isometry3d T_target_source;
22 
23  bool converged;
24  size_t iterations;
25  size_t num_inliers;
26 
27  Eigen::Matrix<double, 6, 6> H;
28  Eigen::Matrix<double, 6, 1> b;
29  double error;
30 };
31 
32 } // namespace small_gicp
Definition: flat_container.hpp:12
Registration result.
Definition: registration_result.hpp:11
Eigen::Isometry3d T_target_source
Estimated transformation.
Definition: registration_result.hpp:21
Eigen::Matrix< double, 6, 6 > H
Final information matrix.
Definition: registration_result.hpp:27
size_t iterations
Number of optimization iterations.
Definition: registration_result.hpp:24
RegistrationResult(const Eigen::Isometry3d &T=Eigen::Isometry3d::Identity())
Definition: registration_result.hpp:12
Eigen::Matrix< double, 6, 1 > b
Final information vector.
Definition: registration_result.hpp:28
size_t num_inliers
Number of inliear points.
Definition: registration_result.hpp:25
bool converged
If the optimization converged.
Definition: registration_result.hpp:23
double error
Final error.
Definition: registration_result.hpp:29