MRPT logo

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

The ICP algorithm return information. More...

#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
CMetricMap::TMatchingPairList correspondences
 All the found correspondences (not consistent).
std::vector< TPairPlusDistancecorrespondences_dists_maha
 Mahalanobis distance for each potential correspondence.


Detailed Description

The ICP algorithm return information.

Definition at line 162 of file CGridMapAligner.h.


Constructor & Destructor Documentation

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

Initialization.

Definition at line 166 of file CGridMapAligner.h.


Member Data Documentation

size_t mrpt::slam::CGridMapAligner::CGridMapAligner::TReturnInfo::cbSize

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

Definition at line 173 of file CGridMapAligner.h.

CMetricMap::TMatchingPairList mrpt::slam::CGridMapAligner::CGridMapAligner::TReturnInfo::correspondences

All the found correspondences (not consistent).

Definition at line 197 of file CGridMapAligner.h.

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

Mahalanobis distance for each potential correspondence.

Definition at line 208 of file CGridMapAligner.h.

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

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

Definition at line 177 of file CGridMapAligner.h.

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

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

Definition at line 194 of file CGridMapAligner.h.

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

Definition at line 194 of file CGridMapAligner.h.

CPose2D mrpt::slam::CGridMapAligner::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 181 of file CGridMapAligner.h.

CPosePDFSOGPtr mrpt::slam::CGridMapAligner::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 191 of file CGridMapAligner.h.

CPosePDFSOGPtr mrpt::slam::CGridMapAligner::CGridMapAligner::TReturnInfo::sog2

Definition at line 191 of file CGridMapAligner.h.

CPosePDFSOGPtr mrpt::slam::CGridMapAligner::CGridMapAligner::TReturnInfo::sog3

Definition at line 191 of file CGridMapAligner.h.




Page generated by Doxygen 1.5.8 for MRPT 0.6.5 SVN:exported at Mon Jan 12 13:00:16 UTC 2009