Main MRPT website > C++ reference
MRPT logo
Classes | Public Member Functions | Public Attributes

mrpt::slam::CGridMapAligner::TReturnInfo Struct Reference


Detailed Description

The ICP algorithm return information.

Definition at line 151 of file CGridMapAligner.h.

#include <mrpt/slam/CGridMapAligner.h>

List of all members.

Classes

struct  TPairPlusDistance

Public Member Functions

 TReturnInfo ()
 Initialization.

Public Attributes

size_t cbSize
 Size of the structure, do not change, it's set automatically.
float goodness
 A goodness measure for the alignment, it is a [0,1] range indicator of percentage of correspondences.
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).
CPosePDFSOGPtr 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.

CPosePDFSOGPtr sog2
CPosePDFSOGPtr sog3
CLandmarksMapPtr landmarks_map1
 The landmarks of each map (the indices of these landmarks correspond to those in "correspondences").
CLandmarksMapPtr landmarks_map2
mrpt::utils::TMatchingPairList correspondences
 All the found correspondences (not consistent).
std::vector< TPairPlusDistancecorrespondences_dists_maha
 Mahalanobis distance for each potential correspondence.
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.

Constructor & Destructor Documentation

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

Initialization.

Definition at line 155 of file CGridMapAligner.h.


Member Data Documentation

Size of the structure, do not change, it's set automatically.

Definition at line 162 of file CGridMapAligner.h.

All the found correspondences (not consistent).

Definition at line 186 of file CGridMapAligner.h.

Mahalanobis distance for each potential correspondence.

Definition at line 197 of file CGridMapAligner.h.

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

Definition at line 166 of file CGridMapAligner.h.

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

Definition at line 199 of file CGridMapAligner.h.

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

Definition at line 183 of file CGridMapAligner.h.

Definition at line 183 of file CGridMapAligner.h.

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 170 of file CGridMapAligner.h.

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 180 of file CGridMapAligner.h.

Definition at line 180 of file CGridMapAligner.h.

Definition at line 180 of file CGridMapAligner.h.




Page generated by Doxygen 1.7.1 for MRPT 0.9.4 SVN: at Mon Jan 10 23:33:19 UTC 2011