<!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>types.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> > <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 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 List</span></a></li> <li><a href="globals.html"><span>File Members</span></a></li> </ul> </div> <div class="header"> <div class="headertitle"> <div class="title">types.h</div> </div> </div> <div class="contents"> <a href="vision_2include_2mrpt_2vision_2types_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 <jlblanco@ctima.uma.es> |</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 <http://www.gnu.org/licenses/>. |</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_types_H</span> <a name="l00030"></a>00030 <span class="preprocessor"></span><span class="preprocessor">#define mrpt_vision_types_H</span> <a name="l00031"></a>00031 <span class="preprocessor"></span> <a name="l00032"></a>00032 <span class="preprocessor">#include <<a class="code" href="_c_image_8h.html">mrpt/utils/CImage.h</a>></span> <a name="l00033"></a>00033 <span class="preprocessor">#include <<a class="code" href="_c_loadable_options_8h.html">mrpt/utils/CLoadableOptions.h</a>></span> <a name="l00034"></a>00034 <span class="preprocessor">#include <<a class="code" href="_t_matching_pair_8h.html">mrpt/utils/TMatchingPair.h</a>></span> <a name="l00035"></a>00035 <a name="l00036"></a>00036 <span class="preprocessor">#include <<a class="code" href="vision_2include_2mrpt_2vision_2link__pragmas_8h.html">mrpt/vision/link_pragmas.h</a>></span> <a name="l00037"></a>00037 <a name="l00038"></a>00038 <span class="keyword">namespace </span>mrpt <a name="l00039"></a>00039 { <a name="l00040"></a>00040 <span class="keyword">namespace </span>vision <a name="l00041"></a>00041 {<span class="comment"></span> <a name="l00042"></a>00042 <span class="comment"> /** \addtogroup mrpt_vision_grp</span> <a name="l00043"></a>00043 <span class="comment"> * @{ */</span> <a name="l00044"></a>00044 <a name="l00045"></a>00045 <span class="keyword">using</span> std::vector; <a name="l00046"></a>00046 <span class="comment">//using namespace mrpt::slam;</span> <a name="l00047"></a>00047 <span class="keyword">using namespace </span>mrpt::math; <a name="l00048"></a>00048 <span class="keyword">using namespace </span>mrpt::utils; <a name="l00049"></a>00049 <a name="l00050"></a>00050 <a name="l00051"></a><a class="code" href="group__mrpt__vision__grp.html#ga5bfc93fce347933b63640f2de874ba26">00051</a> <span class="keyword">typedef</span> uint64_t <a class="code" href="group__mrpt__vision__grp.html#ga5bfc93fce347933b63640f2de874ba26" title="Definition of a feature ID.">TFeatureID</a>; <span class="comment">//!< Definition of a feature ID</span> <a name="l00052"></a>00052 <span class="comment"></span> <a name="l00053"></a><a class="code" href="group__mrpt__vision__grp.html#ga6c3892de843a8cf3bb52017d2933020f">00053</a> <span class="keyword">typedef</span> uint64_t <a class="code" href="group__mrpt__vision__grp.html#ga6c3892de843a8cf3bb52017d2933020f" title="Unique IDs for landmarks.">TLandmarkID</a>; <span class="comment">//!< Unique IDs for landmarks</span> <a name="l00054"></a><a class="code" href="group__mrpt__vision__grp.html#gae9363bed7e308d38b23c0bcac8b5e5d8">00054</a> <span class="comment"></span> <span class="keyword">typedef</span> uint64_t <a class="code" href="group__mrpt__vision__grp.html#gae9363bed7e308d38b23c0bcac8b5e5d8" title="Unique IDs for camera frames (poses)">TCameraPoseID</a>; <span class="comment">//!< Unique IDs for camera frames (poses)</span> <a name="l00055"></a>00055 <span class="comment"></span> <a name="l00056"></a><a class="code" href="group__mrpt__vision__grp.html#ga62b8ac1f5f748ac325c921ee16b28ff7">00056</a> <span class="keyword">typedef</span> mrpt<a class="code" href="classstd_1_1map.html" title="STL class.">::aligned_containers<TCameraPoseID,CPose3D>::map_t</a> <a class="code" href="group__mrpt__vision__grp.html#ga62b8ac1f5f748ac325c921ee16b28ff7" title="A list of camera frames (6D poses) indexed by unique IDs.">TFramePosesMap</a>; <span class="comment">//!< A list of camera frames (6D poses) indexed by unique IDs.</span> <a name="l00057"></a><a class="code" href="group__mrpt__vision__grp.html#gabe5f1a7756ced9db83e245414fd54def">00057</a> <span class="comment"></span> <span class="keyword">typedef</span> mrpt<a class="code" href="classstd_1_1vector.html" title="STL class.">::aligned_containers<CPose3D>::vector_t</a> <a class="code" href="group__mrpt__vision__grp.html#gabe5f1a7756ced9db83e245414fd54def" title="A list of camera frames (6D poses), which assumes indexes are unique, consecutive IDs...">TFramePosesVec</a>; <span class="comment">//!< A list of camera frames (6D poses), which assumes indexes are unique, consecutive IDs.</span> <a name="l00058"></a>00058 <span class="comment"></span> <a name="l00059"></a><a class="code" href="group__mrpt__vision__grp.html#gaef17b094c368f8a0ea926e8af3183feb">00059</a> <span class="keyword">typedef</span> std<a class="code" href="classstd_1_1map.html" title="STL class.">::map<TLandmarkID,TPoint3D></a> <a class="code" href="group__mrpt__vision__grp.html#gaef17b094c368f8a0ea926e8af3183feb" title="A list of landmarks (3D points) indexed by unique IDs.">TLandmarkLocationsMap</a>; <span class="comment">//!< A list of landmarks (3D points) indexed by unique IDs.</span> <a name="l00060"></a><a class="code" href="group__mrpt__vision__grp.html#gaa8fa8b53643b4e650a959867691e3adc">00060</a> <span class="comment"></span> <span class="keyword">typedef</span> std<a class="code" href="classstd_1_1vector.html">::vector<TPoint3D></a> <a class="code" href="group__mrpt__vision__grp.html#gaa8fa8b53643b4e650a959867691e3adc" title="A list of landmarks (3D points), which assumes indexes are unique, consecutive IDs.">TLandmarkLocationsVec</a>; <span class="comment">//!< A list of landmarks (3D points), which assumes indexes are unique, consecutive IDs.</span> <a name="l00061"></a>00061 <span class="comment"></span> <a name="l00062"></a>00062 <span class="comment"></span> <a name="l00063"></a>00063 <span class="comment"> /** Types of features - This means that the point has been detected with this algorithm, which is independent of additional descriptors a feature may also have</span> <a name="l00064"></a>00064 <span class="comment"> */</span> <a name="l00065"></a><a class="code" href="group__mrpt__vision__grp.html#ga3a5b54ab814bafc8bb108e37bbee4e19">00065</a> <span class="keyword">enum</span> <a class="code" href="group__mrpt__vision__grp.html#ga3a5b54ab814bafc8bb108e37bbee4e19" title="Types of features - This means that the point has been detected with this algorithm, which is independent of additional descriptors a feature may also have.">TFeatureType</a> <a name="l00066"></a>00066 { <a name="l00067"></a><a class="code" href="group__mrpt__vision__grp.html#gga3a5b54ab814bafc8bb108e37bbee4e19a9a6d1ea2a8c8957c81147e2ce5e9f3f1">00067</a> <a class="code" href="group__mrpt__vision__grp.html#gga3a5b54ab814bafc8bb108e37bbee4e19a9a6d1ea2a8c8957c81147e2ce5e9f3f1" title="Non-defined feature (also used for Occupancy features)">featNotDefined</a> = -1, <span class="comment">//!< Non-defined feature (also used for Occupancy features)</span> <a name="l00068"></a><a class="code" href="group__mrpt__vision__grp.html#gga3a5b54ab814bafc8bb108e37bbee4e19af521d70dbb18c7c919297ac034645d4e">00068</a> <span class="comment"></span> <a class="code" href="group__mrpt__vision__grp.html#gga3a5b54ab814bafc8bb108e37bbee4e19af521d70dbb18c7c919297ac034645d4e" title="Kanade-Lucas-Tomasi feature [SHI'94].">featKLT</a> = 0, <span class="comment">//!< Kanade-Lucas-Tomasi feature [SHI'94]</span> <a name="l00069"></a><a class="code" href="group__mrpt__vision__grp.html#gga3a5b54ab814bafc8bb108e37bbee4e19a7850031018540bfc2eee15ccce8a0ca5">00069</a> <span class="comment"></span> <a class="code" href="group__mrpt__vision__grp.html#gga3a5b54ab814bafc8bb108e37bbee4e19a7850031018540bfc2eee15ccce8a0ca5" title="Harris border and corner detector [HARRIS].">featHarris</a>, <span class="comment">//!< Harris border and corner detector [HARRIS]</span> <a name="l00070"></a><a class="code" href="group__mrpt__vision__grp.html#gga3a5b54ab814bafc8bb108e37bbee4e19aeefe4a844cd023b8dc922b01386d98f2">00070</a> <span class="comment"></span> <a class="code" href="group__mrpt__vision__grp.html#gga3a5b54ab814bafc8bb108e37bbee4e19aeefe4a844cd023b8dc922b01386d98f2" title="Binary corder detector.">featBCD</a>, <span class="comment">//!< Binary corder detector</span> <a name="l00071"></a><a class="code" href="group__mrpt__vision__grp.html#gga3a5b54ab814bafc8bb108e37bbee4e19a8a50f7cac59b399dec959c764bcedd62">00071</a> <span class="comment"></span> <a class="code" href="group__mrpt__vision__grp.html#gga3a5b54ab814bafc8bb108e37bbee4e19a8a50f7cac59b399dec959c764bcedd62" title="Scale Invariant Feature Transform [LOWE'04].">featSIFT</a>, <span class="comment">//!< Scale Invariant Feature Transform [LOWE'04]</span> <a name="l00072"></a><a class="code" href="group__mrpt__vision__grp.html#gga3a5b54ab814bafc8bb108e37bbee4e19a0928aa6d11142c924e2f2e60598559d5">00072</a> <span class="comment"></span> <a class="code" href="group__mrpt__vision__grp.html#gga3a5b54ab814bafc8bb108e37bbee4e19a0928aa6d11142c924e2f2e60598559d5" title="Speeded Up Robust Feature [BAY'06].">featSURF</a>, <span class="comment">//!< Speeded Up Robust Feature [BAY'06]</span> <a name="l00073"></a><a class="code" href="group__mrpt__vision__grp.html#gga3a5b54ab814bafc8bb108e37bbee4e19a40951a6fbc35e0b47a5883f70dd09e0c">00073</a> <span class="comment"></span> <a class="code" href="group__mrpt__vision__grp.html#gga3a5b54ab814bafc8bb108e37bbee4e19a40951a6fbc35e0b47a5883f70dd09e0c" title="A especial case: this is not an image feature, but a 2D/3D beacon (used for range-only SLAM from mrpt...">featBeacon</a>, <span class="comment">//!< A especial case: this is not an image feature, but a 2D/3D beacon (used for range-only SLAM from mrpt::slam::CLandmark)</span> <a name="l00074"></a><a class="code" href="group__mrpt__vision__grp.html#gga3a5b54ab814bafc8bb108e37bbee4e19a809c126ef20588226acd0893fa7a6ed5">00074</a> <span class="comment"></span> <a class="code" href="group__mrpt__vision__grp.html#gga3a5b54ab814bafc8bb108e37bbee4e19a809c126ef20588226acd0893fa7a6ed5" title="FAST feature detector, OpenCV's implementation ("Faster and better: A machine learning approach to co...">featFAST</a>, <span class="comment">//!< FAST feature detector, OpenCV's implementation ("Faster and better: A machine learning approach to corner detection", E. Rosten, R. Porter and T. Drummond, PAMI, 2009).</span> <a name="l00075"></a><a class="code" href="group__mrpt__vision__grp.html#gga3a5b54ab814bafc8bb108e37bbee4e19aa7ab4f83542ee3a069cb05a25af0984c">00075</a> <span class="comment"></span> <a class="code" href="group__mrpt__vision__grp.html#gga3a5b54ab814bafc8bb108e37bbee4e19aa7ab4f83542ee3a069cb05a25af0984c" title="FASTER-9 detector, Edward Rosten's libcvd implementation optimized for SSE2.">featFASTER9</a>, <span class="comment">//!< FASTER-9 detector, Edward Rosten's libcvd implementation optimized for SSE2.</span> <a name="l00076"></a><a class="code" href="group__mrpt__vision__grp.html#gga3a5b54ab814bafc8bb108e37bbee4e19a8dd8e13c6510ea136028e6338f795006">00076</a> <span class="comment"></span> <a class="code" href="group__mrpt__vision__grp.html#gga3a5b54ab814bafc8bb108e37bbee4e19a8dd8e13c6510ea136028e6338f795006" title="FASTER-9 detector, Edward Rosten's libcvd implementation optimized for SSE2.">featFASTER10</a>, <span class="comment">//!< FASTER-9 detector, Edward Rosten's libcvd implementation optimized for SSE2.</span> <a name="l00077"></a><a class="code" href="group__mrpt__vision__grp.html#gga3a5b54ab814bafc8bb108e37bbee4e19aa630e1c730c034cecffc4d11f7337c71">00077</a> <span class="comment"></span> <a class="code" href="group__mrpt__vision__grp.html#gga3a5b54ab814bafc8bb108e37bbee4e19aa630e1c730c034cecffc4d11f7337c71" title="FASTER-9 detector, Edward Rosten's libcvd implementation optimized for SSE2.">featFASTER12</a> <span class="comment">//!< FASTER-9 detector, Edward Rosten's libcvd implementation optimized for SSE2.</span> <a name="l00078"></a>00078 <span class="comment"></span> }; <a name="l00079"></a>00079 <span class="comment"></span> <a name="l00080"></a>00080 <span class="comment"> /** The bitwise OR combination of values of TDescriptorType are used in CFeatureExtraction::computeDescriptors to indicate which descriptors are to be computed for features.</span> <a name="l00081"></a>00081 <span class="comment"> */</span> <a name="l00082"></a><a class="code" href="group__mrpt__vision__grp.html#ga1953f4dfcaf2e07e1049bc0a6bbf53ba">00082</a> <span class="keyword">enum</span> <a class="code" href="group__mrpt__vision__grp.html#ga1953f4dfcaf2e07e1049bc0a6bbf53ba" title="The bitwise OR combination of values of TDescriptorType are used in CFeatureExtraction::computeDescri...">TDescriptorType</a> <a name="l00083"></a>00083 { <a name="l00084"></a><a class="code" href="group__mrpt__vision__grp.html#gga1953f4dfcaf2e07e1049bc0a6bbf53baad98c1e9e6948d609e0a2b639dffc0867">00084</a> <a class="code" href="group__mrpt__vision__grp.html#gga1953f4dfcaf2e07e1049bc0a6bbf53baad98c1e9e6948d609e0a2b639dffc0867" title="Used in some methods to mean "any of the present descriptors".">descAny</a> = 0, <span class="comment">//!< Used in some methods to mean "any of the present descriptors"</span> <a name="l00085"></a><a class="code" href="group__mrpt__vision__grp.html#gga1953f4dfcaf2e07e1049bc0a6bbf53baaa6d87aecd8225b626044ddd641eecf99">00085</a> <span class="comment"></span> <a class="code" href="group__mrpt__vision__grp.html#gga1953f4dfcaf2e07e1049bc0a6bbf53baaa6d87aecd8225b626044ddd641eecf99" title="SIFT descriptors.">descSIFT</a> = 1, <span class="comment">//!< SIFT descriptors</span> <a name="l00086"></a><a class="code" href="group__mrpt__vision__grp.html#gga1953f4dfcaf2e07e1049bc0a6bbf53baa15c8a84d8e1efe0fc5c07587e124f3b0">00086</a> <span class="comment"></span> <a class="code" href="group__mrpt__vision__grp.html#gga1953f4dfcaf2e07e1049bc0a6bbf53baa15c8a84d8e1efe0fc5c07587e124f3b0" title="SURF descriptors.">descSURF</a> = 2, <span class="comment">//!< SURF descriptors</span> <a name="l00087"></a><a class="code" href="group__mrpt__vision__grp.html#gga1953f4dfcaf2e07e1049bc0a6bbf53baa3b3c2bd8233f458981d88226e9e2b517">00087</a> <span class="comment"></span> <a class="code" href="group__mrpt__vision__grp.html#gga1953f4dfcaf2e07e1049bc0a6bbf53baa3b3c2bd8233f458981d88226e9e2b517" title="Intensity-domain spin image descriptors.">descSpinImages</a> = 4, <span class="comment">//!< Intensity-domain spin image descriptors</span> <a name="l00088"></a><a class="code" href="group__mrpt__vision__grp.html#gga1953f4dfcaf2e07e1049bc0a6bbf53baa9b8e2f748db92bffe1d6b7a21d21726f">00088</a> <span class="comment"></span> <a class="code" href="group__mrpt__vision__grp.html#gga1953f4dfcaf2e07e1049bc0a6bbf53baa9b8e2f748db92bffe1d6b7a21d21726f" title="Polar image descriptor.">descPolarImages</a> = 8, <span class="comment">//!< Polar image descriptor</span> <a name="l00089"></a><a class="code" href="group__mrpt__vision__grp.html#gga1953f4dfcaf2e07e1049bc0a6bbf53baa390c61465755c909c19e4b2fc5763af6">00089</a> <span class="comment"></span> <a class="code" href="group__mrpt__vision__grp.html#gga1953f4dfcaf2e07e1049bc0a6bbf53baa390c61465755c909c19e4b2fc5763af6" title="Log-Polar image descriptor.">descLogPolarImages</a> = 16 <span class="comment">//!< Log-Polar image descriptor</span> <a name="l00090"></a>00090 <span class="comment"></span> }; <a name="l00091"></a>00091 <a name="l00092"></a><a class="code" href="group__mrpt__vision__grp.html#ga0437f34e59ac06cddc3a490e2605bb71">00092</a> <span class="keyword">enum</span> <a class="code" href="group__mrpt__vision__grp.html#ga0437f34e59ac06cddc3a490e2605bb71">TFeatureTrackStatus</a> <a name="l00093"></a>00093 { <a name="l00094"></a>00094 <span class="comment">// Init value</span> <a name="l00095"></a><a class="code" href="group__mrpt__vision__grp.html#gga0437f34e59ac06cddc3a490e2605bb71a7b4b02aab37b191b162d7ecfd74c4fe4">00095</a> <a class="code" href="group__mrpt__vision__grp.html#gga0437f34e59ac06cddc3a490e2605bb71a7b4b02aab37b191b162d7ecfd74c4fe4" title="Inactive (right after detection, and before being tried to track)">status_IDLE</a> = 0, <span class="comment">//!< Inactive (right after detection, and before being tried to track)</span> <a name="l00096"></a>00096 <span class="comment"></span> <a name="l00097"></a>00097 <span class="comment">// Ok:</span> <a name="l00098"></a><a class="code" href="group__mrpt__vision__grp.html#gga0437f34e59ac06cddc3a490e2605bb71a0aae44767d442aabe1ded915e815b68f">00098</a> <a class="code" href="group__mrpt__vision__grp.html#gga0437f34e59ac06cddc3a490e2605bb71a0aae44767d442aabe1ded915e815b68f" title="Feature correctly tracked.">status_TRACKED</a> = 5, <span class="comment">//!< Feature correctly tracked</span> <a name="l00099"></a>00099 <span class="comment"></span> <a name="l00100"></a>00100 <span class="comment">// Bad:</span> <a name="l00101"></a><a class="code" href="group__mrpt__vision__grp.html#gga0437f34e59ac06cddc3a490e2605bb71a1911a86068b8ba81d0ea8739c3d7a795">00101</a> <a class="code" href="group__mrpt__vision__grp.html#gga0437f34e59ac06cddc3a490e2605bb71a1911a86068b8ba81d0ea8739c3d7a795" title="Feature felt Out Of Bounds.">status_OOB</a> = 1, <span class="comment">//!< Feature felt Out Of Bounds</span> <a name="l00102"></a><a class="code" href="group__mrpt__vision__grp.html#gga0437f34e59ac06cddc3a490e2605bb71a49ca2957bd7ecaaa912902105b24c5e0">00102</a> <span class="comment"></span> <a class="code" href="group__mrpt__vision__grp.html#gga0437f34e59ac06cddc3a490e2605bb71a49ca2957bd7ecaaa912902105b24c5e0" title="Unable to track this feature.">status_LOST</a> = 10, <span class="comment">//!< Unable to track this feature</span> <a name="l00103"></a>00103 <span class="comment"></span> <a name="l00104"></a>00104 <span class="comment">// KLT specific:</span> <a name="l00105"></a><a class="code" href="group__mrpt__vision__grp.html#gga0437f34e59ac06cddc3a490e2605bb71a9879fb00796ddd90580b390667c02710">00105</a> <a class="code" href="group__mrpt__vision__grp.html#gga0437f34e59ac06cddc3a490e2605bb71a9879fb00796ddd90580b390667c02710" title="Inactive.">statusKLT_IDLE</a> = 0, <span class="comment">//!< Inactive</span> <a name="l00106"></a><a class="code" href="group__mrpt__vision__grp.html#gga0437f34e59ac06cddc3a490e2605bb71a209430eccc30485a0549a1ba3fea75c7">00106</a> <span class="comment"></span> <a class="code" href="group__mrpt__vision__grp.html#gga0437f34e59ac06cddc3a490e2605bb71a209430eccc30485a0549a1ba3fea75c7" title="Out Of Bounds (Value identical to status_OOB)">statusKLT_OOB</a> = 1, <span class="comment">//!< Out Of Bounds (Value identical to status_OOB)</span> <a name="l00107"></a><a class="code" href="group__mrpt__vision__grp.html#gga0437f34e59ac06cddc3a490e2605bb71ae7d7ef9e6306fb1a546223664b7d43af">00107</a> <span class="comment"></span> <a class="code" href="group__mrpt__vision__grp.html#gga0437f34e59ac06cddc3a490e2605bb71ae7d7ef9e6306fb1a546223664b7d43af" title="Determinant of the matrix too small.">statusKLT_SMALL_DET</a> = 2, <span class="comment">//!< Determinant of the matrix too small</span> <a name="l00108"></a><a class="code" href="group__mrpt__vision__grp.html#gga0437f34e59ac06cddc3a490e2605bb71a4574d88abb293be6abb2d5a9f412ce68">00108</a> <span class="comment"></span> <a class="code" href="group__mrpt__vision__grp.html#gga0437f34e59ac06cddc3a490e2605bb71a4574d88abb293be6abb2d5a9f412ce68" title="Error too big.">statusKLT_LARGE_RESIDUE</a> = 3, <span class="comment">//!< Error too big</span> <a name="l00109"></a><a class="code" href="group__mrpt__vision__grp.html#gga0437f34e59ac06cddc3a490e2605bb71afe042395cd26c5b51149533b15a99f39">00109</a> <span class="comment"></span> <a class="code" href="group__mrpt__vision__grp.html#gga0437f34e59ac06cddc3a490e2605bb71afe042395cd26c5b51149533b15a99f39">statusKLT_MAX_RESIDUE</a> = 4, <a name="l00110"></a><a class="code" href="group__mrpt__vision__grp.html#gga0437f34e59ac06cddc3a490e2605bb71ab3fa909025d3002ce2c3772a8d9def9a">00110</a> <a class="code" href="group__mrpt__vision__grp.html#gga0437f34e59ac06cddc3a490e2605bb71ab3fa909025d3002ce2c3772a8d9def9a" title="Feature correctly tracked (Value identical to status_TRACKED)">statusKLT_TRACKED</a> = 5, <span class="comment">//!< Feature correctly tracked (Value identical to status_TRACKED)</span> <a name="l00111"></a><a class="code" href="group__mrpt__vision__grp.html#gga0437f34e59ac06cddc3a490e2605bb71abf7ddf49b7347c2280d013d76856bd9d">00111</a> <span class="comment"></span> <a class="code" href="group__mrpt__vision__grp.html#gga0437f34e59ac06cddc3a490e2605bb71abf7ddf49b7347c2280d013d76856bd9d" title="Iteration maximum reached.">statusKLT_MAX_ITERATIONS</a> = 6 <span class="comment">//!< Iteration maximum reached</span> <a name="l00112"></a>00112 <span class="comment"></span> }; <a name="l00113"></a>00113 <a name="l00114"></a><a class="code" href="group__mrpt__vision__grp.html#ga9ba0cae6d18573372451f923bb21fa55">00114</a> <span class="keyword">typedef</span> <a class="code" href="group__mrpt__vision__grp.html#ga0437f34e59ac06cddc3a490e2605bb71">TFeatureTrackStatus</a> <a class="code" href="group__mrpt__vision__grp.html#ga9ba0cae6d18573372451f923bb21fa55" title="For backward compatibility.">TKLTFeatureStatus</a>; <span class="comment">//!< For backward compatibility</span> <a name="l00115"></a>00115 <span class="comment"></span> <a name="l00116"></a>00116 <span class="comment"></span> <a name="l00117"></a>00117 <span class="comment"> /** One feature observation entry, used within sequences with TSequenceFeatureObservations */</span> <a name="l00118"></a>00118 <span class="keyword">struct </span><a class="code" href="vision_2include_2mrpt_2vision_2link__pragmas_8h.html#aa4a17fb846aac61f4e57b17b6f784559">VISION_IMPEXP</a> <a class="code" href="structmrpt_1_1vision_1_1_t_feature_observation.html" title="One feature observation entry, used within sequences with TSequenceFeatureObservations.">TFeatureObservation</a> <a name="l00119"></a>00119 { <a name="l00120"></a><a class="code" href="structmrpt_1_1vision_1_1_t_feature_observation.html#a4637b246c67278eda4707639f6ea4138">00120</a> <span class="keyword">inline</span> <a class="code" href="structmrpt_1_1vision_1_1_t_feature_observation.html#a4637b246c67278eda4707639f6ea4138">TFeatureObservation</a>() { } <a name="l00121"></a><a class="code" href="structmrpt_1_1vision_1_1_t_feature_observation.html#aec89364531d63fda5b37c8ec5a8d6fa1">00121</a> <span class="keyword">inline</span> <a class="code" href="structmrpt_1_1vision_1_1_t_feature_observation.html#aec89364531d63fda5b37c8ec5a8d6fa1">TFeatureObservation</a>(<span class="keyword">const</span> <a class="code" href="group__mrpt__vision__grp.html#ga6c3892de843a8cf3bb52017d2933020f" title="Unique IDs for landmarks.">TLandmarkID</a> _id_feature, <span class="keyword">const</span> <a class="code" href="group__mrpt__vision__grp.html#gae9363bed7e308d38b23c0bcac8b5e5d8" title="Unique IDs for camera frames (poses)">TCameraPoseID</a> _id_frame, <span class="keyword">const</span> <a class="code" href="structmrpt_1_1utils_1_1_t_pixel_coordf.html" title="A pair (x,y) of pixel coordinates (subpixel resolution).">TPixelCoordf</a> _px) : id_feature(_id_feature), id_frame(_id_frame), px(_px) { } <a name="l00122"></a>00122 <a name="l00123"></a><a class="code" href="structmrpt_1_1vision_1_1_t_feature_observation.html#a563c2bfabbc763a83165678e9a8ed255">00123</a> <a class="code" href="group__mrpt__vision__grp.html#ga6c3892de843a8cf3bb52017d2933020f" title="Unique IDs for landmarks.">TLandmarkID</a> <a class="code" href="structmrpt_1_1vision_1_1_t_feature_observation.html#a563c2bfabbc763a83165678e9a8ed255" title="A unique ID of this feature.">id_feature</a>; <span class="comment">//!< A unique ID of this feature</span> <a name="l00124"></a><a class="code" href="structmrpt_1_1vision_1_1_t_feature_observation.html#a81f385555e4edf73562a4beb0fbd1009">00124</a> <span class="comment"></span> <a class="code" href="group__mrpt__vision__grp.html#gae9363bed7e308d38b23c0bcac8b5e5d8" title="Unique IDs for camera frames (poses)">TCameraPoseID</a> <a class="code" href="structmrpt_1_1vision_1_1_t_feature_observation.html#a81f385555e4edf73562a4beb0fbd1009" title="A unique ID of a "frame" (camera position) from where the feature was observed.">id_frame</a>; <span class="comment">//!< A unique ID of a "frame" (camera position) from where the feature was observed.</span> <a name="l00125"></a><a class="code" href="structmrpt_1_1vision_1_1_t_feature_observation.html#a56073a134c3b96a9a6efdd9bef06ee00">00125</a> <span class="comment"></span> <a class="code" href="structmrpt_1_1utils_1_1_t_pixel_coordf.html" title="A pair (x,y) of pixel coordinates (subpixel resolution).">TPixelCoordf</a> <a class="code" href="structmrpt_1_1vision_1_1_t_feature_observation.html#a56073a134c3b96a9a6efdd9bef06ee00" title="The pixel coordinates of the observed feature.">px</a>; <span class="comment">//!< The pixel coordinates of the observed feature</span> <a name="l00126"></a>00126 <span class="comment"></span> }; <a name="l00127"></a>00127 <span class="comment"></span> <a name="l00128"></a>00128 <span class="comment"> /** One relative feature observation entry, used with some relative bundle-adjustment functions.</span> <a name="l00129"></a>00129 <span class="comment"> */</span> <a name="l00130"></a>00130 <span class="keyword">struct </span><a class="code" href="structmrpt_1_1vision_1_1_t_relative_feature_pos.html" title="One relative feature observation entry, used with some relative bundle-adjustment functions...">TRelativeFeaturePos</a> <a name="l00131"></a>00131 { <a name="l00132"></a><a class="code" href="structmrpt_1_1vision_1_1_t_relative_feature_pos.html#a4e2f1064269fd214bdd8bbbebc1d9786">00132</a> <span class="keyword">inline</span> <a class="code" href="structmrpt_1_1vision_1_1_t_relative_feature_pos.html#a4e2f1064269fd214bdd8bbbebc1d9786">TRelativeFeaturePos</a>() { } <a name="l00133"></a><a class="code" href="structmrpt_1_1vision_1_1_t_relative_feature_pos.html#ac4abcdb8e4caf778350beab0f062f7d9">00133</a> <span class="keyword">inline</span> <a class="code" href="structmrpt_1_1vision_1_1_t_relative_feature_pos.html#ac4abcdb8e4caf778350beab0f062f7d9">TRelativeFeaturePos</a>(<span class="keyword">const</span> <a class="code" href="group__mrpt__vision__grp.html#gae9363bed7e308d38b23c0bcac8b5e5d8" title="Unique IDs for camera frames (poses)">mrpt::vision::TCameraPoseID</a> _id_frame_base, <span class="keyword">const</span> <a class="code" href="structmrpt_1_1math_1_1_t_point3_d.html" title="Lightweight 3D point.">mrpt::math::TPoint3D</a> _pos) : <a class="code" href="structmrpt_1_1vision_1_1_t_relative_feature_pos.html#a2a543b92776e092ebaf6badfd3d8758a" title="The ID of the camera frame which is the coordinate reference of pos.">id_frame_base</a>(_id_frame_base), <a class="code" href="structmrpt_1_1vision_1_1_t_relative_feature_pos.html#a425a9a3094d32abebc9aad37ab15e68c" title="The (x,y,z) location of the feature, wrt to the camera frame id_frame_base.">pos</a>(_pos) { } <a name="l00134"></a>00134 <a name="l00135"></a><a class="code" href="structmrpt_1_1vision_1_1_t_relative_feature_pos.html#a2a543b92776e092ebaf6badfd3d8758a">00135</a> mrpt<a class="code" href="group__mrpt__vision__grp.html#gae9363bed7e308d38b23c0bcac8b5e5d8" title="Unique IDs for camera frames (poses)">::vision::TCameraPoseID</a> <a class="code" href="structmrpt_1_1vision_1_1_t_relative_feature_pos.html#a2a543b92776e092ebaf6badfd3d8758a" title="The ID of the camera frame which is the coordinate reference of pos.">id_frame_base</a>; <span class="comment">//!< The ID of the camera frame which is the coordinate reference of \a pos</span> <a name="l00136"></a><a class="code" href="structmrpt_1_1vision_1_1_t_relative_feature_pos.html#a425a9a3094d32abebc9aad37ab15e68c">00136</a> <span class="comment"></span> mrpt<a class="code" href="structmrpt_1_1math_1_1_t_point3_d.html" title="Lightweight 3D point.">::math::TPoint3D</a> <a class="code" href="structmrpt_1_1vision_1_1_t_relative_feature_pos.html#a425a9a3094d32abebc9aad37ab15e68c" title="The (x,y,z) location of the feature, wrt to the camera frame id_frame_base.">pos</a>; <span class="comment">//!< The (x,y,z) location of the feature, wrt to the camera frame \a id_frame_base</span> <a name="l00137"></a>00137 <span class="comment"></span> }; <a name="l00138"></a>00138 <span class="comment"></span> <a name="l00139"></a>00139 <span class="comment"> /** An index of feature IDs and their relative locations */</span> <a name="l00140"></a><a class="code" href="group__mrpt__vision__grp.html#gac7efcc456498739aa62ed14e8173892a">00140</a> <span class="keyword">typedef</span> std<a class="code" href="classstd_1_1map.html" title="STL class.">::map<mrpt::vision::TFeatureID, TRelativeFeaturePos></a> <a class="code" href="group__mrpt__vision__grp.html#gac7efcc456498739aa62ed14e8173892a" title="An index of feature IDs and their relative locations.">TRelativeFeaturePosMap</a>; <a name="l00141"></a>00141 <span class="comment"></span> <a name="l00142"></a>00142 <span class="comment"> /** A complete sequence of observations of features from different camera frames (poses).</span> <a name="l00143"></a>00143 <span class="comment"> * This structure is the input to some (Bundle-adjustment) methods in mrpt::vision</span> <a name="l00144"></a>00144 <span class="comment"> * \note Pixel coordinates can be either "raw" or "undistorted". Read the doc of functions handling this structure to see what they expect.</span> <a name="l00145"></a>00145 <span class="comment"> * \sa mrpt::vision::bundle_adj_full</span> <a name="l00146"></a>00146 <span class="comment"> */</span> <a name="l00147"></a>00147 <span class="keyword">struct </span><a class="code" href="vision_2include_2mrpt_2vision_2link__pragmas_8h.html#aa4a17fb846aac61f4e57b17b6f784559">VISION_IMPEXP</a> <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).">TSequenceFeatureObservations</a> : <span class="keyword">public</span> std::<a class="code" href="classstd_1_1vector.html" title="STL class.">vector</a><TFeatureObservation> <a name="l00148"></a>00148 { <a name="l00149"></a><a class="code" href="structmrpt_1_1vision_1_1_t_sequence_feature_observations.html#ac548b74abe757a69326f26ce2b484ead">00149</a> <span class="keyword">typedef</span> std<a class="code" href="classstd_1_1vector.html">::vector<TFeatureObservation></a> <a class="code" href="structmrpt_1_1vision_1_1_t_sequence_feature_observations.html#ac548b74abe757a69326f26ce2b484ead">BASE</a>; <a name="l00150"></a>00150 <a name="l00151"></a><a class="code" href="structmrpt_1_1vision_1_1_t_sequence_feature_observations.html#af8b82039badd2873dbd76e24a23b88fe">00151</a> <span class="keyword">inline</span> <a class="code" href="structmrpt_1_1vision_1_1_t_sequence_feature_observations.html#af8b82039badd2873dbd76e24a23b88fe">TSequenceFeatureObservations</a>() {} <a name="l00152"></a><a class="code" href="structmrpt_1_1vision_1_1_t_sequence_feature_observations.html#a96b35f3cf50bcde483952d19d709300a">00152</a> <span class="keyword">inline</span> <a class="code" href="structmrpt_1_1vision_1_1_t_sequence_feature_observations.html#a96b35f3cf50bcde483952d19d709300a">TSequenceFeatureObservations</a>(<span class="keywordtype">size_t</span> <a class="code" href="namespacemrpt_1_1math.html#a632ae0aecf78103f87f18f9ac33f7170">size</a>) : <a class="code" href="classstd_1_1vector.html">BASE</a>(size) {} <a name="l00153"></a><a class="code" href="structmrpt_1_1vision_1_1_t_sequence_feature_observations.html#a5321b9cdd719e2b06e00fa5ad06cce95">00153</a> <span class="keyword">inline</span> <a class="code" href="structmrpt_1_1vision_1_1_t_sequence_feature_observations.html#a5321b9cdd719e2b06e00fa5ad06cce95">TSequenceFeatureObservations</a>(<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).">TSequenceFeatureObservations</a>& o) : <a class="code" href="classstd_1_1vector.html">BASE</a>(o) {} <a name="l00154"></a>00154 <span class="comment"></span> <a name="l00155"></a>00155 <span class="comment"> /** Saves all entries to a text file, with each line having this format: #FRAME_ID #FEAT_ID #PIXEL_X #PIXEL_Y</span> <a name="l00156"></a>00156 <span class="comment"> * The file is self-descripting, since the first line contains a comment line (starting with '%') explaining the format.</span> <a name="l00157"></a>00157 <span class="comment"> * Generated files can be loaded from MATLAB.</span> <a name="l00158"></a>00158 <span class="comment"> * \sa loadFromTextFile \exception std::exception On I/O error */</span> <a name="l00159"></a>00159 <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> &filName, <span class="keywordtype">bool</span> skipFirstCommentLine = <span class="keyword">false</span>) <span class="keyword">const</span>; <a name="l00160"></a>00160 <span class="comment"></span> <a name="l00161"></a>00161 <span class="comment"> /** Load from a text file, in the format described in \a saveToTextFile \exception std::exception On I/O or format error */</span> <a name="l00162"></a>00162 <span class="keywordtype">void</span> <a class="code" href="eigen__plugins_8h.html#ad3c68c35368d8a0254192e3c34ea5f61" title="Load matrix from a text file, compatible with MATLAB text format.">loadFromTextFile</a>(<span class="keyword">const</span> <a class="code" href="classstd_1_1string.html" title="STL class.">std::string</a> &filName); <a name="l00163"></a>00163 <span class="comment"></span> <a name="l00164"></a>00164 <span class="comment"> /** Save the list of observations + the point locations + the camera frame poses to a pair of files in the format</span> <a name="l00165"></a>00165 <span class="comment"> * used by the Sparse Bundle Adjustment (SBA) C++ library.</span> <a name="l00166"></a>00166 <span class="comment"> *</span> <a name="l00167"></a>00167 <span class="comment"> * Point file lines: X Y Z nframes frame0 x0 y0 frame1 x1 y1 ...</span> <a name="l00168"></a>00168 <span class="comment"> *</span> <a name="l00169"></a>00169 <span class="comment"> * Camera file lines: qr qx qy qz x y z (Pose as a quaternion)</span> <a name="l00170"></a>00170 <span class="comment"> * \return false on any error</span> <a name="l00171"></a>00171 <span class="comment"> */</span> <a name="l00172"></a>00172 <span class="keywordtype">bool</span> saveAsSBAFiles( <a name="l00173"></a>00173 <span class="keyword">const</span> <a class="code" href="classstd_1_1vector.html">TLandmarkLocationsVec</a> &pts, <a name="l00174"></a>00174 <span class="keyword">const</span> <a class="code" href="classstd_1_1string.html" title="STL class.">std::string</a> &pts_file, <a name="l00175"></a>00175 <span class="keyword">const</span> <a class="code" href="classstd_1_1vector.html" title="STL class.">TFramePosesVec</a> &cams, <a name="l00176"></a>00176 <span class="keyword">const</span> <a class="code" href="classstd_1_1string.html" title="STL class.">std::string</a> &cams_file) <span class="keyword">const</span>; <a name="l00177"></a>00177 <a name="l00178"></a>00178 <span class="comment"></span> <a name="l00179"></a>00179 <span class="comment"> /** Remove all those features that don't have a minimum number of observations from different camera frame IDs.</span> <a name="l00180"></a>00180 <span class="comment"> * \return the number of erased entries.</span> <a name="l00181"></a>00181 <span class="comment"> * \sa After calling this you may want to call \a compressIDs */</span> <a name="l00182"></a>00182 <span class="keywordtype">size_t</span> removeFewObservedFeatures(<span class="keywordtype">size_t</span> minNumObservations = 3); <a name="l00183"></a>00183 <span class="comment"></span> <a name="l00184"></a>00184 <span class="comment"> /** Remove all but one out of \a decimate_ratio camera frame IDs from the list (eg: from N camera pose IDs at return there will be just N/decimate_ratio)</span> <a name="l00185"></a>00185 <span class="comment"> * The algorithm first builds a sorted list of frame IDs, then keep the lowest ID, remove the next "decimate_ratio-1", and so on.</span> <a name="l00186"></a>00186 <span class="comment"> * \sa After calling this you may want to call \a compressIDs */</span> <a name="l00187"></a>00187 <span class="keywordtype">void</span> decimateCameraFrames(<span class="keyword">const</span> <span class="keywordtype">size_t</span> decimate_ratio); <a name="l00188"></a>00188 <span class="comment"></span> <a name="l00189"></a>00189 <span class="comment"> /** Rearrange frame and feature IDs such as they start at 0 and there are no gaps.</span> <a name="l00190"></a>00190 <span class="comment"> * \param old2new_camIDs If provided, the mapping from old to new IDs is stored here.</span> <a name="l00191"></a>00191 <span class="comment"> * \param old2new_lmIDs If provided, the mapping from old to new IDs is stored here. */</span> <a name="l00192"></a>00192 <span class="keywordtype">void</span> compressIDs( <a name="l00193"></a>00193 <a class="code" href="classstd_1_1map.html" title="STL class.">std::map<TCameraPoseID,TCameraPoseID></a> *old2new_camIDs=NULL, <a name="l00194"></a>00194 <a class="code" href="classstd_1_1map.html" title="STL class.">std::map<TLandmarkID,TLandmarkID></a> *old2new_lmIDs=NULL ); <a name="l00195"></a>00195 <a name="l00196"></a>00196 }; <a name="l00197"></a>00197 <span class="comment"></span> <a name="l00198"></a>00198 <span class="comment"> /** Parameters associated to a stereo system</span> <a name="l00199"></a>00199 <span class="comment"> */</span> <a name="l00200"></a>00200 <span class="keyword">struct </span><a class="code" href="vision_2include_2mrpt_2vision_2link__pragmas_8h.html#aa4a17fb846aac61f4e57b17b6f784559">VISION_IMPEXP</a> TStereoSystemParams : <span class="keyword">public</span> mrpt::utils::<a class="code" href="classmrpt_1_1utils_1_1_c_loadable_options.html" title="This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...">CLoadableOptions</a> <a name="l00201"></a>00201 {<span class="comment"></span> <a name="l00202"></a>00202 <span class="comment"> /** Initilization of default parameters</span> <a name="l00203"></a>00203 <span class="comment"> */</span> <a name="l00204"></a>00204 TStereoSystemParams( ); <a name="l00205"></a>00205 <span class="comment"></span> <a name="l00206"></a>00206 <span class="comment"> /** See utils::CLoadableOptions</span> <a name="l00207"></a>00207 <span class="comment"> */</span> <a name="l00208"></a>00208 <span class="keywordtype">void</span> loadFromConfigFile( <a name="l00209"></a>00209 <span class="keyword">const</span> <a class="code" href="classmrpt_1_1utils_1_1_c_config_file_base.html" title="This class allows loading and storing values and vectors of different types from a configuration text...">mrpt::utils::CConfigFileBase</a> &source, <a name="l00210"></a>00210 <span class="keyword">const</span> <a class="code" href="classstd_1_1string.html" title="STL class.">std::string</a> &section); <a name="l00211"></a>00211 <span class="comment"></span> <a name="l00212"></a>00212 <span class="comment"> /** See utils::CLoadableOptions</span> <a name="l00213"></a>00213 <span class="comment"> */</span> <a name="l00214"></a>00214 <span class="keywordtype">void</span> dumpToTextStream(<a class="code" href="classmrpt_1_1utils_1_1_c_stream.html" title="This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...">CStream</a> &out) <span class="keyword">const</span>; <a name="l00215"></a>00215 <span class="comment"></span> <a name="l00216"></a>00216 <span class="comment"> /** Method for propagating the feature's image coordinate uncertainty into 3D space. Default value: Prop_Linear</span> <a name="l00217"></a>00217 <span class="comment"> */</span> <a name="l00218"></a><a class="code" href="structmrpt_1_1vision_1_1_t_stereo_system_params.html#a74f759c8c5008d295b9d3360039eaa12">00218</a> <span class="keyword">enum</span> <a class="code" href="structmrpt_1_1vision_1_1_t_stereo_system_params.html#a74f759c8c5008d295b9d3360039eaa12" title="Method for propagating the feature's image coordinate uncertainty into 3D space.">TUnc_Prop_Method</a> <a name="l00219"></a>00219 {<span class="comment"></span> <a name="l00220"></a>00220 <span class="comment"> /** Linear propagation of the uncertainty</span> <a name="l00221"></a>00221 <span class="comment"> */</span> <a name="l00222"></a><a class="code" href="structmrpt_1_1vision_1_1_t_stereo_system_params.html#a74f759c8c5008d295b9d3360039eaa12a5514c5212e07f9b73af9b3a99913c02b">00222</a> Prop_Linear = -1,<span class="comment"></span> <a name="l00223"></a>00223 <span class="comment"> /** Uncertainty propagation through the Unscented Transformation</span> <a name="l00224"></a>00224 <span class="comment"> */</span> <a name="l00225"></a><a class="code" href="structmrpt_1_1vision_1_1_t_stereo_system_params.html#a74f759c8c5008d295b9d3360039eaa12ae9249a778142858d54b92832ffbc7683">00225</a> <a class="code" href="structmrpt_1_1vision_1_1_t_stereo_system_params.html#a74f759c8c5008d295b9d3360039eaa12ae9249a778142858d54b92832ffbc7683" title="Uncertainty propagation through the Unscented Transformation.">Prop_UT</a>,<span class="comment"></span> <a name="l00226"></a>00226 <span class="comment"> /** Uncertainty propagation through the Scaled Unscented Transformation</span> <a name="l00227"></a>00227 <span class="comment"> */</span> <a name="l00228"></a><a class="code" href="structmrpt_1_1vision_1_1_t_stereo_system_params.html#a74f759c8c5008d295b9d3360039eaa12ae479deae88cf7201cba7f1e8f9deda01">00228</a> Prop_SUT <a name="l00229"></a>00229 }; <a name="l00230"></a>00230 <a name="l00231"></a><a class="code" href="structmrpt_1_1vision_1_1_t_stereo_system_params.html#a4152885bffa0b883f23125fd15999d1f">00231</a> <a class="code" href="structmrpt_1_1vision_1_1_t_stereo_system_params.html#a74f759c8c5008d295b9d3360039eaa12" title="Method for propagating the feature's image coordinate uncertainty into 3D space.">TUnc_Prop_Method</a> <a class="code" href="structmrpt_1_1vision_1_1_t_stereo_system_params.html#a4152885bffa0b883f23125fd15999d1f">uncPropagation</a>; <a name="l00232"></a>00232 <span class="comment"></span> <a name="l00233"></a>00233 <span class="comment"> /** Stereo Fundamental matrix */</span> <a name="l00234"></a><a class="code" href="structmrpt_1_1vision_1_1_t_stereo_system_params.html#adc0d8253a024468fb4d15b2207b7e26b">00234</a> <a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html">CMatrixDouble33</a> <a class="code" href="structmrpt_1_1vision_1_1_t_stereo_system_params.html#adc0d8253a024468fb4d15b2207b7e26b" title="Stereo Fundamental matrix.">F</a>; <a name="l00235"></a>00235 <span class="comment"></span> <a name="l00236"></a>00236 <span class="comment"> /** Intrinsic parameters</span> <a name="l00237"></a>00237 <span class="comment"> */</span> <a name="l00238"></a><a class="code" href="structmrpt_1_1vision_1_1_t_stereo_system_params.html#a7205ec592fd506c42d9f6dd1455e5b8f">00238</a> <a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html">CMatrixDouble33</a> <a class="code" href="structmrpt_1_1vision_1_1_t_stereo_system_params.html#a7205ec592fd506c42d9f6dd1455e5b8f" title="Intrinsic parameters.">K</a>;<span class="comment"></span> <a name="l00239"></a>00239 <span class="comment"> /** Baseline. Default value: baseline = 0.119f; [Bumblebee]</span> <a name="l00240"></a>00240 <span class="comment"> */</span> <a name="l00241"></a><a class="code" href="structmrpt_1_1vision_1_1_t_stereo_system_params.html#af0fffd9658897530fa1fbeade354a102">00241</a> <span class="keywordtype">float</span> <a class="code" href="structmrpt_1_1vision_1_1_t_stereo_system_params.html#af0fffd9658897530fa1fbeade354a102" title="Baseline.">baseline</a>;<span class="comment"></span> <a name="l00242"></a>00242 <span class="comment"> /** Standard deviation of the error in feature detection. Default value: stdPixel = 1</span> <a name="l00243"></a>00243 <span class="comment"> */</span> <a name="l00244"></a><a class="code" href="structmrpt_1_1vision_1_1_t_stereo_system_params.html#ab541a86e63fe3ea6f9bec9c883594822">00244</a> <span class="keywordtype">float</span> <a class="code" href="structmrpt_1_1vision_1_1_t_stereo_system_params.html#ab541a86e63fe3ea6f9bec9c883594822" title="Standard deviation of the error in feature detection.">stdPixel</a>;<span class="comment"></span> <a name="l00245"></a>00245 <span class="comment"> /** Standard deviation of the error in disparity computation. Default value: stdDisp = 1</span> <a name="l00246"></a>00246 <span class="comment"> */</span> <a name="l00247"></a><a class="code" href="structmrpt_1_1vision_1_1_t_stereo_system_params.html#a8555ef62aada1a79b1183017a115675b">00247</a> <span class="keywordtype">float</span> <a class="code" href="structmrpt_1_1vision_1_1_t_stereo_system_params.html#a8555ef62aada1a79b1183017a115675b" title="Standard deviation of the error in disparity computation.">stdDisp</a>;<span class="comment"></span> <a name="l00248"></a>00248 <span class="comment"> /** Maximum allowed distance. Default value: maxZ = 20.0f</span> <a name="l00249"></a>00249 <span class="comment"> */</span> <a name="l00250"></a><a class="code" href="structmrpt_1_1vision_1_1_t_stereo_system_params.html#a0f3dde4aa45f1d02d4444055b4e3f0da">00250</a> <span class="keywordtype">float</span> <a class="code" href="structmrpt_1_1vision_1_1_t_stereo_system_params.html#a0f3dde4aa45f1d02d4444055b4e3f0da" title="Maximum allowed distance.">maxZ</a>;<span class="comment"></span> <a name="l00251"></a>00251 <span class="comment"> /** Maximum allowed distance. Default value: minZ = 0.5f</span> <a name="l00252"></a>00252 <span class="comment"> */</span> <a name="l00253"></a><a class="code" href="structmrpt_1_1vision_1_1_t_stereo_system_params.html#ab16af063dfc099838905f6e2310602f3">00253</a> <span class="keywordtype">float</span> <a class="code" href="structmrpt_1_1vision_1_1_t_stereo_system_params.html#ab16af063dfc099838905f6e2310602f3" title="Maximum allowed distance.">minZ</a>;<span class="comment"></span> <a name="l00254"></a>00254 <span class="comment"> /** Maximum allowed height. Default value: maxY = 3.0f</span> <a name="l00255"></a>00255 <span class="comment"> */</span> <a name="l00256"></a><a class="code" href="structmrpt_1_1vision_1_1_t_stereo_system_params.html#aab405b3cc3bd4ce91b37ead38fb6abb9">00256</a> <span class="keywordtype">float</span> <a class="code" href="structmrpt_1_1vision_1_1_t_stereo_system_params.html#aab405b3cc3bd4ce91b37ead38fb6abb9" title="Maximum allowed height.">maxY</a>;<span class="comment"></span> <a name="l00257"></a>00257 <span class="comment"> /** K factor for the UT. Default value: k = 1.5f</span> <a name="l00258"></a>00258 <span class="comment"> */</span> <a name="l00259"></a><a class="code" href="structmrpt_1_1vision_1_1_t_stereo_system_params.html#a43cd4cc290582b7109e5ac88dc79ed15">00259</a> <span class="keywordtype">float</span> <a class="code" href="structmrpt_1_1vision_1_1_t_stereo_system_params.html#a43cd4cc290582b7109e5ac88dc79ed15" title="K factor for the UT.">factor_k</a>;<span class="comment"></span> <a name="l00260"></a>00260 <span class="comment"> /** Alpha factor for SUT. Default value: a = 1e-3</span> <a name="l00261"></a>00261 <span class="comment"> */</span> <a name="l00262"></a><a class="code" href="structmrpt_1_1vision_1_1_t_stereo_system_params.html#a088cd9ebea9a555d41ce47150156d687">00262</a> <span class="keywordtype">float</span> <a class="code" href="structmrpt_1_1vision_1_1_t_stereo_system_params.html#a088cd9ebea9a555d41ce47150156d687" title="Alpha factor for SUT.">factor_a</a>;<span class="comment"></span> <a name="l00263"></a>00263 <span class="comment"> /** Beta factor for the SUT. Default value: b = 2.0f</span> <a name="l00264"></a>00264 <span class="comment"> */</span> <a name="l00265"></a><a class="code" href="structmrpt_1_1vision_1_1_t_stereo_system_params.html#a4bce7cf4cf9ff8aac0859b29eb8360e8">00265</a> <span class="keywordtype">float</span> <a class="code" href="structmrpt_1_1vision_1_1_t_stereo_system_params.html#a4bce7cf4cf9ff8aac0859b29eb8360e8" title="Beta factor for the SUT.">factor_b</a>; <a name="l00266"></a>00266 <span class="comment"></span> <a name="l00267"></a>00267 <span class="comment"> /** Parameters initialization</span> <a name="l00268"></a>00268 <span class="comment"> */</span> <a name="l00269"></a>00269 <span class="comment">//TStereoSystemParams();</span> <a name="l00270"></a>00270 <a name="l00271"></a>00271 }; <span class="comment">// End struct TStereoSystemParams</span> <a name="l00272"></a>00272 <span class="comment"></span> <a name="l00273"></a>00273 <span class="comment"> /** A structure for storing a 3D ROI</span> <a name="l00274"></a>00274 <span class="comment"> */</span> <a name="l00275"></a>00275 <span class="keyword">struct </span><a class="code" href="vision_2include_2mrpt_2vision_2link__pragmas_8h.html#aa4a17fb846aac61f4e57b17b6f784559">VISION_IMPEXP</a> <a class="code" href="structmrpt_1_1vision_1_1_t_r_o_i.html" title="A structure for storing a 3D ROI.">TROI</a> <a name="l00276"></a>00276 { <a name="l00277"></a>00277 <span class="comment">// Constructors</span> <a name="l00278"></a>00278 <a class="code" href="structmrpt_1_1vision_1_1_t_r_o_i.html" title="A structure for storing a 3D ROI.">TROI</a>(); <a name="l00279"></a>00279 TROI(<span class="keywordtype">float</span> x1, <span class="keywordtype">float</span> x2, <span class="keywordtype">float</span> y1, <span class="keywordtype">float</span> y2, <span class="keywordtype">float</span> z1, <span class="keywordtype">float</span> z2); <a name="l00280"></a>00280 <a name="l00281"></a>00281 <span class="comment">// Members</span> <a name="l00282"></a><a class="code" href="structmrpt_1_1vision_1_1_t_r_o_i.html#aa6eb5053d8006b2240e493717d2a867a">00282</a> <span class="keywordtype">float</span> <a class="code" href="structmrpt_1_1vision_1_1_t_r_o_i.html#aa6eb5053d8006b2240e493717d2a867a">xMin</a>; <a name="l00283"></a><a class="code" href="structmrpt_1_1vision_1_1_t_r_o_i.html#ad256b28c7bea7d0d70d29f6dfa1bc3d9">00283</a> <span class="keywordtype">float</span> <a class="code" href="structmrpt_1_1vision_1_1_t_r_o_i.html#ad256b28c7bea7d0d70d29f6dfa1bc3d9">xMax</a>; <a name="l00284"></a><a class="code" href="structmrpt_1_1vision_1_1_t_r_o_i.html#ac786630189f3b9e8c01ab499427c441d">00284</a> <span class="keywordtype">float</span> <a class="code" href="structmrpt_1_1vision_1_1_t_r_o_i.html#ac786630189f3b9e8c01ab499427c441d">yMin</a>; <a name="l00285"></a><a class="code" href="structmrpt_1_1vision_1_1_t_r_o_i.html#a76587f31eb6df0e09feaf79968da548d">00285</a> <span class="keywordtype">float</span> <a class="code" href="structmrpt_1_1vision_1_1_t_r_o_i.html#a76587f31eb6df0e09feaf79968da548d">yMax</a>; <a name="l00286"></a><a class="code" href="structmrpt_1_1vision_1_1_t_r_o_i.html#ad51472281e39357269eef990711ec7d4">00286</a> <span class="keywordtype">float</span> <a class="code" href="structmrpt_1_1vision_1_1_t_r_o_i.html#ad51472281e39357269eef990711ec7d4">zMin</a>; <a name="l00287"></a><a class="code" href="structmrpt_1_1vision_1_1_t_r_o_i.html#a0db15507c4e26c6ab2c802ba33ff94c5">00287</a> <span class="keywordtype">float</span> <a class="code" href="structmrpt_1_1vision_1_1_t_r_o_i.html#a0db15507c4e26c6ab2c802ba33ff94c5">zMax</a>; <a name="l00288"></a>00288 }; <span class="comment">// end struct TROI</span> <a name="l00289"></a>00289 <span class="comment"></span> <a name="l00290"></a>00290 <span class="comment"> /** A structure for defining a ROI within an image</span> <a name="l00291"></a>00291 <span class="comment"> */</span> <a name="l00292"></a>00292 <span class="keyword">struct </span><a class="code" href="vision_2include_2mrpt_2vision_2link__pragmas_8h.html#aa4a17fb846aac61f4e57b17b6f784559">VISION_IMPEXP</a> <a class="code" href="structmrpt_1_1vision_1_1_t_image_r_o_i.html" title="A structure for defining a ROI within an image.">TImageROI</a> <a name="l00293"></a>00293 { <a name="l00294"></a>00294 <span class="comment">// Constructors</span> <a name="l00295"></a>00295 <a class="code" href="structmrpt_1_1vision_1_1_t_image_r_o_i.html" title="A structure for defining a ROI within an image.">TImageROI</a>(); <a name="l00296"></a>00296 TImageROI( <span class="keywordtype">float</span> x1, <span class="keywordtype">float</span> x2, <span class="keywordtype">float</span> y1, <span class="keywordtype">float</span> y2 ); <a name="l00297"></a>00297 <a name="l00298"></a>00298 <span class="comment">// Members</span><span class="comment"></span> <a name="l00299"></a>00299 <span class="comment"> /** X coordinate limits [0,imageWidth)</span> <a name="l00300"></a>00300 <span class="comment"> */</span> <a name="l00301"></a><a class="code" href="structmrpt_1_1vision_1_1_t_image_r_o_i.html#af3107ab7a9d584e84aa822639f4cd63e">00301</a> <span class="keywordtype">float</span> <a class="code" href="structmrpt_1_1vision_1_1_t_image_r_o_i.html#af3107ab7a9d584e84aa822639f4cd63e" title="X coordinate limits [0,imageWidth)">xMin</a>, xMax;<span class="comment"></span> <a name="l00302"></a>00302 <span class="comment"> /** Y coordinate limits [0,imageHeight)</span> <a name="l00303"></a>00303 <span class="comment"> */</span> <a name="l00304"></a><a class="code" href="structmrpt_1_1vision_1_1_t_image_r_o_i.html#a4a89f0a93668fcd8db2f8393fe0efedb">00304</a> <span class="keywordtype">float</span> <a class="code" href="structmrpt_1_1vision_1_1_t_image_r_o_i.html#a4a89f0a93668fcd8db2f8393fe0efedb" title="Y coordinate limits [0,imageHeight)">yMin</a>, yMax; <a name="l00305"></a>00305 }; <span class="comment">// end struct TImageROI</span> <a name="l00306"></a>00306 <span class="comment"></span> <a name="l00307"></a>00307 <span class="comment"> /** A structure containing options for the matching</span> <a name="l00308"></a>00308 <span class="comment"> */</span> <a name="l00309"></a>00309 <span class="keyword">struct </span><a class="code" href="vision_2include_2mrpt_2vision_2link__pragmas_8h.html#aa4a17fb846aac61f4e57b17b6f784559">VISION_IMPEXP</a> <a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html" title="A structure containing options for the matching.">TMatchingOptions</a> : <span class="keyword">public</span> mrpt::utils::<a class="code" href="classmrpt_1_1utils_1_1_c_loadable_options.html" title="This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...">CLoadableOptions</a> <a name="l00310"></a>00310 { <a name="l00311"></a>00311 <span class="comment"></span> <a name="l00312"></a>00312 <span class="comment"> /** Method for propagating the feature's image coordinate uncertainty into 3D space. Default value: Prop_Linear</span> <a name="l00313"></a>00313 <span class="comment"> */</span> <a name="l00314"></a><a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a3b561c3772383b87cf37f400173d9e43">00314</a> <span class="keyword">enum</span> <a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a3b561c3772383b87cf37f400173d9e43" title="Method for propagating the feature's image coordinate uncertainty into 3D space.">TMatchingMethod</a> <a name="l00315"></a>00315 {<span class="comment"></span> <a name="l00316"></a>00316 <span class="comment"> /** Matching by cross correlation of the image patches</span> <a name="l00317"></a>00317 <span class="comment"> */</span> <a name="l00318"></a><a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a3b561c3772383b87cf37f400173d9e43a2a827a4a65d508efd2a4d49a943e673c">00318</a> mmCorrelation = 0,<span class="comment"></span> <a name="l00319"></a>00319 <span class="comment"> /** Matching by Euclidean distance between SIFT descriptors</span> <a name="l00320"></a>00320 <span class="comment"> */</span> <a name="l00321"></a><a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a3b561c3772383b87cf37f400173d9e43a9bb56101669fa8adb0a977eeb7b107de">00321</a> <a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a3b561c3772383b87cf37f400173d9e43a9bb56101669fa8adb0a977eeb7b107de" title="Matching by Euclidean distance between SIFT descriptors.">mmDescriptorSIFT</a>,<span class="comment"></span> <a name="l00322"></a>00322 <span class="comment"> /** Matching by Euclidean distance between SURF descriptors</span> <a name="l00323"></a>00323 <span class="comment"> */</span> <a name="l00324"></a><a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a3b561c3772383b87cf37f400173d9e43aafabd98ffec70f046dec0b0475fe0162">00324</a> <a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a3b561c3772383b87cf37f400173d9e43aafabd98ffec70f046dec0b0475fe0162" title="Matching by Euclidean distance between SURF descriptors.">mmDescriptorSURF</a>,<span class="comment"></span> <a name="l00325"></a>00325 <span class="comment"> /** Matching by sum of absolute differences of the image patches</span> <a name="l00326"></a>00326 <span class="comment"> */</span> <a name="l00327"></a><a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a3b561c3772383b87cf37f400173d9e43a012aed6aac26defc88c731824923bc51">00327</a> mmSAD <a name="l00328"></a>00328 }; <a name="l00329"></a>00329 <a name="l00330"></a>00330 <span class="comment">// For determining</span> <a name="l00331"></a><a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#ad837d34e9340d9aae00b637f87963de2">00331</a> <span class="keywordtype">bool</span> <a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#ad837d34e9340d9aae00b637f87963de2" title="Whether or not take into account the epipolar restriction for finding correspondences.">useEpipolarRestriction</a>; <span class="comment">//!< Whether or not take into account the epipolar restriction for finding correspondences</span> <a name="l00332"></a><a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a0daee890b1a9c379cc3ee3fe258e5b5e">00332</a> <span class="comment"></span> <span class="keywordtype">bool</span> <a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a0daee890b1a9c379cc3ee3fe258e5b5e" title="Whether or not there is a fundamental matrix.">hasFundamentalMatrix</a>; <span class="comment">//!< Whether or not there is a fundamental matrix</span> <a name="l00333"></a><a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a00dd2c93dba02fc053b2ba3dad3369e4">00333</a> <span class="comment"></span> <span class="keywordtype">bool</span> <a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a00dd2c93dba02fc053b2ba3dad3369e4" title="Whether or not the stereo rig has the optical axes parallel.">parallelOpticalAxis</a>; <span class="comment">//!< Whether or not the stereo rig has the optical axes parallel</span> <a name="l00334"></a><a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a01fd112682043f7668afdc61a4f61bc9">00334</a> <span class="comment"></span> <span class="keywordtype">bool</span> <a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a01fd112682043f7668afdc61a4f61bc9" title="Whether or not employ the x-coord restriction for finding correspondences (bumblebee camera...">useXRestriction</a>; <span class="comment">//!< Whether or not employ the x-coord restriction for finding correspondences (bumblebee camera, for example)</span> <a name="l00335"></a><a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a6e213086a0543fcacd89b0e4e577f604">00335</a> <span class="comment"></span> <span class="keywordtype">bool</span> <a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a6e213086a0543fcacd89b0e4e577f604" title="Whether or not to add the matches found into the input matched list (if false the input list will be ...">addMatches</a>; <span class="comment">//!< Whether or not to add the matches found into the input matched list (if false the input list will be cleared before being filled with the new matches)</span> <a name="l00336"></a>00336 <span class="comment"></span> <a name="l00337"></a><a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#aa313d061f8af42eb9a73ecf740cc5214">00337</a> <a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html">CMatrixDouble33</a> <a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#aa313d061f8af42eb9a73ecf740cc5214">F</a>; <a name="l00338"></a>00338 <a name="l00339"></a>00339 <span class="comment">// General</span> <a name="l00340"></a><a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#ab6cade63b551cfadb686a08321b464f5">00340</a> <a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a3b561c3772383b87cf37f400173d9e43" title="Method for propagating the feature's image coordinate uncertainty into 3D space.">TMatchingMethod</a> <a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#ab6cade63b551cfadb686a08321b464f5" title="Matching method.">matching_method</a>; <span class="comment">//!< Matching method</span> <a name="l00341"></a><a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a0e4d37fafba30aea3a010e4d5106212e">00341</a> <span class="comment"></span> <span class="keywordtype">float</span> <a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a0e4d37fafba30aea3a010e4d5106212e" title="Epipolar constraint (rows of pixels)">epipolar_TH</a>; <span class="comment">//!< Epipolar constraint (rows of pixels)</span> <a name="l00342"></a>00342 <span class="comment"></span> <a name="l00343"></a>00343 <span class="comment">// SIFT</span> <a name="l00344"></a><a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a4affe67b6cf6b03062fd60555623008d">00344</a> <span class="keywordtype">float</span> <a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a4affe67b6cf6b03062fd60555623008d" title="Maximum Euclidean Distance Between SIFT Descriptors.">maxEDD_TH</a>; <span class="comment">//!< Maximum Euclidean Distance Between SIFT Descriptors</span> <a name="l00345"></a><a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a42358061aba70dcd7b1a2bcd08786cf8">00345</a> <span class="comment"></span> <span class="keywordtype">float</span> <a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a42358061aba70dcd7b1a2bcd08786cf8" title="Boundary Ratio between the two lowest EDD.">EDD_RATIO</a>; <span class="comment">//!< Boundary Ratio between the two lowest EDD</span> <a name="l00346"></a>00346 <span class="comment"></span> <a name="l00347"></a>00347 <span class="comment">// KLT</span> <a name="l00348"></a><a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#aae8c136ebd768f9a20114265ead69985">00348</a> <span class="keywordtype">float</span> <a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#aae8c136ebd768f9a20114265ead69985" title="Minimum Value of the Cross Correlation.">minCC_TH</a>; <span class="comment">//!< Minimum Value of the Cross Correlation</span> <a name="l00349"></a><a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a56165608cf10ccd1cb285ebefc4ce522">00349</a> <span class="comment"></span> <span class="keywordtype">float</span> <a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a56165608cf10ccd1cb285ebefc4ce522" title="Minimum Difference Between the Maximum Cross Correlation Values.">minDCC_TH</a>; <span class="comment">//!< Minimum Difference Between the Maximum Cross Correlation Values</span> <a name="l00350"></a><a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a1dca82278b820d647290a36c4f789657">00350</a> <span class="comment"></span> <span class="keywordtype">float</span> <a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a1dca82278b820d647290a36c4f789657" title="Maximum Ratio Between the two highest CC values.">rCC_TH</a>; <span class="comment">//!< Maximum Ratio Between the two highest CC values</span> <a name="l00351"></a>00351 <span class="comment"></span> <a name="l00352"></a>00352 <span class="comment">// SURF</span> <a name="l00353"></a><a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#ae3596140dfa710e14deba9f263610376">00353</a> <span class="keywordtype">float</span> <a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#ae3596140dfa710e14deba9f263610376" title="Maximum Euclidean Distance Between SURF Descriptors.">maxEDSD_TH</a>; <span class="comment">//!< Maximum Euclidean Distance Between SURF Descriptors</span> <a name="l00354"></a><a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#aea64ded630c1046a4a4ca2030a9d3952">00354</a> <span class="comment"></span> <span class="keywordtype">float</span> <a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#aea64ded630c1046a4a4ca2030a9d3952" title="Boundary Ratio between the two lowest SURF EDSD.">EDSD_RATIO</a>; <span class="comment">//!< Boundary Ratio between the two lowest SURF EDSD</span> <a name="l00355"></a>00355 <span class="comment"></span> <a name="l00356"></a>00356 <span class="comment">// SAD</span> <a name="l00357"></a><a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a7effd731afe84a9e74681bab6d16c134">00357</a> <span class="keywordtype">double</span> <a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a7effd731afe84a9e74681bab6d16c134" title="Minimum Euclidean Distance Between Sum of Absolute Differences.">maxSAD_TH</a>; <span class="comment">//!< Minimum Euclidean Distance Between Sum of Absolute Differences</span> <a name="l00358"></a><a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a6781dda8f91ff671e308fdc309a99cb4">00358</a> <span class="comment"></span> <span class="keywordtype">double</span> <a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a6781dda8f91ff671e308fdc309a99cb4" title="Boundary Ratio between the two highest SAD.">SAD_RATIO</a>; <span class="comment">//!< Boundary Ratio between the two highest SAD</span> <a name="l00359"></a>00359 <span class="comment"></span> <a name="l00360"></a>00360 <span class="comment">// // To estimate depth</span> <a name="l00361"></a><a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a687e2eb5b17b9138189e5ed9e4b94d95">00361</a> <span class="keywordtype">bool</span> <a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a687e2eb5b17b9138189e5ed9e4b94d95" title="Whether or not estimate the 3D position of the real features for the matches (only with parallelOptic...">estimateDepth</a>; <span class="comment">//!< Whether or not estimate the 3D position of the real features for the matches (only with parallelOpticalAxis by now).</span> <a name="l00362"></a><a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a2103f36a9d375522d3e25303721d921f">00362</a> <span class="comment"></span> <span class="keywordtype">double</span> <a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html#a2103f36a9d375522d3e25303721d921f" title="The maximum allowed depth for the matching. If its computed depth is larger than this, the match won't be considered.">maxDepthThreshold</a>; <span class="comment">//!< The maximum allowed depth for the matching. If its computed depth is larger than this, the match won't be considered.</span> <a name="l00363"></a>00363 <span class="comment"></span><span class="comment">// double fx,cx,cy,baseline; //!< Intrinsic parameters of the stereo rig</span> <a name="l00364"></a>00364 <span class="comment"></span> <a name="l00365"></a>00365 <span class="comment"> /** Constructor</span> <a name="l00366"></a>00366 <span class="comment"> */</span> <a name="l00367"></a>00367 <a class="code" href="structmrpt_1_1vision_1_1_t_matching_options.html" title="A structure containing options for the matching.">TMatchingOptions</a>( ); <a name="l00368"></a>00368 <span class="comment"></span> <a name="l00369"></a>00369 <span class="comment"> /** See utils::CLoadableOptions</span> <a name="l00370"></a>00370 <span class="comment"> */</span> <a name="l00371"></a>00371 <span class="keywordtype">void</span> loadFromConfigFile( <a name="l00372"></a>00372 <span class="keyword">const</span> <a class="code" href="classmrpt_1_1utils_1_1_c_config_file_base.html" title="This class allows loading and storing values and vectors of different types from a configuration text...">mrpt::utils::CConfigFileBase</a> &source, <a name="l00373"></a>00373 <span class="keyword">const</span> <a class="code" href="classstd_1_1string.html" title="STL class.">std::string</a> &section); <a name="l00374"></a>00374 <span class="comment"></span> <a name="l00375"></a>00375 <span class="comment"> /** See utils::CLoadableOptions</span> <a name="l00376"></a>00376 <span class="comment"> */</span> <a name="l00377"></a>00377 <span class="keywordtype">void</span> dumpToTextStream(<a class="code" href="classmrpt_1_1utils_1_1_c_stream.html" title="This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...">CStream</a> &out) <span class="keyword">const</span>; <a name="l00378"></a>00378 <a name="l00379"></a>00379 }; <span class="comment">// end struct TMatchingOptions</span> <a name="l00380"></a>00380 <span class="comment"></span> <a name="l00381"></a>00381 <span class="comment"> /** Struct containing the output after matching multi-resolution SIFT-like descriptors</span> <a name="l00382"></a>00382 <span class="comment"> */</span> <a name="l00383"></a>00383 <span class="keyword">struct </span><a class="code" href="vision_2include_2mrpt_2vision_2link__pragmas_8h.html#aa4a17fb846aac61f4e57b17b6f784559">VISION_IMPEXP</a> <a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_matching_output.html" title="Struct containing the output after matching multi-resolution SIFT-like descriptors.">TMultiResMatchingOutput</a> <a name="l00384"></a>00384 { <a name="l00385"></a><a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_matching_output.html#a93bedf309c91bdfc24d03353cb2b2a7b">00385</a> <span class="keywordtype">int</span> <a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_matching_output.html#a93bedf309c91bdfc24d03353cb2b2a7b">nMatches</a>; <a name="l00386"></a>00386 <a name="l00387"></a><a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_matching_output.html#a5b8430944a8a5f545ebf9cc8559ced4a">00387</a> std<a class="code" href="classstd_1_1vector.html">::vector<int></a> <a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_matching_output.html#a5b8430944a8a5f545ebf9cc8559ced4a" title="Contains the indexes within the second list corresponding to the first one.">firstListCorrespondences</a>; <span class="comment">//!< Contains the indexes within the second list corresponding to the first one.</span> <a name="l00388"></a><a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_matching_output.html#aba190ffc5091917b5f335cbc35fa1df4">00388</a> <span class="comment"></span> std<a class="code" href="classstd_1_1vector.html">::vector<int></a> <a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_matching_output.html#aba190ffc5091917b5f335cbc35fa1df4" title="Contains the indexes within the first list corresponding to the second one.">secondListCorrespondences</a>; <span class="comment">//!< Contains the indexes within the first list corresponding to the second one.</span> <a name="l00389"></a><a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_matching_output.html#a6d42c7f617f612e3d8c264f4495af7e7">00389</a> <span class="comment"></span> std<a class="code" href="classstd_1_1vector.html">::vector<int></a> <a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_matching_output.html#a6d42c7f617f612e3d8c264f4495af7e7" title="Contains the scales of the first list where the correspondence was found.">firstListFoundScales</a>; <span class="comment">//!< Contains the scales of the first list where the correspondence was found.</span> <a name="l00390"></a><a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_matching_output.html#a1b694c01d070e735ef465759f601abca">00390</a> <span class="comment"></span> std<a class="code" href="classstd_1_1vector.html">::vector<double></a> <a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_matching_output.html#a1b694c01d070e735ef465759f601abca" title="Contains the distances between the descriptors.">firstListDistance</a>; <span class="comment">//!< Contains the distances between the descriptors.</span> <a name="l00391"></a>00391 <span class="comment"></span> <a name="l00392"></a><a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_matching_output.html#aad4b5027a7560dac2ad27f490dd6a859">00392</a> <a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_matching_output.html" title="Struct containing the output after matching multi-resolution SIFT-like descriptors.">TMultiResMatchingOutput</a>() : nMatches(0), <a name="l00393"></a>00393 firstListCorrespondences(), secondListCorrespondences(), <a name="l00394"></a>00394 firstListFoundScales(), firstListDistance() {} <a name="l00395"></a>00395 <a name="l00396"></a>00396 }; <span class="comment">// end struct TMultiResMatchingOutput</span> <a name="l00397"></a>00397 <span class="comment"></span> <a name="l00398"></a>00398 <span class="comment"> /** Struct containing the options when matching multi-resolution SIFT-like descriptors</span> <a name="l00399"></a>00399 <span class="comment"> */</span> <a name="l00400"></a>00400 <span class="keyword">struct </span><a class="code" href="vision_2include_2mrpt_2vision_2link__pragmas_8h.html#aa4a17fb846aac61f4e57b17b6f784559">VISION_IMPEXP</a> TMultiResDescMatchOptions : <span class="keyword">public</span> mrpt::utils::<a class="code" href="classmrpt_1_1utils_1_1_c_loadable_options.html" title="This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...">CLoadableOptions</a> <a name="l00401"></a>00401 { <a name="l00402"></a><a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_match_options.html#afb2d4cb73d625207f5c7afdf4428b31a">00402</a> <span class="keywordtype">bool</span> <a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_match_options.html#afb2d4cb73d625207f5c7afdf4428b31a" title="Whether or not use the filter based on orientation test.">useOriFilter</a>; <span class="comment">//!< Whether or not use the filter based on orientation test</span> <a name="l00403"></a><a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_match_options.html#a8296acf781c3a1dd65a86b881dafd6f4">00403</a> <span class="comment"></span> <span class="keywordtype">double</span> <a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_match_options.html#a8296acf781c3a1dd65a86b881dafd6f4" title="The threshold for the orientation test.">oriThreshold</a>; <span class="comment">//!< The threshold for the orientation test</span> <a name="l00404"></a>00404 <span class="comment"></span> <a name="l00405"></a><a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_match_options.html#a06582fd9ec5ce60b9aaee739da43fe14">00405</a> <span class="keywordtype">bool</span> <a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_match_options.html#a06582fd9ec5ce60b9aaee739da43fe14" title="Whether or not use the filter based on the depth test.">useDepthFilter</a>; <span class="comment">//!< Whether or not use the filter based on the depth test</span> <a name="l00406"></a>00406 <span class="comment"></span> <a name="l00407"></a><a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_match_options.html#a671898c4efba8ace8067f73d2253b59c">00407</a> <span class="keywordtype">double</span> <a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_match_options.html#a671898c4efba8ace8067f73d2253b59c" title="The absolute threshold in descriptor distance for considering a match.">matchingThreshold</a>; <span class="comment">//!< The absolute threshold in descriptor distance for considering a match</span> <a name="l00408"></a><a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_match_options.html#a8e0cd3113265617a961ebb71c214da92">00408</a> <span class="comment"></span> <span class="keywordtype">double</span> <a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_match_options.html#a8e0cd3113265617a961ebb71c214da92" title="The ratio between the two lowest distances threshold for considering a match.">matchingRatioThreshold</a>; <span class="comment">//!< The ratio between the two lowest distances threshold for considering a match</span> <a name="l00409"></a><a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_match_options.html#a6cc1e3441738e4181b3cbb60a121feda">00409</a> <span class="comment"></span> <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> lowScl1, <a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_match_options.html#a6cc1e3441738e4181b3cbb60a121feda" title="The lowest scales in the two features to be taken into account in the matching process.">lowScl2</a>; <span class="comment">//!< The lowest scales in the two features to be taken into account in the matching process</span> <a name="l00410"></a><a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_match_options.html#a998ac9c5e619974b3420a0de9949246b">00410</a> <span class="comment"></span> <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> highScl1, <a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_match_options.html#a998ac9c5e619974b3420a0de9949246b" title="The highest scales in the two features to be taken into account in the matching process.">highScl2</a>; <span class="comment">//!< The highest scales in the two features to be taken into account in the matching process</span> <a name="l00411"></a>00411 <span class="comment"></span> <a name="l00412"></a><a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_match_options.html#acab5cb6795b347c73df4b772135216bd">00412</a> <span class="keywordtype">int</span> <a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_match_options.html#acab5cb6795b347c73df4b772135216bd" title="Size of the squared area where to search for a match.">searchAreaSize</a>; <span class="comment">//!< Size of the squared area where to search for a match.</span> <a name="l00413"></a><a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_match_options.html#a001a9ee48560953aa1eac663a9f72b96">00413</a> <span class="comment"></span> <span class="keywordtype">int</span> <a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_match_options.html#a001a9ee48560953aa1eac663a9f72b96" title="The allowed number of frames since a certain feature was seen for the last time.">lastSeenThreshold</a>; <span class="comment">//!< The allowed number of frames since a certain feature was seen for the last time.</span> <a name="l00414"></a><a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_match_options.html#a6f52bdfeddc7375364e6fdc74fb3b80b">00414</a> <span class="comment"></span> <span class="keywordtype">int</span> <a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_match_options.html#a6f52bdfeddc7375364e6fdc74fb3b80b" title="The minimum number of frames for a certain feature to be considered stable.">timesSeenThreshold</a>; <span class="comment">//!< The minimum number of frames for a certain feature to be considered stable.</span> <a name="l00415"></a>00415 <span class="comment"></span> <a name="l00416"></a><a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_match_options.html#ac53e3693451974ebcc1c5cccbb773d9f">00416</a> <span class="keywordtype">int</span> <a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_match_options.html#ac53e3693451974ebcc1c5cccbb773d9f" title="The minimum number of features allowed in the system. If current number is below this value...">minFeaturesToFind</a>; <span class="comment">//!< The minimum number of features allowed in the system. If current number is below this value, more features will be found.</span> <a name="l00417"></a><a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_match_options.html#a2c13f733a70237359c6e0ad66de70264">00417</a> <span class="comment"></span> <span class="keywordtype">int</span> <a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_match_options.html#a2c13f733a70237359c6e0ad66de70264" title="The minimum number of features allowed in the system to not be considered to be lost.">minFeaturesToBeLost</a>; <span class="comment">//!< The minimum number of features allowed in the system to not be considered to be lost.</span> <a name="l00418"></a>00418 <span class="comment"></span><span class="comment"></span> <a name="l00419"></a>00419 <span class="comment"> /** Default constructor</span> <a name="l00420"></a>00420 <span class="comment"> */</span> <a name="l00421"></a><a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_match_options.html#aa64690fef1bc4b3fe4f4e001b6210f48">00421</a> <a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_match_options.html" title="Struct containing the options when matching multi-resolution SIFT-like descriptors.">TMultiResDescMatchOptions</a>() : <a name="l00422"></a>00422 useOriFilter( true ), oriThreshold( 0.2 ), <a name="l00423"></a>00423 useDepthFilter( true ), matchingThreshold( 1e4 ), matchingRatioThreshold( 0.5 ), <a name="l00424"></a>00424 lowScl1(0), lowScl2(0), highScl1(6), highScl2(6), searchAreaSize(20), lastSeenThreshold(10), timesSeenThreshold(5), <a name="l00425"></a>00425 minFeaturesToFind(30), minFeaturesToBeLost(5) {} <a name="l00426"></a>00426 <a name="l00427"></a><a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_match_options.html#a26a180c862e6126992c8197f7602bd57">00427</a> <a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_match_options.html" title="Struct containing the options when matching multi-resolution SIFT-like descriptors.">TMultiResDescMatchOptions</a>( <a name="l00428"></a>00428 <span class="keyword">const</span> <span class="keywordtype">bool</span> &_useOriFilter, <span class="keyword">const</span> <span class="keywordtype">double</span> &_oriThreshold, <span class="keyword">const</span> <span class="keywordtype">bool</span> &_useDepthFilter, <a name="l00429"></a>00429 <span class="keyword">const</span> <span class="keywordtype">double</span> &_th, <span class="keyword">const</span> <span class="keywordtype">double</span> &_th2, <span class="keyword">const</span> <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> &_lwscl1, <span class="keyword">const</span> <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> &_lwscl2, <a name="l00430"></a>00430 <span class="keyword">const</span> <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> &_hwscl1, <span class="keyword">const</span> <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> &_hwscl2, <span class="keyword">const</span> <span class="keywordtype">int</span> &_searchAreaSize, <span class="keyword">const</span> <span class="keywordtype">int</span> &_lsth, <span class="keyword">const</span> <span class="keywordtype">int</span> &_tsth, <a name="l00431"></a>00431 <span class="keyword">const</span> <span class="keywordtype">int</span> &_minFeaturesToFind, <span class="keyword">const</span> <span class="keywordtype">int</span> &_minFeaturesToBeLost ) : <a name="l00432"></a>00432 useOriFilter( _useOriFilter ), oriThreshold( _oriThreshold ), useDepthFilter( _useDepthFilter ), <a name="l00433"></a>00433 matchingThreshold ( _th ), matchingRatioThreshold ( _th2 ), lowScl1( _lwscl1 ), lowScl2( _lwscl2 ), <a name="l00434"></a>00434 highScl1( _hwscl1 ), highScl2( _hwscl2 ), searchAreaSize( _searchAreaSize ), lastSeenThreshold( _lsth ), timesSeenThreshold( _tsth ), <a name="l00435"></a>00435 minFeaturesToFind( _minFeaturesToFind ), minFeaturesToBeLost(_minFeaturesToBeLost) {} <a name="l00436"></a>00436 <a name="l00437"></a>00437 <span class="keywordtype">void</span> loadFromConfigFile( <span class="keyword">const</span> <a class="code" href="classmrpt_1_1utils_1_1_c_config_file_base.html" title="This class allows loading and storing values and vectors of different types from a configuration text...">mrpt::utils::CConfigFileBase</a> &cfg, <span class="keyword">const</span> <a class="code" href="classstd_1_1string.html" title="STL class.">std::string</a> &section ); <a name="l00438"></a>00438 <span class="keywordtype">void</span> saveToConfigFile( <a class="code" href="classmrpt_1_1utils_1_1_c_config_file_base.html" title="This class allows loading and storing values and vectors of different types from a configuration text...">mrpt::utils::CConfigFileBase</a> &cfg, <span class="keyword">const</span> <a class="code" href="classstd_1_1string.html" title="STL class.">std::string</a> &section ); <a name="l00439"></a>00439 <span class="keywordtype">void</span> dumpToTextStream( <a class="code" href="classmrpt_1_1utils_1_1_c_stream.html" title="This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...">mrpt::utils::CStream</a> &out) <span class="keyword">const</span>; <a name="l00440"></a>00440 <a name="l00441"></a>00441 }; <span class="comment">// end TMultiResDescMatchOptions</span> <a name="l00442"></a>00442 <span class="comment"></span> <a name="l00443"></a>00443 <span class="comment"> /** Struct containing the options when computing the multi-resolution SIFT-like descriptors</span> <a name="l00444"></a>00444 <span class="comment"> */</span> <a name="l00445"></a>00445 <span class="keyword">struct </span><a class="code" href="vision_2include_2mrpt_2vision_2link__pragmas_8h.html#aa4a17fb846aac61f4e57b17b6f784559">VISION_IMPEXP</a> TMultiResDescOptions : <span class="keyword">public</span> mrpt::utils::<a class="code" href="classmrpt_1_1utils_1_1_c_loadable_options.html" title="This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...">CLoadableOptions</a> <a name="l00446"></a>00446 { <a name="l00447"></a><a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_options.html#aa30ee4c3367b2faf9c6fad056d79ede3">00447</a> <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> <a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_options.html#aa30ee4c3367b2faf9c6fad056d79ede3" title="The size of the base patch.">basePSize</a>; <span class="comment">//!< The size of the base patch</span> <a name="l00448"></a><a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_options.html#a34b92a86ce96fdfcce080ce48a33a1d7">00448</a> <span class="comment"></span> <a class="code" href="classstd_1_1vector.html">vector<double></a> <a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_options.html#a34b92a86ce96fdfcce080ce48a33a1d7" title="The set of scales relatives to the base patch.">scales</a>; <span class="comment">//!< The set of scales relatives to the base patch</span> <a name="l00449"></a><a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_options.html#a8be725bc5fe1ff89c0b8ceb28c583030">00449</a> <span class="comment"></span> <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> <a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_options.html#a8be725bc5fe1ff89c0b8ceb28c583030">comLScl</a>, comHScl; <span class="comment">//!< The subset of scales for which to compute the descriptors</span> <a name="l00450"></a><a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_options.html#ab2fbc9e79e634c68893a46c0b5192e32">00450</a> <span class="comment"></span> <span class="keywordtype">double</span> sg1, sg2, <a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_options.html#ab2fbc9e79e634c68893a46c0b5192e32" title="The sigmas for the Gaussian kernels.">sg3</a>; <span class="comment">//!< The sigmas for the Gaussian kernels</span> <a name="l00451"></a><a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_options.html#a29937f5647d97725e4c96da2b94cf17e">00451</a> <span class="comment"></span> <span class="keywordtype">bool</span> <a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_options.html#a29937f5647d97725e4c96da2b94cf17e" title="Whether or not to compute the depth of the feature.">computeDepth</a>; <span class="comment">//!< Whether or not to compute the depth of the feature</span> <a name="l00452"></a><a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_options.html#a53ccc1f7b94e081f4b3a0d3ebcedd9ee">00452</a> <span class="comment"></span> <span class="keywordtype">bool</span> <a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_options.html#a53ccc1f7b94e081f4b3a0d3ebcedd9ee" title="Whether or not to blur the image previously to compute the descriptors.">blurImage</a>; <span class="comment">//!< Whether or not to blur the image previously to compute the descriptors</span> <a name="l00453"></a><a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_options.html#af9b1dfdc07e222e0e48febefd5d8df2a">00453</a> <span class="comment"></span> <span class="keywordtype">double</span> <a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_options.html#af9b1dfdc07e222e0e48febefd5d8df2a">fx</a>,cx,cy,baseline; <span class="comment">//!< Intrinsic stereo pair parameters for computing the depth of the feature</span> <a name="l00454"></a><a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_options.html#a0fa105eb24adfae4a3e39a71c21b93a0">00454</a> <span class="comment"></span> <span class="keywordtype">bool</span> <a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_options.html#a0fa105eb24adfae4a3e39a71c21b93a0" title="Whether or not compute the coefficients for mantaining a HASH table of descriptors (for relocalizatio...">computeHashCoeffs</a>; <span class="comment">//!< Whether or not compute the coefficients for mantaining a HASH table of descriptors (for relocalization)</span> <a name="l00455"></a>00455 <span class="comment"></span> <a name="l00456"></a><a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_options.html#a2b282ca2a11e2c52e9ce27eb2c8f11ed">00456</a> <span class="keywordtype">double</span> <a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_options.html#a2b282ca2a11e2c52e9ce27eb2c8f11ed" title="The SIFT-like descriptor is cropped at this value during normalization.">cropValue</a>; <span class="comment">//!< The SIFT-like descriptor is cropped at this value during normalization</span> <a name="l00457"></a>00457 <span class="comment"></span><span class="comment"></span> <a name="l00458"></a>00458 <span class="comment"> /** Default constructor</span> <a name="l00459"></a>00459 <span class="comment"> */</span> <a name="l00460"></a><a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_options.html#a31ed666082ecf084e43dced52d7c870c">00460</a> <a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_options.html" title="Struct containing the options when computing the multi-resolution SIFT-like descriptors.">TMultiResDescOptions</a>() : <a name="l00461"></a>00461 basePSize(23), sg1 (0.5), sg2(7.5), sg3(8.0), computeDepth(true), blurImage(true), fx(0.0), cx(0.0), cy(0.0), baseline(0.0), computeHashCoeffs(false), cropValue(0.2) <a name="l00462"></a>00462 { <a name="l00463"></a>00463 scales.resize(7); <a name="l00464"></a>00464 scales[0] = 0.5; <a name="l00465"></a>00465 scales[1] = 0.8; <a name="l00466"></a>00466 scales[2] = 1.0; <a name="l00467"></a>00467 scales[3] = 1.2; <a name="l00468"></a>00468 scales[4] = 1.5; <a name="l00469"></a>00469 scales[5] = 1.8; <a name="l00470"></a>00470 scales[6] = 2.0; <a name="l00471"></a>00471 comLScl = 0; <a name="l00472"></a>00472 comHScl = 6; <a name="l00473"></a>00473 } <a name="l00474"></a>00474 <a name="l00475"></a><a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_options.html#a4c62f68f77cc5cff2d45a70de24150da">00475</a> <a class="code" href="structmrpt_1_1vision_1_1_t_multi_res_desc_options.html" title="Struct containing the options when computing the multi-resolution SIFT-like descriptors.">TMultiResDescOptions</a>( <span class="keyword">const</span> <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> &_basePSize, <span class="keyword">const</span> <a class="code" href="classstd_1_1vector.html">vector<double></a> &_scales, <a name="l00476"></a>00476 <span class="keyword">const</span> <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> &_comLScl, <span class="keyword">const</span> <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> &_comHScl, <a name="l00477"></a>00477 <span class="keyword">const</span> <span class="keywordtype">double</span> &_sg1, <span class="keyword">const</span> <span class="keywordtype">double</span> &_sg2, <span class="keyword">const</span> <span class="keywordtype">double</span> &_sg3, <a name="l00478"></a>00478 <span class="keyword">const</span> <span class="keywordtype">bool</span> &_computeDepth, <span class="keyword">const</span> <span class="keywordtype">bool</span> _blurImage, <span class="keyword">const</span> <span class="keywordtype">double</span> &_fx, <span class="keyword">const</span> <span class="keywordtype">double</span> &_cx, <span class="keyword">const</span> <span class="keywordtype">double</span> &_cy, <span class="keyword">const</span> <span class="keywordtype">double</span> &_baseline, <span class="keyword">const</span> <span class="keywordtype">bool</span> &_computeHashCoeffs, <span class="keyword">const</span> <span class="keywordtype">double</span> &_cropValue ): <a name="l00479"></a>00479 basePSize( _basePSize ), comLScl( _comLScl ), comHScl( _comHScl ), <a name="l00480"></a>00480 sg1( _sg1 ), sg2( _sg2 ), sg3( _sg3 ), <a name="l00481"></a>00481 computeDepth( _computeDepth ), blurImage( _blurImage ), fx( _fx ), cx( _cx ), cy( _cy ), baseline( _baseline ), computeHashCoeffs( _computeHashCoeffs), cropValue( _cropValue ) <a name="l00482"></a>00482 { <a name="l00483"></a>00483 scales.resize( _scales.size() ); <a name="l00484"></a>00484 <span class="keywordflow">for</span>(<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> k = 0; k < _scales.size(); ++k) <a name="l00485"></a>00485 scales[k] = _scales[k]; <a name="l00486"></a>00486 } <a name="l00487"></a>00487 <a name="l00488"></a>00488 <span class="keywordtype">void</span> loadFromConfigFile( <span class="keyword">const</span> <a class="code" href="classmrpt_1_1utils_1_1_c_config_file_base.html" title="This class allows loading and storing values and vectors of different types from a configuration text...">mrpt::utils::CConfigFileBase</a> &cfg, <span class="keyword">const</span> <a class="code" href="classstd_1_1string.html" title="STL class.">std::string</a> &section ); <a name="l00489"></a>00489 <span class="keywordtype">void</span> saveToConfigFile( <a class="code" href="classmrpt_1_1utils_1_1_c_config_file_base.html" title="This class allows loading and storing values and vectors of different types from a configuration text...">mrpt::utils::CConfigFileBase</a> &cfg, <span class="keyword">const</span> <a class="code" href="classstd_1_1string.html" title="STL class.">std::string</a> &section ); <a name="l00490"></a>00490 <span class="keywordtype">void</span> dumpToTextStream( <a class="code" href="classmrpt_1_1utils_1_1_c_stream.html" title="This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...">mrpt::utils::CStream</a> &out) <span class="keyword">const</span>; <a name="l00491"></a>00491 <a name="l00492"></a>00492 }; <span class="comment">// end TMultiResDescOptions</span> <a name="l00493"></a>00493 <a name="l00494"></a>00494 <span class="comment"></span> <a name="l00495"></a>00495 <span class="comment"> /** @} */</span> <span class="comment">// end of grouping</span> <a name="l00496"></a>00496 <a name="l00497"></a>00497 } <a name="l00498"></a>00498 } <a name="l00499"></a>00499 <a name="l00500"></a>00500 <a name="l00501"></a>00501 <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>