Sophie

Sophie

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

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>CPose3DPDFGaussianInf.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">CPose3DPDFGaussianInf.h</div>  </div>
</div>
<div class="contents">
<a href="_c_pose3_d_p_d_f_gaussian_inf_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 CPose3DPDFGaussianInf_H</span>
<a name="l00029"></a>00029 <span class="preprocessor"></span><span class="preprocessor">#define CPose3DPDFGaussianInf_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_pose3_d_p_d_f_8h.html">mrpt/poses/CPose3DPDF.h</a>&gt;</span>
<a name="l00032"></a>00032 <span class="preprocessor">#include &lt;<a class="code" href="_c_pose_p_d_f_8h.html">mrpt/poses/CPosePDF.h</a>&gt;</span>
<a name="l00033"></a>00033 <span class="preprocessor">#include &lt;<a class="code" href="_c_matrix_d_8h.html">mrpt/math/CMatrixD.h</a>&gt;</span>
<a name="l00034"></a>00034 
<a name="l00035"></a>00035 <span class="keyword">namespace </span>mrpt
<a name="l00036"></a>00036 {
<a name="l00037"></a>00037 <span class="keyword">namespace </span>poses
<a name="l00038"></a>00038 {
<a name="l00039"></a>00039         <span class="keyword">class </span>CPosePDFGaussian;
<a name="l00040"></a>00040         <span class="keyword">class </span>CPose3DQuatPDFGaussian;
<a name="l00041"></a>00041 
<a name="l00042"></a><a class="code" href="structmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian_inf_ptr.html#ab5a9609d7fa7a4a6356f4084c8163f58">00042</a>         <a class="code" href="_c_serializable_8h.html#ab89b7a3de0a1baf5a5af4454add7d0f8" title="This declaration must be inserted in all CSerializable classes definition, before the class declarati...">DEFINE_SERIALIZABLE_PRE_CUSTOM_BASE</a>( <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian_inf.html" title="Declares a class that represents a Probability Density function (PDF) of a 3D pose  as a Gaussian des...">CPose3DPDFGaussianInf</a> , <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f.html" title="Declares a class that represents a Probability Density Function (PDF) of a 3D pose (6D actually)...">CPose3DPDF</a> )
<a name="l00043"></a>00043 
<a name="l00044"></a>00044         <span class="comment">/** Declares a class that represents a Probability Density function (PDF) of a 3D pose \f$ p(\mathbf{x}) = [x ~ y ~ z ~ yaw ~ pitch ~ roll]^t \f$ as a Gaussian described by its mean and its inverse covariance matrix.</span>
<a name="l00045"></a>00045 <span class="comment">         *</span>
<a name="l00046"></a>00046 <span class="comment">         *   This class implements that PDF using a mono-modal Gaussian distribution in &quot;information&quot; form (inverse covariance matrix).</span>
<a name="l00047"></a>00047 <span class="comment">         *</span>
<a name="l00048"></a>00048 <span class="comment">         *  Uncertainty of pose composition operations (\f$ y = x \oplus u \f$) is implemented in the method &quot;CPose3DPDFGaussianInf::operator+=&quot;.</span>
<a name="l00049"></a>00049 <span class="comment">         *</span>
<a name="l00050"></a>00050 <span class="comment">         *  For further details on implemented methods and the theory behind them,</span>
<a name="l00051"></a>00051 <span class="comment">         *  see &lt;a href=&quot;http://www.mrpt.org/6D_poses:equivalences_compositions_and_uncertainty&quot; &gt;this report&lt;/a&gt;.</span>
<a name="l00052"></a>00052 <span class="comment">         *</span>
<a name="l00053"></a>00053 <span class="comment">         * \sa CPose3D, CPose3DPDF, CPose3DPDFParticles, CPose3DPDFGaussian</span>
<a name="l00054"></a>00054 <span class="comment">         * \ingroup poses_pdf_grp</span>
<a name="l00055"></a>00055 <span class="comment">         */</span>
<a name="l00056"></a>00056         class <a class="code" href="base_2include_2mrpt_2base_2link__pragmas_8h.html#a6045fa0129b1a3d6c8bf895470e66574">BASE_IMPEXP</a> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian_inf.html" title="Declares a class that represents a Probability Density function (PDF) of a 3D pose  as a Gaussian des...">CPose3DPDFGaussianInf</a> : public <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f.html" title="Declares a class that represents a Probability Density Function (PDF) of a 3D pose (6D actually)...">CPose3DPDF</a>
<a name="l00057"></a>00057         {
<a name="l00058"></a>00058                 <span class="comment">// This must be added to any CSerializable derived class:</span>
<a name="l00059"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian_inf.html#ab43d6d71455f85503f21258857adcbc1">00059</a>                 <a class="code" href="_c_serializable_8h.html#a72ab55bf7ae009c89b75715cfa21e84d" title="This declaration must be inserted in all CSerializable classes definition, within the class declarati...">DEFINE_SERIALIZABLE</a>( <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian_inf.html" title="Declares a class that represents a Probability Density function (PDF) of a 3D pose  as a Gaussian des...">CPose3DPDFGaussianInf</a> )
<a name="l00060"></a>00060 
<a name="l00061"></a>00061         protected:<span class="comment"></span>
<a name="l00062"></a>00062 <span class="comment">                /** Assures the symmetry of the covariance matrix (eventually certain operations in the math-coprocessor lead to non-symmetric matrixes!)</span>
<a name="l00063"></a>00063 <span class="comment">                  */</span>
<a name="l00064"></a>00064                 <span class="keywordtype">void</span>  assureSymmetry();
<a name="l00065"></a>00065 
<a name="l00066"></a>00066          public:<span class="comment"></span>
<a name="l00067"></a>00067 <span class="comment">                /** @name Data fields</span>
<a name="l00068"></a>00068 <span class="comment">                        @{   */</span>
<a name="l00069"></a>00069 
<a name="l00070"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian_inf.html#a0780ff6283d03e426947004c517c9792">00070</a>                 <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html" title="A class used to store a 3D pose (a 3D translation + a rotation in 3D).">CPose3D</a>                         <a class="code" href="eigen__plugins_8h.html#a378ef7ee1218e4aa29b595c6e0f8ee4a" title="Computes the mean of the entire matrix.">mean</a>;           <span class="comment">//!&lt; The mean value</span>
<a name="l00071"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian_inf.html#a8f7a64a3fab152f45c505cd8d6c1ab3a">00071</a> <span class="comment"></span>                <a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html">CMatrixDouble66</a>         cov_inv;        <span class="comment">//!&lt; The inverse of the 6x6 covariance matrix</span>
<a name="l00072"></a>00072 <span class="comment"></span><span class="comment"></span>
<a name="l00073"></a>00073 <span class="comment">                /** @} */</span>
<a name="l00074"></a>00074 
<a name="l00075"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian_inf.html#a2b337f0416639d708ebe6a5fc56a833a">00075</a>                 inline const <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html" title="A class used to store a 3D pose (a 3D translation + a rotation in 3D).">CPose3D</a> &amp; getPoseMean()<span class="keyword"> const </span>{ <span class="keywordflow">return</span> <a class="code" href="eigen__plugins_8h.html#a378ef7ee1218e4aa29b595c6e0f8ee4a" title="Computes the mean of the entire matrix.">mean</a>; }
<a name="l00076"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian_inf.html#ab1c015f8f254302f908d6eff0892433b">00076</a>                 <span class="keyword">inline</span>       <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html" title="A class used to store a 3D pose (a 3D translation + a rotation in 3D).">CPose3D</a> &amp; <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian_inf.html#ab1c015f8f254302f908d6eff0892433b">getPoseMean</a>()       { <span class="keywordflow">return</span> <a class="code" href="eigen__plugins_8h.html#a378ef7ee1218e4aa29b595c6e0f8ee4a" title="Computes the mean of the entire matrix.">mean</a>; }
<a name="l00077"></a>00077 <span class="comment"></span>
<a name="l00078"></a>00078 <span class="comment">                 /** Default constructor - mean: all zeros, inverse covariance=all zeros -&gt; so be careful!</span>
<a name="l00079"></a>00079 <span class="comment">                  */</span>
<a name="l00080"></a>00080                 <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian_inf.html" title="Declares a class that represents a Probability Density function (PDF) of a 3D pose  as a Gaussian des...">CPose3DPDFGaussianInf</a>();
<a name="l00081"></a>00081 <span class="comment"></span>
<a name="l00082"></a>00082 <span class="comment">                /** Constructor with a mean value, inverse covariance=all zeros -&gt; so be careful! */</span>
<a name="l00083"></a>00083                 <span class="keyword">explicit</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian_inf.html" title="Declares a class that represents a Probability Density function (PDF) of a 3D pose  as a Gaussian des...">CPose3DPDFGaussianInf</a>( <span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html" title="A class used to store a 3D pose (a 3D translation + a rotation in 3D).">CPose3D</a> &amp;init_Mean );
<a name="l00084"></a>00084 <span class="comment"></span>
<a name="l00085"></a>00085 <span class="comment">                /** Uninitialized constructor: leave all fields uninitialized - Call with UNINITIALIZED_POSE as argument</span>
<a name="l00086"></a>00086 <span class="comment">                  */</span>
<a name="l00087"></a>00087                 <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian_inf.html" title="Declares a class that represents a Probability Density function (PDF) of a 3D pose  as a Gaussian des...">CPose3DPDFGaussianInf</a>(<a class="code" href="namespacemrpt_1_1poses.html#ac46e1fb95d438a441b6f396d9c79f430">TConstructorFlags_Poses</a> constructor_dummy_param);
<a name="l00088"></a>00088 <span class="comment"></span>
<a name="l00089"></a>00089 <span class="comment">                /** Constructor with mean and inv cov. */</span>
<a name="l00090"></a>00090                 <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian_inf.html" title="Declares a class that represents a Probability Density function (PDF) of a 3D pose  as a Gaussian des...">CPose3DPDFGaussianInf</a>( <span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html" title="A class used to store a 3D pose (a 3D translation + a rotation in 3D).">CPose3D</a> &amp;init_Mean, <span class="keyword">const</span> <a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html">CMatrixDouble66</a> &amp;init_CovInv );
<a name="l00091"></a>00091 <span class="comment"></span>
<a name="l00092"></a>00092 <span class="comment">                /** Constructor from a 6D pose PDF described as a Quaternion</span>
<a name="l00093"></a>00093 <span class="comment">                  */</span>
<a name="l00094"></a>00094                 <span class="keyword">explicit</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian_inf.html" title="Declares a class that represents a Probability Density function (PDF) of a 3D pose  as a Gaussian des...">CPose3DPDFGaussianInf</a>( <span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_quat_p_d_f_gaussian.html" title="Declares a class that represents a Probability Density function (PDF) of a 3D pose using a quaternion...">CPose3DQuatPDFGaussian</a> &amp;o);
<a name="l00095"></a>00095 <span class="comment"></span>
<a name="l00096"></a>00096 <span class="comment">                 /** Returns an estimate of the pose, (the mean, or mathematical expectation of the PDF).</span>
<a name="l00097"></a>00097 <span class="comment">                   * \sa getCovariance</span>
<a name="l00098"></a>00098 <span class="comment">                   */</span>
<a name="l00099"></a>00099                 <span class="keywordtype">void</span> getMean(<a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html" title="A class used to store a 3D pose (a 3D translation + a rotation in 3D).">CPose3D</a> &amp;mean_pose) <span class="keyword">const</span>;
<a name="l00100"></a>00100 <span class="comment"></span>
<a name="l00101"></a>00101 <span class="comment">                /** Returns an estimate of the pose covariance matrix (6x6 cov matrix) and the mean, both at once.</span>
<a name="l00102"></a>00102 <span class="comment">                  * \sa getMean</span>
<a name="l00103"></a>00103 <span class="comment">                  */</span>
<a name="l00104"></a>00104                 <span class="keywordtype">void</span> getCovarianceAndMean(<a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html">CMatrixDouble66</a> &amp;<a class="code" href="namespacemrpt_1_1math.html#a43f4e051fc574fd75b6800ad4fb25037" title="Computes the covariance matrix from a list of samples in an NxM matrix, where each row is a sample...">cov</a>,<a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html" title="A class used to store a 3D pose (a 3D translation + a rotation in 3D).">CPose3D</a> &amp;mean_point) <span class="keyword">const</span>;
<a name="l00105"></a>00105 <span class="comment"></span>
<a name="l00106"></a>00106 <span class="comment">                /** Copy operator, translating if necesary (for example, between particles and gaussian representations)</span>
<a name="l00107"></a>00107 <span class="comment">                  */</span>
<a name="l00108"></a>00108                 <span class="keywordtype">void</span>  copyFrom(<span class="keyword">const</span> CPose3DPDF &amp;o);
<a name="l00109"></a>00109 <span class="comment"></span>
<a name="l00110"></a>00110 <span class="comment">                /** Copy operator, translating if necesary (for example, between particles and gaussian representations)</span>
<a name="l00111"></a>00111 <span class="comment">                  */</span>
<a name="l00112"></a>00112                 <span class="keywordtype">void</span>  copyFrom(<span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose_p_d_f.html" title="Declares a class that represents a probability density function (pdf) of a 2D pose (x...">CPosePDF</a> &amp;o);
<a name="l00113"></a>00113 <span class="comment"></span>
<a name="l00114"></a>00114 <span class="comment">                /** Copy from a 6D pose PDF described as a Quaternion</span>
<a name="l00115"></a>00115 <span class="comment">                  */</span>
<a name="l00116"></a>00116                 <span class="keywordtype">void</span> copyFrom( <span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_quat_p_d_f_gaussian.html" title="Declares a class that represents a Probability Density function (PDF) of a 3D pose using a quaternion...">CPose3DQuatPDFGaussian</a> &amp;o);
<a name="l00117"></a>00117 <span class="comment"></span>
<a name="l00118"></a>00118 <span class="comment">                /** Save the PDF to a text file, containing the 3D pose in the first line, then the covariance matrix in next 3 lines.</span>
<a name="l00119"></a>00119 <span class="comment">                 */</span>
<a name="l00120"></a>00120                 <span class="keywordtype">void</span>  <a class="code" href="eigen__plugins_8h.html#abea6659e38ab7a50b625ea1a4af3ec72" title="Save matrix to a text file, compatible with MATLAB text format (see also the methods of matrix classe...">saveToTextFile</a>(<span class="keyword">const</span> <a class="code" href="classstd_1_1string.html" title="STL class.">std::string</a> &amp;file) <span class="keyword">const</span>;
<a name="l00121"></a>00121 <span class="comment"></span>
<a name="l00122"></a>00122 <span class="comment">                /** This can be used to convert a PDF from local coordinates to global, providing the point (newReferenceBase) from which</span>
<a name="l00123"></a>00123 <span class="comment">                  *   &quot;to project&quot; the current pdf. Result PDF substituted the currently stored one in the object.</span>
<a name="l00124"></a>00124 <span class="comment">                  */</span>
<a name="l00125"></a>00125                 <span class="keywordtype">void</span>  changeCoordinatesReference(  <span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html" title="A class used to store a 3D pose (a 3D translation + a rotation in 3D).">CPose3D</a> &amp;newReferenceBase );
<a name="l00126"></a>00126 <span class="comment"></span>
<a name="l00127"></a>00127 <span class="comment">                /** Draws a single sample from the distribution</span>
<a name="l00128"></a>00128 <span class="comment">                  */</span>
<a name="l00129"></a>00129                 <span class="keywordtype">void</span>  drawSingleSample( <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html" title="A class used to store a 3D pose (a 3D translation + a rotation in 3D).">CPose3D</a> &amp;outPart ) <span class="keyword">const</span>;
<a name="l00130"></a>00130 <span class="comment"></span>
<a name="l00131"></a>00131 <span class="comment">                /** Draws a number of samples from the distribution, and saves as a list of 1x6 vectors, where each row contains a (x,y,phi) datum.</span>
<a name="l00132"></a>00132 <span class="comment">                  */</span>
<a name="l00133"></a>00133                 <span class="keywordtype">void</span>  drawManySamples( <span class="keywordtype">size_t</span> N, <a class="code" href="classstd_1_1vector.html">std::vector&lt;vector_double&gt;</a> &amp; outSamples ) <span class="keyword">const</span>;
<a name="l00134"></a>00134 <span class="comment"></span>
<a name="l00135"></a>00135 <span class="comment">                /** Bayesian fusion of two points gauss. distributions, then save the result in this object.</span>
<a name="l00136"></a>00136 <span class="comment">                  *  The process is as follows:&lt;br&gt;</span>
<a name="l00137"></a>00137 <span class="comment">                  *             - (x1,S1): Mean and variance of the p1 distribution.</span>
<a name="l00138"></a>00138 <span class="comment">                  *             - (x2,S2): Mean and variance of the p2 distribution.</span>
<a name="l00139"></a>00139 <span class="comment">                  *             - (x,S): Mean and variance of the resulting distribution.</span>
<a name="l00140"></a>00140 <span class="comment">                  *</span>
<a name="l00141"></a>00141 <span class="comment">                  *    S = (S1&lt;sup&gt;-1&lt;/sup&gt; + S2&lt;sup&gt;-1&lt;/sup&gt;)&lt;sup&gt;-1&lt;/sup&gt;;</span>
<a name="l00142"></a>00142 <span class="comment">                  *    x = S * ( S1&lt;sup&gt;-1&lt;/sup&gt;*x1 + S2&lt;sup&gt;-1&lt;/sup&gt;*x2 );</span>
<a name="l00143"></a>00143 <span class="comment">                  */</span>
<a name="l00144"></a>00144                 <span class="keywordtype">void</span>  bayesianFusion( <span class="keyword">const</span> CPose3DPDF &amp;p1, <span class="keyword">const</span> CPose3DPDF &amp;p2 );
<a name="l00145"></a>00145 <span class="comment"></span>
<a name="l00146"></a>00146 <span class="comment">                /** Returns a new PDF such as: NEW_PDF = (0,0,0) - THIS_PDF</span>
<a name="l00147"></a>00147 <span class="comment">                  */</span>
<a name="l00148"></a>00148                 <span class="keywordtype">void</span>     inverse(CPose3DPDF &amp;o) <span class="keyword">const</span>;
<a name="l00149"></a>00149 <span class="comment"></span>
<a name="l00150"></a>00150 <span class="comment">                /** Unary - operator, returns the PDF of the inverse pose.  */</span>
<a name="l00151"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian_inf.html#a016877d2d548a52df0ade53e21f3455a">00151</a>                 <span class="keyword">inline</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian_inf.html" title="Declares a class that represents a Probability Density function (PDF) of a 3D pose  as a Gaussian des...">CPose3DPDFGaussianInf</a> <a class="code" href="namespacemrpt_1_1poses.html#a678c1606b35876eae036755599a22d84" title="Unary - operator: return the inverse pose &quot;-p&quot; (Note that is NOT the same than a pose with negative x...">operator -</a>()<span class="keyword"> const</span>
<a name="l00152"></a>00152 <span class="keyword">                </span>{
<a name="l00153"></a>00153                         <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian_inf.html" title="Declares a class that represents a Probability Density function (PDF) of a 3D pose  as a Gaussian des...">CPose3DPDFGaussianInf</a> p(<a class="code" href="namespacemrpt_1_1poses.html#ac46e1fb95d438a441b6f396d9c79f430aefbfdff7ad639a9a8019af9de5f3c592">UNINITIALIZED_POSE</a>);
<a name="l00154"></a>00154                         this-&gt;inverse(p);
<a name="l00155"></a>00155                         <span class="keywordflow">return</span> p;
<a name="l00156"></a>00156                 }
<a name="l00157"></a>00157 <span class="comment"></span>
<a name="l00158"></a>00158 <span class="comment">                /** Makes: thisPDF = thisPDF + Ap, where &quot;+&quot; is pose composition (both the mean, and the covariance matrix are updated).</span>
<a name="l00159"></a>00159 <span class="comment">                  */</span>
<a name="l00160"></a>00160                 <span class="keywordtype">void</span>  <a class="code" href="group__container__ops__grp.html#ga28127b8dfe78fea7644c4f2a3517cdef" title="a+=b (element-wise sum)">operator += </a>( <span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html" title="A class used to store a 3D pose (a 3D translation + a rotation in 3D).">CPose3D</a> &amp;Ap);
<a name="l00161"></a>00161 <span class="comment"></span>
<a name="l00162"></a>00162 <span class="comment">                /** Makes: thisPDF = thisPDF + Ap, where &quot;+&quot; is pose composition (both the mean, and the covariance matrix are updated).</span>
<a name="l00163"></a>00163 <span class="comment">                  */</span>
<a name="l00164"></a>00164                 <span class="keywordtype">void</span>  <a class="code" href="group__container__ops__grp.html#ga28127b8dfe78fea7644c4f2a3517cdef" title="a+=b (element-wise sum)">operator += </a>( <span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian_inf.html" title="Declares a class that represents a Probability Density function (PDF) of a 3D pose  as a Gaussian des...">CPose3DPDFGaussianInf</a> &amp;Ap);
<a name="l00165"></a>00165 <span class="comment"></span>
<a name="l00166"></a>00166 <span class="comment">                /** Makes: thisPDF = thisPDF - Ap, where &quot;-&quot; is pose inverse composition (both the mean, and the covariance matrix are updated).</span>
<a name="l00167"></a>00167 <span class="comment">                  */</span>
<a name="l00168"></a>00168                 <span class="keywordtype">void</span>  operator -= ( <span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian_inf.html" title="Declares a class that represents a Probability Density function (PDF) of a 3D pose  as a Gaussian des...">CPose3DPDFGaussianInf</a> &amp;Ap);
<a name="l00169"></a>00169 <span class="comment"></span>
<a name="l00170"></a>00170 <span class="comment">                /** Evaluates the PDF at a given point.</span>
<a name="l00171"></a>00171 <span class="comment">                  */</span>
<a name="l00172"></a>00172                 <span class="keywordtype">double</span>  evaluatePDF( <span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html" title="A class used to store a 3D pose (a 3D translation + a rotation in 3D).">CPose3D</a> &amp;x ) <span class="keyword">const</span>;
<a name="l00173"></a>00173 <span class="comment"></span>
<a name="l00174"></a>00174 <span class="comment">                /** Evaluates the ratio PDF(x) / PDF(MEAN), that is, the normalized PDF in the range [0,1].</span>
<a name="l00175"></a>00175 <span class="comment">                  */</span>
<a name="l00176"></a>00176                 <span class="keywordtype">double</span>  evaluateNormalizedPDF( <span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html" title="A class used to store a 3D pose (a 3D translation + a rotation in 3D).">CPose3D</a> &amp;x ) <span class="keyword">const</span>;
<a name="l00177"></a>00177 <span class="comment"></span>
<a name="l00178"></a>00178 <span class="comment">                /** Computes the Mahalanobis distance between the centers of two Gaussians.</span>
<a name="l00179"></a>00179 <span class="comment">                  *  The variables with a variance exactly equal to 0 are not taken into account in the process, but</span>
<a name="l00180"></a>00180 <span class="comment">                  *   &quot;infinity&quot; is returned if the corresponding elements are not exactly equal.</span>
<a name="l00181"></a>00181 <span class="comment">                  */</span>
<a name="l00182"></a>00182                 <span class="keywordtype">double</span>  mahalanobisDistanceTo( <span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian_inf.html" title="Declares a class that represents a Probability Density function (PDF) of a 3D pose  as a Gaussian des...">CPose3DPDFGaussianInf</a>&amp; theOther);
<a name="l00183"></a>00183 <span class="comment"></span>
<a name="l00184"></a>00184 <span class="comment">                /** This static method computes the pose composition Jacobians, with these formulas:</span>
<a name="l00185"></a>00185 <span class="comment">                        \code</span>
<a name="l00186"></a>00186 <span class="comment">                                df_dx =</span>
<a name="l00187"></a>00187 <span class="comment">                                [ 1, 0, 0, -sin(yaw)*cos(p)*xu+(-sin(yaw)*sin(p)*sin(r)-cos(yaw)*cos(r))*yu+(-sin(yaw)*sin(p)*cos(r)+cos(yaw)*sin(r))*zu, -cos(yaw)*sin(p)*xu+cos(yaw)*cos(p)*sin(r)*yu+cos(yaw)*cos(p)*cos(r)*zu, (cos(yaw)*sin(p)*cos(r)+sin(yaw)*sin(r))*yu+(-cos(yaw)*sin(p)*sin(r)+sin(yaw)*cos(r))*zu]</span>
<a name="l00188"></a>00188 <span class="comment">                                [ 0, 1, 0,    cos(yaw)*cos(p)*xu+(cos(yaw)*sin(p)*sin(r)-sin(yaw)*cos(r))*yu+(cos(yaw)*sin(p)*cos(r)+sin(yaw)*sin(r))*zu, -sin(yaw)*sin(p)*xu+sin(yaw)*cos(p)*sin(r)*yu+sin(yaw)*cos(p)*cos(r)*zu, (sin(yaw)*sin(p)*cos(r)-cos(yaw)*sin(r))*yu+(-sin(yaw)*sin(p)*sin(r)-cos(yaw)*cos(r))*zu]</span>
<a name="l00189"></a>00189 <span class="comment">                                [ 0, 0, 1,                                                                                                             0, -cos(p)*xu-sin(p)*sin(r)*yu-sin(p)*cos(r)*zu,                            cos(p)*cos(r)*yu-cos(p)*sin(r)*zu]</span>
<a name="l00190"></a>00190 <span class="comment">                                [ 0, 0, 0, 1, 0, 0]</span>
<a name="l00191"></a>00191 <span class="comment">                                [ 0, 0, 0, 0, 1, 0]</span>
<a name="l00192"></a>00192 <span class="comment">                                [ 0, 0, 0, 0, 0, 1]</span>
<a name="l00193"></a>00193 <span class="comment"></span>
<a name="l00194"></a>00194 <span class="comment">                                df_du =</span>
<a name="l00195"></a>00195 <span class="comment">                                [ cos(yaw)*cos(p), cos(yaw)*sin(p)*sin(r)-sin(yaw)*cos(r), cos(yaw)*sin(p)*cos(r)+sin(yaw)*sin(r), 0, 0, 0]</span>
<a name="l00196"></a>00196 <span class="comment">                                [ sin(yaw)*cos(p), sin(yaw)*sin(p)*sin(r)+cos(yaw)*cos(r), sin(yaw)*sin(p)*cos(r)-cos(yaw)*sin(r), 0, 0, 0]</span>
<a name="l00197"></a>00197 <span class="comment">                                [ -sin(p),         cos(p)*sin(r),                          cos(p)*cos(r),                          0, 0, 0]</span>
<a name="l00198"></a>00198 <span class="comment">                                [ 0, 0, 0, 1, 0, 0]</span>
<a name="l00199"></a>00199 <span class="comment">                                [ 0, 0, 0, 0, 1, 0]</span>
<a name="l00200"></a>00200 <span class="comment">                                [ 0, 0, 0, 0, 0, 1]</span>
<a name="l00201"></a>00201 <span class="comment">                        \endcode</span>
<a name="l00202"></a>00202 <span class="comment">                  */</span>
<a name="l00203"></a>00203                 <span class="keyword">static</span> <span class="keywordtype">void</span> jacobiansPoseComposition(
<a name="l00204"></a>00204                         <span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html" title="A class used to store a 3D pose (a 3D translation + a rotation in 3D).">CPose3D</a> &amp;x,
<a name="l00205"></a>00205                         <span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html" title="A class used to store a 3D pose (a 3D translation + a rotation in 3D).">CPose3D</a> &amp;u,
<a name="l00206"></a>00206                         <a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html">CMatrixDouble66</a>  &amp;df_dx,
<a name="l00207"></a>00207                         <a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html">CMatrixDouble66</a>  &amp;df_du);
<a name="l00208"></a>00208 <span class="comment"></span>
<a name="l00209"></a>00209 <span class="comment">                /** Returns a 3x3 matrix with submatrix of the inverse covariance for the variables (x,y,yaw) only.</span>
<a name="l00210"></a>00210 <span class="comment">                  */</span>
<a name="l00211"></a>00211                 <span class="keywordtype">void</span> getInvCovSubmatrix2D( <a class="code" href="classmrpt_1_1math_1_1_c_matrix_template_numeric.html" title="A matrix of dynamic size.">CMatrixDouble</a> &amp;out_cov ) <span class="keyword">const</span>;
<a name="l00212"></a>00212 
<a name="l00213"></a>00213         }; <span class="comment">// End of class def.</span>
<a name="l00214"></a>00214 
<a name="l00215"></a>00215 <span class="comment"></span>
<a name="l00216"></a>00216 <span class="comment">        /** Pose composition for two 3D pose Gaussians  \sa CPose3DPDFGaussian::operator +=  */</span>
<a name="l00217"></a><a class="code" href="namespacemrpt_1_1poses.html#a6b249b103a8090c7ab4952707b7c32b0">00217</a>         <span class="keyword">inline</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian_inf.html" title="Declares a class that represents a Probability Density function (PDF) of a 3D pose  as a Gaussian des...">CPose3DPDFGaussianInf</a> <a class="code" href="namespacemrpt_1_1poses.html#afb287beee02202a14b09f1011b648e6f" title="Compose a 2D point from a new coordinate base given by a 2D pose.">operator +</a>( <span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian_inf.html" title="Declares a class that represents a Probability Density function (PDF) of a 3D pose  as a Gaussian des...">CPose3DPDFGaussianInf</a> &amp;x, <span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian_inf.html" title="Declares a class that represents a Probability Density function (PDF) of a 3D pose  as a Gaussian des...">CPose3DPDFGaussianInf</a> &amp;u )
<a name="l00218"></a>00218         {
<a name="l00219"></a>00219                 <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian_inf.html" title="Declares a class that represents a Probability Density function (PDF) of a 3D pose  as a Gaussian des...">CPose3DPDFGaussianInf</a>   res(x);
<a name="l00220"></a>00220                 res+=u;
<a name="l00221"></a>00221                 <span class="keywordflow">return</span> res;
<a name="l00222"></a>00222         }
<a name="l00223"></a>00223 <span class="comment"></span>
<a name="l00224"></a>00224 <span class="comment">        /** Pose composition for two 3D pose Gaussians  \sa CPose3DPDFGaussianInf::operator -=  */</span>
<a name="l00225"></a><a class="code" href="namespacemrpt_1_1poses.html#ace6b981a60627ffccea2edb22f8bdefb">00225</a>         <span class="keyword">inline</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian_inf.html" title="Declares a class that represents a Probability Density function (PDF) of a 3D pose  as a Gaussian des...">CPose3DPDFGaussianInf</a> <a class="code" href="namespacemrpt_1_1poses.html#a678c1606b35876eae036755599a22d84" title="Unary - operator: return the inverse pose &quot;-p&quot; (Note that is NOT the same than a pose with negative x...">operator -</a>( <span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian_inf.html" title="Declares a class that represents a Probability Density function (PDF) of a 3D pose  as a Gaussian des...">CPose3DPDFGaussianInf</a> &amp;x, <span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian_inf.html" title="Declares a class that represents a Probability Density function (PDF) of a 3D pose  as a Gaussian des...">CPose3DPDFGaussianInf</a> &amp;u )
<a name="l00226"></a>00226         {
<a name="l00227"></a>00227                 <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian_inf.html" title="Declares a class that represents a Probability Density function (PDF) of a 3D pose  as a Gaussian des...">CPose3DPDFGaussianInf</a>   res(x);
<a name="l00228"></a>00228                 res-=u;
<a name="l00229"></a>00229                 <span class="keywordflow">return</span> res;
<a name="l00230"></a>00230         }
<a name="l00231"></a>00231 <span class="comment"></span>
<a name="l00232"></a>00232 <span class="comment">        /** Dumps the mean and covariance matrix to a text stream.</span>
<a name="l00233"></a>00233 <span class="comment">          */</span>
<a name="l00234"></a>00234         std::ostream  <a class="code" href="base_2include_2mrpt_2base_2link__pragmas_8h.html#a6045fa0129b1a3d6c8bf895470e66574">BASE_IMPEXP</a> &amp; <a class="code" href="namespacemrpt_1_1poses.html#aa4247c4d793d20edb770e56f22b286f1" title="Dumps a point as a string [x,y] or [x,y,z].">operator &lt;&lt; </a>(<a class="code" href="classstd_1_1ostream.html" title="STL class.">std::ostream</a> &amp; out, <span class="keyword">const</span> CPose3DPDFGaussianInf&amp; obj);
<a name="l00235"></a>00235 
<a name="l00236"></a>00236         <span class="keywordtype">bool</span> <a class="code" href="base_2include_2mrpt_2base_2link__pragmas_8h.html#a6045fa0129b1a3d6c8bf895470e66574">BASE_IMPEXP</a> <a class="code" href="namespacemrpt_1_1poses.html#acd8c946fdfab1501027f3a9347181ebf">operator==</a>(<span class="keyword">const</span> CPose3DPDFGaussianInf &amp;p1,<span class="keyword">const</span> CPose3DPDFGaussianInf &amp;p2);
<a name="l00237"></a>00237 
<a name="l00238"></a>00238         } <span class="comment">// End of namespace</span>
<a name="l00239"></a>00239 } <span class="comment">// End of namespace</span>
<a name="l00240"></a>00240 
<a name="l00241"></a>00241 <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>