OptimalTF_Result.h
Go to the documentation of this file.
1 /* -------------------------------------------------------------------------
2  * A repertory of multi primitive-to-primitive (MP2P) ICP algorithms in C++
3  * Copyright (C) 2018-2021 Jose Luis Blanco, University of Almeria
4  * See LICENSE for license information.
5  * ------------------------------------------------------------------------- */
12 #pragma once
13 
14 #include <mp2p_icp/Pairings.h>
15 #include <mrpt/poses/CPose3D.h>
16 
17 namespace mp2p_icp
18 {
25 {
26  mrpt::poses::CPose3D optimalPose;
27  double optimalScale = 1.0;
28 
31 };
32 
35 } // namespace mp2p_icp
mp2p_icp::OptimalTF_Result::optimalPose
mrpt::poses::CPose3D optimalPose
Definition: OptimalTF_Result.h:26
mp2p_icp
Definition: covariance.h:17
mp2p_icp::OptimalTF_Result::optimalScale
double optimalScale
Definition: OptimalTF_Result.h:27
mp2p_icp::OptimalTF_Result
Definition: OptimalTF_Result.h:24
mp2p_icp::OptimalTF_Result::outliers
OutlierIndices outliers
Definition: OptimalTF_Result.h:30
Pairings.h
Common types for all SE(3) optimal transformation methods.
mp2p_icp::OutlierIndices
Definition: Pairings.h:187


mrpt_local_obstacles
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Mon Aug 14 2023 02:09:04