Sophie

Sophie

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

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>bundle_adjustment.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">bundle_adjustment.h</div>  </div>
</div>
<div class="contents">
<a href="bundle__adjustment_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 
<a name="l00029"></a>00029 <span class="preprocessor">#ifndef mrpt_vision_ba_H</span>
<a name="l00030"></a>00030 <span class="preprocessor"></span><span class="preprocessor">#define mrpt_vision_ba_H</span>
<a name="l00031"></a>00031 <span class="preprocessor"></span>
<a name="l00032"></a>00032 <span class="preprocessor">#include &lt;<a class="code" href="vision_2include_2mrpt_2vision_2types_8h.html">mrpt/vision/types.h</a>&gt;</span>
<a name="l00033"></a>00033 <span class="preprocessor">#include &lt;<a class="code" href="_t_camera_8h.html">mrpt/utils/TCamera.h</a>&gt;</span>
<a name="l00034"></a>00034 <span class="preprocessor">#include &lt;<a class="code" href="_t_parameters_8h.html">mrpt/utils/TParameters.h</a>&gt;</span>
<a name="l00035"></a>00035 <span class="preprocessor">#include &lt;<a class="code" href="lightweight__geom__data_8h.html">mrpt/math/lightweight_geom_data.h</a>&gt;</span>
<a name="l00036"></a>00036 
<a name="l00037"></a>00037 <span class="comment">// The methods declared in this file are implemented in separate files in: vision/src/ba_*.cpp</span>
<a name="l00038"></a>00038 <span class="keyword">namespace </span>mrpt
<a name="l00039"></a>00039 {
<a name="l00040"></a><a class="code" href="namespacemrpt_1_1vision.html">00040</a>         <span class="keyword">namespace </span>vision
<a name="l00041"></a>00041         {
<a name="l00042"></a>00042                 <span class="keyword">using</span> mrpt<a class="code" href="structmrpt_1_1math_1_1_t_pose3_d.html" title="Lightweight 3D pose (three spatial coordinates, plus three angular coordinates).">::math::TPose3D</a>;
<a name="l00043"></a>00043                 <span class="keyword">using</span> mrpt<a class="code" href="structmrpt_1_1math_1_1_t_point3_d.html" title="Lightweight 3D point.">::math::TPoint3D</a>;
<a name="l00044"></a>00044                 <span class="keyword">using</span> mrpt<a class="code" href="classmrpt_1_1utils_1_1_t_camera.html" title="Structure to hold the parameters of a pinhole camera model.">::utils::TCamera</a>;
<a name="l00045"></a>00045 <span class="comment"></span>
<a name="l00046"></a>00046 <span class="comment">                /** \defgroup bundle_adj Bundle-Adjustment methods </span>
<a name="l00047"></a>00047 <span class="comment">                  * \ingroup mrpt_vision_grp</span>
<a name="l00048"></a>00048 <span class="comment">                  */</span>
<a name="l00049"></a>00049 
<a name="l00050"></a>00050 <span class="comment"></span>
<a name="l00051"></a>00051 <span class="comment">                /** @name Bundle-Adjustment methods</span>
<a name="l00052"></a>00052 <span class="comment">                    @{ */</span>
<a name="l00053"></a>00053 <span class="comment"></span>
<a name="l00054"></a>00054 <span class="comment">                /** A functor type for BA methods \sa bundle_adj_full */</span>
<a name="l00055"></a><a class="code" href="namespacemrpt_1_1vision.html#a7e12f372278c656321223eec4aced3fb">00055</a>                 <span class="keyword">typedef</span> void (*<a class="code" href="namespacemrpt_1_1vision.html#a7e12f372278c656321223eec4aced3fb" title="A functor type for BA methods.">TBundleAdjustmentFeedbackFunctor</a>)(
<a name="l00056"></a>00056                         <span class="keyword">const</span> <span class="keywordtype">size_t</span> cur_iter,
<a name="l00057"></a>00057                         <span class="keyword">const</span> <span class="keywordtype">double</span> cur_total_sq_error,
<a name="l00058"></a>00058                         <span class="keyword">const</span> <span class="keywordtype">size_t</span> max_iters,
<a name="l00059"></a>00059                         <span class="keyword">const</span> mrpt<a class="code" href="structmrpt_1_1vision_1_1_t_sequence_feature_observations.html" title="A complete sequence of observations of features from different camera frames (poses).">::vision::TSequenceFeatureObservations</a> &amp; input_observations,
<a name="l00060"></a>00060                         <span class="keyword">const</span> mrpt<a class="code" href="classstd_1_1vector.html" title="STL class.">::vision::TFramePosesVec</a> &amp; current_frame_estimate,
<a name="l00061"></a>00061                         <span class="keyword">const</span> mrpt<a class="code" href="classstd_1_1vector.html">::vision::TLandmarkLocationsVec</a> &amp; current_landmark_estimate );
<a name="l00062"></a>00062 
<a name="l00063"></a>00063 <span class="comment"></span>
<a name="l00064"></a>00064 <span class="comment">                /** Sparse Levenberg-Marquart solution to bundle adjustment - optimizes all the camera frames &amp; the landmark locations.</span>
<a name="l00065"></a>00065 <span class="comment">                  * At input a gross estimation of the frame poses &amp; the landmark points must be supplied. If you don&#39;t have such a</span>
<a name="l00066"></a>00066 <span class="comment">                  *  starting point, use mrpt::vision::ba_initial_estimate() to compute it.</span>
<a name="l00067"></a>00067 <span class="comment">                  *</span>
<a name="l00068"></a>00068 <span class="comment">                  * At output the best found solution will be returned in the variables. Optionally, a functor can be passed for having</span>
<a name="l00069"></a>00069 <span class="comment">                  *  feedback on the progress at each iteration (you can use it to refresh a GUI, display a progress bar, etc...).</span>
<a name="l00070"></a>00070 <span class="comment">                  *</span>
<a name="l00071"></a>00071 <span class="comment">                  * This implementation is almost entirely an adapted version from RobotVision (at OpenSLAM.org) (C) by Hauke Strasdat (Imperial College London), licensed under GNU LGPL.</span>
<a name="l00072"></a>00072 <span class="comment">                  *  See the related paper:  H. Strasdat, J.M.M. Montiel, A.J. Davison: &quot;Scale Drift-Aware Large Scale Monocular SLAM&quot;, RSS2010, http://www.roboticsproceedings.org/rss06/p10.html</span>
<a name="l00073"></a>00073 <span class="comment">                  *</span>
<a name="l00074"></a>00074 <span class="comment">                  *  List of optional parameters in &quot;extra_params&quot;:</span>
<a name="l00075"></a>00075 <span class="comment">                  *             - &quot;verbose&quot; : Verbose output (default=0)</span>
<a name="l00076"></a>00076 <span class="comment">                  *             - &quot;max_iterations&quot;: Maximum number of iterations to run (default=50)</span>
<a name="l00077"></a>00077 <span class="comment">                  *             - &quot;robust_kernel&quot;: If !=0, use a robust kernel against outliers (default=1)</span>
<a name="l00078"></a>00078 <span class="comment">                  *             - &quot;kernel_param&quot;: The pseudo-huber kernel parameter (default=3)</span>
<a name="l00079"></a>00079 <span class="comment">                  *             - &quot;mu&quot;: Initial mu for LevMarq (default=-1 -&gt; autoguess)</span>
<a name="l00080"></a>00080 <span class="comment">                  *             - &quot;num_fix_frames&quot;: Number of first frame poses to don&#39;t optimize (keep unmodified as they come in)  (default=1: the first pose is the reference and is not modified)</span>
<a name="l00081"></a>00081 <span class="comment">                  *             - &quot;num_fix_points&quot;: Idem, for the landmarks positions (default=0: optimize all)</span>
<a name="l00082"></a>00082 <span class="comment">                  *             - &quot;profiler&quot;: If !=0, displays profiling information to the console at return.</span>
<a name="l00083"></a>00083 <span class="comment">                  *</span>
<a name="l00084"></a>00084 <span class="comment">                  * \note In this function, all coordinates are absolute. Camera frames are such that +Z points forward from the focal point (see the figure in mrpt::slam::CObservationImage).</span>
<a name="l00085"></a>00085 <span class="comment">                  * \note The first frame pose will be not updated since at least one frame must remain fixed.</span>
<a name="l00086"></a>00086 <span class="comment">                  *</span>
<a name="l00087"></a>00087 <span class="comment">                  * \param observations [IN] All the feature observations (WITHOUT distortion), indexed by feature ID as lists of &lt;frame_ID, (x,y)&gt;. See TSequenceFeatureObservations.</span>
<a name="l00088"></a>00088 <span class="comment">                  * \param camera_params [IN] The camera parameters, mainly used for the intrinsic 3x3 matrix. Distortion params are ignored since it&#39;s assumed that \a observations are already undistorted pixels.</span>
<a name="l00089"></a>00089 <span class="comment">                  * \param frame_poses [IN/OUT] Input: Gross estimation of each frame poses. Output: The found optimal solution.</span>
<a name="l00090"></a>00090 <span class="comment">                  * \param landmark_points [IN/OUT] Input: Gross estimation of each landmark point. Output: The found optimal solution.</span>
<a name="l00091"></a>00091 <span class="comment">                  * \param extra_params [IN] Optional extra parameters. Read above.</span>
<a name="l00092"></a>00092 <span class="comment">                  * \param user_feedback [IN] If provided, this functor will be called at each iteration to provide a feedback to the user.</span>
<a name="l00093"></a>00093 <span class="comment">                  *</span>
<a name="l00094"></a>00094 <span class="comment">                  * \return The final overall squared error.</span>
<a name="l00095"></a>00095 <span class="comment">                  * \ingroup bundle_adj</span>
<a name="l00096"></a>00096 <span class="comment">                  */</span>
<a name="l00097"></a>00097                 <span class="keywordtype">double</span> <a class="code" href="vision_2include_2mrpt_2vision_2link__pragmas_8h.html#aa4a17fb846aac61f4e57b17b6f784559">VISION_IMPEXP</a> <a class="code" href="group__bundle__adj.html#gabb5e8247d164906bce57a3c05b001953" title="Sparse Levenberg-Marquart solution to bundle adjustment - optimizes all the camera frames &amp; the landm...">bundle_adj_full</a>(
<a name="l00098"></a>00098                         <span class="keyword">const</span> <a class="code" href="structmrpt_1_1vision_1_1_t_sequence_feature_observations.html" title="A complete sequence of observations of features from different camera frames (poses).">mrpt::vision::TSequenceFeatureObservations</a>   &amp; observations,
<a name="l00099"></a>00099                         <span class="keyword">const</span> <a class="code" href="classmrpt_1_1utils_1_1_t_camera.html" title="Structure to hold the parameters of a pinhole camera model.">mrpt::utils::TCamera</a>                        &amp; camera_params,
<a name="l00100"></a>00100                         <a class="code" href="classstd_1_1vector.html" title="STL class.">mrpt::vision::TFramePosesVec</a>                       &amp; frame_poses,
<a name="l00101"></a>00101                         <a class="code" href="classstd_1_1vector.html">mrpt::vision::TLandmarkLocationsVec</a>                &amp; landmark_points,
<a name="l00102"></a>00102                         <span class="keyword">const</span> <a class="code" href="structmrpt_1_1utils_1_1_t_parameters.html" title="For usage when passing a dynamic number of (numeric) arguments to a function, by name.">mrpt::utils::TParametersDouble</a> &amp; extra_params = <a class="code" href="structmrpt_1_1utils_1_1_t_parameters.html" title="For usage when passing a dynamic number of (numeric) arguments to a function, by name.">mrpt::utils::TParametersDouble</a>(),
<a name="l00103"></a>00103                         <span class="keyword">const</span> <a class="code" href="namespacemrpt_1_1vision.html#a7e12f372278c656321223eec4aced3fb" title="A functor type for BA methods.">mrpt::vision::TBundleAdjustmentFeedbackFunctor</a> user_feedback = NULL
<a name="l00104"></a>00104                         );
<a name="l00105"></a>00105 
<a name="l00106"></a>00106 <span class="comment"></span>
<a name="l00107"></a>00107 <span class="comment">                /** @} */</span>
<a name="l00108"></a>00108 
<a name="l00109"></a>00109 <span class="comment"></span>
<a name="l00110"></a>00110 <span class="comment">                /** @name Bundle-Adjustment Auxiliary methods</span>
<a name="l00111"></a>00111 <span class="comment">                    @{ */</span>
<a name="l00112"></a>00112 <span class="comment"></span>
<a name="l00113"></a>00113 <span class="comment">                /** Fills the frames &amp; landmark points maps with an initial gross estimate from the sequence \a observations, so they can be fed to bundle adjustment methods.</span>
<a name="l00114"></a>00114 <span class="comment">                  * \sa bundle_adj_full</span>
<a name="l00115"></a>00115 <span class="comment">                  * \ingroup bundle_adj</span>
<a name="l00116"></a>00116 <span class="comment">                  */</span>
<a name="l00117"></a>00117                 <span class="keywordtype">void</span> <a class="code" href="vision_2include_2mrpt_2vision_2link__pragmas_8h.html#aa4a17fb846aac61f4e57b17b6f784559">VISION_IMPEXP</a> <a class="code" href="group__bundle__adj.html#ga3d11e2afc4d575bacd1699f9ba0f479a" title="Fills the frames &amp; landmark points maps with an initial gross estimate from the sequence observations...">ba_initial_estimate</a>(
<a name="l00118"></a>00118                         <span class="keyword">const</span> <a class="code" href="structmrpt_1_1vision_1_1_t_sequence_feature_observations.html" title="A complete sequence of observations of features from different camera frames (poses).">mrpt::vision::TSequenceFeatureObservations</a>   &amp; observations,
<a name="l00119"></a>00119                         <span class="keyword">const</span> <a class="code" href="classmrpt_1_1utils_1_1_t_camera.html" title="Structure to hold the parameters of a pinhole camera model.">mrpt::utils::TCamera</a>                        &amp; camera_params,
<a name="l00120"></a>00120                         <a class="code" href="classstd_1_1vector.html" title="STL class.">mrpt::vision::TFramePosesVec</a>                       &amp; frame_poses,
<a name="l00121"></a>00121                         <a class="code" href="classstd_1_1vector.html">mrpt::vision::TLandmarkLocationsVec</a>                &amp; landmark_points );
<a name="l00122"></a>00122 <span class="comment"></span>
<a name="l00123"></a>00123 <span class="comment">                //! \overload</span>
<a name="l00124"></a>00124 <span class="comment"></span>                <span class="keywordtype">void</span> <a class="code" href="vision_2include_2mrpt_2vision_2link__pragmas_8h.html#aa4a17fb846aac61f4e57b17b6f784559">VISION_IMPEXP</a> <a class="code" href="group__bundle__adj.html#ga3d11e2afc4d575bacd1699f9ba0f479a" title="Fills the frames &amp; landmark points maps with an initial gross estimate from the sequence observations...">ba_initial_estimate</a>(
<a name="l00125"></a>00125                         <span class="keyword">const</span> <a class="code" href="structmrpt_1_1vision_1_1_t_sequence_feature_observations.html" title="A complete sequence of observations of features from different camera frames (poses).">mrpt::vision::TSequenceFeatureObservations</a>   &amp; observations,
<a name="l00126"></a>00126                         <span class="keyword">const</span> <a class="code" href="classmrpt_1_1utils_1_1_t_camera.html" title="Structure to hold the parameters of a pinhole camera model.">mrpt::utils::TCamera</a>                        &amp; camera_params,
<a name="l00127"></a>00127                         <a class="code" href="classstd_1_1map.html" title="STL class.">mrpt::vision::TFramePosesMap</a>                       &amp; frame_poses,
<a name="l00128"></a>00128                         <a class="code" href="classstd_1_1map.html" title="STL class.">mrpt::vision::TLandmarkLocationsMap</a>                &amp; landmark_points );
<a name="l00129"></a>00129 
<a name="l00130"></a>00130 <span class="comment"></span>
<a name="l00131"></a>00131 <span class="comment">                /** Compute reprojection error vector (used from within Bundle Adjustment methods, but can be used in general)</span>
<a name="l00132"></a>00132 <span class="comment">                  *  See mrpt::vision::bundle_adj_full for a description of most parameters.</span>
<a name="l00133"></a>00133 <span class="comment">                  * \param frame_poses_are_inverse If set to true, global camera poses are \f$ \ominus F \f$ instead of \f$ F \f$, for each F in frame_poses.</span>
<a name="l00134"></a>00134 <span class="comment">                  *</span>
<a name="l00135"></a>00135 <span class="comment">                  *  \return Overall squared reprojection error.</span>
<a name="l00136"></a>00136 <span class="comment">                  * \ingroup bundle_adj</span>
<a name="l00137"></a>00137 <span class="comment">                  */</span>
<a name="l00138"></a>00138                 <span class="keywordtype">double</span> <a class="code" href="vision_2include_2mrpt_2vision_2link__pragmas_8h.html#aa4a17fb846aac61f4e57b17b6f784559">VISION_IMPEXP</a> <a class="code" href="group__bundle__adj.html#ga008e17744135c93e2ab9ae735372435c" title="Compute reprojection error vector (used from within Bundle Adjustment methods, but can be used in gen...">reprojectionResiduals</a>(
<a name="l00139"></a>00139                         <span class="keyword">const</span> <a class="code" href="structmrpt_1_1vision_1_1_t_sequence_feature_observations.html" title="A complete sequence of observations of features from different camera frames (poses).">mrpt::vision::TSequenceFeatureObservations</a>   &amp; observations,
<a name="l00140"></a>00140                         <span class="keyword">const</span> <a class="code" href="classmrpt_1_1utils_1_1_t_camera.html" title="Structure to hold the parameters of a pinhole camera model.">mrpt::utils::TCamera</a>                        &amp; camera_params,
<a name="l00141"></a>00141                         <span class="keyword">const</span> <a class="code" href="classstd_1_1vector.html" title="STL class.">mrpt::vision::TFramePosesVec</a>                 &amp; frame_poses,
<a name="l00142"></a>00142                         <span class="keyword">const</span> <a class="code" href="classstd_1_1vector.html">mrpt::vision::TLandmarkLocationsVec</a>          &amp; landmark_points,
<a name="l00143"></a>00143                         <a class="code" href="classstd_1_1vector.html" title="STL class.">std::vector</a>&lt;<a class="code" href="classmrpt_1_1math_1_1_c_array.html" title="A STL container (as wrapper) for arrays of constant size defined at compile time - Users will most li...">CArray&lt;double,2&gt;</a> &gt; &amp; out_residuals,
<a name="l00144"></a>00144                         <span class="keyword">const</span> <span class="keywordtype">bool</span>  frame_poses_are_inverse,
<a name="l00145"></a>00145                         <span class="keyword">const</span> <span class="keywordtype">bool</span>  use_robust_kernel = <span class="keyword">true</span>,
<a name="l00146"></a>00146                         <span class="keyword">const</span> <span class="keywordtype">double</span> kernel_param = 3.0
<a name="l00147"></a>00147                         );
<a name="l00148"></a>00148 <span class="comment"></span>
<a name="l00149"></a>00149 <span class="comment">                //! \overload</span>
<a name="l00150"></a>00150 <span class="comment"></span>                <span class="keywordtype">double</span> <a class="code" href="vision_2include_2mrpt_2vision_2link__pragmas_8h.html#aa4a17fb846aac61f4e57b17b6f784559">VISION_IMPEXP</a> <a class="code" href="group__bundle__adj.html#ga008e17744135c93e2ab9ae735372435c" title="Compute reprojection error vector (used from within Bundle Adjustment methods, but can be used in gen...">reprojectionResiduals</a>(
<a name="l00151"></a>00151                         <span class="keyword">const</span> <a class="code" href="structmrpt_1_1vision_1_1_t_sequence_feature_observations.html" title="A complete sequence of observations of features from different camera frames (poses).">mrpt::vision::TSequenceFeatureObservations</a>   &amp; observations,
<a name="l00152"></a>00152                         <span class="keyword">const</span> <a class="code" href="classmrpt_1_1utils_1_1_t_camera.html" title="Structure to hold the parameters of a pinhole camera model.">mrpt::utils::TCamera</a>                        &amp; camera_params,
<a name="l00153"></a>00153                         <span class="keyword">const</span> <a class="code" href="classstd_1_1map.html" title="STL class.">mrpt::vision::TFramePosesMap</a>                 &amp; frame_poses,
<a name="l00154"></a>00154                         <span class="keyword">const</span> <a class="code" href="classstd_1_1map.html" title="STL class.">mrpt::vision::TLandmarkLocationsMap</a>          &amp; landmark_points,
<a name="l00155"></a>00155                         <a class="code" href="classstd_1_1vector.html" title="STL class.">std::vector</a>&lt;<a class="code" href="classmrpt_1_1math_1_1_c_array.html" title="A STL container (as wrapper) for arrays of constant size defined at compile time - Users will most li...">CArray&lt;double,2&gt;</a> &gt; &amp; out_residuals,
<a name="l00156"></a>00156                         <span class="keyword">const</span> <span class="keywordtype">bool</span>  frame_poses_are_inverse,
<a name="l00157"></a>00157                         <span class="keyword">const</span> <span class="keywordtype">bool</span>  use_robust_kernel = <span class="keyword">true</span>,
<a name="l00158"></a>00158                         <span class="keyword">const</span> <span class="keywordtype">double</span> kernel_param = 3.0
<a name="l00159"></a>00159                         );
<a name="l00160"></a>00160 
<a name="l00161"></a>00161 <span class="comment"></span>
<a name="l00162"></a>00162 <span class="comment">                /** For each pose in the vector \a frame_poses, adds a &quot;delta&quot; increment to the manifold, with the &quot;delta&quot; given in the se(3) Lie algebra:</span>
<a name="l00163"></a>00163 <span class="comment">                  *</span>
<a name="l00164"></a>00164 <span class="comment">                  *    new_frame_poses[i] = frame_poses[i] [+] delta[(first_idx+6*i):(first_idx+6*i+5)]    , for every pose in \a frame_poses</span>
<a name="l00165"></a>00165 <span class="comment">                  *</span>
<a name="l00166"></a>00166 <span class="comment">                  *  With the left-multiplication convention of the manifold exp(delta) operator, that is:</span>
<a name="l00167"></a>00167 <span class="comment">                  *</span>
<a name="l00168"></a>00168 <span class="comment">                  *     p &lt;-- p [+] delta ==&gt;  p &lt;-- exp(delta) * p</span>
<a name="l00169"></a>00169 <span class="comment">                  *</span>
<a name="l00170"></a>00170 <span class="comment">                  * \param delta_num_vals Used just for sanity check, must be equal to &quot;frame_poses.size() * 6&quot;</span>
<a name="l00171"></a>00171 <span class="comment">                  * \ingroup bundle_adj</span>
<a name="l00172"></a>00172 <span class="comment">                  */</span>
<a name="l00173"></a>00173                 <span class="keywordtype">void</span> <a class="code" href="vision_2include_2mrpt_2vision_2link__pragmas_8h.html#aa4a17fb846aac61f4e57b17b6f784559">VISION_IMPEXP</a> <a class="code" href="group__bundle__adj.html#ga96e2458ae31058a3a0125258ca469d44" title="For each pose in the vector frame_poses, adds a &quot;delta&quot; increment to the manifold, with the &quot;delta&quot; given in the se(3) Lie algebra:">add_se3_deltas_to_frames</a>(
<a name="l00174"></a>00174                         <span class="keyword">const</span> <a class="code" href="classstd_1_1vector.html" title="STL class.">mrpt::vision::TFramePosesVec</a> &amp; frame_poses,
<a name="l00175"></a>00175                         <span class="keyword">const</span> <a class="code" href="structmrpt_1_1dynamicsize__vector.html" title="The base class of MRPT vectors, actually, Eigen column matrices of dynamic size with specialized cons...">mrpt::vector_double</a> &amp;delta,
<a name="l00176"></a>00176                         <span class="keyword">const</span> <span class="keywordtype">size_t</span>         delta_first_idx,
<a name="l00177"></a>00177                         <span class="keyword">const</span> <span class="keywordtype">size_t</span>         delta_num_vals,
<a name="l00178"></a>00178                         <a class="code" href="classstd_1_1vector.html" title="STL class.">mrpt::vision::TFramePosesVec</a>       &amp; new_frame_poses,
<a name="l00179"></a>00179                         <span class="keyword">const</span> <span class="keywordtype">size_t</span>         num_fix_frames );
<a name="l00180"></a>00180 <span class="comment"></span>
<a name="l00181"></a>00181 <span class="comment">                /** For each pose in the vector \a frame_poses, adds a &quot;delta&quot; increment to the manifold, with the &quot;delta&quot; given in the se(3) Lie algebra:</span>
<a name="l00182"></a>00182 <span class="comment">                  *</span>
<a name="l00183"></a>00183 <span class="comment">                  *    new_landmark_points[i] = landmark_points[i] + delta[(first_idx+3*i):(first_idx+3*i+2)]    , for every pose in \a landmark_points</span>
<a name="l00184"></a>00184 <span class="comment">                  *</span>
<a name="l00185"></a>00185 <span class="comment">                  * \param delta_num_vals Used just for sanity check, must be equal to &quot;landmark_points.size() * 3&quot;</span>
<a name="l00186"></a>00186 <span class="comment">                  * \ingroup bundle_adj</span>
<a name="l00187"></a>00187 <span class="comment">                  */</span>
<a name="l00188"></a>00188                 <span class="keywordtype">void</span> <a class="code" href="vision_2include_2mrpt_2vision_2link__pragmas_8h.html#aa4a17fb846aac61f4e57b17b6f784559">VISION_IMPEXP</a> <a class="code" href="group__bundle__adj.html#gad10bdb5e4afebe6c3b535dc888b235b1" title="For each pose in the vector frame_poses, adds a &quot;delta&quot; increment to the manifold, with the &quot;delta&quot; given in the se(3) Lie algebra:">add_3d_deltas_to_points</a>(
<a name="l00189"></a>00189                         <span class="keyword">const</span> <a class="code" href="classstd_1_1vector.html">mrpt::vision::TLandmarkLocationsVec</a> &amp; landmark_points,
<a name="l00190"></a>00190                         <span class="keyword">const</span> <a class="code" href="structmrpt_1_1dynamicsize__vector.html" title="The base class of MRPT vectors, actually, Eigen column matrices of dynamic size with specialized cons...">mrpt::vector_double</a>       &amp; delta,
<a name="l00191"></a>00191                         <span class="keyword">const</span> <span class="keywordtype">size_t</span>                delta_first_idx,
<a name="l00192"></a>00192                         <span class="keyword">const</span> <span class="keywordtype">size_t</span>                delta_num_vals,
<a name="l00193"></a>00193                         <a class="code" href="classstd_1_1vector.html">mrpt::vision::TLandmarkLocationsVec</a>        &amp; new_landmark_points,
<a name="l00194"></a>00194                         <span class="keyword">const</span> <span class="keywordtype">size_t</span>                num_fix_points );
<a name="l00195"></a>00195 <span class="comment"></span>
<a name="l00196"></a>00196 <span class="comment">                /** @} */</span>
<a name="l00197"></a>00197         }
<a name="l00198"></a>00198 }
<a name="l00199"></a>00199 <span class="preprocessor">#endif</span>
<a name="l00200"></a>00200 <span class="preprocessor"></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>