Sophie

Sophie

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

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>CConsistentObservationAlignment.h Source File</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><a href="annotated.html"><span>Classes</span></a></li>
      <li class="current"><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="files.html"><span>File&#160;List</span></a></li>
      <li><a href="globals.html"><span>File&#160;Members</span></a></li>
    </ul>
  </div>
<div class="header">
  <div class="headertitle">
<div class="title">CConsistentObservationAlignment.h</div>  </div>
</div>
<div class="contents">
<a href="_c_consistent_observation_alignment_8h.html">Go to the documentation of this file.</a><div class="fragment"><pre class="fragment"><a name="l00001"></a>00001 <span class="comment">/* +---------------------------------------------------------------------------+</span>
<a name="l00002"></a>00002 <span class="comment">   |          The Mobile Robot Programming Toolkit (MRPT) C++ library          |</span>
<a name="l00003"></a>00003 <span class="comment">   |                                                                           |</span>
<a name="l00004"></a>00004 <span class="comment">   |                       http://www.mrpt.org/                                |</span>
<a name="l00005"></a>00005 <span class="comment">   |                                                                           |</span>
<a name="l00006"></a>00006 <span class="comment">   |   Copyright (C) 2005-2011  University of Malaga                           |</span>
<a name="l00007"></a>00007 <span class="comment">   |                                                                           |</span>
<a name="l00008"></a>00008 <span class="comment">   |    This software was written by the Machine Perception and Intelligent    |</span>
<a name="l00009"></a>00009 <span class="comment">   |      Robotics Lab, University of Malaga (Spain).                          |</span>
<a name="l00010"></a>00010 <span class="comment">   |    Contact: Jose-Luis Blanco  &lt;jlblanco@ctima.uma.es&gt;                     |</span>
<a name="l00011"></a>00011 <span class="comment">   |                                                                           |</span>
<a name="l00012"></a>00012 <span class="comment">   |  This file is part of the MRPT project.                                   |</span>
<a name="l00013"></a>00013 <span class="comment">   |                                                                           |</span>
<a name="l00014"></a>00014 <span class="comment">   |     MRPT is free software: you can redistribute it and/or modify          |</span>
<a name="l00015"></a>00015 <span class="comment">   |     it under the terms of the GNU General Public License as published by  |</span>
<a name="l00016"></a>00016 <span class="comment">   |     the Free Software Foundation, either version 3 of the License, or     |</span>
<a name="l00017"></a>00017 <span class="comment">   |     (at your option) any later version.                                   |</span>
<a name="l00018"></a>00018 <span class="comment">   |                                                                           |</span>
<a name="l00019"></a>00019 <span class="comment">   |   MRPT is distributed in the hope that it will be useful,                 |</span>
<a name="l00020"></a>00020 <span class="comment">   |     but WITHOUT ANY WARRANTY; without even the implied warranty of        |</span>
<a name="l00021"></a>00021 <span class="comment">   |     MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the         |</span>
<a name="l00022"></a>00022 <span class="comment">   |     GNU General Public License for more details.                          |</span>
<a name="l00023"></a>00023 <span class="comment">   |                                                                           |</span>
<a name="l00024"></a>00024 <span class="comment">   |     You should have received a copy of the GNU General Public License     |</span>
<a name="l00025"></a>00025 <span class="comment">   |     along with MRPT.  If not, see &lt;http://www.gnu.org/licenses/&gt;.         |</span>
<a name="l00026"></a>00026 <span class="comment">   |                                                                           |</span>
<a name="l00027"></a>00027 <span class="comment">   +---------------------------------------------------------------------------+ */</span>
<a name="l00028"></a>00028 <span class="preprocessor">#ifndef CCONSISTENTOBSERVATIONALIGNMENT_H</span>
<a name="l00029"></a>00029 <span class="preprocessor"></span><span class="preprocessor">#define CCONSISTENTOBSERVATIONALIGNMENT_H</span>
<a name="l00030"></a>00030 <span class="preprocessor"></span>
<a name="l00031"></a>00031 <span class="preprocessor">#include &lt;<a class="code" href="_c_simple_map_8h.html">mrpt/slam/CSimpleMap.h</a>&gt;</span>
<a name="l00032"></a>00032 <span class="preprocessor">#include &lt;<a class="code" href="_c_pose2_d_8h.html">mrpt/poses/CPose2D.h</a>&gt;</span>
<a name="l00033"></a>00033 <span class="preprocessor">#include &lt;<a class="code" href="_c_points_map_8h.html">mrpt/slam/CPointsMap.h</a>&gt;</span>
<a name="l00034"></a>00034 <span class="preprocessor">#include &lt;<a class="code" href="_c_i_c_p_8h.html">mrpt/slam/CICP.h</a>&gt;</span>
<a name="l00035"></a>00035 <span class="preprocessor">#include &lt;<a class="code" href="_c_pose_p_d_f_gaussian_8h.html">mrpt/poses/CPosePDFGaussian.h</a>&gt;</span>
<a name="l00036"></a>00036 <span class="preprocessor">#include &lt;<a class="code" href="_c_occupancy_grid_map2_d_8h.html">mrpt/slam/COccupancyGridMap2D.h</a>&gt;</span>
<a name="l00037"></a>00037 
<a name="l00038"></a>00038 <span class="preprocessor">#include &lt;<a class="code" href="_c_debug_output_capable_8h.html">mrpt/utils/CDebugOutputCapable.h</a>&gt;</span>
<a name="l00039"></a>00039 <span class="preprocessor">#include &lt;<a class="code" href="_c_matrix_8h.html">mrpt/math/CMatrix.h</a>&gt;</span>
<a name="l00040"></a>00040 <span class="preprocessor">#include &lt;<a class="code" href="_c_matrix_template_objects_8h.html">mrpt/math/CMatrixTemplateObjects.h</a>&gt;</span>
<a name="l00041"></a>00041 
<a name="l00042"></a>00042 <span class="preprocessor">#include &lt;<a class="code" href="slam_2include_2mrpt_2slam_2link__pragmas_8h.html">mrpt/slam/link_pragmas.h</a>&gt;</span>
<a name="l00043"></a>00043 
<a name="l00044"></a>00044 <span class="keyword">namespace </span>mrpt
<a name="l00045"></a>00045 {
<a name="l00046"></a>00046         <span class="keyword">namespace </span>slam
<a name="l00047"></a>00047         {
<a name="l00048"></a>00048                 <span class="keyword">using namespace </span>mrpt::math;
<a name="l00049"></a>00049 <span class="comment"></span>
<a name="l00050"></a>00050 <span class="comment">                /** An algorithm for globally, consistent alignment of a</span>
<a name="l00051"></a>00051 <span class="comment">                 *    sequence of observations.</span>
<a name="l00052"></a>00052 <span class="comment">                 *  This algorithm is based on the work of Lu &amp; Milios</span>
<a name="l00053"></a>00053 <span class="comment">                 *    [Globally Consistent Range Scan Alignment for Environment Mapping, 1997]</span>
<a name="l00054"></a>00054 <span class="comment">                 *    for a global optimal estimation of laser range scan poses, but in</span>
<a name="l00055"></a>00055 <span class="comment">                 *    this case it has been extended to include any type of</span>
<a name="l00056"></a>00056 <span class="comment">                 *    observations as long as points-map-like operators are implemented over them.</span>
<a name="l00057"></a>00057 <span class="comment">                 *    &lt;br&gt;</span>
<a name="l00058"></a>00058 <span class="comment">                 *    &lt;b&gt;This class work in the following way:&lt;/b&gt;&lt;br&gt;</span>
<a name="l00059"></a>00059 <span class="comment">                 *      The input is a set of observations with associated &quot;global&quot; poses. This is</span>
<a name="l00060"></a>00060 <span class="comment">                 *       supplied with a &quot;CSimpleMap&quot; object, but the probabilistic poses</span>
<a name="l00061"></a>00061 <span class="comment">                 *       are ignored since only the mean values for the pose of each node are taken.&lt;br&gt;</span>
<a name="l00062"></a>00062 <span class="comment">                 *      After invoking the algorithm with CConsistentObservationAlignment::execute(),</span>
<a name="l00063"></a>00063 <span class="comment">                 *       a new &quot;CSimpleMap&quot; object is returned, where the</span>
<a name="l00064"></a>00064 <span class="comment">                 *      NOTE: The first node on the input map is used as reference and therefore</span>
<a name="l00065"></a>00065 <span class="comment">                 *                its pose is the only one which will never change.</span>
<a name="l00066"></a>00066 <span class="comment">                 *    </span>
<a name="l00067"></a>00067 <span class="comment">             * \note This class is superseded by more modern implementations of graph-slam. See mrpt::graphslam</span>
<a name="l00068"></a>00068 <span class="comment">                 *</span>
<a name="l00069"></a>00069 <span class="comment">                 * \sa CSimpleMap, CPosePDF, CObservation, utils::CDebugOutputCapable   \ingroup mrpt_slam_grp</span>
<a name="l00070"></a>00070 <span class="comment">                 */</span>
<a name="l00071"></a>00071                 <span class="keyword">class </span><a class="code" href="slam_2include_2mrpt_2slam_2link__pragmas_8h.html#a26118d9c67fb641718c989b57c9acf64">SLAM_IMPEXP</a> CConsistentObservationAlignment : <span class="keyword">public</span> mrpt::utils::CDebugOutputCapable
<a name="l00072"></a>00072                 {
<a name="l00073"></a>00073                 <span class="keyword">protected</span>:<span class="comment"></span>
<a name="l00074"></a>00074 <span class="comment">                        /** A sequence of probabilistic poses:</span>
<a name="l00075"></a>00075 <span class="comment">                          */</span>
<a name="l00076"></a><a class="code" href="classmrpt_1_1slam_1_1_c_consistent_observation_alignment.html#a4500270ac40c2322cc7576e83420c33e">00076</a>                         <span class="keyword">typedef</span> std<a class="code" href="classstd_1_1vector.html" title="STL class.">::vector&lt;CPosePDFGaussianPtr&gt;</a>        <a class="code" href="classmrpt_1_1slam_1_1_c_consistent_observation_alignment.html#a4500270ac40c2322cc7576e83420c33e" title="A sequence of probabilistic poses:">vector_posesPdf</a>;
<a name="l00077"></a>00077 
<a name="l00078"></a>00078                 <span class="keyword">public</span>:
<a name="l00079"></a>00079 
<a name="l00080"></a>00080                         <a class="code" href="classmrpt_1_1slam_1_1_c_consistent_observation_alignment.html" title="An algorithm for globally, consistent alignment of a sequence of observations.">CConsistentObservationAlignment</a>();
<a name="l00081"></a>00081 <span class="comment"></span>
<a name="l00082"></a>00082 <span class="comment">                        /** The options for the method.</span>
<a name="l00083"></a>00083 <span class="comment">                          */</span>
<a name="l00084"></a>00084                         <span class="keyword">struct </span><a class="code" href="slam_2include_2mrpt_2slam_2link__pragmas_8h.html#a26118d9c67fb641718c989b57c9acf64">SLAM_IMPEXP</a> <a class="code" href="structmrpt_1_1slam_1_1_c_consistent_observation_alignment_1_1_t_options.html" title="The options for the method.">TOptions</a>
<a name="l00085"></a>00085                         {<span class="comment"></span>
<a name="l00086"></a>00086 <span class="comment">                                /** Initialization:</span>
<a name="l00087"></a>00087 <span class="comment">                                  */</span>
<a name="l00088"></a>00088                                 <a class="code" href="structmrpt_1_1slam_1_1_c_consistent_observation_alignment_1_1_t_options.html" title="The options for the method.">TOptions</a>();
<a name="l00089"></a>00089 <span class="comment"></span>
<a name="l00090"></a>00090 <span class="comment">                                /** If set to true (default), the matching will be performed against grid maps, instead of points maps:</span>
<a name="l00091"></a>00091 <span class="comment">                                  */</span>
<a name="l00092"></a><a class="code" href="structmrpt_1_1slam_1_1_c_consistent_observation_alignment_1_1_t_options.html#abf6e4ea1c8e9a2aed37202e655e24857">00092</a>                                 <span class="keywordtype">bool</span>            <a class="code" href="structmrpt_1_1slam_1_1_c_consistent_observation_alignment_1_1_t_options.html#abf6e4ea1c8e9a2aed37202e655e24857" title="If set to true (default), the matching will be performed against grid maps, instead of points maps:...">matchAgainstGridmap</a>;
<a name="l00093"></a>00093 <span class="comment"></span>
<a name="l00094"></a>00094 <span class="comment">                                /** The resolution of the grid maps (default = 0.02m)</span>
<a name="l00095"></a>00095 <span class="comment">                                  */</span>
<a name="l00096"></a><a class="code" href="structmrpt_1_1slam_1_1_c_consistent_observation_alignment_1_1_t_options.html#aaa4617da7519a68280f76b90f74380b1">00096</a>                                 <span class="keywordtype">float</span>           <a class="code" href="structmrpt_1_1slam_1_1_c_consistent_observation_alignment_1_1_t_options.html#aaa4617da7519a68280f76b90f74380b1" title="The resolution of the grid maps (default = 0.02m)">gridMapsResolution</a>;
<a name="l00097"></a>00097 <span class="comment"></span>
<a name="l00098"></a>00098 <span class="comment">                                /** The options for building temporary maps.</span>
<a name="l00099"></a>00099 <span class="comment">                                  */</span>
<a name="l00100"></a><a class="code" href="structmrpt_1_1slam_1_1_c_consistent_observation_alignment_1_1_t_options.html#a350aadd73ac87c5ce413c363729846bf">00100</a>                                 <a class="code" 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>::TInsertionOptions                   <a class="code" href="structmrpt_1_1slam_1_1_c_consistent_observation_alignment_1_1_t_options.html#a350aadd73ac87c5ce413c363729846bf" title="The options for building temporary maps.">pointsMapOptions</a>;
<a name="l00101"></a>00101 <span class="comment"></span>
<a name="l00102"></a>00102 <span class="comment">                                /** The options for building temporary maps.</span>
<a name="l00103"></a>00103 <span class="comment">                                  */</span>
<a name="l00104"></a><a class="code" href="structmrpt_1_1slam_1_1_c_consistent_observation_alignment_1_1_t_options.html#a8eed0c166ec051952998b50d8c90901d">00104</a>                                 <a class="code" href="classmrpt_1_1slam_1_1_c_occupancy_grid_map2_d.html" title="A class for storing an occupancy grid map.">COccupancyGridMap2D</a>::TInsertionOptions  <a class="code" href="structmrpt_1_1slam_1_1_c_consistent_observation_alignment_1_1_t_options.html#a8eed0c166ec051952998b50d8c90901d" title="The options for building temporary maps.">gridInsertOptions</a>;
<a name="l00105"></a>00105 <span class="comment"></span>
<a name="l00106"></a>00106 <span class="comment">                                /** The options for the ICP algorithm.</span>
<a name="l00107"></a>00107 <span class="comment">                                  */</span>
<a name="l00108"></a><a class="code" href="structmrpt_1_1slam_1_1_c_consistent_observation_alignment_1_1_t_options.html#a37b07499a4323c6526756972552e82ed">00108</a>                                 <a class="code" 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>::TConfigParams                             <a class="code" href="structmrpt_1_1slam_1_1_c_consistent_observation_alignment_1_1_t_options.html#a37b07499a4323c6526756972552e82ed" title="The options for the ICP algorithm.">icpOptions</a>;
<a name="l00109"></a>00109 
<a name="l00110"></a>00110                         } options;
<a name="l00111"></a>00111 <span class="comment"></span>
<a name="l00112"></a>00112 <span class="comment">                        /** Executes the algorithm. See description in CConsistentObservationAlignment.</span>
<a name="l00113"></a>00113 <span class="comment">                         *</span>
<a name="l00114"></a>00114 <span class="comment">                         * \param inputMap The input to the algorithm: a set of nodes situated (with global coordinates) and observations from each node.</span>
<a name="l00115"></a>00115 <span class="comment">                         * \param outputMap The globally consistent map, where probabilitic poses are filled with gaussian PDFs, where the mean is the globally optimal estimation and the covariance is also computed.</span>
<a name="l00116"></a>00116 <span class="comment">                         */</span>
<a name="l00117"></a>00117                         <span class="keywordtype">void</span>  execute(
<a name="l00118"></a>00118                                 <a class="code" href="classmrpt_1_1slam_1_1_c_simple_map.html" title="This class stores a sequence of &lt;Probabilistic Pose,SensoryFrame&gt; pairs, thus a &quot;metric map&quot; can be t...">CSimpleMap</a>              &amp;inputMap,
<a name="l00119"></a>00119                                 <a class="code" href="classmrpt_1_1slam_1_1_c_simple_map.html" title="This class stores a sequence of &lt;Probabilistic Pose,SensoryFrame&gt; pairs, thus a &quot;metric map&quot; can be t...">CSimpleMap</a>              &amp;outputMap );
<a name="l00120"></a>00120 <span class="comment"></span>
<a name="l00121"></a>00121 <span class="comment">                        /** This alternate method provides the basic consistent alignment algorithm to any user-supplied matrix of pose constrainsts, returning the optimal poses of all the nodes relative to the first one.</span>
<a name="l00122"></a>00122 <span class="comment">                         * \param in_PoseConstraints This is a NxN matrix where element M(i,j) is the pose constrainst between node &quot;i&quot; and &quot;j&quot;. Please, fill out only the upper-triangle part of the matrix (diagonal and lowe-part entries are not used).</span>
<a name="l00123"></a>00123 <span class="comment">                         * \param out_OptimalPoses The 1xN vector with the consistent global poses of all nodes, where the first node is always at (0,0,0deg).</span>
<a name="l00124"></a>00124 <span class="comment">                         */</span>
<a name="l00125"></a>00125                         <span class="keyword">static</span> <span class="keywordtype">void</span>  optimizeUserSuppliedData(
<a name="l00126"></a>00126                                 <a class="code" href="classmrpt_1_1math_1_1_c_matrix_template_objects.html" title="This template class extends the class &quot;CMatrixTemplate&quot; for storing &quot;objects&quot; at each matrix entry...">math::CMatrixTemplateObjects&lt;CPosePDFGaussian&gt;</a>          &amp;in_PoseConstraints,
<a name="l00127"></a>00127                                 <a class="code" href="classmrpt_1_1math_1_1_c_matrix_template_objects.html" title="This template class extends the class &quot;CMatrixTemplate&quot; for storing &quot;objects&quot; at each matrix entry...">math::CMatrixTemplateObjects&lt;CPosePDFGaussian&gt;</a>          &amp;out_OptimalPoses );
<a name="l00128"></a>00128 <span class="comment"></span>
<a name="l00129"></a>00129 <span class="comment">                        /** A textual description for the implemented algorithm.</span>
<a name="l00130"></a>00130 <span class="comment">                         */</span>
<a name="l00131"></a>00131                         std<a class="code" href="classstd_1_1string.html" title="STL class.">::string</a>             getAlgorithmName();
<a name="l00132"></a>00132 
<a name="l00133"></a>00133                 }; <span class="comment">// End of class def.</span>
<a name="l00134"></a>00134 
<a name="l00135"></a>00135         } <span class="comment">// End of namespace</span>
<a name="l00136"></a>00136 } <span class="comment">// End of namespace</span>
<a name="l00137"></a>00137 
<a name="l00138"></a>00138 <span class="preprocessor">#endif</span>
</pre></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>