Sophie

Sophie

distrib > Fedora > 15 > i386 > by-pkgid > 2f6559b7006594cad03af173263c219e > files > 4122

mrpt-doc-0.9.4-0.1.20110110svn2383.fc15.i686.rpm

<!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::CICP 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> &gt; <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.7.2 -->
<script type="text/javascript"><!--
var searchBox = new SearchBox("searchBox", "search",false,'Search');
--></script>
<div class="navigation" id="top">
  <div class="tabs">
    <ul class="tablist">
      <li><a href="index.html"><span>Main&#160;Page</span></a></li>
      <li><a href="pages.html"><span>Related&#160;Pages</span></a></li>
      <li><a href="modules.html"><span>Modules</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 id="searchli">
        <div id="MSearchBox" class="MSearchBoxInactive">
          <span class="left">
            <form id="FSearchBox" action="search.php" method="get">
              <img id="MSearchSelect" src="search/mag.png" alt=""/>
              <input type="text" id="MSearchField" name="query" value="Search" size="20" accesskey="S" 
                     onfocus="searchBox.OnSearchFieldFocus(true)" 
                     onblur="searchBox.OnSearchFieldFocus(false)"/>
            </form>
          </span><span class="right"></span>
        </div>
      </li>
    </ul>
  </div>
  <div class="tabs2">
    <ul class="tablist">
      <li><a href="annotated.html"><span>Class&#160;List</span></a></li>
      <li><a href="classes.html"><span>Class&#160;Index</span></a></li>
      <li><a href="hierarchy.html"><span>Class&#160;Hierarchy</span></a></li>
      <li><a href="functions.html"><span>Class&#160;Members</span></a></li>
    </ul>
  </div>
  <div class="navpath">
    <ul>
      <li><a class="el" href="namespacemrpt.html">mrpt</a>      </li>
      <li><a class="el" href="namespacemrpt_1_1slam.html">slam</a>      </li>
      <li><a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p.html">CICP</a>      </li>
    </ul>
  </div>
</div>
<div class="header">
  <div class="summary">
<a href="#nested-classes">Classes</a> &#124;
<a href="#pub-methods">Public Member Functions</a> &#124;
<a href="#pub-attribs">Public Attributes</a> &#124;
<a href="#pro-methods">Protected Member Functions</a>  </div>
  <div class="headertitle">
<h1>mrpt::slam::CICP Class Reference</h1>  </div>
</div>
<div class="contents">
<!-- doxytag: class="mrpt::slam::CICP" --><!-- doxytag: inherits="mrpt::slam::CMetricMapsAlignmentAlgorithm" --><hr/><a name="_details"></a><h2>Detailed Description</h2>
<p>Several implementations of ICP (Iterative closest point) algorithms for aligning two point maps. </p>
<p>See <a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p.html#a73a709e50ebe5c8c3c63c9f2b0e49140" title="An implementation of CMetricMapsAlignmentAlgorithm for the case of a point maps and a occupancy grid/...">CICP::AlignPDF</a> for the entry point of the algorithm, and <a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p_1_1_t_config_params.html" title="The ICP algorithm configuration data.">CICP::TConfigParams</a> for all the parameters to the method. The algorithm has been exteneded with multihypotheses-support for the correspondences, which generates a Sum-of-Gaussians (SOG) PDF as output. See <a class="el" href="namespacemrpt_1_1scanmatching.html#a1714c0f5d66a47509926ffdbfcd261d6" title="This method implements a RANSAC-based robust estimation of the rigid transformation between two plane...">scanmatching::robustRigidTransformation</a>.</p>
<p>For further details on the method, check the wiki: <a href="http://www.mrpt.org/Scan_Matching_Algorithms">http://www.mrpt.org/Scan_Matching_Algorithms</a></p>
<p>For a paper explaining the used equations, see for example: J. Martinez, J. Gonzalez, J. Morales, A. Mandow, A. Garcia-Cerezo, "Genetic and ICP Laser Point Matching for 2D Mobile Robot Motion Estimation", Journal of Field Robotics, vol. 23, no. 1, 2006. ( <a href="http://babel.isa.uma.es/~jlblanco/papers/martinez2006gil.pdf">http://babel.isa.uma.es/~jlblanco/papers/martinez2006gil.pdf</a> )</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_i_c_p_8h_source.html#l00066">66</a> of file <a class="el" href="_c_i_c_p_8h_source.html">CICP.h</a>.</p>

<p><code>#include &lt;<a class="el" href="_c_i_c_p_8h_source.html">mrpt/slam/CICP.h</a>&gt;</code></p>
<!-- startSectionHeader --><div class="dynheader">
Inheritance diagram for mrpt::slam::CICP:<!-- endSectionHeader --></div>
<!-- startSectionSummary --><!-- endSectionSummary --><!-- startSectionContent --><div class="dyncontent">
<div class="center"><img src="classmrpt_1_1slam_1_1_c_i_c_p__inherit__graph.png" border="0" usemap="#mrpt_1_1slam_1_1_c_i_c_p_inherit__map" alt="Inheritance graph"/></div>
<map name="mrpt_1_1slam_1_1_c_i_c_p_inherit__map" id="mrpt_1_1slam_1_1_c_i_c_p_inherit__map">
</map>
<center><span class="legend">[<a href="graph_legend.html">legend</a>]</span></center><!-- endSectionContent --></div>

<p><a href="classmrpt_1_1slam_1_1_c_i_c_p-members.html">List of all members.</a></p>
<table class="memberdecls">
<tr><td colspan="2"><h2><a name="nested-classes"></a>
Classes</h2></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">class &#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p_1_1_t_config_params.html">TConfigParams</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The ICP algorithm configuration data.  <a href="classmrpt_1_1slam_1_1_c_i_c_p_1_1_t_config_params.html#_details">More...</a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">struct &#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="structmrpt_1_1slam_1_1_c_i_c_p_1_1_t_return_info.html">TReturnInfo</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The ICP algorithm return information.  <a href="structmrpt_1_1slam_1_1_c_i_c_p_1_1_t_return_info.html#_details">More...</a><br/></td></tr>
<tr><td colspan="2"><h2><a name="pub-methods"></a>
Public Member Functions</h2></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p.html#a03c787f3328250801118933dbc9d97dd">CICP</a> ()</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Constructor with the default options.  <a href="#a03c787f3328250801118933dbc9d97dd"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p.html#a90f68da0ac5ccafa22850691a59bcc49">CICP</a> (const <a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p_1_1_t_config_params.html">TConfigParams</a> &amp;icpParams)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Constructor that directly set the ICP params from a given struct.  <a href="#a90f68da0ac5ccafa22850691a59bcc49"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">virtual&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p.html#a9c69682c870276c32f204e44218b3e56">~CICP</a> ()</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Destructor.  <a href="#a9c69682c870276c32f204e44218b3e56"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="structmrpt_1_1poses_1_1_c_pose_p_d_f_ptr.html">CPosePDFPtr</a>&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p.html#a73a709e50ebe5c8c3c63c9f2b0e49140">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> &amp;initialEstimationPDF, float *runningTime=NULL, void *info=NULL)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">An implementation of <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> for the case of a point maps and a occupancy grid/point map.  <a href="#a73a709e50ebe5c8c3c63c9f2b0e49140"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="structmrpt_1_1poses_1_1_c_pose3_d_p_d_f_ptr.html">CPose3DPDFPtr</a>&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p.html#af6dd4e59ce84dfe62b6597021d78edde">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> &amp;initialEstimationPDF, float *runningTime=NULL, void *info=NULL)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Align a pair of metric maps, aligning the full 6D pose.  <a href="#af6dd4e59ce84dfe62b6597021d78edde"></a><br/></td></tr>
<tr><td colspan="2"><h2><a name="pub-attribs"></a>
Public Attributes</h2></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p_1_1_t_config_params.html">TConfigParams</a>&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p.html#ac5276790c90522d2c506a0265305bcef">options</a></td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The options employed by the ICP align.  <a href="#ac5276790c90522d2c506a0265305bcef"></a><br/></td></tr>
<tr><td colspan="2"><h2><a name="pro-methods"></a>
Protected Member Functions</h2></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">float&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p.html#a4cbc99445e6f8be55355f77bab4de3d5">kernel</a> (const float &amp;x2, const float &amp;rho2)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Computes: </p>
<p class="formulaDsp">
<img class="formulaDsp" alt="\[ K(x^2) = \frac{x^2}{x^2+\rho^2} \]" src="form_110.png"/>
</p>
<p> or just return the input if options.useKernel = false.  <a href="#a4cbc99445e6f8be55355f77bab4de3d5"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="structmrpt_1_1poses_1_1_c_pose_p_d_f_ptr.html">CPosePDFPtr</a>&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p.html#a9f606c6a0322234ed0c7840661cd081f">ICP_Method_Classic</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> &amp;initialEstimationPDF, <a class="el" href="structmrpt_1_1slam_1_1_c_i_c_p_1_1_t_return_info.html">TReturnInfo</a> &amp;outInfo)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The internal method implementing <a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p.html#a73a709e50ebe5c8c3c63c9f2b0e49140" title="An implementation of CMetricMapsAlignmentAlgorithm for the case of a point maps and a occupancy grid/...">CICP::AlignPDF</a> when options.ICP_algorithm is icpClassic.  <a href="#a9f606c6a0322234ed0c7840661cd081f"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="structmrpt_1_1poses_1_1_c_pose_p_d_f_ptr.html">CPosePDFPtr</a>&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p.html#ad4c9db4f1dc4f60af7e6594c1fb61452">ICP_Method_LM</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> &amp;initialEstimationPDF, <a class="el" href="structmrpt_1_1slam_1_1_c_i_c_p_1_1_t_return_info.html">TReturnInfo</a> &amp;outInfo)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The internal method implementing <a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p.html#a73a709e50ebe5c8c3c63c9f2b0e49140" title="An implementation of CMetricMapsAlignmentAlgorithm for the case of a point maps and a occupancy grid/...">CICP::AlignPDF</a> when options.ICP_algorithm is icpLevenbergMarquardt.  <a href="#ad4c9db4f1dc4f60af7e6594c1fb61452"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="structmrpt_1_1poses_1_1_c_pose_p_d_f_ptr.html">CPosePDFPtr</a>&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p.html#a2deaf855d0d56fad46ec5aaf96bc69ca">ICP_Method_IKF</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> &amp;initialEstimationPDF, <a class="el" href="structmrpt_1_1slam_1_1_c_i_c_p_1_1_t_return_info.html">TReturnInfo</a> &amp;outInfo)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The internal method implementing <a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p.html#a73a709e50ebe5c8c3c63c9f2b0e49140" title="An implementation of CMetricMapsAlignmentAlgorithm for the case of a point maps and a occupancy grid/...">CICP::AlignPDF</a> when options.ICP_algorithm is icpIKF.  <a href="#a2deaf855d0d56fad46ec5aaf96bc69ca"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="structmrpt_1_1poses_1_1_c_pose3_d_p_d_f_ptr.html">CPose3DPDFPtr</a>&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p.html#a0534344d4461b1ca162207166461ae2b">ICP3D_Method_Classic</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> &amp;initialEstimationPDF, <a class="el" href="structmrpt_1_1slam_1_1_c_i_c_p_1_1_t_return_info.html">TReturnInfo</a> &amp;outInfo)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The internal method implementing <a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p.html#af6dd4e59ce84dfe62b6597021d78edde" title="Align a pair of metric maps, aligning the full 6D pose.">CICP::Align3DPDF</a> when options.ICP_algorithm is icpClassic.  <a href="#a0534344d4461b1ca162207166461ae2b"></a><br/></td></tr>
</table>
<hr/><h2>Constructor &amp; Destructor Documentation</h2>
<a class="anchor" id="a03c787f3328250801118933dbc9d97dd"></a><!-- doxytag: member="mrpt::slam::CICP::CICP" ref="a03c787f3328250801118933dbc9d97dd" args="()" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">mrpt::slam::CICP::CICP </td>
          <td>(</td>
          <td class="paramname">&#160;)</td>
          <td><code> [inline]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Constructor with the default options. </p>

<p>Definition at line <a class="el" href="_c_i_c_p_8h_source.html#l00178">178</a> of file <a class="el" href="_c_i_c_p_8h_source.html">CICP.h</a>.</p>

</div>
</div>
<a class="anchor" id="a90f68da0ac5ccafa22850691a59bcc49"></a><!-- doxytag: member="mrpt::slam::CICP::CICP" ref="a90f68da0ac5ccafa22850691a59bcc49" args="(const TConfigParams &amp;icpParams)" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">mrpt::slam::CICP::CICP </td>
          <td>(</td>
          <td class="paramtype">const <a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p_1_1_t_config_params.html">TConfigParams</a> &amp;&#160;</td>
          <td class="paramname"> <em>icpParams</em>&#160;)</td>
          <td><code> [inline]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Constructor that directly set the ICP params from a given struct. </p>
<dl class="see"><dt><b>See also:</b></dt><dd><a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p.html#ac5276790c90522d2c506a0265305bcef" title="The options employed by the ICP align.">options</a> </dd></dl>

<p>Definition at line <a class="el" href="_c_i_c_p_8h_source.html#l00180">180</a> of file <a class="el" href="_c_i_c_p_8h_source.html">CICP.h</a>.</p>

</div>
</div>
<a class="anchor" id="a9c69682c870276c32f204e44218b3e56"></a><!-- doxytag: member="mrpt::slam::CICP::~CICP" ref="a9c69682c870276c32f204e44218b3e56" args="()" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">virtual mrpt::slam::CICP::~CICP </td>
          <td>(</td>
          <td class="paramname">&#160;)</td>
          <td><code> [inline, virtual]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Destructor. </p>

<p>Definition at line <a class="el" href="_c_i_c_p_8h_source.html#l00182">182</a> of file <a class="el" href="_c_i_c_p_8h_source.html">CICP.h</a>.</p>

</div>
</div>
<hr/><h2>Member Function Documentation</h2>
<a class="anchor" id="af6dd4e59ce84dfe62b6597021d78edde"></a><!-- doxytag: member="mrpt::slam::CICP::Align3DPDF" ref="af6dd4e59ce84dfe62b6597021d78edde" args="(const CMetricMap *m1, const CMetricMap *m2, const CPose3DPDFGaussian &amp;initialEstimationPDF, float *runningTime=NULL, void *info=NULL)" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname"><a class="el" href="structmrpt_1_1poses_1_1_c_pose3_d_p_d_f_ptr.html">CPose3DPDFPtr</a> mrpt::slam::CICP::Align3DPDF </td>
          <td>(</td>
          <td class="paramtype">const <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map.html">CMetricMap</a> *&#160;</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> *&#160;</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> &amp;&#160;</td>
          <td class="paramname"> <em>initialEstimationPDF</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">float *&#160;</td>
          <td class="paramname"> <em>runningTime</em> = <code>NULL</code>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">void *&#160;</td>
          <td class="paramname"> <em>info</em> = <code>NULL</code>&#160;</td>
        </tr>
        <tr>
          <td></td>
          <td>)</td>
          <td></td><td><code> [virtual]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Align 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 class="params">
    <tr><td class="paramname">m1</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 class="paramname">m2</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 or other sensors...">CPointsMap</a> derived class) The pose of this map respect to m1 is to be estimated. </td></tr>
    <tr><td class="paramname">initialEstimationPDF</td><td>[IN] An initial gross estimation for the displacement. </td></tr>
    <tr><td class="paramname">runningTime</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 class="paramname">info</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 two point maps...">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>

</div>
</div>
<a class="anchor" id="a73a709e50ebe5c8c3c63c9f2b0e49140"></a><!-- doxytag: member="mrpt::slam::CICP::AlignPDF" ref="a73a709e50ebe5c8c3c63c9f2b0e49140" args="(const CMetricMap *m1, const CMetricMap *m2, const CPosePDFGaussian &amp;initialEstimationPDF, float *runningTime=NULL, void *info=NULL)" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname"><a class="el" href="structmrpt_1_1poses_1_1_c_pose_p_d_f_ptr.html">CPosePDFPtr</a> mrpt::slam::CICP::AlignPDF </td>
          <td>(</td>
          <td class="paramtype">const <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map.html">CMetricMap</a> *&#160;</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> *&#160;</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> &amp;&#160;</td>
          <td class="paramname"> <em>initialEstimationPDF</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">float *&#160;</td>
          <td class="paramname"> <em>runningTime</em> = <code>NULL</code>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">void *&#160;</td>
          <td class="paramname"> <em>info</em> = <code>NULL</code>&#160;</td>
        </tr>
        <tr>
          <td></td>
          <td>)</td>
          <td></td><td><code> [virtual]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>An implementation of <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> for the case of a point maps and a occupancy grid/point map. </p>
<p>This method computes the PDF of the displacement (relative pose) between two maps: <b>the relative pose of m2 with respect 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 "CICP::options" </dd>
<dd>
The output PDF is a CPosePDFGaussian if "doRANSAC=false", or a CPosePDFSOG otherwise.</dd></dl>
<dl><dt><b>Parameters:</b></dt><dd>
  <table class="params">
    <tr><td class="paramname">m1</td><td>[IN] The first map (CAN BE A mrpt::poses::CPointsMap derived class or a mrpt::slam::COccupancyGrid2D class) </td></tr>
    <tr><td class="paramname">m2</td><td>[IN] The second map. (MUST BE A mrpt::poses::CPointsMap derived class)The pose of this map respect to m1 is to be estimated. </td></tr>
    <tr><td class="paramname">initialEstimationPDF</td><td>[IN] An initial gross estimation for the displacement. </td></tr>
    <tr><td class="paramname">runningTime</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 class="paramname">info</td><td>[OUT] A pointer to a <a class="el" href="structmrpt_1_1slam_1_1_c_i_c_p_1_1_t_return_info.html" title="The ICP algorithm return information.">CICP::TReturnInfo</a>, 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_metric_maps_alignment_algorithm.html" title="A base class for any algorithm able of maps alignment.">CMetricMapsAlignmentAlgorithm</a>, <a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p.html#ac5276790c90522d2c506a0265305bcef" title="The options employed by the ICP align.">CICP::options</a>, <a class="el" href="structmrpt_1_1slam_1_1_c_i_c_p_1_1_t_return_info.html" title="The ICP algorithm return information.">CICP::TReturnInfo</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="a0534344d4461b1ca162207166461ae2b"></a><!-- doxytag: member="mrpt::slam::CICP::ICP3D_Method_Classic" ref="a0534344d4461b1ca162207166461ae2b" args="(const CMetricMap *m1, const CMetricMap *m2, const CPose3DPDFGaussian &amp;initialEstimationPDF, TReturnInfo &amp;outInfo)" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname"><a class="el" href="structmrpt_1_1poses_1_1_c_pose3_d_p_d_f_ptr.html">CPose3DPDFPtr</a> mrpt::slam::CICP::ICP3D_Method_Classic </td>
          <td>(</td>
          <td class="paramtype">const <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map.html">CMetricMap</a> *&#160;</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> *&#160;</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> &amp;&#160;</td>
          <td class="paramname"> <em>initialEstimationPDF</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype"><a class="el" href="structmrpt_1_1slam_1_1_c_i_c_p_1_1_t_return_info.html">TReturnInfo</a> &amp;&#160;</td>
          <td class="paramname"> <em>outInfo</em>&#160;</td>
        </tr>
        <tr>
          <td></td>
          <td>)</td>
          <td></td><td><code> [protected]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>The internal method implementing <a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p.html#af6dd4e59ce84dfe62b6597021d78edde" title="Align a pair of metric maps, aligning the full 6D pose.">CICP::Align3DPDF</a> when options.ICP_algorithm is icpClassic. </p>

</div>
</div>
<a class="anchor" id="a9f606c6a0322234ed0c7840661cd081f"></a><!-- doxytag: member="mrpt::slam::CICP::ICP_Method_Classic" ref="a9f606c6a0322234ed0c7840661cd081f" args="(const CMetricMap *m1, const CMetricMap *m2, const CPosePDFGaussian &amp;initialEstimationPDF, TReturnInfo &amp;outInfo)" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname"><a class="el" href="structmrpt_1_1poses_1_1_c_pose_p_d_f_ptr.html">CPosePDFPtr</a> mrpt::slam::CICP::ICP_Method_Classic </td>
          <td>(</td>
          <td class="paramtype">const <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map.html">CMetricMap</a> *&#160;</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> *&#160;</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> &amp;&#160;</td>
          <td class="paramname"> <em>initialEstimationPDF</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype"><a class="el" href="structmrpt_1_1slam_1_1_c_i_c_p_1_1_t_return_info.html">TReturnInfo</a> &amp;&#160;</td>
          <td class="paramname"> <em>outInfo</em>&#160;</td>
        </tr>
        <tr>
          <td></td>
          <td>)</td>
          <td></td><td><code> [protected]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>The internal method implementing <a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p.html#a73a709e50ebe5c8c3c63c9f2b0e49140" title="An implementation of CMetricMapsAlignmentAlgorithm for the case of a point maps and a occupancy grid/...">CICP::AlignPDF</a> when options.ICP_algorithm is icpClassic. </p>

</div>
</div>
<a class="anchor" id="a2deaf855d0d56fad46ec5aaf96bc69ca"></a><!-- doxytag: member="mrpt::slam::CICP::ICP_Method_IKF" ref="a2deaf855d0d56fad46ec5aaf96bc69ca" args="(const CMetricMap *m1, const CMetricMap *m2, const CPosePDFGaussian &amp;initialEstimationPDF, TReturnInfo &amp;outInfo)" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname"><a class="el" href="structmrpt_1_1poses_1_1_c_pose_p_d_f_ptr.html">CPosePDFPtr</a> mrpt::slam::CICP::ICP_Method_IKF </td>
          <td>(</td>
          <td class="paramtype">const <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map.html">CMetricMap</a> *&#160;</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> *&#160;</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> &amp;&#160;</td>
          <td class="paramname"> <em>initialEstimationPDF</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype"><a class="el" href="structmrpt_1_1slam_1_1_c_i_c_p_1_1_t_return_info.html">TReturnInfo</a> &amp;&#160;</td>
          <td class="paramname"> <em>outInfo</em>&#160;</td>
        </tr>
        <tr>
          <td></td>
          <td>)</td>
          <td></td><td><code> [protected]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>The internal method implementing <a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p.html#a73a709e50ebe5c8c3c63c9f2b0e49140" title="An implementation of CMetricMapsAlignmentAlgorithm for the case of a point maps and a occupancy grid/...">CICP::AlignPDF</a> when options.ICP_algorithm is icpIKF. </p>

</div>
</div>
<a class="anchor" id="ad4c9db4f1dc4f60af7e6594c1fb61452"></a><!-- doxytag: member="mrpt::slam::CICP::ICP_Method_LM" ref="ad4c9db4f1dc4f60af7e6594c1fb61452" args="(const CMetricMap *m1, const CMetricMap *m2, const CPosePDFGaussian &amp;initialEstimationPDF, TReturnInfo &amp;outInfo)" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname"><a class="el" href="structmrpt_1_1poses_1_1_c_pose_p_d_f_ptr.html">CPosePDFPtr</a> mrpt::slam::CICP::ICP_Method_LM </td>
          <td>(</td>
          <td class="paramtype">const <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map.html">CMetricMap</a> *&#160;</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> *&#160;</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> &amp;&#160;</td>
          <td class="paramname"> <em>initialEstimationPDF</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype"><a class="el" href="structmrpt_1_1slam_1_1_c_i_c_p_1_1_t_return_info.html">TReturnInfo</a> &amp;&#160;</td>
          <td class="paramname"> <em>outInfo</em>&#160;</td>
        </tr>
        <tr>
          <td></td>
          <td>)</td>
          <td></td><td><code> [protected]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>The internal method implementing <a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p.html#a73a709e50ebe5c8c3c63c9f2b0e49140" title="An implementation of CMetricMapsAlignmentAlgorithm for the case of a point maps and a occupancy grid/...">CICP::AlignPDF</a> when options.ICP_algorithm is icpLevenbergMarquardt. </p>

</div>
</div>
<a class="anchor" id="a4cbc99445e6f8be55355f77bab4de3d5"></a><!-- doxytag: member="mrpt::slam::CICP::kernel" ref="a4cbc99445e6f8be55355f77bab4de3d5" args="(const float &amp;x2, const float &amp;rho2)" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">float mrpt::slam::CICP::kernel </td>
          <td>(</td>
          <td class="paramtype">const float &amp;&#160;</td>
          <td class="paramname"> <em>x2</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">const float &amp;&#160;</td>
          <td class="paramname"> <em>rho2</em>&#160;</td>
        </tr>
        <tr>
          <td></td>
          <td>)</td>
          <td></td><td><code> [protected]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Computes: </p>
<p class="formulaDsp">
<img class="formulaDsp" alt="\[ K(x^2) = \frac{x^2}{x^2+\rho^2} \]" src="form_110.png"/>
</p>
<p> or just return the input if options.useKernel = false. </p>

</div>
</div>
<hr/><h2>Member Data Documentation</h2>
<a class="anchor" id="ac5276790c90522d2c506a0265305bcef"></a><!-- doxytag: member="mrpt::slam::CICP::options" ref="ac5276790c90522d2c506a0265305bcef" args="" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname"><a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p_1_1_t_config_params.html">TConfigParams</a> <a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p.html#ac5276790c90522d2c506a0265305bcef">mrpt::slam::CICP::options</a></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>The options employed by the ICP align. </p>

<p>Definition at line <a class="el" href="_c_i_c_p_8h_source.html#l00174">174</a> of file <a class="el" href="_c_i_c_p_8h_source.html">CICP.h</a>.</p>

</div>
</div>
</div>
<br><hr><br> <table border="0" width="100%"> <tr> <td> Page generated by <a href="http://www.doxygen.org" target="_blank">Doxygen 1.7.2</a> for MRPT 0.9.4 SVN: at Mon Jan 10 22:30:30 UTC 2011</td><td></td> <td width="100"> </td> <td width="150">  </td></tr> </table> </body></html>