struct mrpt::slam::CGridMapAligner::TReturnInfo
The ICP algorithm return information.
#include <mrpt/slam/CGridMapAligner.h> struct TReturnInfo: public mrpt::slam::TMetricMapAlignmentResult { // structs struct TPairPlusDistance; // fields float goodness {0}; mrpt::poses::CPose2D noRobustEstimation; mrpt::containers::deepcopy_poly_ptr<mrpt::poses::CPosePDFSOG::Ptr> sog1; mrpt::containers::deepcopy_poly_ptr<mrpt::poses::CPosePDFSOG::Ptr> sog2; mrpt::containers::deepcopy_poly_ptr<mrpt::poses::CPosePDFSOG::Ptr> sog3; mrpt::maps::CLandmarksMap::Ptr landmarks_map1; mrpt::maps::CLandmarksMap::Ptr landmarks_map2; mrpt::tfest::TMatchingPairList correspondences; std::vector<TPairPlusDistance> correspondences_dists_maha; std::vector<double> icp_goodness_all_sog_modes; // construction TReturnInfo(); };
Fields
float goodness {0}
A goodness measure for the alignment, it is a [0,1] range indicator of percentage of correspondences.
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).
mrpt::containers::deepcopy_poly_ptr<mrpt::poses::CPosePDFSOG::Ptr> 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.
mrpt::maps::CLandmarksMap::Ptr landmarks_map1
The landmarks of each map (the indices of these landmarks correspond to those in “correspondences”)
mrpt::tfest::TMatchingPairList correspondences
All the found correspondences (not consistent)
std::vector<TPairPlusDistance> correspondences_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.