Main MRPT website > C++ reference for MRPT 1.5.6
List of all members | Classes | Public Member Functions | Public Attributes
mrpt::slam::CGridMapAligner::TReturnInfo Struct Reference

Detailed Description

The ICP algorithm return information.

Definition at line 126 of file CGridMapAligner.h.

#include <mrpt/slam/CGridMapAligner.h>

Classes

struct  TPairPlusDistance
 

Public Member Functions

 TReturnInfo ()
 

Public Attributes

float goodness
 A goodness measure for the alignment, it is a [0,1] range indicator of percentage of correspondences. More...
 
mrpt::poses::CPose2D noRobustEstimation
 The "brute" estimation from using all the available correspondences, provided just for comparison purposes (it is not the robust estimation, available as the result of the Align method). More...
 
mrpt::utils::poly_ptr_ptr< mrpt::poses::CPosePDFSOGPtr > sog1
 The different SOG densities at different steps of the algorithm: More...
 
mrpt::utils::poly_ptr_ptr< mrpt::poses::CPosePDFSOGPtr > sog2
 
mrpt::utils::poly_ptr_ptr< mrpt::poses::CPosePDFSOGPtr > sog3
 
mrpt::maps::CLandmarksMapPtr landmarks_map1
 The landmarks of each map (the indices of these landmarks correspond to those in "correspondences") More...
 
mrpt::maps::CLandmarksMapPtr landmarks_map2
 
mrpt::utils::TMatchingPairList correspondences
 All the found correspondences (not consistent) More...
 
std::vector< TPairPlusDistancecorrespondences_dists_maha
 Mahalanobis distance for each potential correspondence. More...
 
std::vector< double > icp_goodness_all_sog_modes
 The ICP goodness of all potential SOG modes at the stage "sog2", thus before the removing of "bad" ICP matches. More...
 

Constructor & Destructor Documentation

◆ TReturnInfo()

mrpt::slam::CGridMapAligner::TReturnInfo::TReturnInfo ( )
inline

Definition at line 128 of file CGridMapAligner.h.

Member Data Documentation

◆ correspondences

mrpt::utils::TMatchingPairList mrpt::slam::CGridMapAligner::TReturnInfo::correspondences

All the found correspondences (not consistent)

Definition at line 156 of file CGridMapAligner.h.

◆ correspondences_dists_maha

std::vector<TPairPlusDistance> mrpt::slam::CGridMapAligner::TReturnInfo::correspondences_dists_maha

Mahalanobis distance for each potential correspondence.

Definition at line 167 of file CGridMapAligner.h.

◆ goodness

float mrpt::slam::CGridMapAligner::TReturnInfo::goodness

A goodness measure for the alignment, it is a [0,1] range indicator of percentage of correspondences.

Definition at line 136 of file CGridMapAligner.h.

◆ icp_goodness_all_sog_modes

std::vector<double> mrpt::slam::CGridMapAligner::TReturnInfo::icp_goodness_all_sog_modes

The ICP goodness of all potential SOG modes at the stage "sog2", thus before the removing of "bad" ICP matches.

Definition at line 169 of file CGridMapAligner.h.

◆ landmarks_map1

mrpt::maps::CLandmarksMapPtr mrpt::slam::CGridMapAligner::TReturnInfo::landmarks_map1

The landmarks of each map (the indices of these landmarks correspond to those in "correspondences")

Definition at line 153 of file CGridMapAligner.h.

◆ landmarks_map2

mrpt::maps::CLandmarksMapPtr mrpt::slam::CGridMapAligner::TReturnInfo::landmarks_map2

Definition at line 153 of file CGridMapAligner.h.

◆ noRobustEstimation

mrpt::poses::CPose2D mrpt::slam::CGridMapAligner::TReturnInfo::noRobustEstimation

The "brute" estimation from using all the available correspondences, provided just for comparison purposes (it is not the robust estimation, available as the result of the Align method).

Definition at line 140 of file CGridMapAligner.h.

◆ sog1

mrpt::utils::poly_ptr_ptr<mrpt::poses::CPosePDFSOGPtr> mrpt::slam::CGridMapAligner::TReturnInfo::sog1

The different SOG densities at different steps of the algorithm:

  • sog1 : Directly from the matching of features
  • sog2 : Merged of sog1
  • sog3 : sog2 refined with ICP
  • The final sog is the merge of sog3.

Definition at line 150 of file CGridMapAligner.h.

◆ sog2

mrpt::utils::poly_ptr_ptr<mrpt::poses::CPosePDFSOGPtr> mrpt::slam::CGridMapAligner::TReturnInfo::sog2

Definition at line 150 of file CGridMapAligner.h.

◆ sog3

mrpt::utils::poly_ptr_ptr<mrpt::poses::CPosePDFSOGPtr> mrpt::slam::CGridMapAligner::TReturnInfo::sog3

Definition at line 150 of file CGridMapAligner.h.




Page generated by Doxygen 1.8.14 for MRPT 1.5.6 Git: 4c65e8431 Tue Apr 24 08:18:17 2018 +0200 at lun oct 28 01:35:26 CET 2019