<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN"> <html><head><meta http-equiv="Content-Type" content="text/html;charset=iso-8859-1"> <title>The MRPT project: mrpt::slam::CGridMapAligner Class Reference</title> <link href="doxygen.css" rel="stylesheet" type="text/css"> <link href="tabs.css" rel="stylesheet" type="text/css"> </head><body> <div align="left"><a href="http://www.mrpt.org/">Main MRPT website</a> > <b>C++ reference</b> </div> <div align="right"> <a href="index.html"><img border="0" src="mrpt_logo.png" alt="MRPT logo"></a> </div> <!-- Generated by Doxygen 1.6.2-20100208 --> <script type="text/javascript"><!-- var searchBox = new SearchBox("searchBox", "search",false,'Search'); --></script> <div class="navigation" id="top"> <div class="tabs"> <ul> <li><a href="index.html"><span>Main Page</span></a></li> <li><a href="pages.html"><span>Related Pages</span></a></li> <li><a href="namespaces.html"><span>Namespaces</span></a></li> <li class="current"><a href="annotated.html"><span>Classes</span></a></li> <li><a href="files.html"><span>Files</span></a></li> <li> <div id="MSearchBox" class="MSearchBoxInactive"> <img id="MSearchSelect" src="search/search.png" onmouseover="return searchBox.OnSearchSelectShow()" onmouseout="return searchBox.OnSearchSelectHide()" alt=""/> <input type="text" id="MSearchField" value="Search" accesskey="S" onfocus="searchBox.OnSearchFieldFocus(true)" onblur="searchBox.OnSearchFieldFocus(false)" onkeyup="searchBox.OnSearchFieldChange(event)"/> <a id="MSearchClose" href="javascript:searchBox.CloseResultsWindow()"><img id="MSearchCloseImg" border="0" src="search/close.png" alt=""/></a> </div> </li> </ul> </div> <div class="tabs"> <ul> <li><a href="annotated.html"><span>Class List</span></a></li> <li><a href="classes.html"><span>Class Index</span></a></li> <li><a href="hierarchy.html"><span>Class Hierarchy</span></a></li> <li><a href="functions.html"><span>Class Members</span></a></li> </ul> </div> <div class="navpath"><a class="el" href="namespacemrpt.html">mrpt</a>::<a class="el" href="namespacemrpt_1_1slam.html">slam</a>::<a class="el" href="classmrpt_1_1slam_1_1_c_grid_map_aligner.html">CGridMapAligner</a> </div> </div> <div class="contents"> <h1>mrpt::slam::CGridMapAligner Class Reference</h1><!-- doxytag: class="mrpt::slam::CGridMapAligner" --><!-- doxytag: inherits="mrpt::slam::CMetricMapsAlignmentAlgorithm" --> <p>A class for aligning two multi-metric maps (with an occupancy grid maps and a points map, at least) based on features extraction and matching. <a href="#_details">More...</a></p> <p><code>#include <<a class="el" href="_c_grid_map_aligner_8h_source.html">mrpt/slam/CGridMapAligner.h</a>></code></p> <div class="dynheader"> Inheritance diagram for mrpt::slam::CGridMapAligner:</div> <div class="dynsection"> <div class="center"><img src="classmrpt_1_1slam_1_1_c_grid_map_aligner__inherit__graph.png" border="0" usemap="#mrpt_1_1slam_1_1_c_grid_map_aligner_inherit__map" alt="Inheritance graph"/></div> <map name="mrpt_1_1slam_1_1_c_grid_map_aligner_inherit__map" id="mrpt_1_1slam_1_1_c_grid_map_aligner_inherit__map"> <area shape="rect" id="node2" href="classmrpt_1_1slam_1_1_c_metric_maps_alignment_algorithm.html" title="A base class for any algorithm able of maps alignment." alt="" coords="5,83,288,112"/><area shape="rect" id="node4" href="classmrpt_1_1utils_1_1_c_debug_output_capable.html" title="This base class provides a common printf-like method to send debug information to..." alt="" coords="36,5,257,35"/></map> <center><span class="legend">[<a href="graph_legend.html">legend</a>]</span></center></div> <div class="dynheader"> Collaboration diagram for mrpt::slam::CGridMapAligner:</div> <div class="dynsection"> <div class="center"><img src="classmrpt_1_1slam_1_1_c_grid_map_aligner__coll__graph.png" border="0" usemap="#mrpt_1_1slam_1_1_c_grid_map_aligner_coll__map" alt="Collaboration graph"/></div> <map name="mrpt_1_1slam_1_1_c_grid_map_aligner_coll__map" id="mrpt_1_1slam_1_1_c_grid_map_aligner_coll__map"> <area shape="rect" id="node2" href="classmrpt_1_1slam_1_1_c_metric_maps_alignment_algorithm.html" title="A base class for any algorithm able of maps alignment." alt="" coords="2808,60,3091,89"/><area shape="rect" id="node4" href="classmrpt_1_1utils_1_1_c_debug_output_capable.html" title="This base class provides a common printf-like method to send debug information to..." alt="" coords="2305,5,2527,35"/><area shape="rect" id="node6" href="classmrpt_1_1slam_1_1_c_occupancy_grid_map_feature_extractor.html" title="A class for detecting features from occupancy grid maps." alt="" coords="2792,167,3107,196"/><area shape="rect" id="node8" href="classmrpt_1_1utils_1_1_c_observer.html" title="Inherit from this class to get notified about events from any CObservable object..." alt="" coords="7,108,156,137"/><area shape="rect" id="node12" href="classmrpt_1_1utils_1_1_c_observable.html" title="Inherit from this class for those objects capable of being observed by a CObserver..." alt="" coords="671,160,833,189"/><area shape="rect" id="node21" href="classmrpt_1_1slam_1_1_c_metric_map.html" title="Declares a virtual base class for all metric maps storage classes." alt="" coords="1292,163,1455,192"/><area shape="rect" id="node19" href="classmrpt_1_1slam_1_1_c_occupancy_grid_map2_d.html" title="A class for storing an occupancy grid map." alt="" coords="1801,441,2036,471"/><area shape="rect" id="node23" href="classmrpt_1_1utils_1_1_c_serializable.html" title="The virtual base class which provides a unified interface for all persistent objects..." alt="" coords="669,261,835,291"/><area shape="rect" id="node25" href="classmrpt_1_1utils_1_1_c_object.html" title="The virtual base class of all MRPT classes with a unified RTTI system." alt="" coords="248,1313,384,1343"/><area shape="rect" id="node27" href="structmrpt_1_1utils_1_1_t_runtime_class_id.html" title="A structure that holds runtime class type information." alt="" coords="657,1361,847,1391"/><area shape="rect" id="node34" href="classmrpt_1_1slam_1_1_c_occupancy_grid_map2_d_1_1_t_likelihood_options.html" title="With this struct options are provided to the observation likelihood computation process..." alt="" coords="1197,696,1549,725"/><area shape="rect" id="node36" href="classmrpt_1_1utils_1_1_c_loadable_options.html" title="This is a virtual base class for sets of options than can be loaded from and/or saved..." alt="" coords="655,801,849,831"/><area shape="rect" id="node40" href="classmrpt_1_1slam_1_1_c_occupancy_grid_map2_d_1_1_t_insertion_options.html" title="With this struct options are provided to the observation insertion process." alt="" coords="1201,749,1545,779"/><area shape="rect" id="node62" href="classmrpt_1_1slam_1_1_c_grid_map_aligner_1_1_t_config_params.html" title="The ICP algorithm configuration data." alt="" coords="1773,855,2064,884"/><area shape="rect" id="node65" href="structmrpt_1_1vision_1_1_c_feature_extraction_1_1_t_options.html" title="The set of parameters for all the detectors & descriptor algorithms." alt="" coords="1237,1053,1509,1083"/><area shape="rect" id="node43" href="classmrpt_1_1slam_1_1_c_occupancy_grid_map2_d_1_1_t_likelihood_output.html" title="Some members of this struct will contain intermediate or output data after calling..." alt="" coords="1200,441,1547,471"/><area shape="rect" id="node49" href="structmrpt_1_1slam_1_1_c_occupancy_grid_map2_d_1_1_t_update_cells_info_change_only.html" title="An internal structure for storing data related to counting the new information apported..." alt="" coords="1165,803,1581,832"/><area shape="rect" id="node58" href="structmrpt_1_1slam_1_1_c_occupancy_grid_map2_d_1_1_t_critical_points_list.html" title="The structure used to store the set of Voronoi diagram critical points." alt="" coords="1199,388,1548,417"/><area shape="rect" id="node68" href="structmrpt_1_1vision_1_1_c_feature_extraction_1_1_t_options_1_1_t_harris_options.html" title="mrpt::vision::CFeatureExtraction::TOptions::THarrisOptions" alt="" coords="568,947,936,976"/><area shape="rect" id="node70" href="structmrpt_1_1vision_1_1_c_feature_extraction_1_1_t_options_1_1_t_b_c_d_options.html" title="mrpt::vision::CFeatureExtraction::TOptions::TBCDOptions" alt="" coords="571,1000,933,1029"/><area shape="rect" id="node72" href="structmrpt_1_1vision_1_1_c_feature_extraction_1_1_t_options_1_1_t_polar_images_options.html" title="PolarImagesOptions Options." alt="" coords="549,1053,955,1083"/><area shape="rect" id="node74" href="structmrpt_1_1vision_1_1_c_feature_extraction_1_1_t_options_1_1_t_spin_images_options.html" title="mrpt::vision::CFeatureExtraction::TOptions::TSpinImagesOptions" alt="" coords="551,1107,953,1136"/><area shape="rect" id="node76" href="structmrpt_1_1vision_1_1_c_feature_extraction_1_1_t_options_1_1_t_s_i_f_t_options.html" title="mrpt::vision::CFeatureExtraction::TOptions::TSIFTOptions" alt="" coords="571,1160,933,1189"/><area shape="rect" id="node78" href="structmrpt_1_1vision_1_1_c_feature_extraction_1_1_t_options_1_1_t_f_a_s_t_options.html" title="mrpt::vision::CFeatureExtraction::TOptions::TFASTOptions" alt="" coords="569,1213,935,1243"/><area shape="rect" id="node80" href="structmrpt_1_1vision_1_1_c_feature_extraction_1_1_t_options_1_1_t_k_l_t_options.html" title="mrpt::vision::CFeatureExtraction::TOptions::TKLTOptions" alt="" coords="573,1267,931,1296"/><area shape="rect" id="node82" href="structmrpt_1_1vision_1_1_c_feature_extraction_1_1_t_options_1_1_t_s_u_r_f_options.html" title="mrpt::vision::CFeatureExtraction::TOptions::TSURFOptions" alt="" coords="567,1415,937,1444"/><area shape="rect" id="node84" href="structmrpt_1_1vision_1_1_c_feature_extraction_1_1_t_options_1_1_t_log_polar_images_options.html" title="LogPolarImagesOptions Options." alt="" coords="539,893,965,923"/></map> <center><span class="legend">[<a href="graph_legend.html">legend</a>]</span></center></div> <p><a href="classmrpt_1_1slam_1_1_c_grid_map_aligner-members.html">List of all members.</a></p> <table border="0" cellpadding="0" cellspacing="0"> <tr><td colspan="2"><h2>Classes</h2></td></tr> <tr><td class="memItemLeft" align="right" valign="top">class </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_grid_map_aligner_1_1_t_config_params.html">TConfigParams</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">The ICP algorithm configuration data. <a href="classmrpt_1_1slam_1_1_c_grid_map_aligner_1_1_t_config_params.html#_details">More...</a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">struct </td><td class="memItemRight" valign="bottom"><a class="el" href="structmrpt_1_1slam_1_1_c_grid_map_aligner_1_1_t_return_info.html">TReturnInfo</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">The ICP algorithm return information. <a href="structmrpt_1_1slam_1_1_c_grid_map_aligner_1_1_t_return_info.html#_details">More...</a><br/></td></tr> <tr><td colspan="2"><h2>Public Types</h2></td></tr> <tr><td class="memItemLeft" align="right" valign="top">enum </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_grid_map_aligner.html#ac1eb308374b6e0e5d661a10b6bb3e93a">TAlignerMethod</a> { <a class="el" href="classmrpt_1_1slam_1_1_c_grid_map_aligner.html#ac1eb308374b6e0e5d661a10b6bb3e93aafc7357caa6e462972b8ab485c82567cb">amRobustMatch</a> = 0, <a class="el" href="classmrpt_1_1slam_1_1_c_grid_map_aligner.html#ac1eb308374b6e0e5d661a10b6bb3e93aa905865f9e2966076896c11940f89577f">amCorrelation</a>, <a class="el" href="classmrpt_1_1slam_1_1_c_grid_map_aligner.html#ac1eb308374b6e0e5d661a10b6bb3e93aa95be4b7301e64a3f24ddf43a26e4403e">amModifiedRANSAC</a> }</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight"><p>The type for selecting the grid-map alignment algorithm. </p> <a href="classmrpt_1_1slam_1_1_c_grid_map_aligner.html#ac1eb308374b6e0e5d661a10b6bb3e93a">More...</a><br/></td></tr> <tr><td colspan="2"><h2>Public Member Functions</h2></td></tr> <tr><td class="memItemLeft" align="right" valign="top"> </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_grid_map_aligner.html#acba7228111475f09336bba5dab9aaf26">CGridMapAligner</a> ()</td></tr> <tr><td class="memItemLeft" align="right" valign="top">CPosePDFPtr </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_grid_map_aligner.html#a40fb440cf36849f9d7f48ece9816ef73">AlignPDF</a> (const <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map.html">CMetricMap</a> *m1, const <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map.html">CMetricMap</a> *m2, const <a class="el" href="classmrpt_1_1poses_1_1_c_pose_p_d_f_gaussian.html">CPosePDFGaussian</a> &initialEstimationPDF, float *runningTime=NULL, void *info=NULL)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">The method for aligning a pair of 2D points map. <a href="#a40fb440cf36849f9d7f48ece9816ef73"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">CPose3DPDFPtr </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_grid_map_aligner.html#aa3e34e6a6e6f94965f792dd8712b75a4">Align3DPDF</a> (const <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map.html">CMetricMap</a> *m1, const <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map.html">CMetricMap</a> *m2, const <a class="el" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian.html">CPose3DPDFGaussian</a> &initialEstimationPDF, float *runningTime=NULL, void *info=NULL)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">The virtual method for aligning a pair of metric maps, aligning the full 6D pose. <a href="#aa3e34e6a6e6f94965f792dd8712b75a4"></a><br/></td></tr> <tr><td colspan="2"><h2>Public Attributes</h2></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="classmrpt_1_1slam_1_1_c_grid_map_aligner_1_1_t_config_params.html">mrpt::slam::CGridMapAligner::TConfigParams</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_grid_map_aligner.html#a851c121158237079ee2213ac34729efd">options</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">The ICP algorithm configuration data. <a href="#a851c121158237079ee2213ac34729efd"></a><br/></td></tr> <tr><td colspan="2"><h2>Private Member Functions</h2></td></tr> <tr><td class="memItemLeft" align="right" valign="top">CPosePDFPtr </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_grid_map_aligner.html#a981d48f00c82db578a7f606cc553af0a">AlignPDF_correlation</a> (const <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map.html">CMetricMap</a> *m1, const <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map.html">CMetricMap</a> *m2, const <a class="el" href="classmrpt_1_1poses_1_1_c_pose_p_d_f_gaussian.html">CPosePDFGaussian</a> &initialEstimationPDF, float *runningTime=NULL, void *info=NULL)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Private member, implements one the algorithms. <a href="#a981d48f00c82db578a7f606cc553af0a"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">CPosePDFPtr </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_grid_map_aligner.html#aa07787306274b394711c895d9a178046">AlignPDF_robustMatch</a> (const <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map.html">CMetricMap</a> *m1, const <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map.html">CMetricMap</a> *m2, const <a class="el" href="classmrpt_1_1poses_1_1_c_pose_p_d_f_gaussian.html">CPosePDFGaussian</a> &initialEstimationPDF, float *runningTime=NULL, void *info=NULL)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Private member, implements both, the "robustMatch" and the newer "modifiedRANSAC" algorithms. <a href="#aa07787306274b394711c895d9a178046"></a><br/></td></tr> <tr><td colspan="2"><h2>Private Attributes</h2></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="classmrpt_1_1slam_1_1_c_occupancy_grid_map_feature_extractor.html">COccupancyGridMapFeatureExtractor</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_grid_map_aligner.html#a93dc7aeec7634e06fb20d985715af91c">m_grid_feat_extr</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Grid map features extractor. <a href="#a93dc7aeec7634e06fb20d985715af91c"></a><br/></td></tr> </table> <hr/><a name="_details"></a><h2>Detailed Description</h2> <p>A class for aligning two multi-metric maps (with an occupancy grid maps and a points map, at least) based on features extraction and matching. </p> <p>The matching pose is returned as a Sum of Gaussians (<a class="el" href="classmrpt_1_1poses_1_1_c_pose_p_d_f_s_o_g.html" title="Declares a class that represents a Probability Density function (PDF) of a 2D pose...">poses::CPosePDFSOG</a>).</p> <p>This method was reported in the paper: <br/> </p> <p>See <a class="el" href="classmrpt_1_1slam_1_1_c_metric_maps_alignment_algorithm.html#aa6dafc1cecd79b3181dc6509f87e5d68" title="The method for aligning a pair of metric maps, aligning only 2D + orientation.">CGridMapAligner::Align</a> for more instructions.</p> <dl class="see"><dt><b>See also:</b></dt><dd><a class="el" href="classmrpt_1_1slam_1_1_c_metric_maps_alignment_algorithm.html" title="A base class for any algorithm able of maps alignment.">CMetricMapsAlignmentAlgorithm</a> </dd></dl> <p>Definition at line <a class="el" href="_c_grid_map_aligner_8h_source.html#l00056">56</a> of file <a class="el" href="_c_grid_map_aligner_8h_source.html">CGridMapAligner.h</a>.</p> <hr/><h2>Member Enumeration Documentation</h2> <a class="anchor" id="ac1eb308374b6e0e5d661a10b6bb3e93a"></a><!-- doxytag: member="mrpt::slam::CGridMapAligner::TAlignerMethod" ref="ac1eb308374b6e0e5d661a10b6bb3e93a" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">enum <a class="el" href="classmrpt_1_1slam_1_1_c_grid_map_aligner.html#ac1eb308374b6e0e5d661a10b6bb3e93a">mrpt::slam::CGridMapAligner::TAlignerMethod</a></td> </tr> </table> </div> <div class="memdoc"> <p>The type for selecting the grid-map alignment algorithm. </p> <dl><dt><b>Enumerator: </b></dt><dd><table border="0" cellspacing="2" cellpadding="0"> <tr><td valign="top"><em><a class="anchor" id="ac1eb308374b6e0e5d661a10b6bb3e93aafc7357caa6e462972b8ab485c82567cb"></a><!-- doxytag: member="amRobustMatch" ref="ac1eb308374b6e0e5d661a10b6bb3e93aafc7357caa6e462972b8ab485c82567cb" args="" -->amRobustMatch</em> </td><td> </td></tr> <tr><td valign="top"><em><a class="anchor" id="ac1eb308374b6e0e5d661a10b6bb3e93aa905865f9e2966076896c11940f89577f"></a><!-- doxytag: member="amCorrelation" ref="ac1eb308374b6e0e5d661a10b6bb3e93aa905865f9e2966076896c11940f89577f" args="" -->amCorrelation</em> </td><td> </td></tr> <tr><td valign="top"><em><a class="anchor" id="ac1eb308374b6e0e5d661a10b6bb3e93aa95be4b7301e64a3f24ddf43a26e4403e"></a><!-- doxytag: member="amModifiedRANSAC" ref="ac1eb308374b6e0e5d661a10b6bb3e93aa95be4b7301e64a3f24ddf43a26e4403e" args="" -->amModifiedRANSAC</em> </td><td> </td></tr> </table> </dd> </dl> <p>Definition at line <a class="el" href="_c_grid_map_aligner_8h_source.html#l00086">86</a> of file <a class="el" href="_c_grid_map_aligner_8h_source.html">CGridMapAligner.h</a>.</p> </div> </div> <hr/><h2>Constructor & Destructor Documentation</h2> <a class="anchor" id="acba7228111475f09336bba5dab9aaf26"></a><!-- doxytag: member="mrpt::slam::CGridMapAligner::CGridMapAligner" ref="acba7228111475f09336bba5dab9aaf26" args="()" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">mrpt::slam::CGridMapAligner::CGridMapAligner </td> <td>(</td> <td class="paramname"></td> <td> ) </td> <td><code> [inline]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Definition at line <a class="el" href="_c_grid_map_aligner_8h_source.html#l00080">80</a> of file <a class="el" href="_c_grid_map_aligner_8h_source.html">CGridMapAligner.h</a>.</p> </div> </div> <hr/><h2>Member Function Documentation</h2> <a class="anchor" id="aa3e34e6a6e6f94965f792dd8712b75a4"></a><!-- doxytag: member="mrpt::slam::CGridMapAligner::Align3DPDF" ref="aa3e34e6a6e6f94965f792dd8712b75a4" args="(const CMetricMap *m1, const CMetricMap *m2, const CPose3DPDFGaussian &initialEstimationPDF, float *runningTime=NULL, void *info=NULL)" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">CPose3DPDFPtr mrpt::slam::CGridMapAligner::Align3DPDF </td> <td>(</td> <td class="paramtype">const <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map.html">CMetricMap</a> * </td> <td class="paramname"> <em>m1</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map.html">CMetricMap</a> * </td> <td class="paramname"> <em>m2</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const <a class="el" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian.html">CPose3DPDFGaussian</a> & </td> <td class="paramname"> <em>initialEstimationPDF</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">float * </td> <td class="paramname"> <em>runningTime</em> = <code>NULL</code>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">void * </td> <td class="paramname"> <em>info</em> = <code>NULL</code></td><td> </td> </tr> <tr> <td></td> <td>)</td> <td></td><td></td><td><code> [inline, virtual]</code></td> </tr> </table> </div> <div class="memdoc"> <p>The virtual method for aligning a pair of metric maps, aligning the full 6D pose. </p> <p>The meaning of some parameters are implementation dependant, so look at the derived classes for more details. The goal is to find a PDF for the pose displacement between maps, that is, <b>the pose of m2 relative to m1</b>. This pose is returned as a PDF rather than a single value.</p> <dl class="note"><dt><b>Note:</b></dt><dd>This method can be configurated with a "options" structure in the implementation classes.</dd></dl> <dl><dt><b>Parameters:</b></dt><dd> <table border="0" cellspacing="2" cellpadding="0"> <tr><td valign="top"></td><td valign="top"><em>m1</em> </td><td>[IN] The first map (MUST BE A <a class="el" href="classmrpt_1_1slam_1_1_c_occupancy_grid_map2_d.html" title="A class for storing an occupancy grid map.">COccupancyGridMap2D</a> derived class) </td></tr> <tr><td valign="top"></td><td valign="top"><em>m2</em> </td><td>[IN] The second map. (MUST BE A <a class="el" href="classmrpt_1_1slam_1_1_c_points_map.html" title="A cloud of points in 2D or 3D, which can be built from a sequence of laser scans...">CPointsMap</a> derived class) The pose of this map respect to m1 is to be estimated. </td></tr> <tr><td valign="top"></td><td valign="top"><em>initialEstimationPDF</em> </td><td>[IN] An initial gross estimation for the displacement. </td></tr> <tr><td valign="top"></td><td valign="top"><em>runningTime</em> </td><td>[OUT] A pointer to a container for obtaining the algorithm running time in seconds, or NULL if you don't need it. </td></tr> <tr><td valign="top"></td><td valign="top"><em>info</em> </td><td>[OUT] See derived classes for details, or NULL if it isn't needed.</td></tr> </table> </dd> </dl> <dl class="return"><dt><b>Returns:</b></dt><dd>A smart pointer to the output estimated pose PDF. </dd></dl> <dl class="see"><dt><b>See also:</b></dt><dd><a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p.html" title="Several implementations of ICP (Iterative closest point) algorithms for aligning...">CICP</a> </dd></dl> <p>Implements <a class="el" href="classmrpt_1_1slam_1_1_c_metric_maps_alignment_algorithm.html#a017eed60f3088264f504f90856dfd77b">mrpt::slam::CMetricMapsAlignmentAlgorithm</a>.</p> <p>Definition at line <a class="el" href="_c_grid_map_aligner_8h_source.html#l00251">251</a> of file <a class="el" href="_c_grid_map_aligner_8h_source.html">CGridMapAligner.h</a>.</p> <p>References <a class="el" href="utils__defs_8h_source.html#l00237">THROW_EXCEPTION</a>.</p> </div> </div> <a class="anchor" id="a40fb440cf36849f9d7f48ece9816ef73"></a><!-- doxytag: member="mrpt::slam::CGridMapAligner::AlignPDF" ref="a40fb440cf36849f9d7f48ece9816ef73" args="(const CMetricMap *m1, const CMetricMap *m2, const CPosePDFGaussian &initialEstimationPDF, float *runningTime=NULL, void *info=NULL)" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">CPosePDFPtr mrpt::slam::CGridMapAligner::AlignPDF </td> <td>(</td> <td class="paramtype">const <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map.html">CMetricMap</a> * </td> <td class="paramname"> <em>m1</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map.html">CMetricMap</a> * </td> <td class="paramname"> <em>m2</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const <a class="el" href="classmrpt_1_1poses_1_1_c_pose_p_d_f_gaussian.html">CPosePDFGaussian</a> & </td> <td class="paramname"> <em>initialEstimationPDF</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">float * </td> <td class="paramname"> <em>runningTime</em> = <code>NULL</code>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">void * </td> <td class="paramname"> <em>info</em> = <code>NULL</code></td><td> </td> </tr> <tr> <td></td> <td>)</td> <td></td><td></td><td><code> [virtual]</code></td> </tr> </table> </div> <div class="memdoc"> <p>The method for aligning a pair of 2D points map. </p> <p>The meaning of some parameters are implementation dependant, so look for derived classes for instructions. The target is to find a PDF for the pose displacement between maps, thus <b>the pose of m2 relative to m1</b>. This pose is returned as a PDF rather than a single value.</p> <p>NOTE: This method can be configurated with "options"</p> <dl><dt><b>Parameters:</b></dt><dd> <table border="0" cellspacing="2" cellpadding="0"> <tr><td valign="top"></td><td valign="top"><em>m1</em> </td><td>[IN] The first map (Must be a <a class="el" href="classmrpt_1_1slam_1_1_c_multi_metric_map.html" title="This class stores any customizable set of metric maps.">mrpt::slam::CMultiMetricMap</a> class) </td></tr> <tr><td valign="top"></td><td valign="top"><em>m2</em> </td><td>[IN] The second map (Must be a <a class="el" href="classmrpt_1_1slam_1_1_c_multi_metric_map.html" title="This class stores any customizable set of metric maps.">mrpt::slam::CMultiMetricMap</a> class) </td></tr> <tr><td valign="top"></td><td valign="top"><em>initialEstimationPDF</em> </td><td>[IN] (IGNORED IN THIS ALGORITHM!) </td></tr> <tr><td valign="top"></td><td valign="top"><em>runningTime</em> </td><td>[OUT] A pointer to a container for obtaining the algorithm running time in seconds, or NULL if you don't need it. </td></tr> <tr><td valign="top"></td><td valign="top"><em>info</em> </td><td>[OUT] A pointer to a CAlignerFromMotionDraws::TReturnInfo struct, or NULL if result information are not required.</td></tr> </table> </dd> </dl> <dl class="note"><dt><b>Note:</b></dt><dd>The returned PDF depends on the selected alignment method:<ul> <li>"amRobustMatch" --> A "poses::CPosePDFSOG" object.</li> <li>"amCorrelation" --> A "poses::CPosePDFGrid" object.</li> </ul> </dd></dl> <dl class="return"><dt><b>Returns:</b></dt><dd>A smart pointer to the output estimated pose PDF. </dd></dl> <dl class="see"><dt><b>See also:</b></dt><dd>CPointsMapAlignmentAlgorithm, <a class="el" href="classmrpt_1_1slam_1_1_c_grid_map_aligner.html#a851c121158237079ee2213ac34729efd" title="The ICP algorithm configuration data.">options</a> </dd></dl> <p>Implements <a class="el" href="classmrpt_1_1slam_1_1_c_metric_maps_alignment_algorithm.html#add1ed631acbf0a3b4a6087fa24da9bd6">mrpt::slam::CMetricMapsAlignmentAlgorithm</a>.</p> </div> </div> <a class="anchor" id="a981d48f00c82db578a7f606cc553af0a"></a><!-- doxytag: member="mrpt::slam::CGridMapAligner::AlignPDF_correlation" ref="a981d48f00c82db578a7f606cc553af0a" args="(const CMetricMap *m1, const CMetricMap *m2, const CPosePDFGaussian &initialEstimationPDF, float *runningTime=NULL, void *info=NULL)" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">CPosePDFPtr mrpt::slam::CGridMapAligner::AlignPDF_correlation </td> <td>(</td> <td class="paramtype">const <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map.html">CMetricMap</a> * </td> <td class="paramname"> <em>m1</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map.html">CMetricMap</a> * </td> <td class="paramname"> <em>m2</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const <a class="el" href="classmrpt_1_1poses_1_1_c_pose_p_d_f_gaussian.html">CPosePDFGaussian</a> & </td> <td class="paramname"> <em>initialEstimationPDF</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">float * </td> <td class="paramname"> <em>runningTime</em> = <code>NULL</code>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">void * </td> <td class="paramname"> <em>info</em> = <code>NULL</code></td><td> </td> </tr> <tr> <td></td> <td>)</td> <td></td><td></td><td><code> [private]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Private member, implements one the algorithms. </p> </div> </div> <a class="anchor" id="aa07787306274b394711c895d9a178046"></a><!-- doxytag: member="mrpt::slam::CGridMapAligner::AlignPDF_robustMatch" ref="aa07787306274b394711c895d9a178046" args="(const CMetricMap *m1, const CMetricMap *m2, const CPosePDFGaussian &initialEstimationPDF, float *runningTime=NULL, void *info=NULL)" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">CPosePDFPtr mrpt::slam::CGridMapAligner::AlignPDF_robustMatch </td> <td>(</td> <td class="paramtype">const <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map.html">CMetricMap</a> * </td> <td class="paramname"> <em>m1</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map.html">CMetricMap</a> * </td> <td class="paramname"> <em>m2</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const <a class="el" href="classmrpt_1_1poses_1_1_c_pose_p_d_f_gaussian.html">CPosePDFGaussian</a> & </td> <td class="paramname"> <em>initialEstimationPDF</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">float * </td> <td class="paramname"> <em>runningTime</em> = <code>NULL</code>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">void * </td> <td class="paramname"> <em>info</em> = <code>NULL</code></td><td> </td> </tr> <tr> <td></td> <td>)</td> <td></td><td></td><td><code> [private]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Private member, implements both, the "robustMatch" and the newer "modifiedRANSAC" algorithms. </p> </div> </div> <hr/><h2>Member Data Documentation</h2> <a class="anchor" id="a93dc7aeec7634e06fb20d985715af91c"></a><!-- doxytag: member="mrpt::slam::CGridMapAligner::m_grid_feat_extr" ref="a93dc7aeec7634e06fb20d985715af91c" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname"><a class="el" href="classmrpt_1_1slam_1_1_c_occupancy_grid_map_feature_extractor.html">COccupancyGridMapFeatureExtractor</a> <a class="el" href="classmrpt_1_1slam_1_1_c_grid_map_aligner.html#a93dc7aeec7634e06fb20d985715af91c">mrpt::slam::CGridMapAligner::m_grid_feat_extr</a><code> [private]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Grid map features extractor. </p> <p>Definition at line <a class="el" href="_c_grid_map_aligner_8h_source.html#l00077">77</a> of file <a class="el" href="_c_grid_map_aligner_8h_source.html">CGridMapAligner.h</a>.</p> </div> </div> <a class="anchor" id="a851c121158237079ee2213ac34729efd"></a><!-- doxytag: member="mrpt::slam::CGridMapAligner::options" ref="a851c121158237079ee2213ac34729efd" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname"> <a class="el" href="classmrpt_1_1slam_1_1_c_grid_map_aligner_1_1_t_config_params.html">mrpt::slam::CGridMapAligner::TConfigParams</a> <a class="el" href="classmrpt_1_1slam_1_1_c_grid_map_aligner.html#a851c121158237079ee2213ac34729efd">mrpt::slam::CGridMapAligner::options</a></td> </tr> </table> </div> <div class="memdoc"> <p>The ICP algorithm configuration data. </p> </div> </div> </div> <!--- window showing the filter options --> <div id="MSearchSelectWindow" onmouseover="return searchBox.OnSearchSelectShow()" onmouseout="return searchBox.OnSearchSelectHide()" onkeydown="return searchBox.OnSearchSelectKey(event)"> <a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(0)"><span class="SelectionMark"> </span>All</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(1)"><span class="SelectionMark"> </span>Classes</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(2)"><span class="SelectionMark"> </span>Namespaces</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(3)"><span class="SelectionMark"> </span>Files</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(4)"><span class="SelectionMark"> </span>Functions</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(5)"><span class="SelectionMark"> </span>Variables</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(6)"><span class="SelectionMark"> </span>Typedefs</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(7)"><span class="SelectionMark"> </span>Enumerations</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(8)"><span class="SelectionMark"> </span>Enumerator</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(9)"><span class="SelectionMark"> </span>Friends</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(10)"><span class="SelectionMark"> </span>Defines</a></div> <!-- iframe showing the search results (closed by default) --> <div id="MSearchResultsWindow"> <iframe src="" frameborder="0" name="MSearchResults" id="MSearchResults"> </iframe> </div> <br><hr><br> <table border="0" width="100%"> <tr> <td> Page generated by <a href="http://www.doxygen.org" target="_blank">Doxygen 1.6.2-20100208</a> for MRPT 0.9.0 SVN: at Wed Jul 14 12:48:09 UTC 2010</td><td></td> <td width="100"> </td> <td width="150"> </td></tr> </table> </body></html>