<!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 methods</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> > <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 Page</span></a></li> <li><a href="pages.html"><span>Related 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><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> <div class="header"> <div class="headertitle"> <div class="title">Bundle-Adjustment methods</div> </div> <div class="ingroups"><a class="el" href="group__mrpt__vision__grp.html">[mrpt-vision]</a></div></div> <div class="contents"> <div class="dynheader"> Collaboration diagram for Bundle-Adjustment methods:</div> <div class="dyncontent"> <center><table><tr><td><img src="group__bundle__adj.png" border="0" alt="" usemap="#group____bundle____adj"/> <map name="group____bundle____adj" id="group____bundle____adj"> <area shape="rect" id="node1" href="group__mrpt__vision__grp.html" title=" Back to list of all libraries | See all modules   " alt="" coords="6,5,101,32"/></map> </td></tr></table></center> </div> <table class="memberdecls"> <tr><td colspan="2"><h2><a name="member-group"></a> Bundle-Adjustment methods</h2></td></tr> <tr><td class="memItemLeft" align="right" valign="top">double VISION_IMPEXP </td><td class="memItemRight" valign="bottom"><a class="el" href="group__bundle__adj.html#gabb5e8247d164906bce57a3c05b001953">mrpt::vision::bundle_adj_full</a> (const <a class="el" href="structmrpt_1_1vision_1_1_t_sequence_feature_observations.html">mrpt::vision::TSequenceFeatureObservations</a> &observations, const <a class="el" href="classmrpt_1_1utils_1_1_t_camera.html">mrpt::utils::TCamera</a> &camera_params, <a class="el" href="group__mrpt__vision__grp.html#gabe5f1a7756ced9db83e245414fd54def">mrpt::vision::TFramePosesVec</a> &frame_poses, <a class="el" href="group__mrpt__vision__grp.html#gaa8fa8b53643b4e650a959867691e3adc">mrpt::vision::TLandmarkLocationsVec</a> &landmark_points, const <a class="el" href="namespacemrpt_1_1utils.html#a694777f2a3544999baea34e43a42eceb">mrpt::utils::TParametersDouble</a> &extra_params=<a class="el" href="namespacemrpt_1_1utils.html#a694777f2a3544999baea34e43a42eceb">mrpt::utils::TParametersDouble</a>(), const <a class="el" href="namespacemrpt_1_1vision.html#a7e12f372278c656321223eec4aced3fb">mrpt::vision::TBundleAdjustmentFeedbackFunctor</a> user_feedback=NULL)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Sparse Levenberg-Marquart solution to bundle adjustment - optimizes all the camera frames & the landmark locations. <a href="#gabb5e8247d164906bce57a3c05b001953"></a><br/></td></tr> <tr><td colspan="2"><h2><a name="member-group"></a> Bundle-Adjustment Auxiliary methods</h2></td></tr> <tr><td class="memItemLeft" align="right" valign="top">void VISION_IMPEXP </td><td class="memItemRight" valign="bottom"><a class="el" href="group__bundle__adj.html#ga3d11e2afc4d575bacd1699f9ba0f479a">mrpt::vision::ba_initial_estimate</a> (const <a class="el" href="structmrpt_1_1vision_1_1_t_sequence_feature_observations.html">mrpt::vision::TSequenceFeatureObservations</a> &observations, const <a class="el" href="classmrpt_1_1utils_1_1_t_camera.html">mrpt::utils::TCamera</a> &camera_params, <a class="el" href="group__mrpt__vision__grp.html#gabe5f1a7756ced9db83e245414fd54def">mrpt::vision::TFramePosesVec</a> &frame_poses, <a class="el" href="group__mrpt__vision__grp.html#gaa8fa8b53643b4e650a959867691e3adc">mrpt::vision::TLandmarkLocationsVec</a> &landmark_points)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Fills the frames & landmark points maps with an initial gross estimate from the sequence <em>observations</em>, so they can be fed to bundle adjustment methods. <a href="#ga3d11e2afc4d575bacd1699f9ba0f479a"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">double VISION_IMPEXP </td><td class="memItemRight" valign="bottom"><a class="el" href="group__bundle__adj.html#ga008e17744135c93e2ab9ae735372435c">mrpt::vision::reprojectionResiduals</a> (const <a class="el" href="structmrpt_1_1vision_1_1_t_sequence_feature_observations.html">mrpt::vision::TSequenceFeatureObservations</a> &observations, const <a class="el" href="classmrpt_1_1utils_1_1_t_camera.html">mrpt::utils::TCamera</a> &camera_params, const <a class="el" href="group__mrpt__vision__grp.html#gabe5f1a7756ced9db83e245414fd54def">mrpt::vision::TFramePosesVec</a> &frame_poses, const <a class="el" href="group__mrpt__vision__grp.html#gaa8fa8b53643b4e650a959867691e3adc">mrpt::vision::TLandmarkLocationsVec</a> &landmark_points, <a class="el" href="classstd_1_1vector.html">std::vector</a>< CArray< double, 2 > > &out_residuals, const bool frame_poses_are_inverse, const bool use_robust_kernel=true, const double kernel_param=3.0)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Compute reprojection error vector (used from within Bundle Adjustment methods, but can be used in general) See <a class="el" href="group__bundle__adj.html#gabb5e8247d164906bce57a3c05b001953" title="Sparse Levenberg-Marquart solution to bundle adjustment - optimizes all the camera frames & the landm...">mrpt::vision::bundle_adj_full</a> for a description of most parameters. <a href="#ga008e17744135c93e2ab9ae735372435c"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">void VISION_IMPEXP </td><td class="memItemRight" valign="bottom"><a class="el" href="group__bundle__adj.html#ga96e2458ae31058a3a0125258ca469d44">mrpt::vision::add_se3_deltas_to_frames</a> (const <a class="el" href="group__mrpt__vision__grp.html#gabe5f1a7756ced9db83e245414fd54def">mrpt::vision::TFramePosesVec</a> &frame_poses, const <a class="el" href="namespacemrpt.html#a4a6aab2c98368ca6b554c04f8fe84cfb">mrpt::vector_double</a> &delta, const size_t delta_first_idx, const size_t delta_num_vals, <a class="el" href="group__mrpt__vision__grp.html#gabe5f1a7756ced9db83e245414fd54def">mrpt::vision::TFramePosesVec</a> &new_frame_poses, const size_t num_fix_frames)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">For each pose in the vector <em>frame_poses</em>, adds a "delta" increment to the manifold, with the "delta" given in the se(3) Lie algebra: <a href="#ga96e2458ae31058a3a0125258ca469d44"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">void VISION_IMPEXP </td><td class="memItemRight" valign="bottom"><a class="el" href="group__bundle__adj.html#gad10bdb5e4afebe6c3b535dc888b235b1">mrpt::vision::add_3d_deltas_to_points</a> (const <a class="el" href="group__mrpt__vision__grp.html#gaa8fa8b53643b4e650a959867691e3adc">mrpt::vision::TLandmarkLocationsVec</a> &landmark_points, const <a class="el" href="namespacemrpt.html#a4a6aab2c98368ca6b554c04f8fe84cfb">mrpt::vector_double</a> &delta, const size_t delta_first_idx, const size_t delta_num_vals, <a class="el" href="group__mrpt__vision__grp.html#gaa8fa8b53643b4e650a959867691e3adc">mrpt::vision::TLandmarkLocationsVec</a> &new_landmark_points, const size_t num_fix_points)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">For each pose in the vector <em>frame_poses</em>, adds a "delta" increment to the manifold, with the "delta" given in the se(3) Lie algebra: <a href="#gad10bdb5e4afebe6c3b535dc888b235b1"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">void VISION_IMPEXP </td><td class="memItemRight" valign="bottom"><a class="el" href="group__bundle__adj.html#gab92c9a153aa4c107299f26be55179a0e">mrpt::vision::ba_initial_estimate</a> (const <a class="el" href="structmrpt_1_1vision_1_1_t_sequence_feature_observations.html">mrpt::vision::TSequenceFeatureObservations</a> &observations, const <a class="el" href="classmrpt_1_1utils_1_1_t_camera.html">mrpt::utils::TCamera</a> &camera_params, <a class="el" href="group__mrpt__vision__grp.html#ga62b8ac1f5f748ac325c921ee16b28ff7">mrpt::vision::TFramePosesMap</a> &frame_poses, <a class="el" href="group__mrpt__vision__grp.html#gaef17b094c368f8a0ea926e8af3183feb">mrpt::vision::TLandmarkLocationsMap</a> &landmark_points)</td></tr> <tr><td class="memItemLeft" align="right" valign="top">double VISION_IMPEXP </td><td class="memItemRight" valign="bottom"><a class="el" href="group__bundle__adj.html#ga2c437db09dbcaf05c33d2bb0e38a56b8">mrpt::vision::reprojectionResiduals</a> (const <a class="el" href="structmrpt_1_1vision_1_1_t_sequence_feature_observations.html">mrpt::vision::TSequenceFeatureObservations</a> &observations, const <a class="el" href="classmrpt_1_1utils_1_1_t_camera.html">mrpt::utils::TCamera</a> &camera_params, const <a class="el" href="group__mrpt__vision__grp.html#ga62b8ac1f5f748ac325c921ee16b28ff7">mrpt::vision::TFramePosesMap</a> &frame_poses, const <a class="el" href="group__mrpt__vision__grp.html#gaef17b094c368f8a0ea926e8af3183feb">mrpt::vision::TLandmarkLocationsMap</a> &landmark_points, <a class="el" href="classstd_1_1vector.html">std::vector</a>< CArray< double, 2 > > &out_residuals, const bool frame_poses_are_inverse, const bool use_robust_kernel=true, const double kernel_param=3.0)</td></tr> </table> <hr/><h2>Function Documentation</h2> <a class="anchor" id="gad10bdb5e4afebe6c3b535dc888b235b1"></a><!-- doxytag: member="mrpt::vision::add_3d_deltas_to_points" ref="gad10bdb5e4afebe6c3b535dc888b235b1" args="(const mrpt::vision::TLandmarkLocationsVec &landmark_points, const mrpt::vector_double &delta, const size_t delta_first_idx, const size_t delta_num_vals, mrpt::vision::TLandmarkLocationsVec &new_landmark_points, const size_t num_fix_points)" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">void VISION_IMPEXP mrpt::vision::add_3d_deltas_to_points </td> <td>(</td> <td class="paramtype">const <a class="el" href="group__mrpt__vision__grp.html#gaa8fa8b53643b4e650a959867691e3adc">mrpt::vision::TLandmarkLocationsVec</a> & </td> <td class="paramname"><em>landmark_points</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const <a class="el" href="namespacemrpt.html#a4a6aab2c98368ca6b554c04f8fe84cfb">mrpt::vector_double</a> & </td> <td class="paramname"><em>delta</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const size_t </td> <td class="paramname"><em>delta_first_idx</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const size_t </td> <td class="paramname"><em>delta_num_vals</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype"><a class="el" href="group__mrpt__vision__grp.html#gaa8fa8b53643b4e650a959867691e3adc">mrpt::vision::TLandmarkLocationsVec</a> & </td> <td class="paramname"><em>new_landmark_points</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const size_t </td> <td class="paramname"><em>num_fix_points</em> </td> </tr> <tr> <td></td> <td>)</td> <td></td><td></td> </tr> </table> </div> <div class="memdoc"> <p>For each pose in the vector <em>frame_poses</em>, adds a "delta" increment to the manifold, with the "delta" given in the se(3) Lie algebra: </p> <p>new_landmark_points[i] = landmark_points[i] + delta[(first_idx+3*i):(first_idx+3*i+2)] , for every pose in <em>landmark_points</em> </p> <dl><dt><b>Parameters:</b></dt><dd> <table class="params"> <tr><td class="paramname">delta_num_vals</td><td>Used just for sanity check, must be equal to "landmark_points.size() * 3" </td></tr> </table> </dd> </dl> </div> </div> <a class="anchor" id="ga96e2458ae31058a3a0125258ca469d44"></a><!-- doxytag: member="mrpt::vision::add_se3_deltas_to_frames" ref="ga96e2458ae31058a3a0125258ca469d44" args="(const mrpt::vision::TFramePosesVec &frame_poses, const mrpt::vector_double &delta, const size_t delta_first_idx, const size_t delta_num_vals, mrpt::vision::TFramePosesVec &new_frame_poses, const size_t num_fix_frames)" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">void VISION_IMPEXP mrpt::vision::add_se3_deltas_to_frames </td> <td>(</td> <td class="paramtype">const <a class="el" href="group__mrpt__vision__grp.html#gabe5f1a7756ced9db83e245414fd54def">mrpt::vision::TFramePosesVec</a> & </td> <td class="paramname"><em>frame_poses</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const <a class="el" href="namespacemrpt.html#a4a6aab2c98368ca6b554c04f8fe84cfb">mrpt::vector_double</a> & </td> <td class="paramname"><em>delta</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const size_t </td> <td class="paramname"><em>delta_first_idx</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const size_t </td> <td class="paramname"><em>delta_num_vals</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype"><a class="el" href="group__mrpt__vision__grp.html#gabe5f1a7756ced9db83e245414fd54def">mrpt::vision::TFramePosesVec</a> & </td> <td class="paramname"><em>new_frame_poses</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const size_t </td> <td class="paramname"><em>num_fix_frames</em> </td> </tr> <tr> <td></td> <td>)</td> <td></td><td></td> </tr> </table> </div> <div class="memdoc"> <p>For each pose in the vector <em>frame_poses</em>, adds a "delta" increment to the manifold, with the "delta" given in the se(3) Lie algebra: </p> <p>new_frame_poses[i] = frame_poses[i] [+] delta[(first_idx+6*i):(first_idx+6*i+5)] , for every pose in <em>frame_poses</em> </p> <p>With the left-multiplication convention of the manifold exp(delta) operator, that is:</p> <p>p <-- p [+] delta ==> p <-- exp(delta) * p</p> <dl><dt><b>Parameters:</b></dt><dd> <table class="params"> <tr><td class="paramname">delta_num_vals</td><td>Used just for sanity check, must be equal to "frame_poses.size() * 6" </td></tr> </table> </dd> </dl> </div> </div> <a class="anchor" id="ga3d11e2afc4d575bacd1699f9ba0f479a"></a><!-- doxytag: member="mrpt::vision::ba_initial_estimate" ref="ga3d11e2afc4d575bacd1699f9ba0f479a" args="(const mrpt::vision::TSequenceFeatureObservations &observations, const mrpt::utils::TCamera &camera_params, mrpt::vision::TFramePosesVec &frame_poses, mrpt::vision::TLandmarkLocationsVec &landmark_points)" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">void VISION_IMPEXP mrpt::vision::ba_initial_estimate </td> <td>(</td> <td class="paramtype">const <a class="el" href="structmrpt_1_1vision_1_1_t_sequence_feature_observations.html">mrpt::vision::TSequenceFeatureObservations</a> & </td> <td class="paramname"><em>observations</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const <a class="el" href="classmrpt_1_1utils_1_1_t_camera.html">mrpt::utils::TCamera</a> & </td> <td class="paramname"><em>camera_params</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype"><a class="el" href="group__mrpt__vision__grp.html#gabe5f1a7756ced9db83e245414fd54def">mrpt::vision::TFramePosesVec</a> & </td> <td class="paramname"><em>frame_poses</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype"><a class="el" href="group__mrpt__vision__grp.html#gaa8fa8b53643b4e650a959867691e3adc">mrpt::vision::TLandmarkLocationsVec</a> & </td> <td class="paramname"><em>landmark_points</em> </td> </tr> <tr> <td></td> <td>)</td> <td></td><td></td> </tr> </table> </div> <div class="memdoc"> <p>Fills the frames & landmark points maps with an initial gross estimate from the sequence <em>observations</em>, so they can be fed to bundle adjustment methods. </p> <dl class="see"><dt><b>See also:</b></dt><dd><a class="el" href="group__bundle__adj.html#gabb5e8247d164906bce57a3c05b001953" title="Sparse Levenberg-Marquart solution to bundle adjustment - optimizes all the camera frames & the landm...">bundle_adj_full</a> </dd></dl> </div> </div> <a class="anchor" id="gab92c9a153aa4c107299f26be55179a0e"></a><!-- doxytag: member="mrpt::vision::ba_initial_estimate" ref="gab92c9a153aa4c107299f26be55179a0e" args="(const mrpt::vision::TSequenceFeatureObservations &observations, const mrpt::utils::TCamera &camera_params, mrpt::vision::TFramePosesMap &frame_poses, mrpt::vision::TLandmarkLocationsMap &landmark_points)" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">void VISION_IMPEXP mrpt::vision::ba_initial_estimate </td> <td>(</td> <td class="paramtype">const <a class="el" href="structmrpt_1_1vision_1_1_t_sequence_feature_observations.html">mrpt::vision::TSequenceFeatureObservations</a> & </td> <td class="paramname"><em>observations</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const <a class="el" href="classmrpt_1_1utils_1_1_t_camera.html">mrpt::utils::TCamera</a> & </td> <td class="paramname"><em>camera_params</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype"><a class="el" href="group__mrpt__vision__grp.html#ga62b8ac1f5f748ac325c921ee16b28ff7">mrpt::vision::TFramePosesMap</a> & </td> <td class="paramname"><em>frame_poses</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype"><a class="el" href="group__mrpt__vision__grp.html#gaef17b094c368f8a0ea926e8af3183feb">mrpt::vision::TLandmarkLocationsMap</a> & </td> <td class="paramname"><em>landmark_points</em> </td> </tr> <tr> <td></td> <td>)</td> <td></td><td></td> </tr> </table> </div> <div class="memdoc"> <p>This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. </p> </div> </div> <a class="anchor" id="gabb5e8247d164906bce57a3c05b001953"></a><!-- doxytag: member="mrpt::vision::bundle_adj_full" ref="gabb5e8247d164906bce57a3c05b001953" args="(const mrpt::vision::TSequenceFeatureObservations &observations, const mrpt::utils::TCamera &camera_params, mrpt::vision::TFramePosesVec &frame_poses, mrpt::vision::TLandmarkLocationsVec &landmark_points, const mrpt::utils::TParametersDouble &extra_params=mrpt::utils::TParametersDouble(), const mrpt::vision::TBundleAdjustmentFeedbackFunctor user_feedback=NULL)" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">double VISION_IMPEXP mrpt::vision::bundle_adj_full </td> <td>(</td> <td class="paramtype">const <a class="el" href="structmrpt_1_1vision_1_1_t_sequence_feature_observations.html">mrpt::vision::TSequenceFeatureObservations</a> & </td> <td class="paramname"><em>observations</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const <a class="el" href="classmrpt_1_1utils_1_1_t_camera.html">mrpt::utils::TCamera</a> & </td> <td class="paramname"><em>camera_params</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype"><a class="el" href="group__mrpt__vision__grp.html#gabe5f1a7756ced9db83e245414fd54def">mrpt::vision::TFramePosesVec</a> & </td> <td class="paramname"><em>frame_poses</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype"><a class="el" href="group__mrpt__vision__grp.html#gaa8fa8b53643b4e650a959867691e3adc">mrpt::vision::TLandmarkLocationsVec</a> & </td> <td class="paramname"><em>landmark_points</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const <a class="el" href="namespacemrpt_1_1utils.html#a694777f2a3544999baea34e43a42eceb">mrpt::utils::TParametersDouble</a> & </td> <td class="paramname"><em>extra_params</em> = <code><a class="el" href="namespacemrpt_1_1utils.html#a694777f2a3544999baea34e43a42eceb">mrpt::utils::TParametersDouble</a>()</code>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const <a class="el" href="namespacemrpt_1_1vision.html#a7e12f372278c656321223eec4aced3fb">mrpt::vision::TBundleAdjustmentFeedbackFunctor</a> </td> <td class="paramname"><em>user_feedback</em> = <code>NULL</code> </td> </tr> <tr> <td></td> <td>)</td> <td></td><td></td> </tr> </table> </div> <div class="memdoc"> <p>Sparse Levenberg-Marquart solution to bundle adjustment - optimizes all the camera frames & the landmark locations. </p> <p>At input a gross estimation of the frame poses & the landmark points must be supplied. If you don't have such a starting point, use <a class="el" href="group__bundle__adj.html#ga3d11e2afc4d575bacd1699f9ba0f479a" title="Fills the frames & landmark points maps with an initial gross estimate from the sequence observations...">mrpt::vision::ba_initial_estimate()</a> to compute it.</p> <p>At output the best found solution will be returned in the variables. Optionally, a functor can be passed for having feedback on the progress at each iteration (you can use it to refresh a GUI, display a progress bar, etc...).</p> <p>This implementation is almost entirely an adapted version from RobotVision (at OpenSLAM.org) (C) by Hauke Strasdat (Imperial College London), licensed under GNU LGPL. See the related paper: H. Strasdat, J.M.M. Montiel, A.J. Davison: "Scale Drift-Aware Large Scale Monocular SLAM", RSS2010, <a href="http://www.roboticsproceedings.org/rss06/p10.html">http://www.roboticsproceedings.org/rss06/p10.html</a></p> <p>List of optional parameters in "extra_params":</p> <ul> <li>"verbose" : Verbose output (default=0)</li> <li>"max_iterations": Maximum number of iterations to run (default=50)</li> <li>"robust_kernel": If !=0, use a robust kernel against outliers (default=1)</li> <li>"kernel_param": The pseudo-huber kernel parameter (default=3)</li> <li>"mu": Initial mu for LevMarq (default=-1 -> autoguess)</li> <li>"num_fix_frames": Number of first frame poses to don't optimize (keep unmodified as they come in) (default=1: the first pose is the reference and is not modified)</li> <li>"num_fix_points": Idem, for the landmarks positions (default=0: optimize all)</li> <li>"profiler": If !=0, displays profiling information to the console at return.</li> </ul> <dl class="note"><dt><b>Note:</b></dt><dd>In this function, all coordinates are absolute. Camera frames are such that +Z points forward from the focal point (see the figure in <a class="el" href="classmrpt_1_1slam_1_1_c_observation_image.html" title="Declares a class derived from "CObservation" that encapsules an image from a camera, whose relative pose to robot is also stored.">mrpt::slam::CObservationImage</a>). </dd> <dd> The first frame pose will be not updated since at least one frame must remain fixed.</dd></dl> <dl><dt><b>Parameters:</b></dt><dd> <table class="params"> <tr><td class="paramname">observations</td><td>[IN] All the feature observations (WITHOUT distortion), indexed by feature ID as lists of <frame_ID, (x,y)>. See <a class="el" href="structmrpt_1_1vision_1_1_t_sequence_feature_observations.html" title="A complete sequence of observations of features from different camera frames (poses).">TSequenceFeatureObservations</a>. </td></tr> <tr><td class="paramname">camera_params</td><td>[IN] The camera parameters, mainly used for the intrinsic 3x3 matrix. Distortion params are ignored since it's assumed that <em>observations</em> are already undistorted pixels. </td></tr> <tr><td class="paramname">frame_poses</td><td>[IN/OUT] Input: Gross estimation of each frame poses. Output: The found optimal solution. </td></tr> <tr><td class="paramname">landmark_points</td><td>[IN/OUT] Input: Gross estimation of each landmark point. Output: The found optimal solution. </td></tr> <tr><td class="paramname">extra_params</td><td>[IN] Optional extra parameters. Read above. </td></tr> <tr><td class="paramname">user_feedback</td><td>[IN] If provided, this functor will be called at each iteration to provide a feedback to the user.</td></tr> </table> </dd> </dl> <dl class="return"><dt><b>Returns:</b></dt><dd>The final overall squared error. </dd></dl> </div> </div> <a class="anchor" id="ga008e17744135c93e2ab9ae735372435c"></a><!-- doxytag: member="mrpt::vision::reprojectionResiduals" ref="ga008e17744135c93e2ab9ae735372435c" args="(const mrpt::vision::TSequenceFeatureObservations &observations, const mrpt::utils::TCamera &camera_params, const mrpt::vision::TFramePosesVec &frame_poses, const mrpt::vision::TLandmarkLocationsVec &landmark_points, std::vector< CArray< double, 2 > > &out_residuals, const bool frame_poses_are_inverse, const bool use_robust_kernel=true, const double kernel_param=3.0)" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">double VISION_IMPEXP mrpt::vision::reprojectionResiduals </td> <td>(</td> <td class="paramtype">const <a class="el" href="structmrpt_1_1vision_1_1_t_sequence_feature_observations.html">mrpt::vision::TSequenceFeatureObservations</a> & </td> <td class="paramname"><em>observations</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const <a class="el" href="classmrpt_1_1utils_1_1_t_camera.html">mrpt::utils::TCamera</a> & </td> <td class="paramname"><em>camera_params</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const <a class="el" href="group__mrpt__vision__grp.html#gabe5f1a7756ced9db83e245414fd54def">mrpt::vision::TFramePosesVec</a> & </td> <td class="paramname"><em>frame_poses</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const <a class="el" href="group__mrpt__vision__grp.html#gaa8fa8b53643b4e650a959867691e3adc">mrpt::vision::TLandmarkLocationsVec</a> & </td> <td class="paramname"><em>landmark_points</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype"><a class="el" href="classstd_1_1vector.html">std::vector</a>< CArray< double, 2 > > & </td> <td class="paramname"><em>out_residuals</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const bool </td> <td class="paramname"><em>frame_poses_are_inverse</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const bool </td> <td class="paramname"><em>use_robust_kernel</em> = <code>true</code>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const double </td> <td class="paramname"><em>kernel_param</em> = <code>3.0</code> </td> </tr> <tr> <td></td> <td>)</td> <td></td><td></td> </tr> </table> </div> <div class="memdoc"> <p>Compute reprojection error vector (used from within Bundle Adjustment methods, but can be used in general) See <a class="el" href="group__bundle__adj.html#gabb5e8247d164906bce57a3c05b001953" title="Sparse Levenberg-Marquart solution to bundle adjustment - optimizes all the camera frames & the landm...">mrpt::vision::bundle_adj_full</a> for a description of most parameters. </p> <dl><dt><b>Parameters:</b></dt><dd> <table class="params"> <tr><td class="paramname">frame_poses_are_inverse</td><td>If set to true, global camera poses are <img class="formulaInl" alt="$ \ominus F $" src="form_115.png"/> instead of <img class="formulaInl" alt="$ F $" src="form_116.png"/>, for each F in frame_poses.</td></tr> </table> </dd> </dl> <dl class="return"><dt><b>Returns:</b></dt><dd>Overall squared reprojection error. </dd></dl> </div> </div> <a class="anchor" id="ga2c437db09dbcaf05c33d2bb0e38a56b8"></a><!-- doxytag: member="mrpt::vision::reprojectionResiduals" ref="ga2c437db09dbcaf05c33d2bb0e38a56b8" args="(const mrpt::vision::TSequenceFeatureObservations &observations, const mrpt::utils::TCamera &camera_params, const mrpt::vision::TFramePosesMap &frame_poses, const mrpt::vision::TLandmarkLocationsMap &landmark_points, std::vector< CArray< double, 2 > > &out_residuals, const bool frame_poses_are_inverse, const bool use_robust_kernel=true, const double kernel_param=3.0)" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">double VISION_IMPEXP mrpt::vision::reprojectionResiduals </td> <td>(</td> <td class="paramtype">const <a class="el" href="structmrpt_1_1vision_1_1_t_sequence_feature_observations.html">mrpt::vision::TSequenceFeatureObservations</a> & </td> <td class="paramname"><em>observations</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const <a class="el" href="classmrpt_1_1utils_1_1_t_camera.html">mrpt::utils::TCamera</a> & </td> <td class="paramname"><em>camera_params</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const <a class="el" href="group__mrpt__vision__grp.html#ga62b8ac1f5f748ac325c921ee16b28ff7">mrpt::vision::TFramePosesMap</a> & </td> <td class="paramname"><em>frame_poses</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const <a class="el" href="group__mrpt__vision__grp.html#gaef17b094c368f8a0ea926e8af3183feb">mrpt::vision::TLandmarkLocationsMap</a> & </td> <td class="paramname"><em>landmark_points</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype"><a class="el" href="classstd_1_1vector.html">std::vector</a>< CArray< double, 2 > > & </td> <td class="paramname"><em>out_residuals</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const bool </td> <td class="paramname"><em>frame_poses_are_inverse</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const bool </td> <td class="paramname"><em>use_robust_kernel</em> = <code>true</code>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">const double </td> <td class="paramname"><em>kernel_param</em> = <code>3.0</code> </td> </tr> <tr> <td></td> <td>)</td> <td></td><td></td> </tr> </table> </div> <div class="memdoc"> <p>This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. </p> </div> </div> </div> <br><hr><br> <table border="0" width="100%"> <tr> <td> Page generated by <a href="http://www.doxygen.org" target="_blank">Doxygen 1.7.5</a> for MRPT 0.9.5 SVN: at Sun Sep 25 17:20:18 UTC 2011</td><td></td> <td width="100"> </td> <td width="150"> </td></tr> </table> </body></html>