<!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>The MRPT project: CSimplePointsMap.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.6.2-20100208 --> <script type="text/javascript"><!-- var searchBox = new SearchBox("searchBox", "search",false,'Search'); --></script> <div class="navigation" id="top"> <div class="tabs"> <ul> <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="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"> <img id="MSearchSelect" src="search/search.png" onmouseover="return searchBox.OnSearchSelectShow()" onmouseout="return searchBox.OnSearchSelectHide()" alt=""/> <input type="text" id="MSearchField" value="Search" accesskey="S" onfocus="searchBox.OnSearchFieldFocus(true)" onblur="searchBox.OnSearchFieldFocus(false)" onkeyup="searchBox.OnSearchFieldChange(event)"/> <a id="MSearchClose" href="javascript:searchBox.CloseResultsWindow()"><img id="MSearchCloseImg" border="0" src="search/close.png" alt=""/></a> </div> </li> </ul> </div> <div class="tabs"> <ul> <li><a href="files.html"><span>File List</span></a></li> <li><a href="globals.html"><span>File Members</span></a></li> </ul> </div> <h1>CSimplePointsMap.h</h1><a href="_c_simple_points_map_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://mrpt.sourceforge.net/ |</span> <a name="l00005"></a>00005 <span class="comment"> | |</span> <a name="l00006"></a>00006 <span class="comment"> | Copyright (C) 2005-2010 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 <span class="preprocessor">#ifndef CSimplePointsMap_H</span> <a name="l00029"></a>00029 <span class="preprocessor"></span><span class="preprocessor">#define CSimplePointsMap_H</span> <a name="l00030"></a>00030 <span class="preprocessor"></span> <a name="l00031"></a>00031 <span class="preprocessor">#include <<a class="code" href="_c_points_map_8h.html">mrpt/slam/CPointsMap.h</a>></span> <a name="l00032"></a>00032 <span class="preprocessor">#include <<a class="code" href="_c_observation2_d_range_scan_8h.html">mrpt/slam/CObservation2DRangeScan.h</a>></span> <a name="l00033"></a>00033 <span class="preprocessor">#include <<a class="code" href="_c_observation3_d_range_scan_8h.html">mrpt/slam/CObservation3DRangeScan.h</a>></span> <a name="l00034"></a>00034 <span class="preprocessor">#include <<a class="code" href="_c_serializable_8h.html">mrpt/utils/CSerializable.h</a>></span> <a name="l00035"></a>00035 <span class="preprocessor">#include <<a class="code" href="_c_matrix_8h.html">mrpt/math/CMatrix.h</a>></span> <a name="l00036"></a>00036 <a name="l00037"></a>00037 <span class="preprocessor">#include <<a class="code" href="maps_2include_2mrpt_2maps_2link__pragmas_8h.html">mrpt/maps/link_pragmas.h</a>></span> <a name="l00038"></a>00038 <a name="l00039"></a>00039 <span class="keyword">namespace </span>mrpt <a name="l00040"></a>00040 { <a name="l00041"></a>00041 <span class="keyword">namespace </span>slam <a name="l00042"></a>00042 { <a name="l00043"></a>00043 <a name="l00044"></a>00044 <a class="code" href="_c_serializable_8h.html#a9ef523d787f6cb837a0585b790882588" title="This declaration must be inserted in all CSerializable classes definition, before...">DEFINE_SERIALIZABLE_PRE_CUSTOM_BASE_LINKAGE</a>( CSimplePointsMap , CPointsMap, <a class="code" href="maps_2include_2mrpt_2maps_2link__pragmas_8h.html#ad401479c152d92658375c646837e33ed">MAPS_IMPEXP</a> ) <a name="l00045"></a>00045 <a name="l00046"></a>00046 <span class="comment">/** A cloud of points in 2D or 3D, which can be built from a sequence of laser scans.</span> <a name="l00047"></a>00047 <span class="comment"> * This class stores the coordinates (x,y,z) and a "weight", or counter of how many times that point has been seen, used only if points fusion is enabled in the options structure.</span> <a name="l00048"></a>00048 <span class="comment"> * \sa CMetricMap, CPoint, mrpt::utils::CSerializable</span> <a name="l00049"></a>00049 <span class="comment"> */</span> <a name="l00050"></a><a class="code" href="classmrpt_1_1slam_1_1_c_simple_points_map.html">00050</a> class <a class="code" href="maps_2include_2mrpt_2maps_2link__pragmas_8h.html#ad401479c152d92658375c646837e33ed">MAPS_IMPEXP</a> <a class="code" href="classmrpt_1_1slam_1_1_c_simple_points_map.html" title="A cloud of points in 2D or 3D, which can be built from a sequence of laser scans...">CSimplePointsMap</a> : public <a class="code" href="classmrpt_1_1slam_1_1_c_points_map.html" title="A cloud of points in 2D or 3D, which can be built from a sequence of laser scans...">CPointsMap</a> <a name="l00051"></a>00051 { <a name="l00052"></a>00052 <span class="comment">// This must be added to any CSerializable derived class:</span> <a name="l00053"></a>00053 <a class="code" href="_c_serializable_8h.html#a72ab55bf7ae009c89b75715cfa21e84d" title="This declaration must be inserted in all CSerializable classes definition, within...">DEFINE_SERIALIZABLE</a>( <a class="code" href="classmrpt_1_1slam_1_1_c_simple_points_map.html" title="A cloud of points in 2D or 3D, which can be built from a sequence of laser scans...">CSimplePointsMap</a> ) <a name="l00054"></a>00054 <span class="keyword">public</span>: <a name="l00055"></a>00055 <span class="comment"></span> <a name="l00056"></a>00056 <span class="comment"> /** Destructor</span> <a name="l00057"></a>00057 <span class="comment"> */</span> <a name="l00058"></a>00058 <span class="keyword">virtual</span> ~<a class="code" href="classmrpt_1_1slam_1_1_c_simple_points_map.html" title="A cloud of points in 2D or 3D, which can be built from a sequence of laser scans...">CSimplePointsMap</a>(); <a name="l00059"></a>00059 <span class="comment"></span> <a name="l00060"></a>00060 <span class="comment"> /** Default constructor</span> <a name="l00061"></a>00061 <span class="comment"> */</span> <a name="l00062"></a>00062 <a class="code" href="classmrpt_1_1slam_1_1_c_simple_points_map.html" title="A cloud of points in 2D or 3D, which can be built from a sequence of laser scans...">CSimplePointsMap</a>(); <a name="l00063"></a>00063 <span class="comment"></span> <a name="l00064"></a>00064 <span class="comment"> /** Copy operator</span> <a name="l00065"></a>00065 <span class="comment"> */</span> <a name="l00066"></a>00066 <span class="keywordtype">void</span> copyFrom(<span class="keyword">const</span> CPointsMap &obj); <a name="l00067"></a>00067 <span class="comment"></span> <a name="l00068"></a>00068 <span class="comment"> /** Transform the range scan into a set of cartesian coordinated</span> <a name="l00069"></a>00069 <span class="comment"> * points. The options in "insertionOptions" are considered in this method.</span> <a name="l00070"></a>00070 <span class="comment"> * \param rangeScan The scan to be inserted into this map</span> <a name="l00071"></a>00071 <span class="comment"> * \param robotPose The robot 3D pose, default to (0,0,0|0deg,0deg,0deg). It is used to compute the sensor pose relative to the robot actual pose. Recall sensor pose is embeded in the observation class.</span> <a name="l00072"></a>00072 <span class="comment"> *</span> <a name="l00073"></a>00073 <span class="comment"> * NOTE: Only ranges marked as "valid=true" in the observation will be inserted</span> <a name="l00074"></a>00074 <span class="comment"> *</span> <a name="l00075"></a>00075 <span class="comment"> * \sa CObservation2DRangeScan</span> <a name="l00076"></a>00076 <span class="comment"> */</span> <a name="l00077"></a>00077 <span class="keywordtype">void</span> loadFromRangeScan( <a name="l00078"></a>00078 <span class="keyword">const</span> <a class="code" href="classmrpt_1_1slam_1_1_c_observation2_d_range_scan.html" title="Declares a class derived from &quot;CObservation&quot; that encapsules a 2D range...">CObservation2DRangeScan</a> &rangeScan, <a name="l00079"></a>00079 <span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html" title="A class used to store a 3D pose.">CPose3D</a> *robotPose = NULL ); <a name="l00080"></a>00080 <span class="comment"></span> <a name="l00081"></a>00081 <span class="comment"> /** Enter the set of cartesian coordinated points from the 3D range scan into</span> <a name="l00082"></a>00082 <span class="comment"> * the map. The options in "insertionOptions" are considered in this method.</span> <a name="l00083"></a>00083 <span class="comment"> * \param rangeScan The 3D scan to be inserted into this map</span> <a name="l00084"></a>00084 <span class="comment"> * \param robotPose The robot 3D pose, default to (0,0,0|0deg,0deg,0deg). It is used to compute the sensor pose relative to the robot actual pose. Recall sensor pose is embeded in the observation class.</span> <a name="l00085"></a>00085 <span class="comment"> *</span> <a name="l00086"></a>00086 <span class="comment"> * NOTE: Only ranges marked as "valid=true" in the observation will be inserted</span> <a name="l00087"></a>00087 <span class="comment"> *</span> <a name="l00088"></a>00088 <span class="comment"> * \sa CObservation3DRangeScan</span> <a name="l00089"></a>00089 <span class="comment"> */</span> <a name="l00090"></a>00090 <span class="keywordtype">void</span> loadFromRangeScan( <a name="l00091"></a>00091 <span class="keyword">const</span> <a class="code" href="classmrpt_1_1slam_1_1_c_observation3_d_range_scan.html" title="Declares a class derived from &quot;CObservation&quot; that encapsules a 3D range...">CObservation3DRangeScan</a> &rangeScan, <a name="l00092"></a>00092 <span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html" title="A class used to store a 3D pose.">CPose3D</a> *robotPose = NULL ); <a name="l00093"></a>00093 <span class="comment"></span> <a name="l00094"></a>00094 <span class="comment"> /** Load from a text file. In each line there are a point coordinates.</span> <a name="l00095"></a>00095 <span class="comment"> * Returns false if any error occured, true elsewere.</span> <a name="l00096"></a>00096 <span class="comment"> */</span> <a name="l00097"></a>00097 <span class="keywordtype">bool</span> load2D_from_text_file(std::string file); <a name="l00098"></a>00098 <span class="comment"></span> <a name="l00099"></a>00099 <span class="comment"> /** Load from a text file. In each line there are a point coordinates.</span> <a name="l00100"></a>00100 <span class="comment"> * Returns false if any error occured, true elsewere.</span> <a name="l00101"></a>00101 <span class="comment"> */</span> <a name="l00102"></a>00102 <span class="keywordtype">bool</span> load3D_from_text_file(std::string file); <a name="l00103"></a>00103 <a name="l00104"></a>00104 <span class="comment"></span> <a name="l00105"></a>00105 <span class="comment"> /** Insert the contents of another map into this one, fusing the previous content with the new one.</span> <a name="l00106"></a>00106 <span class="comment"> * This means that points very close to existing ones will be "fused", rather than "added". This prevents</span> <a name="l00107"></a>00107 <span class="comment"> * the unbounded increase in size of these class of maps.</span> <a name="l00108"></a>00108 <span class="comment"> * NOTICE that "otherMap" is neither translated nor rotated here, so if this is desired it must done</span> <a name="l00109"></a>00109 <span class="comment"> * before calling this method.</span> <a name="l00110"></a>00110 <span class="comment"> * \param otherMap The other map whose points are to be inserted into this one.</span> <a name="l00111"></a>00111 <span class="comment"> * \param minDistForFuse Minimum distance (in meters) between two points, each one in a map, to be considered the same one and be fused rather than added.</span> <a name="l00112"></a>00112 <span class="comment"> * \param notFusedPoints If a pointer is supplied, this list will contain at output a list with a "bool" value per point in "this" map. This will be false/true according to that point having been fused or not.</span> <a name="l00113"></a>00113 <span class="comment"> * \sa insertAnotherMap</span> <a name="l00114"></a>00114 <span class="comment"> */</span> <a name="l00115"></a>00115 <span class="keywordtype">void</span> fuseWith( CPointsMap *otherMap, <a name="l00116"></a>00116 <span class="keywordtype">float</span> minDistForFuse = 0.02f, <a name="l00117"></a>00117 std::vector<bool> *notFusedPoints = NULL); <a name="l00118"></a>00118 <span class="comment"></span> <a name="l00119"></a>00119 <span class="comment"> /** Insert the contents of another map into this one, without fusing close points.</span> <a name="l00120"></a>00120 <span class="comment"> * \param otherMap The other map whose points are to be inserted into this one.</span> <a name="l00121"></a>00121 <span class="comment"> * \param otherPose The pose of the other map in the coordinates of THIS map</span> <a name="l00122"></a>00122 <span class="comment"> * \sa fuseWith</span> <a name="l00123"></a>00123 <span class="comment"> */</span> <a name="l00124"></a>00124 <span class="keywordtype">void</span> insertAnotherMap( <a name="l00125"></a>00125 CPointsMap *otherMap, <a name="l00126"></a>00126 <a class="code" href="classmrpt_1_1poses_1_1_c_pose2_d.html" title="A class used to store a 2D pose.">CPose2D</a> otherPose); <a name="l00127"></a>00127 <span class="comment"></span> <a name="l00128"></a>00128 <span class="comment"> /** Changes a given point from map, as a 2D point. First index is 0.</span> <a name="l00129"></a>00129 <span class="comment"> * \exception Throws std::exception on index out of bound.</span> <a name="l00130"></a>00130 <span class="comment"> */</span> <a name="l00131"></a>00131 <span class="keyword">virtual</span> <span class="keywordtype">void</span> setPoint(<span class="keywordtype">size_t</span> index,<a class="code" href="classmrpt_1_1poses_1_1_c_point2_d.html" title="A class used to store a 2D point.">CPoint2D</a> &p); <a name="l00132"></a>00132 <span class="comment"></span> <a name="l00133"></a>00133 <span class="comment"> /** Changes a given point from map, as a 3D point. First index is 0.</span> <a name="l00134"></a>00134 <span class="comment"> * \exception Throws std::exception on index out of bound.</span> <a name="l00135"></a>00135 <span class="comment"> */</span> <a name="l00136"></a>00136 <span class="keyword">virtual</span> <span class="keywordtype">void</span> setPoint(<span class="keywordtype">size_t</span> index,<a class="code" href="classmrpt_1_1poses_1_1_c_point3_d.html" title="A class used to store a 3D point.">CPoint3D</a> &p); <a name="l00137"></a>00137 <span class="comment"></span> <a name="l00138"></a>00138 <span class="comment"> /** Changes a given point from map. First index is 0.</span> <a name="l00139"></a>00139 <span class="comment"> * \exception Throws std::exception on index out of bound.</span> <a name="l00140"></a>00140 <span class="comment"> */</span> <a name="l00141"></a>00141 <span class="keyword">virtual</span> <span class="keywordtype">void</span> setPoint(<span class="keywordtype">size_t</span> index,<span class="keywordtype">float</span> x, <span class="keywordtype">float</span> y); <a name="l00142"></a>00142 <span class="comment"></span> <a name="l00143"></a>00143 <span class="comment"> /** Changes a given point from map. First index is 0.</span> <a name="l00144"></a>00144 <span class="comment"> * \exception Throws std::exception on index out of bound.</span> <a name="l00145"></a>00145 <span class="comment"> */</span> <a name="l00146"></a>00146 <span class="keyword">virtual</span> <span class="keywordtype">void</span> setPoint(<span class="keywordtype">size_t</span> index,<span class="keywordtype">float</span> x, <span class="keywordtype">float</span> y, <span class="keywordtype">float</span> z); <a name="l00147"></a>00147 <span class="comment"></span> <a name="l00148"></a>00148 <span class="comment"> /** Provides a way to insert individual points into the map:</span> <a name="l00149"></a>00149 <span class="comment"> */</span> <a name="l00150"></a>00150 <span class="keywordtype">void</span> insertPoint( <span class="keywordtype">float</span> x, <span class="keywordtype">float</span> y, <span class="keywordtype">float</span> z = 0 ); <a name="l00151"></a>00151 <span class="comment"></span> <a name="l00152"></a>00152 <span class="comment"> /** Provides a way to insert individual points into the map:</span> <a name="l00153"></a>00153 <span class="comment"> */</span> <a name="l00154"></a><a class="code" href="classmrpt_1_1slam_1_1_c_simple_points_map.html#a15e538bb56ff33223591c223713eb8be">00154</a> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1slam_1_1_c_simple_points_map.html#a15e538bb56ff33223591c223713eb8be" title="Provides a way to insert individual points into the map:.">insertPoint</a>( <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> &new_pnt ) { <a name="l00155"></a>00155 this->insertPoint(new_pnt.<a class="code" href="structmrpt_1_1math_1_1_t_point3_d.html#a5014ee49d97866d293568300b619a7e2" title="X coordinate.">x</a>,new_pnt.<a class="code" href="structmrpt_1_1math_1_1_t_point3_d.html#aec879c0d61d8446e93b7d09344931d37" title="Y coordinate.">y</a>,new_pnt.<a class="code" href="structmrpt_1_1math_1_1_t_point3_d.html#a61df04839b9146696e696fc7af3bc307" title="Z coordinate.">z</a>); <a name="l00156"></a>00156 } <a name="l00157"></a>00157 <span class="comment"></span> <a name="l00158"></a>00158 <span class="comment"> /** Remove from the map the points marked in a bool's array as "true".</span> <a name="l00159"></a>00159 <span class="comment"> *</span> <a name="l00160"></a>00160 <span class="comment"> * \exception std::exception If mask size is not equal to points count.</span> <a name="l00161"></a>00161 <span class="comment"> */</span> <a name="l00162"></a>00162 <span class="keywordtype">void</span> applyDeletionMask( std::vector<bool> &mask ); <a name="l00163"></a>00163 <span class="comment"></span> <a name="l00164"></a>00164 <span class="comment"> /** This method is called at the end of each "prediction-update-map insertion" cycle within "mrpt::slam::CMetricMapBuilderRBPF::processActionObservation".</span> <a name="l00165"></a>00165 <span class="comment"> * This method should normally do nothing, but in some cases can be used to free auxiliary cached variables.</span> <a name="l00166"></a>00166 <span class="comment"> */</span> <a name="l00167"></a>00167 <span class="keywordtype">void</span> auxParticleFilterCleanUp(); <a name="l00168"></a>00168 <span class="comment"></span> <a name="l00169"></a>00169 <span class="comment"> /** Reserves memory for a given number of points: the size of the map does not change, it only reserves the memory.</span> <a name="l00170"></a>00170 <span class="comment"> * This is useful for situations where it is approximately known the final size of the map. This method is more</span> <a name="l00171"></a>00171 <span class="comment"> * efficient than constantly increasing the size of the buffers. Refer to the STL C++ library's "reserve" methods.</span> <a name="l00172"></a>00172 <span class="comment"> */</span> <a name="l00173"></a>00173 <span class="keywordtype">void</span> reserve(<span class="keywordtype">size_t</span> newLength); <a name="l00174"></a>00174 <a name="l00175"></a>00175 <span class="comment"></span> <a name="l00176"></a>00176 <span class="comment"> /** Set all the points at once from vectors with X,Y and Z coordinates. */</span> <a name="l00177"></a>00177 <span class="keywordtype">void</span> setAllPoints(<span class="keyword">const</span> <a class="code" href="structmrpt_1_1mrpt__base__vector.html">vector_float</a> &X,<span class="keyword">const</span> <a class="code" href="structmrpt_1_1mrpt__base__vector.html">vector_float</a> &Y,<span class="keyword">const</span> <a class="code" href="structmrpt_1_1mrpt__base__vector.html">vector_float</a> &Z); <a name="l00178"></a>00178 <span class="comment"></span> <a name="l00179"></a>00179 <span class="comment"> /** Set all the points at once from vectors with X and Y coordinates (Z=0). */</span> <a name="l00180"></a>00180 <span class="keywordtype">void</span> setAllPoints(<span class="keyword">const</span> <a class="code" href="structmrpt_1_1mrpt__base__vector.html">vector_float</a> &X,<span class="keyword">const</span> <a class="code" href="structmrpt_1_1mrpt__base__vector.html">vector_float</a> &Y); <a name="l00181"></a>00181 <span class="comment"></span> <a name="l00182"></a>00182 <span class="comment"> /** If the map is a simple points map or it's a multi-metric map that contains EXACTLY one simple points map, return it. </span> <a name="l00183"></a>00183 <span class="comment"> * Otherwise, return NULL</span> <a name="l00184"></a>00184 <span class="comment"> */</span> <a name="l00185"></a><a class="code" href="classmrpt_1_1slam_1_1_c_simple_points_map.html#a6c5f6976255dc9b50b218af23f8ea7bf">00185</a> <span class="keyword">virtual</span> <span class="keyword">const</span> <a class="code" href="classmrpt_1_1slam_1_1_c_simple_points_map.html" title="A cloud of points in 2D or 3D, which can be built from a sequence of laser scans...">CSimplePointsMap</a> * <a class="code" href="classmrpt_1_1slam_1_1_c_simple_points_map.html#a6c5f6976255dc9b50b218af23f8ea7bf" title="If the map is a simple points map or it&#39;s a multi-metric map that contains EXACTLY...">getAsSimplePointsMap</a>()<span class="keyword"> const </span>{ <span class="keywordflow">return</span> <span class="keyword">this</span>; } <a name="l00186"></a><a class="code" href="classmrpt_1_1slam_1_1_c_simple_points_map.html#a340ffc456415944bd87fc75c370eb575">00186</a> <span class="keyword">virtual</span> <a class="code" href="classmrpt_1_1slam_1_1_c_simple_points_map.html" title="A cloud of points in 2D or 3D, which can be built from a sequence of laser scans...">CSimplePointsMap</a> * <a class="code" href="classmrpt_1_1slam_1_1_c_simple_points_map.html#a340ffc456415944bd87fc75c370eb575">getAsSimplePointsMap</a>() { <span class="keywordflow">return</span> <span class="keyword">this</span>; } <a name="l00187"></a>00187 <a name="l00188"></a>00188 <span class="keyword">protected</span>:<span class="comment"></span> <a name="l00189"></a>00189 <span class="comment"> /** Clear the map, erasing all the points.</span> <a name="l00190"></a>00190 <span class="comment"> */</span> <a name="l00191"></a>00191 <span class="keyword">virtual</span> <span class="keywordtype">void</span> internal_clear(); <a name="l00192"></a>00192 <span class="comment"></span> <a name="l00193"></a>00193 <span class="comment"> /** Insert the observation information into this map. This method must be implemented</span> <a name="l00194"></a>00194 <span class="comment"> * in derived classes.</span> <a name="l00195"></a>00195 <span class="comment"> * \param obs The observation</span> <a name="l00196"></a>00196 <span class="comment"> * \param robotPose The 3D pose of the robot mobile base in the map reference system, or NULL (default) if you want to use CPose2D(0,0,deg)</span> <a name="l00197"></a>00197 <span class="comment"> *</span> <a name="l00198"></a>00198 <span class="comment"> * \sa CObservation::insertObservationInto</span> <a name="l00199"></a>00199 <span class="comment"> */</span> <a name="l00200"></a>00200 <span class="keywordtype">bool</span> internal_insertObservation( <span class="keyword">const</span> <a class="code" href="classmrpt_1_1slam_1_1_c_observation.html" title="Declares a class that represents any robot&#39;s observation.">CObservation</a> *obs, <span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html" title="A class used to store a 3D pose.">CPose3D</a> *robotPose = NULL ); <a name="l00201"></a>00201 <a name="l00202"></a>00202 }; <span class="comment">// End of class def.</span> <a name="l00203"></a>00203 <a name="l00204"></a>00204 } <span class="comment">// End of namespace</span> <a name="l00205"></a>00205 } <span class="comment">// End of namespace</span> <a name="l00206"></a>00206 <a name="l00207"></a>00207 <span class="preprocessor">#endif</span> </pre></div></div> <!--- window showing the filter options --> <div id="MSearchSelectWindow" onmouseover="return searchBox.OnSearchSelectShow()" onmouseout="return searchBox.OnSearchSelectHide()" onkeydown="return searchBox.OnSearchSelectKey(event)"> <a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(0)"><span class="SelectionMark"> </span>All</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(1)"><span class="SelectionMark"> </span>Classes</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(2)"><span class="SelectionMark"> </span>Namespaces</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(3)"><span class="SelectionMark"> </span>Files</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(4)"><span class="SelectionMark"> </span>Functions</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(5)"><span class="SelectionMark"> </span>Variables</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(6)"><span class="SelectionMark"> </span>Typedefs</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(7)"><span class="SelectionMark"> </span>Enumerations</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(8)"><span class="SelectionMark"> </span>Enumerator</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(9)"><span class="SelectionMark"> </span>Friends</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(10)"><span class="SelectionMark"> </span>Defines</a></div> <!-- iframe showing the search results (closed by default) --> <div id="MSearchResultsWindow"> <iframe src="" frameborder="0" name="MSearchResults" id="MSearchResults"> </iframe> </div> <br><hr><br> <table border="0" width="100%"> <tr> <td> Page generated by <a href="http://www.doxygen.org" target="_blank">Doxygen 1.6.2-20100208</a> for MRPT 0.9.0 SVN: at Wed Jul 14 12:48:09 UTC 2010</td><td></td> <td width="100"> </td> <td width="150"> </td></tr> </table> </body></html>