<!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>mrpt::slam::CMetricMapBuilderICP Class Reference</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 class="current"><a href="annotated.html"><span>Classes</span></a></li> <li><a href="files.html"><span>Files</span></a></li> <li> <div id="MSearchBox" class="MSearchBoxInactive"> <div class="left"> <form id="FSearchBox" action="search.php" method="get"> <img id="MSearchSelect" src="search/mag.png" alt=""/> <input type="text" id="MSearchField" name="query" value="Search" size="20" accesskey="S" onfocus="searchBox.OnSearchFieldFocus(true)" onblur="searchBox.OnSearchFieldFocus(false)"/> </form> </div><div class="right"></div> </div> </li> </ul> </div> <div id="navrow2" class="tabs2"> <ul class="tablist"> <li><a href="annotated.html"><span>Class List</span></a></li> <li><a href="classes.html"><span>Class Index</span></a></li> <li><a href="inherits.html"><span>Class Hierarchy</span></a></li> <li><a href="functions.html"><span>Class Members</span></a></li> </ul> </div> <div id="nav-path" class="navpath"> <ul> <li class="navelem"><a class="el" href="namespacemrpt.html">mrpt</a> </li> <li class="navelem"><a class="el" href="namespacemrpt_1_1slam.html">slam</a> </li> <li class="navelem"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html">CMetricMapBuilderICP</a> </li> </ul> </div> </div> <div class="header"> <div class="summary"> <a href="#nested-classes">Classes</a> | <a href="#pub-methods">Public Member Functions</a> | <a href="#pub-static-methods">Static Public Member Functions</a> | <a href="#pub-attribs">Public Attributes</a> | <a href="#pro-methods">Protected Member Functions</a> | <a href="#pro-attribs">Protected Attributes</a> | <a href="#pri-methods">Private Member Functions</a> | <a href="#pri-attribs">Private Attributes</a> </div> <div class="headertitle"> <div class="title">mrpt::slam::CMetricMapBuilderICP Class Reference<div class="ingroups"><a class="el" href="group__metric__slam__grp.html">Metric SLAM algorithms</a></div></div> </div> </div> <div class="contents"> <!-- doxytag: class="mrpt::slam::CMetricMapBuilderICP" --><!-- doxytag: inherits="mrpt::slam::CMetricMapBuilder" --><hr/><a name="details" id="details"></a><h2>Detailed Description</h2> <div class="textblock"><p>A class for very simple 2D SLAM based on ICP. </p> <p>This is a non-probabilistic pose tracking algorithm. Map are stored as in files as binary dumps of "mrpt::slam::CSimpleMap" objects. The methods are thread-safe. </p> </div> <p><code>#include <<a class="el" href="_c_metric_map_builder_i_c_p_8h_source.html">mrpt/slam/CMetricMapBuilderICP.h</a>></code></p> <div class="dynheader"> Inheritance diagram for mrpt::slam::CMetricMapBuilderICP:</div> <div class="dyncontent"> <div class="center"><img src="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p__inherit__graph.png" border="0" usemap="#mrpt_1_1slam_1_1_c_metric_map_builder_i_c_p_inherit__map" alt="Inheritance graph"/></div> <map name="mrpt_1_1slam_1_1_c_metric_map_builder_i_c_p_inherit__map" id="mrpt_1_1slam_1_1_c_metric_map_builder_i_c_p_inherit__map"> <area shape="rect" id="node2" href="classmrpt_1_1slam_1_1_c_metric_map_builder.html" title="This virtual class is the base for SLAM implementations." alt="" coords="17,80,220,107"/><area shape="rect" id="node4" href="classmrpt_1_1utils_1_1_c_debug_output_capable.html" title="This base class provides a common printf-like method to send debug information to std::cout..." alt="" coords="7,5,229,32"/></map> <center><span class="legend">[<a href="graph_legend.html">legend</a>]</span></center></div> <p><a href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p-members.html">List of all members.</a></p> <table class="memberdecls"> <tr><td colspan="2"><h2><a name="nested-classes"></a> Classes</h2></td></tr> <tr><td class="memItemLeft" align="right" valign="top">struct  </td><td class="memItemRight" valign="bottom"><a class="el" href="structmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p_1_1_t_config_params.html">TConfigParams</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Algorithm configuration params. <a href="structmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p_1_1_t_config_params.html#details">More...</a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">struct  </td><td class="memItemRight" valign="bottom"><a class="el" href="structmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p_1_1_t_dist.html">TDist</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Traveled distances from last map update / ICP-based localization. <a href="structmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p_1_1_t_dist.html#details">More...</a><br/></td></tr> <tr><td colspan="2"><h2><a name="pub-methods"></a> Public Member Functions</h2></td></tr> <tr><td class="memItemLeft" align="right" valign="top"> </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a505be777839d4f1ceb38b0d973ce1fee">CMetricMapBuilderICP</a> ()</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Default constructor - Upon construction, you can set the parameters in ICP_options, then call "initialize". <a href="#a505be777839d4f1ceb38b0d973ce1fee"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">virtual </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a2d1ad8aaa8c13c0c44d098b7b96cab9c">~CMetricMapBuilderICP</a> ()</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Destructor: <a href="#a2d1ad8aaa8c13c0c44d098b7b96cab9c"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">void </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a1106c4ff0e3af8b8ce752fe7e67530be">initialize</a> (const <a class="el" href="classmrpt_1_1slam_1_1_c_simple_map.html">CSimpleMap</a> &initialMap=<a class="el" href="classmrpt_1_1slam_1_1_c_simple_map.html">CSimpleMap</a>(), <a class="el" href="classmrpt_1_1poses_1_1_c_pose_p_d_f.html">CPosePDF</a> *x0=NULL)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Initialize the method, starting with a known location PDF "x0"(if supplied, set to NULL to left unmodified) and a given fixed, past map. <a href="#a1106c4ff0e3af8b8ce752fe7e67530be"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="structmrpt_1_1poses_1_1_c_pose3_d_p_d_f_ptr.html">CPose3DPDFPtr</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a45620c0802954419b152685e22a10981">getCurrentPoseEstimation</a> () const </td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Returns a copy of the current best pose estimation as a pose PDF. <a href="#a45620c0802954419b152685e22a10981"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">void </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a3d57d951672dd166a8725f2de263164f">setCurrentMapFile</a> (const char *mapFile)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Sets the "current map file", thus that map will be loaded if it exists or a new one will be created if it does not, and the updated map will be save to that file when destroying the object. <a href="#a3d57d951672dd166a8725f2de263164f"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">void </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#ae59c6b2a7b0222a85e2cc2cfeca19c10">processActionObservation</a> (<a class="el" href="classmrpt_1_1slam_1_1_c_action_collection.html">CActionCollection</a> &action, <a class="el" href="classmrpt_1_1slam_1_1_c_sensory_frame.html">CSensoryFrame</a> &in_SF)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Appends a new action and observations to update this map: See the description of the class at the top of this page to see a more complete description. <a href="#ae59c6b2a7b0222a85e2cc2cfeca19c10"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">void </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a7abc2ee4a0adccbec65444e434abdd1b">processObservation</a> (const <a class="el" href="structmrpt_1_1slam_1_1_c_observation_ptr.html">CObservationPtr</a> &obs)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">The main method of this class: Process one odometry or sensor observation. <a href="#a7abc2ee4a0adccbec65444e434abdd1b"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">void </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#ac616ad0198e3b2cd68fd75eb2795fedc">getCurrentlyBuiltMap</a> (<a class="el" href="classmrpt_1_1slam_1_1_c_simple_map.html">CSimpleMap</a> &out_map) const </td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Fills "out_map" with the set of "poses"-"sensory-frames", thus the so far built map. <a href="#ac616ad0198e3b2cd68fd75eb2795fedc"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">void </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#aa231bb36a8fe0fa7e7869037132a0c0c">getCurrentMapPoints</a> (<a class="el" href="classstd_1_1vector.html">std::vector</a>< float > &x, <a class="el" href="classstd_1_1vector.html">std::vector</a>< float > &y)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Returns the 2D points of current local map. <a href="#aa231bb36a8fe0fa7e7869037132a0c0c"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="classmrpt_1_1slam_1_1_c_multi_metric_map.html">CMultiMetricMap</a> * </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a64cb24ecb715b33e41712f109cb4c4ca">getCurrentlyBuiltMetricMap</a> ()</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Returns the map built so far. <a href="#a64cb24ecb715b33e41712f109cb4c4ca"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">unsigned int </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a9297996b2194bae02ea112e9a7256027">getCurrentlyBuiltMapSize</a> ()</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Returns just how many sensory-frames are stored in the currently build map. <a href="#a9297996b2194bae02ea112e9a7256027"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">void </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a12b97251df911adff7760d73b09e40f7">saveCurrentEstimationToImage</a> (const <a class="el" href="classstd_1_1string.html">std::string</a> &file, bool formatEMF_BMP=true)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">A useful method for debugging: the current map (and/or poses) estimation is dumped to an image file. <a href="#a12b97251df911adff7760d73b09e40f7"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">void </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder.html#a45414544fc4c56b67c450efbbc6f61b8">clear</a> ()</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Clear all elements of the maps, and reset localization to (0,0,0deg). <a href="#a45414544fc4c56b67c450efbbc6f61b8"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">void </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder.html#ac9982ebd2fcc745ecd760f4c982427a4">enableMapUpdating</a> (bool enable)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Enables or disables the map updating (default state is enabled) <a href="#ac9982ebd2fcc745ecd760f4c982427a4"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">void </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder.html#a20741a2a879dab820f10618424a97b2a">loadCurrentMapFromFile</a> (const <a class="el" href="classstd_1_1string.html">std::string</a> &fileName)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Load map (<a class="el" href="classmrpt_1_1slam_1_1_c_simple_map.html" title="This class stores a sequence of <Probabilistic Pose,SensoryFrame> pairs, thus a "metric map" can be t...">mrpt::slam::CSimpleMap</a>) from a ".simplemap" file. <a href="#a20741a2a879dab820f10618424a97b2a"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">void </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder.html#a5aaa791f174c29a07ccf7f29adafb386">saveCurrentMapToFile</a> (const <a class="el" href="classstd_1_1string.html">std::string</a> &fileName, bool compressGZ=true) const </td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Save map (<a class="el" href="classmrpt_1_1slam_1_1_c_simple_map.html" title="This class stores a sequence of <Probabilistic Pose,SensoryFrame> pairs, thus a "metric map" can be t...">mrpt::slam::CSimpleMap</a>) to a ".simplemap" file. <a href="#a5aaa791f174c29a07ccf7f29adafb386"></a><br/></td></tr> <tr><td colspan="2"><h2><a name="pub-static-methods"></a> Static Public Member Functions</h2></td></tr> <tr><td class="memItemLeft" align="right" valign="top">static void </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1utils_1_1_c_debug_output_capable.html#ab78281b5d70d6e295a8527a10fea66de">printf_debug</a> (const char *frmt,...)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Sends a formated text to "debugOut" if not NULL, or to cout otherwise. <a href="#ab78281b5d70d6e295a8527a10fea66de"></a><br/></td></tr> <tr><td colspan="2"><h2><a name="pub-attribs"></a> Public Attributes</h2></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="structmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p_1_1_t_config_params.html">TConfigParams</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a1ec3c3ee5d8409d04017e7fe441b6a54">ICP_options</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Options for the ICP-SLAM application. <a href="#a1ec3c3ee5d8409d04017e7fe441b6a54"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p_1_1_t_config_params.html">CICP::TConfigParams</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a7ef2b889f11d62dc23bcdebba91b886a">ICP_params</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Options for the ICP algorithm itself. <a href="#a7ef2b889f11d62dc23bcdebba91b886a"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="structmrpt_1_1slam_1_1_c_metric_map_builder_1_1_t_options.html">TOptions</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder.html#a8db543d082103e5300415d4139d9255a">options</a></td></tr> <tr><td colspan="2"><h2><a name="pro-methods"></a> Protected Member Functions</h2></td></tr> <tr><td class="memItemLeft" align="right" valign="top">void </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder.html#ade4637e621a9a02380ba877fc7e20f2a">enterCriticalSection</a> ()</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Enter critical section for map updating: <a href="#ade4637e621a9a02380ba877fc7e20f2a"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">void </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder.html#a02e4f68550a98bc5a2acea71ee9268d9">leaveCriticalSection</a> ()</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Leave critical section for map updating: <a href="#a02e4f68550a98bc5a2acea71ee9268d9"></a><br/></td></tr> <tr><td colspan="2"><h2><a name="pro-attribs"></a> Protected Attributes</h2></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="classmrpt_1_1synch_1_1_c_critical_section.html">synch::CCriticalSection</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder.html#a2effa8714a43d5bdfd27b0e9fee09cb3">critZoneChangingMap</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Critical zones. <a href="#a2effa8714a43d5bdfd27b0e9fee09cb3"></a><br/></td></tr> <tr><td colspan="2"><h2><a name="pri-methods"></a> Private Member Functions</h2></td></tr> <tr><td class="memItemLeft" align="right" valign="top">void </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#ac952c2ac85a91fbd3cf1568fb830b0d1">accumulateRobotDisplacementCounters</a> (const <a class="el" href="classmrpt_1_1poses_1_1_c_pose2_d.html">CPose2D</a> &Apose)</td></tr> <tr><td colspan="2"><h2><a name="pri-attribs"></a> Private Attributes</h2></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="classmrpt_1_1slam_1_1_c_simple_map.html">CSimpleMap</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#af8887a2bff23741cc743c4487c6c58ab">SF_Poses_seq</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">The set of observations that leads to current map: <a href="#af8887a2bff23741cc743c4487c6c58ab"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="classmrpt_1_1slam_1_1_c_multi_metric_map.html">CMultiMetricMap</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a8dde59db8d85102a55a098834ac03531">metricMap</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">The metric map representation as a points map: <a href="#a8dde59db8d85102a55a098834ac03531"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="classstd_1_1string.html">std::string</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a807ddc044dc88e336a7c1f2c3833bd58">currentMapFile</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Current map file. <a href="#a807ddc044dc88e336a7c1f2c3833bd58"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="classmrpt_1_1poses_1_1_c_robot2_d_pose_estimator.html">mrpt::poses::CRobot2DPoseEstimator</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a96c1336bafdc64cd0c240a1294ce7677">m_lastPoseEst</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">The pose estimation by the alignment algorithm (ICP). <a href="#a96c1336bafdc64cd0c240a1294ce7677"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="namespacemrpt_1_1math.html#a58d0ee60eee38e990848ccb8b83e8338">mrpt::math::CMatrixDouble33</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a29c7293ae44e3924c35985f8a6772379">m_lastPoseEst_cov</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Last pose estimation (covariance) <a href="#a29c7293ae44e3924c35985f8a6772379"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="classstd_1_1deque.html">std::deque</a>< <a class="el" href="structmrpt_1_1math_1_1_t_pose2_d.html">mrpt::math::TPose2D</a> > </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a541d8d5d4eb812b4f42950464c029f4c">m_estRobotPath</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">The estimated robot path: <a href="#a541d8d5d4eb812b4f42950464c029f4c"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="classmrpt_1_1poses_1_1_c_pose2_d.html">mrpt::poses::CPose2D</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#add9b23983fc7ebb6bb25db5254ef276b">m_auxAccumOdometry</a></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="structmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p_1_1_t_dist.html">TDist</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a4fa7dbf950beced774e7fb85c014c145">m_distSinceLastICP</a></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="classstd_1_1map.html">std::map</a>< <a class="el" href="classstd_1_1string.html">std::string</a>, <a class="el" href="structmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p_1_1_t_dist.html">TDist</a> > </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a2b12af4396642f176df57972cdbf1f70">m_distSinceLastInsertion</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Indexed by sensor label. <a href="#a2b12af4396642f176df57972cdbf1f70"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">bool </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a3348f38548e25010c6bce0b454405790">m_there_has_been_an_odometry</a></td></tr> </table> <hr/><h2>Constructor & Destructor Documentation</h2> <a class="anchor" id="a505be777839d4f1ceb38b0d973ce1fee"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::CMetricMapBuilderICP" ref="a505be777839d4f1ceb38b0d973ce1fee" args="()" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">mrpt::slam::CMetricMapBuilderICP::CMetricMapBuilderICP </td> <td>(</td> <td class="paramname"></td><td>)</td> <td></td> </tr> </table> </div> <div class="memdoc"> <p>Default constructor - Upon construction, you can set the parameters in ICP_options, then call "initialize". </p> </div> </div> <a class="anchor" id="a2d1ad8aaa8c13c0c44d098b7b96cab9c"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::~CMetricMapBuilderICP" ref="a2d1ad8aaa8c13c0c44d098b7b96cab9c" args="()" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">virtual mrpt::slam::CMetricMapBuilderICP::~CMetricMapBuilderICP </td> <td>(</td> <td class="paramname"></td><td>)</td> <td><code> [virtual]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Destructor: </p> </div> </div> <hr/><h2>Member Function Documentation</h2> <a class="anchor" id="ac952c2ac85a91fbd3cf1568fb830b0d1"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::accumulateRobotDisplacementCounters" ref="ac952c2ac85a91fbd3cf1568fb830b0d1" args="(const CPose2D &Apose)" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">void mrpt::slam::CMetricMapBuilderICP::accumulateRobotDisplacementCounters </td> <td>(</td> <td class="paramtype">const <a class="el" href="classmrpt_1_1poses_1_1_c_pose2_d.html">CPose2D</a> & </td> <td class="paramname"><em>Apose</em></td><td>)</td> <td><code> [private]</code></td> </tr> </table> </div> <div class="memdoc"> </div> </div> <a class="anchor" id="a45414544fc4c56b67c450efbbc6f61b8"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::clear" ref="a45414544fc4c56b67c450efbbc6f61b8" args="()" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">void mrpt::slam::CMetricMapBuilder::clear </td> <td>(</td> <td class="paramname"></td><td>)</td> <td><code> [inherited]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Clear all elements of the maps, and reset localization to (0,0,0deg). </p> <p>Reimplemented in <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#a8535aedd13efe9c73362c41cff57ad8e">mrpt::slam::CMetricMapBuilderRBPF</a>.</p> </div> </div> <a class="anchor" id="ac9982ebd2fcc745ecd760f4c982427a4"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::enableMapUpdating" ref="ac9982ebd2fcc745ecd760f4c982427a4" args="(bool enable)" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">void mrpt::slam::CMetricMapBuilder::enableMapUpdating </td> <td>(</td> <td class="paramtype">bool </td> <td class="paramname"><em>enable</em></td><td>)</td> <td><code> [inline, inherited]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Enables or disables the map updating (default state is enabled) </p> <p>Definition at line <a class="el" href="_c_metric_map_builder_8h_source.html#l00114">114</a> of file <a class="el" href="_c_metric_map_builder_8h_source.html">CMetricMapBuilder.h</a>.</p> </div> </div> <a class="anchor" id="ade4637e621a9a02380ba877fc7e20f2a"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::enterCriticalSection" ref="ade4637e621a9a02380ba877fc7e20f2a" args="()" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">void mrpt::slam::CMetricMapBuilder::enterCriticalSection </td> <td>(</td> <td class="paramname"></td><td>)</td> <td><code> [inline, protected, inherited]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Enter critical section for map updating: </p> <p>Definition at line <a class="el" href="_c_metric_map_builder_8h_source.html#l00063">63</a> of file <a class="el" href="_c_metric_map_builder_8h_source.html">CMetricMapBuilder.h</a>.</p> </div> </div> <a class="anchor" id="ac616ad0198e3b2cd68fd75eb2795fedc"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::getCurrentlyBuiltMap" ref="ac616ad0198e3b2cd68fd75eb2795fedc" args="(CSimpleMap &out_map) const " --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">void mrpt::slam::CMetricMapBuilderICP::getCurrentlyBuiltMap </td> <td>(</td> <td class="paramtype"><a class="el" href="classmrpt_1_1slam_1_1_c_simple_map.html">CSimpleMap</a> & </td> <td class="paramname"><em>out_map</em></td><td>)</td> <td> const<code> [virtual]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Fills "out_map" with the set of "poses"-"sensory-frames", thus the so far built map. </p> <p>Implements <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder.html#accb35416b8bf85da803b83e99bad02db">mrpt::slam::CMetricMapBuilder</a>.</p> </div> </div> <a class="anchor" id="a9297996b2194bae02ea112e9a7256027"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::getCurrentlyBuiltMapSize" ref="a9297996b2194bae02ea112e9a7256027" args="()" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">unsigned int mrpt::slam::CMetricMapBuilderICP::getCurrentlyBuiltMapSize </td> <td>(</td> <td class="paramname"></td><td>)</td> <td><code> [virtual]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Returns just how many sensory-frames are stored in the currently build map. </p> <p>Implements <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder.html#afdea305bbb77c9ead1e909150c4875dc">mrpt::slam::CMetricMapBuilder</a>.</p> </div> </div> <a class="anchor" id="a64cb24ecb715b33e41712f109cb4c4ca"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::getCurrentlyBuiltMetricMap" ref="a64cb24ecb715b33e41712f109cb4c4ca" args="()" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname"><a class="el" href="classmrpt_1_1slam_1_1_c_multi_metric_map.html">CMultiMetricMap</a>* mrpt::slam::CMetricMapBuilderICP::getCurrentlyBuiltMetricMap </td> <td>(</td> <td class="paramname"></td><td>)</td> <td><code> [virtual]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Returns the map built so far. </p> <p>NOTE that for efficiency a pointer to the internal object is passed, DO NOT delete nor modify the object in any way, if desired, make a copy of ir with "duplicate()". </p> <p>Implements <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder.html#a3a6c22213142511cde0f076587f21c7f">mrpt::slam::CMetricMapBuilder</a>.</p> </div> </div> <a class="anchor" id="aa231bb36a8fe0fa7e7869037132a0c0c"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::getCurrentMapPoints" ref="aa231bb36a8fe0fa7e7869037132a0c0c" args="(std::vector< float > &x, std::vector< float > &y)" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">void mrpt::slam::CMetricMapBuilderICP::getCurrentMapPoints </td> <td>(</td> <td class="paramtype"><a class="el" href="classstd_1_1vector.html">std::vector</a>< float > & </td> <td class="paramname"><em>x</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype"><a class="el" href="classstd_1_1vector.html">std::vector</a>< float > & </td> <td class="paramname"><em>y</em> </td> </tr> <tr> <td></td> <td>)</td> <td></td><td></td> </tr> </table> </div> <div class="memdoc"> <p>Returns the 2D points of current local map. </p> </div> </div> <a class="anchor" id="a45620c0802954419b152685e22a10981"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::getCurrentPoseEstimation" ref="a45620c0802954419b152685e22a10981" args="() const " --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname"><a class="el" href="structmrpt_1_1poses_1_1_c_pose3_d_p_d_f_ptr.html">CPose3DPDFPtr</a> mrpt::slam::CMetricMapBuilderICP::getCurrentPoseEstimation </td> <td>(</td> <td class="paramname"></td><td>)</td> <td> const<code> [virtual]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Returns a copy of the current best pose estimation as a pose PDF. </p> <p>Implements <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder.html#a8db935488eb11d47ac17dff0cd2ba091">mrpt::slam::CMetricMapBuilder</a>.</p> </div> </div> <a class="anchor" id="a1106c4ff0e3af8b8ce752fe7e67530be"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::initialize" ref="a1106c4ff0e3af8b8ce752fe7e67530be" args="(const CSimpleMap &initialMap=CSimpleMap(), CPosePDF *x0=NULL)" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">void mrpt::slam::CMetricMapBuilderICP::initialize </td> <td>(</td> <td class="paramtype">const <a class="el" href="classmrpt_1_1slam_1_1_c_simple_map.html">CSimpleMap</a> & </td> <td class="paramname"><em>initialMap</em> = <code><a class="el" href="classmrpt_1_1slam_1_1_c_simple_map.html">CSimpleMap</a>()</code>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype"><a class="el" href="classmrpt_1_1poses_1_1_c_pose_p_d_f.html">CPosePDF</a> * </td> <td class="paramname"><em>x0</em> = <code>NULL</code> </td> </tr> <tr> <td></td> <td>)</td> <td></td><td><code> [virtual]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Initialize the method, starting with a known location PDF "x0"(if supplied, set to NULL to left unmodified) and a given fixed, past map. </p> <p>This method MUST be called if using the default constructor, after loading the configuration into ICP_options. In particular, <a class="el" href="structmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p_1_1_t_config_params.html#a1e858d31f52331e1e85de46938feecf4" title="What maps to create (at least one points map and/or a grid map are needed).">TConfigParams::mapInitializers</a> </p> <p>Implements <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder.html#a05ab1ad7345695e3b050c79ddfb44111">mrpt::slam::CMetricMapBuilder</a>.</p> </div> </div> <a class="anchor" id="a02e4f68550a98bc5a2acea71ee9268d9"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::leaveCriticalSection" ref="a02e4f68550a98bc5a2acea71ee9268d9" args="()" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">void mrpt::slam::CMetricMapBuilder::leaveCriticalSection </td> <td>(</td> <td class="paramname"></td><td>)</td> <td><code> [inline, protected, inherited]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Leave critical section for map updating: </p> <p>Definition at line <a class="el" href="_c_metric_map_builder_8h_source.html#l00067">67</a> of file <a class="el" href="_c_metric_map_builder_8h_source.html">CMetricMapBuilder.h</a>.</p> </div> </div> <a class="anchor" id="a20741a2a879dab820f10618424a97b2a"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::loadCurrentMapFromFile" ref="a20741a2a879dab820f10618424a97b2a" args="(const std::string &fileName)" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">void mrpt::slam::CMetricMapBuilder::loadCurrentMapFromFile </td> <td>(</td> <td class="paramtype">const <a class="el" href="classstd_1_1string.html">std::string</a> & </td> <td class="paramname"><em>fileName</em></td><td>)</td> <td><code> [inherited]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Load map (<a class="el" href="classmrpt_1_1slam_1_1_c_simple_map.html" title="This class stores a sequence of <Probabilistic Pose,SensoryFrame> pairs, thus a "metric map" can be t...">mrpt::slam::CSimpleMap</a>) from a ".simplemap" file. </p> </div> </div> <a class="anchor" id="ab78281b5d70d6e295a8527a10fea66de"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::printf_debug" ref="ab78281b5d70d6e295a8527a10fea66de" args="(const char *frmt,...)" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">static void mrpt::utils::CDebugOutputCapable::printf_debug </td> <td>(</td> <td class="paramtype">const char * </td> <td class="paramname"><em>frmt</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype"> </td> <td class="paramname"><em>...</em> </td> </tr> <tr> <td></td> <td>)</td> <td></td><td><code> [static, inherited]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Sends a formated text to "debugOut" if not NULL, or to cout otherwise. </p> <p>Referenced by <a class="el" href="_c_levenberg_marquardt_8h_source.html#l00098">mrpt::math::CLevenbergMarquardtTempl::execute()</a>.</p> </div> </div> <a class="anchor" id="ae59c6b2a7b0222a85e2cc2cfeca19c10"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::processActionObservation" ref="ae59c6b2a7b0222a85e2cc2cfeca19c10" args="(CActionCollection &action, CSensoryFrame &in_SF)" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">void mrpt::slam::CMetricMapBuilderICP::processActionObservation </td> <td>(</td> <td class="paramtype"><a class="el" href="classmrpt_1_1slam_1_1_c_action_collection.html">CActionCollection</a> & </td> <td class="paramname"><em>action</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype"><a class="el" href="classmrpt_1_1slam_1_1_c_sensory_frame.html">CSensoryFrame</a> & </td> <td class="paramname"><em>in_SF</em> </td> </tr> <tr> <td></td> <td>)</td> <td></td><td><code> [virtual]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Appends a new action and observations to update this map: See the description of the class at the top of this page to see a more complete description. </p> <dl><dt><b>Parameters:</b></dt><dd> <table class="params"> <tr><td class="paramname">action</td><td>The estimation of the incremental pose change in the robot pose. </td></tr> <tr><td class="paramname">in_SF</td><td>The set of observations that robot senses at the new pose. See params in <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder.html#a8db543d082103e5300415d4139d9255a">CMetricMapBuilder::options</a> and <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a1ec3c3ee5d8409d04017e7fe441b6a54" title="Options for the ICP-SLAM application.">CMetricMapBuilderICP::ICP_options</a> </td></tr> </table> </dd> </dl> <dl class="see"><dt><b>See also:</b></dt><dd><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a7abc2ee4a0adccbec65444e434abdd1b" title="The main method of this class: Process one odometry or sensor observation.">processObservation</a> </dd></dl> <p>Implements <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder.html#a8f54b3526d92e6229b95fdb794083355">mrpt::slam::CMetricMapBuilder</a>.</p> </div> </div> <a class="anchor" id="a7abc2ee4a0adccbec65444e434abdd1b"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::processObservation" ref="a7abc2ee4a0adccbec65444e434abdd1b" args="(const CObservationPtr &obs)" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">void mrpt::slam::CMetricMapBuilderICP::processObservation </td> <td>(</td> <td class="paramtype">const <a class="el" href="structmrpt_1_1slam_1_1_c_observation_ptr.html">CObservationPtr</a> & </td> <td class="paramname"><em>obs</em></td><td>)</td> <td></td> </tr> </table> </div> <div class="memdoc"> <p>The main method of this class: Process one odometry or sensor observation. </p> <p>The new entry point of the algorithm (the old one was processActionObservation, which now is a wrapper to this method). See params in <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder.html#a8db543d082103e5300415d4139d9255a">CMetricMapBuilder::options</a> and <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a1ec3c3ee5d8409d04017e7fe441b6a54" title="Options for the ICP-SLAM application.">CMetricMapBuilderICP::ICP_options</a> </p> </div> </div> <a class="anchor" id="a12b97251df911adff7760d73b09e40f7"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::saveCurrentEstimationToImage" ref="a12b97251df911adff7760d73b09e40f7" args="(const std::string &file, bool formatEMF_BMP=true)" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">void mrpt::slam::CMetricMapBuilderICP::saveCurrentEstimationToImage </td> <td>(</td> <td class="paramtype">const <a class="el" href="classstd_1_1string.html">std::string</a> & </td> <td class="paramname"><em>file</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">bool </td> <td class="paramname"><em>formatEMF_BMP</em> = <code>true</code> </td> </tr> <tr> <td></td> <td>)</td> <td></td><td><code> [virtual]</code></td> </tr> </table> </div> <div class="memdoc"> <p>A useful method for debugging: the current map (and/or poses) estimation is dumped to an image file. </p> <dl><dt><b>Parameters:</b></dt><dd> <table class="params"> <tr><td class="paramname">file</td><td>The output file name </td></tr> <tr><td class="paramname">formatEMF_BMP</td><td>Output format = true:EMF, false:BMP </td></tr> </table> </dd> </dl> <p>Implements <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder.html#ad6ed4fe0eb73c5dab4b265f2a55da84d">mrpt::slam::CMetricMapBuilder</a>.</p> </div> </div> <a class="anchor" id="a5aaa791f174c29a07ccf7f29adafb386"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::saveCurrentMapToFile" ref="a5aaa791f174c29a07ccf7f29adafb386" args="(const std::string &fileName, bool compressGZ=true) const " --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">void mrpt::slam::CMetricMapBuilder::saveCurrentMapToFile </td> <td>(</td> <td class="paramtype">const <a class="el" href="classstd_1_1string.html">std::string</a> & </td> <td class="paramname"><em>fileName</em>, </td> </tr> <tr> <td class="paramkey"></td> <td></td> <td class="paramtype">bool </td> <td class="paramname"><em>compressGZ</em> = <code>true</code> </td> </tr> <tr> <td></td> <td>)</td> <td></td><td> const<code> [inherited]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Save map (<a class="el" href="classmrpt_1_1slam_1_1_c_simple_map.html" title="This class stores a sequence of <Probabilistic Pose,SensoryFrame> pairs, thus a "metric map" can be t...">mrpt::slam::CSimpleMap</a>) to a ".simplemap" file. </p> </div> </div> <a class="anchor" id="a3d57d951672dd166a8725f2de263164f"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::setCurrentMapFile" ref="a3d57d951672dd166a8725f2de263164f" args="(const char *mapFile)" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">void mrpt::slam::CMetricMapBuilderICP::setCurrentMapFile </td> <td>(</td> <td class="paramtype">const char * </td> <td class="paramname"><em>mapFile</em></td><td>)</td> <td></td> </tr> </table> </div> <div class="memdoc"> <p>Sets the "current map file", thus that map will be loaded if it exists or a new one will be created if it does not, and the updated map will be save to that file when destroying the object. </p> </div> </div> <hr/><h2>Member Data Documentation</h2> <a class="anchor" id="a2effa8714a43d5bdfd27b0e9fee09cb3"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::critZoneChangingMap" ref="a2effa8714a43d5bdfd27b0e9fee09cb3" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname"><a class="el" href="classmrpt_1_1synch_1_1_c_critical_section.html">synch::CCriticalSection</a> <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder.html#a2effa8714a43d5bdfd27b0e9fee09cb3">mrpt::slam::CMetricMapBuilder::critZoneChangingMap</a><code> [protected, inherited]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Critical zones. </p> <p>Definition at line <a class="el" href="_c_metric_map_builder_8h_source.html#l00059">59</a> of file <a class="el" href="_c_metric_map_builder_8h_source.html">CMetricMapBuilder.h</a>.</p> </div> </div> <a class="anchor" id="a807ddc044dc88e336a7c1f2c3833bd58"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::currentMapFile" ref="a807ddc044dc88e336a7c1f2c3833bd58" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname"><a class="el" href="classstd_1_1string.html">std::string</a> <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a807ddc044dc88e336a7c1f2c3833bd58">mrpt::slam::CMetricMapBuilderICP::currentMapFile</a><code> [private]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Current map file. </p> <p>Definition at line <a class="el" href="_c_metric_map_builder_i_c_p_8h_source.html#l00157">157</a> of file <a class="el" href="_c_metric_map_builder_i_c_p_8h_source.html">CMetricMapBuilderICP.h</a>.</p> </div> </div> <a class="anchor" id="a1ec3c3ee5d8409d04017e7fe441b6a54"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::ICP_options" ref="a1ec3c3ee5d8409d04017e7fe441b6a54" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname"><a class="el" href="structmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p_1_1_t_config_params.html">TConfigParams</a> <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a1ec3c3ee5d8409d04017e7fe441b6a54">mrpt::slam::CMetricMapBuilderICP::ICP_options</a></td> </tr> </table> </div> <div class="memdoc"> <p>Options for the ICP-SLAM application. </p> <dl class="see"><dt><b>See also:</b></dt><dd><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a7ef2b889f11d62dc23bcdebba91b886a" title="Options for the ICP algorithm itself.">ICP_params</a> </dd></dl> <p>Definition at line <a class="el" href="_c_metric_map_builder_i_c_p_8h_source.html#l00086">86</a> of file <a class="el" href="_c_metric_map_builder_i_c_p_8h_source.html">CMetricMapBuilderICP.h</a>.</p> </div> </div> <a class="anchor" id="a7ef2b889f11d62dc23bcdebba91b886a"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::ICP_params" ref="a7ef2b889f11d62dc23bcdebba91b886a" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname"><a class="el" href="classmrpt_1_1slam_1_1_c_i_c_p_1_1_t_config_params.html">CICP::TConfigParams</a> <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a7ef2b889f11d62dc23bcdebba91b886a">mrpt::slam::CMetricMapBuilderICP::ICP_params</a></td> </tr> </table> </div> <div class="memdoc"> <p>Options for the ICP algorithm itself. </p> <dl class="see"><dt><b>See also:</b></dt><dd><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a1ec3c3ee5d8409d04017e7fe441b6a54" title="Options for the ICP-SLAM application.">ICP_options</a> </dd></dl> <p>Definition at line <a class="el" href="_c_metric_map_builder_i_c_p_8h_source.html#l00087">87</a> of file <a class="el" href="_c_metric_map_builder_i_c_p_8h_source.html">CMetricMapBuilderICP.h</a>.</p> </div> </div> <a class="anchor" id="add9b23983fc7ebb6bb25db5254ef276b"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::m_auxAccumOdometry" ref="add9b23983fc7ebb6bb25db5254ef276b" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname"><a class="el" href="classmrpt_1_1poses_1_1_c_pose2_d.html">mrpt::poses::CPose2D</a> <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#add9b23983fc7ebb6bb25db5254ef276b">mrpt::slam::CMetricMapBuilderICP::m_auxAccumOdometry</a><code> [private]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Definition at line <a class="el" href="_c_metric_map_builder_i_c_p_8h_source.html#l00166">166</a> of file <a class="el" href="_c_metric_map_builder_i_c_p_8h_source.html">CMetricMapBuilderICP.h</a>.</p> </div> </div> <a class="anchor" id="a4fa7dbf950beced774e7fb85c014c145"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::m_distSinceLastICP" ref="a4fa7dbf950beced774e7fb85c014c145" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname"><a class="el" href="structmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p_1_1_t_dist.html">TDist</a> <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a4fa7dbf950beced774e7fb85c014c145">mrpt::slam::CMetricMapBuilderICP::m_distSinceLastICP</a><code> [private]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Definition at line <a class="el" href="_c_metric_map_builder_i_c_p_8h_source.html#l00175">175</a> of file <a class="el" href="_c_metric_map_builder_i_c_p_8h_source.html">CMetricMapBuilderICP.h</a>.</p> </div> </div> <a class="anchor" id="a2b12af4396642f176df57972cdbf1f70"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::m_distSinceLastInsertion" ref="a2b12af4396642f176df57972cdbf1f70" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname"><a class="el" href="classstd_1_1map.html">std::map</a><<a class="el" href="classstd_1_1string.html">std::string</a>,<a class="el" href="structmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p_1_1_t_dist.html">TDist</a>> <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a2b12af4396642f176df57972cdbf1f70">mrpt::slam::CMetricMapBuilderICP::m_distSinceLastInsertion</a><code> [private]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Indexed by sensor label. </p> <p>Definition at line <a class="el" href="_c_metric_map_builder_i_c_p_8h_source.html#l00176">176</a> of file <a class="el" href="_c_metric_map_builder_i_c_p_8h_source.html">CMetricMapBuilderICP.h</a>.</p> </div> </div> <a class="anchor" id="a541d8d5d4eb812b4f42950464c029f4c"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::m_estRobotPath" ref="a541d8d5d4eb812b4f42950464c029f4c" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname"><a class="el" href="classstd_1_1deque.html">std::deque</a><<a class="el" href="structmrpt_1_1math_1_1_t_pose2_d.html">mrpt::math::TPose2D</a>> <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a541d8d5d4eb812b4f42950464c029f4c">mrpt::slam::CMetricMapBuilderICP::m_estRobotPath</a><code> [private]</code></td> </tr> </table> </div> <div class="memdoc"> <p>The estimated robot path: </p> <p>Definition at line <a class="el" href="_c_metric_map_builder_i_c_p_8h_source.html#l00165">165</a> of file <a class="el" href="_c_metric_map_builder_i_c_p_8h_source.html">CMetricMapBuilderICP.h</a>.</p> </div> </div> <a class="anchor" id="a96c1336bafdc64cd0c240a1294ce7677"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::m_lastPoseEst" ref="a96c1336bafdc64cd0c240a1294ce7677" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname"><a class="el" href="classmrpt_1_1poses_1_1_c_robot2_d_pose_estimator.html">mrpt::poses::CRobot2DPoseEstimator</a> <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a96c1336bafdc64cd0c240a1294ce7677">mrpt::slam::CMetricMapBuilderICP::m_lastPoseEst</a><code> [private]</code></td> </tr> </table> </div> <div class="memdoc"> <p>The pose estimation by the alignment algorithm (ICP). </p> <p>Last pose estimation (Mean) </p> <p>Definition at line <a class="el" href="_c_metric_map_builder_i_c_p_8h_source.html#l00160">160</a> of file <a class="el" href="_c_metric_map_builder_i_c_p_8h_source.html">CMetricMapBuilderICP.h</a>.</p> </div> </div> <a class="anchor" id="a29c7293ae44e3924c35985f8a6772379"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::m_lastPoseEst_cov" ref="a29c7293ae44e3924c35985f8a6772379" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname"><a class="el" href="namespacemrpt_1_1math.html#a58d0ee60eee38e990848ccb8b83e8338">mrpt::math::CMatrixDouble33</a> <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a29c7293ae44e3924c35985f8a6772379">mrpt::slam::CMetricMapBuilderICP::m_lastPoseEst_cov</a><code> [private]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Last pose estimation (covariance) </p> <p>Definition at line <a class="el" href="_c_metric_map_builder_i_c_p_8h_source.html#l00161">161</a> of file <a class="el" href="_c_metric_map_builder_i_c_p_8h_source.html">CMetricMapBuilderICP.h</a>.</p> </div> </div> <a class="anchor" id="a3348f38548e25010c6bce0b454405790"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::m_there_has_been_an_odometry" ref="a3348f38548e25010c6bce0b454405790" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">bool <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a3348f38548e25010c6bce0b454405790">mrpt::slam::CMetricMapBuilderICP::m_there_has_been_an_odometry</a><code> [private]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Definition at line <a class="el" href="_c_metric_map_builder_i_c_p_8h_source.html#l00177">177</a> of file <a class="el" href="_c_metric_map_builder_i_c_p_8h_source.html">CMetricMapBuilderICP.h</a>.</p> </div> </div> <a class="anchor" id="a8dde59db8d85102a55a098834ac03531"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::metricMap" ref="a8dde59db8d85102a55a098834ac03531" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname"><a class="el" href="classmrpt_1_1slam_1_1_c_multi_metric_map.html">CMultiMetricMap</a> <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#a8dde59db8d85102a55a098834ac03531">mrpt::slam::CMetricMapBuilderICP::metricMap</a><code> [private]</code></td> </tr> </table> </div> <div class="memdoc"> <p>The metric map representation as a points map: </p> <p>Definition at line <a class="el" href="_c_metric_map_builder_i_c_p_8h_source.html#l00153">153</a> of file <a class="el" href="_c_metric_map_builder_i_c_p_8h_source.html">CMetricMapBuilderICP.h</a>.</p> </div> </div> <a class="anchor" id="a8db543d082103e5300415d4139d9255a"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::options" ref="a8db543d082103e5300415d4139d9255a" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname"><a class="el" href="structmrpt_1_1slam_1_1_c_metric_map_builder_1_1_t_options.html">TOptions</a> <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder.html#a8db543d082103e5300415d4139d9255a">mrpt::slam::CMetricMapBuilder::options</a><code> [inherited]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Definition at line <a class="el" href="_c_metric_map_builder_8h_source.html#l00150">150</a> of file <a class="el" href="_c_metric_map_builder_8h_source.html">CMetricMapBuilder.h</a>.</p> </div> </div> <a class="anchor" id="af8887a2bff23741cc743c4487c6c58ab"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderICP::SF_Poses_seq" ref="af8887a2bff23741cc743c4487c6c58ab" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname"><a class="el" href="classmrpt_1_1slam_1_1_c_simple_map.html">CSimpleMap</a> <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_i_c_p.html#af8887a2bff23741cc743c4487c6c58ab">mrpt::slam::CMetricMapBuilderICP::SF_Poses_seq</a><code> [private]</code></td> </tr> </table> </div> <div class="memdoc"> <p>The set of observations that leads to current map: </p> <p>Definition at line <a class="el" href="_c_metric_map_builder_i_c_p_8h_source.html#l00149">149</a> of file <a class="el" href="_c_metric_map_builder_i_c_p_8h_source.html">CMetricMapBuilderICP.h</a>.</p> </div> </div> </div> <br><hr><br> <table border="0" width="100%"> <tr> <td> Page generated by <a href="http://www.doxygen.org" target="_blank">Doxygen 1.7.5</a> for MRPT 0.9.5 SVN: at Sun Sep 25 17:20:18 UTC 2011</td><td></td> <td width="100"> </td> <td width="150"> </td></tr> </table> </body></html>