Sophie

Sophie

distrib > Fedora > 16 > i386 > by-pkgid > 4bc66056a634db26a1f4d0845dc41ca6 > files > 4937

mrpt-doc-0.9.5-0.1.20110925svn2670.fc16.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>mrpt::slam::CMetricMapsAlignmentAlgorithm 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.5 -->
<script type="text/javascript">
var searchBox = new SearchBox("searchBox", "search",false,'Search');
</script>
  <div id="navrow1" 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>
        <div id="MSearchBox" class="MSearchBoxInactive">
          <div 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>
          </div><div class="right"></div>
        </div>
      </li>
    </ul>
  </div>
  <div id="navrow2" 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="inherits.html"><span>Class&#160;Hierarchy</span></a></li>
      <li><a href="functions.html"><span>Class&#160;Members</span></a></li>
    </ul>
  </div>
  <div id="nav-path" class="navpath">
    <ul>
      <li class="navelem"><a class="el" href="namespacemrpt.html">mrpt</a>      </li>
      <li class="navelem"><a class="el" href="namespacemrpt_1_1slam.html">slam</a>      </li>
      <li class="navelem"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_maps_alignment_algorithm.html">CMetricMapsAlignmentAlgorithm</a>      </li>
    </ul>
  </div>
</div>
<div class="header">
  <div class="summary">
<a href="#pub-methods">Public Member Functions</a> &#124;
<a href="#pub-static-methods">Static Public Member Functions</a>  </div>
  <div class="headertitle">
<div class="title">mrpt::slam::CMetricMapsAlignmentAlgorithm Class Reference<div class="ingroups"><a class="el" href="group__mrpt__slam__grp.html">[mrpt-slam]</a></div></div>  </div>
</div>
<div class="contents">
<!-- doxytag: class="mrpt::slam::CMetricMapsAlignmentAlgorithm" --><!-- doxytag: inherits="mrpt::utils::CDebugOutputCapable" --><hr/><a name="details" id="details"></a><h2>Detailed Description</h2>
<div class="textblock"><p>A base class for any algorithm able of maps alignment. </p>
<p>There are two methods depending on an PDF or a single 2D Pose value is available as initial guess for the methods.</p>
<dl class="see"><dt><b>See also:</b></dt><dd><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>, <a class="el" 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 std::cout...">utils::CDebugOutputCapable</a> </dd></dl>
</div>
<p><code>#include &lt;<a class="el" href="_c_metric_maps_alignment_algorithm_8h_source.html">mrpt/slam/CMetricMapsAlignmentAlgorithm.h</a>&gt;</code></p>
<div class="dynheader">
Inheritance diagram for mrpt::slam::CMetricMapsAlignmentAlgorithm:</div>
<div class="dyncontent">
<div class="center"><img src="classmrpt_1_1slam_1_1_c_metric_maps_alignment_algorithm__inherit__graph.png" border="0" usemap="#mrpt_1_1slam_1_1_c_metric_maps_alignment_algorithm_inherit__map" alt="Inheritance graph"/></div>
<map name="mrpt_1_1slam_1_1_c_metric_maps_alignment_algorithm_inherit__map" id="mrpt_1_1slam_1_1_c_metric_maps_alignment_algorithm_inherit__map">
<area shape="rect" id="node5" href="classmrpt_1_1slam_1_1_c_grid_map_aligner.html" title="A class for aligning two multi&#45;metric maps (with an occupancy grid maps and a points map..." alt="" coords="5,155,195,181"/><area shape="rect" id="node7" 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 or a ..." alt="" coords="220,155,345,181"/><area shape="rect" id="node2" href="classmrpt_1_1utils_1_1_c_debug_output_capable.html" title="This base class provides a common printf&#45;like method to send debug information to std::cout..." alt="" coords="79,5,301,32"/></map>
<center><span class="legend">[<a href="graph_legend.html">legend</a>]</span></center></div>

<p><a href="classmrpt_1_1slam_1_1_c_metric_maps_alignment_algorithm-members.html">List of all members.</a></p>
<table class="memberdecls">
<tr><td colspan="2"><h2><a name="pub-methods"></a>
Public Member Functions</h2></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_metric_maps_alignment_algorithm.html#af8229035ad0a58e120e61e690a5639c9">~CMetricMapsAlignmentAlgorithm</a> ()</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Destructor.  <a href="#af8229035ad0a58e120e61e690a5639c9"></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_metric_maps_alignment_algorithm.html#aa6dafc1cecd79b3181dc6509f87e5d68">Align</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_pose2_d.html">CPose2D</a> &amp;grossEst, float *runningTime=NULL, void *info=NULL)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The method for aligning a pair of metric maps, aligning only 2D + orientation.  <a href="#aa6dafc1cecd79b3181dc6509f87e5d68"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">virtual <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_metric_maps_alignment_algorithm.html#add1ed631acbf0a3b4a6087fa24da9bd6">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)=0</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The virtual method for aligning a pair of metric maps, aligning only 2D + orientation.  <a href="#add1ed631acbf0a3b4a6087fa24da9bd6"></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_metric_maps_alignment_algorithm.html#a0c431844ae5fa69e580920d6ab9b145b">Align3D</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.html">CPose3D</a> &amp;grossEst, float *runningTime=NULL, void *info=NULL)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The method for aligning a pair of metric maps, aligning the full 6D pose.  <a href="#a0c431844ae5fa69e580920d6ab9b145b"></a><br/></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">virtual <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_metric_maps_alignment_algorithm.html#a017eed60f3088264f504f90856dfd77b">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)=0</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">The virtual method for aligning a pair of metric maps, aligning the full 6D pose.  <a href="#a017eed60f3088264f504f90856dfd77b"></a><br/></td></tr>
<tr><td colspan="2"><h2><a name="pub-static-methods"></a>
Static Public Member Functions</h2></td></tr>
<tr><td class="memItemLeft" align="right" valign="top">static void&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1utils_1_1_c_debug_output_capable.html#ab78281b5d70d6e295a8527a10fea66de">printf_debug</a> (const char *frmt,...)</td></tr>
<tr><td class="mdescLeft">&#160;</td><td class="mdescRight">Sends a formated text to "debugOut" if not NULL, or to cout otherwise.  <a href="#ab78281b5d70d6e295a8527a10fea66de"></a><br/></td></tr>
</table>
<hr/><h2>Constructor &amp; Destructor Documentation</h2>
<a class="anchor" id="af8229035ad0a58e120e61e690a5639c9"></a><!-- doxytag: member="mrpt::slam::CMetricMapsAlignmentAlgorithm::~CMetricMapsAlignmentAlgorithm" ref="af8229035ad0a58e120e61e690a5639c9" args="()" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">virtual mrpt::slam::CMetricMapsAlignmentAlgorithm::~CMetricMapsAlignmentAlgorithm </td>
          <td>(</td>
          <td class="paramname"></td><td>)</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_metric_maps_alignment_algorithm_8h_source.html#l00056">56</a> of file <a class="el" href="_c_metric_maps_alignment_algorithm_8h_source.html">CMetricMapsAlignmentAlgorithm.h</a>.</p>

</div>
</div>
<hr/><h2>Member Function Documentation</h2>
<a class="anchor" id="aa6dafc1cecd79b3181dc6509f87e5d68"></a><!-- doxytag: member="mrpt::slam::CMetricMapsAlignmentAlgorithm::Align" ref="aa6dafc1cecd79b3181dc6509f87e5d68" args="(const CMetricMap *m1, const CMetricMap *m2, const CPose2D &amp;grossEst, 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::CMetricMapsAlignmentAlgorithm::Align </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_pose2_d.html">CPose2D</a> &amp;&#160;</td>
          <td class="paramname"><em>grossEst</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></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>The method for aligning a pair of metric maps, aligning only 2D + orientation. </p>
<p>The meaning of some parameters and the kind of the maps to be aligned are implementation dependant, so look into the derived classes for instructions. The target is to find a PDF for the pose displacement between maps, <b>thus the pose of m2 relative to m1</b>. This pose is returned as a PDF rather than a single value.</p>
<dl><dt><b>Parameters:</b></dt><dd>
  <table class="params">
    <tr><td class="paramname">m1</td><td>[IN] The first map </td></tr>
    <tr><td class="paramname">m2</td><td>[IN] The second map. The pose of this map respect to m1 is to be estimated. </td></tr>
    <tr><td class="paramname">grossEst</td><td>[IN] An initial gross estimation for the displacement. If a given algorithm doesn't need it, set to <code>CPose2D(0,0,0)</code> for example. </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 or a ...">CICP</a> </dd></dl>

</div>
</div>
<a class="anchor" id="a0c431844ae5fa69e580920d6ab9b145b"></a><!-- doxytag: member="mrpt::slam::CMetricMapsAlignmentAlgorithm::Align3D" ref="a0c431844ae5fa69e580920d6ab9b145b" args="(const CMetricMap *m1, const CMetricMap *m2, const CPose3D &amp;grossEst, 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::CMetricMapsAlignmentAlgorithm::Align3D </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.html">CPose3D</a> &amp;&#160;</td>
          <td class="paramname"><em>grossEst</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></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>The method for aligning a pair of metric maps, aligning the full 6D pose. </p>
<p>The meaning of some parameters and the kind of the maps to be aligned are implementation dependant, so look into the derived classes for instructions. The target is to find a PDF for the pose displacement between maps, <b>thus the pose of m2 relative to m1</b>. This pose is returned as a PDF rather than a single value.</p>
<dl><dt><b>Parameters:</b></dt><dd>
  <table class="params">
    <tr><td class="paramname">m1</td><td>[IN] The first map </td></tr>
    <tr><td class="paramname">m2</td><td>[IN] The second map. The pose of this map respect to m1 is to be estimated. </td></tr>
    <tr><td class="paramname">grossEst</td><td>[IN] An initial gross estimation for the displacement. If a given algorithm doesn't need it, set to <code>CPose3D(0,0,0)</code> for example. </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 or a ...">CICP</a> </dd></dl>

</div>
</div>
<a class="anchor" id="a017eed60f3088264f504f90856dfd77b"></a><!-- doxytag: member="mrpt::slam::CMetricMapsAlignmentAlgorithm::Align3DPDF" ref="a017eed60f3088264f504f90856dfd77b" args="(const CMetricMap *m1, const CMetricMap *m2, const CPose3DPDFGaussian &amp;initialEstimationPDF, float *runningTime=NULL, void *info=NULL)=0" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">virtual <a class="el" href="structmrpt_1_1poses_1_1_c_pose3_d_p_d_f_ptr.html">CPose3DPDFPtr</a> mrpt::slam::CMetricMapsAlignmentAlgorithm::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> [pure 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 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 or a ...">CICP</a> </dd></dl>

<p>Implemented in <a class="el" href="classmrpt_1_1slam_1_1_c_grid_map_aligner.html#aa3e34e6a6e6f94965f792dd8712b75a4">mrpt::slam::CGridMapAligner</a>, and <a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p.html#af6dd4e59ce84dfe62b6597021d78edde">mrpt::slam::CICP</a>.</p>

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

<p>The virtual method for aligning a pair of metric maps, aligning only 2D + orientation. </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 or a ...">CICP</a> </dd></dl>

<p>Implemented in <a class="el" href="classmrpt_1_1slam_1_1_c_grid_map_aligner.html#a40fb440cf36849f9d7f48ece9816ef73">mrpt::slam::CGridMapAligner</a>, and <a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p.html#a73a709e50ebe5c8c3c63c9f2b0e49140">mrpt::slam::CICP</a>.</p>

</div>
</div>
<a class="anchor" id="ab78281b5d70d6e295a8527a10fea66de"></a><!-- doxytag: member="mrpt::slam::CMetricMapsAlignmentAlgorithm::printf_debug" ref="ab78281b5d70d6e295a8527a10fea66de" args="(const char *frmt,...)" -->
<div class="memitem">
<div class="memproto">
      <table class="memname">
        <tr>
          <td class="memname">static void mrpt::utils::CDebugOutputCapable::printf_debug </td>
          <td>(</td>
          <td class="paramtype">const char *&#160;</td>
          <td class="paramname"><em>frmt</em>, </td>
        </tr>
        <tr>
          <td class="paramkey"></td>
          <td></td>
          <td class="paramtype">&#160;</td>
          <td class="paramname"><em>...</em>&#160;</td>
        </tr>
        <tr>
          <td></td>
          <td>)</td>
          <td></td><td><code> [static, inherited]</code></td>
        </tr>
      </table>
</div>
<div class="memdoc">

<p>Sends a formated text to "debugOut" if not NULL, or to cout otherwise. </p>

<p>Referenced by <a class="el" href="_c_levenberg_marquardt_8h_source.html#l00098">mrpt::math::CLevenbergMarquardtTempl::execute()</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.5</a> for MRPT 0.9.5 SVN: at Sun Sep 25 17:20:18 UTC 2011</td><td></td> <td width="100"> </td> <td width="150">  </td></tr> </table>  </body></html>