<!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::CMetricMapBuilderRBPF 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_r_b_p_f.html">CMetricMapBuilderRBPF</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> </div> <div class="headertitle"> <div class="title">mrpt::slam::CMetricMapBuilderRBPF 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::CMetricMapBuilderRBPF" --><!-- doxytag: inherits="mrpt::slam::CMetricMapBuilder" --><hr/><a name="details" id="details"></a><h2>Detailed Description</h2> <div class="textblock"><p>This class implements a Rao-Blackwelized Particle Filter (RBPF) approach to map building (SLAM). </p> <p>Internally, the list of particles, each containing a hypothesis for the robot path plus its associated metric map, is stored in an object of class <a class="el" href="classmrpt_1_1slam_1_1_c_multi_metric_map_p_d_f.html" title="Declares a class that represents a Rao-Blackwellized set of particles for solving the SLAM problem (T...">CMultiMetricMapPDF</a>.</p> <p>This class processes robot actions and observations sequentially (through the method <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#a914dd7413e703c8c22093f340e6423ee" title="Appends a new action and observations to update this map: See the description of the class at the top...">CMetricMapBuilderRBPF::processActionObservation</a>) and exploits the generic design of metric map classes in MRPT to deal with any number and combination of maps simultaneously: the likelihood of observations is the product of the likelihood in the different maps, etc.</p> <p>A number of particle filter methods are implemented as well, by selecting the appropriate values in <a class="el" href="structmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f_1_1_t_construction_options.html#a255075a9c12a6a5f41f87da67d4775ea">TConstructionOptions::PF_options</a>. Not all the PF algorithms are implemented for all kinds of maps.</p> <p>For an example of usage, check the application "rbpf-slam", in "apps/RBPF-SLAM". See also the <a href="http://www.mrpt.org/Application:RBPF-SLAM">wiki page</a>.</p> <dl class="note"><dt><b>Note:</b></dt><dd>Since MRPT 0.7.2, the new variables "localizeLinDistance,localizeAngDistance" are introduced to provide a way to update the robot pose at a different rate than the map is updated. </dd> <dd> Since MRPT 0.7.1 the semantics of the parameters "insertionLinDistance" and "insertionAngDistance" changes: the entire RBFP is now NOT updated unless odometry increments surpass the threshold (previously, only the map was NOT updated). This is done to gain efficiency. </dd> <dd> Since MRPT 0.6.2 this class implements full 6D SLAM. Previous versions worked in 2D + heading only.</dd></dl> <dl class="see"><dt><b>See also:</b></dt><dd><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map.html" title="Declares a virtual base class for all metric maps storage classes.">CMetricMap</a> </dd></dl> </div> <p><code>#include <<a class="el" href="_c_metric_map_builder_r_b_p_f_8h_source.html">mrpt/slam/CMetricMapBuilderRBPF.h</a>></code></p> <div class="dynheader"> Inheritance diagram for mrpt::slam::CMetricMapBuilderRBPF:</div> <div class="dyncontent"> <div class="center"><img src="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f__inherit__graph.png" border="0" usemap="#mrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f_inherit__map" alt="Inheritance graph"/></div> <map name="mrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f_inherit__map" id="mrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f_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="23,80,225,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="13,5,235,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_r_b_p_f-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_r_b_p_f_1_1_t_construction_options.html">TConstructionOptions</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Options for building a <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html" title="This class implements a Rao-Blackwelized Particle Filter (RBPF) approach to map building (SLAM)...">CMetricMapBuilderRBPF</a> object, passed to the constructor. <a href="structmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f_1_1_t_construction_options.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_r_b_p_f_1_1_t_stats.html">TStats</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">This structure will hold stats after each execution of processActionObservation. <a href="structmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f_1_1_t_stats.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_r_b_p_f.html#a0e6b90538795b08ded69dcbdf8e5463c">CMetricMapBuilderRBPF</a> (const <a class="el" href="structmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f_1_1_t_construction_options.html">TConstructionOptions</a> &initializationOptions)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Constructor. <a href="#a0e6b90538795b08ded69dcbdf8e5463c"></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_r_b_p_f.html#a593fd3774b4b52f3361179ce52be6882">~CMetricMapBuilderRBPF</a> ()</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Destructor. <a href="#a593fd3774b4b52f3361179ce52be6882"></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_r_b_p_f.html#a7e6cc1d4bdc90c2fd10e09aa0eca543b">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="#a7e6cc1d4bdc90c2fd10e09aa0eca543b"></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_r_b_p_f.html#a8535aedd13efe9c73362c41cff57ad8e">clear</a> ()</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Clear all elements of the maps. <a href="#a8535aedd13efe9c73362c41cff57ad8e"></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_r_b_p_f.html#a93bf627a068b5b3ea299e8b729564edd">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="#a93bf627a068b5b3ea299e8b729564edd"></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_r_b_p_f.html#a4ab88acfd71654c293dc7d7193b07291">getCurrentMostLikelyPath</a> (<a class="el" href="classstd_1_1deque.html">std::deque</a>< <a class="el" href="structmrpt_1_1math_1_1_t_pose3_d.html">TPose3D</a> > &outPath) const </td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Returns the current most-likely path estimation (the path associated to the most likely particle). <a href="#a4ab88acfd71654c293dc7d7193b07291"></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_r_b_p_f.html#a914dd7413e703c8c22093f340e6423ee">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> &observations)</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="#a914dd7413e703c8c22093f340e6423ee"></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_r_b_p_f.html#af36b951c3429e49414e1231ad3edf35a">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="#af36b951c3429e49414e1231ad3edf35a"></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_r_b_p_f.html#a63b8438c1c0ae5308579847958e1384b">getCurrentlyBuiltMetricMap</a> ()</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Returns the map built so far. <a href="#a63b8438c1c0ae5308579847958e1384b"></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_r_b_p_f.html#a3588366ffb1147c23f57e1ae2cccec66">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="#a3588366ffb1147c23f57e1ae2cccec66"></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_r_b_p_f.html#a244bdf1b8b839b572a8480082011cca4">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="#a244bdf1b8b839b572a8480082011cca4"></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_r_b_p_f.html#a1a496a075824bcdc1e7c98bf29e5fc2f">drawCurrentEstimationToImage</a> (<a class="el" href="classmrpt_1_1utils_1_1_c_canvas.html">utils::CCanvas</a> *img)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">A usefull method for debugging: draws the current map and path hypotheses to a CCanvas. <a href="#a1a496a075824bcdc1e7c98bf29e5fc2f"></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_r_b_p_f.html#ad6fe99ca086939ae20fda03e047f3092">saveCurrentPathEstimationToTextFile</a> (<a class="el" href="classstd_1_1string.html">std::string</a> fil)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">A logging utility: saves the current path estimation for each particle in a text file (a row per particle, each 3-column-entry is a set [x,y,phi], respectively). <a href="#ad6fe99ca086939ae20fda03e047f3092"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">double </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#afa1332008ee35bcdef16dfd4c963e257">getCurrentJointEntropy</a> ()</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="classmrpt_1_1slam_1_1_c_multi_metric_map_p_d_f.html">CMultiMetricMapPDF</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#a567e3937c2c51bb6c91c5f4370a2a9a9">mapPDF</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">The map PDF: It includes a path and associated map for each particle. <a href="#a567e3937c2c51bb6c91c5f4370a2a9a9"></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_r_b_p_f_1_1_t_stats.html">TStats</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#a7248f9700730c83e208f542f30899a3b">m_statsLastIteration</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">This structure will hold stats after each execution of processActionObservation. <a href="#a7248f9700730c83e208f542f30899a3b"></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="structmrpt_1_1bayes_1_1_c_particle_filter_1_1_t_particle_filter_options.html">bayes::CParticleFilter::TParticleFilterOptions</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#a9653b9c2e9afe2de7cc619eda9323b3c">m_PF_options</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">The configuration of the particle filter: <a href="#a9653b9c2e9afe2de7cc619eda9323b3c"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">float </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#ad0227fba9ff6b0e4b9ca491ed79b2f0e">insertionLinDistance</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Distances (linear and angular) for inserting a new observation into the map. <a href="#ad0227fba9ff6b0e4b9ca491ed79b2f0e"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">float </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#a6419d5c06cfe3b2d76b9a0d6f076d24f">insertionAngDistance</a></td></tr> <tr><td class="memItemLeft" align="right" valign="top">float </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#ac23cc1def48847393932b55488103ac0">localizeLinDistance</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Distances (linear and angular) for updating the robot pose estimate (and particles weighs, if applicable). <a href="#ac23cc1def48847393932b55488103ac0"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top">float </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#a603c4090661af389ab52cc496965708e">localizeAngDistance</a></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian.html">mrpt::poses::CPose3DPDFGaussian</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#abdfcc141c475abd6ad54cf0b657c63b8">odoIncrementSinceLastLocalization</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Traveled distance since last localization update. <a href="#abdfcc141c475abd6ad54cf0b657c63b8"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="classmrpt_1_1poses_1_1_c_pose3_d.html">mrpt::poses::CPose3D</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#aad453e506dc2700b5c1d7ba9e652c39a">odoIncrementSinceLastMapUpdate</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Traveled distance since last map update. <a href="#aad453e506dc2700b5c1d7ba9e652c39a"></a><br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="el" href="structmrpt_1_1utils_1_1non__copiable__ptr.html">non_copiable_ptr</a>< <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_r_b_p_f.html#a9ed28ff34b052e1a82cedc5fd70c3e6a">currentMetricMapEstimation</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">A buffer: memory is actually hold within "mapPDF". <a href="#a9ed28ff34b052e1a82cedc5fd70c3e6a"></a><br/></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> </table> <hr/><h2>Constructor & Destructor Documentation</h2> <a class="anchor" id="a0e6b90538795b08ded69dcbdf8e5463c"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderRBPF::CMetricMapBuilderRBPF" ref="a0e6b90538795b08ded69dcbdf8e5463c" args="(const TConstructionOptions &initializationOptions)" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">mrpt::slam::CMetricMapBuilderRBPF::CMetricMapBuilderRBPF </td> <td>(</td> <td class="paramtype">const <a class="el" href="structmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f_1_1_t_construction_options.html">TConstructionOptions</a> & </td> <td class="paramname"><em>initializationOptions</em></td><td>)</td> <td></td> </tr> </table> </div> <div class="memdoc"> <p>Constructor. </p> </div> </div> <a class="anchor" id="a593fd3774b4b52f3361179ce52be6882"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderRBPF::~CMetricMapBuilderRBPF" ref="a593fd3774b4b52f3361179ce52be6882" args="()" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">virtual mrpt::slam::CMetricMapBuilderRBPF::~CMetricMapBuilderRBPF </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="a8535aedd13efe9c73362c41cff57ad8e"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderRBPF::clear" ref="a8535aedd13efe9c73362c41cff57ad8e" args="()" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">void mrpt::slam::CMetricMapBuilderRBPF::clear </td> <td>(</td> <td class="paramname"></td><td>)</td> <td></td> </tr> </table> </div> <div class="memdoc"> <p>Clear all elements of the maps. </p> <p>Reimplemented from <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder.html#a45414544fc4c56b67c450efbbc6f61b8">mrpt::slam::CMetricMapBuilder</a>.</p> </div> </div> <a class="anchor" id="a1a496a075824bcdc1e7c98bf29e5fc2f"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderRBPF::drawCurrentEstimationToImage" ref="a1a496a075824bcdc1e7c98bf29e5fc2f" args="(utils::CCanvas *img)" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">void mrpt::slam::CMetricMapBuilderRBPF::drawCurrentEstimationToImage </td> <td>(</td> <td class="paramtype"><a class="el" href="classmrpt_1_1utils_1_1_c_canvas.html">utils::CCanvas</a> * </td> <td class="paramname"><em>img</em></td><td>)</td> <td></td> </tr> </table> </div> <div class="memdoc"> <p>A usefull method for debugging: draws the current map and path hypotheses to a CCanvas. </p> </div> </div> <a class="anchor" id="ac9982ebd2fcc745ecd760f4c982427a4"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderRBPF::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::CMetricMapBuilderRBPF::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="afa1332008ee35bcdef16dfd4c963e257"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderRBPF::getCurrentJointEntropy" ref="afa1332008ee35bcdef16dfd4c963e257" args="()" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">double mrpt::slam::CMetricMapBuilderRBPF::getCurrentJointEntropy </td> <td>(</td> <td class="paramname"></td><td>)</td> <td></td> </tr> </table> </div> <div class="memdoc"> </div> </div> <a class="anchor" id="af36b951c3429e49414e1231ad3edf35a"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderRBPF::getCurrentlyBuiltMap" ref="af36b951c3429e49414e1231ad3edf35a" args="(CSimpleMap &out_map) const " --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">void mrpt::slam::CMetricMapBuilderRBPF::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="a3588366ffb1147c23f57e1ae2cccec66"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderRBPF::getCurrentlyBuiltMapSize" ref="a3588366ffb1147c23f57e1ae2cccec66" args="()" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">unsigned int mrpt::slam::CMetricMapBuilderRBPF::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="a63b8438c1c0ae5308579847958e1384b"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderRBPF::getCurrentlyBuiltMetricMap" ref="a63b8438c1c0ae5308579847958e1384b" 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::CMetricMapBuilderRBPF::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="a4ab88acfd71654c293dc7d7193b07291"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderRBPF::getCurrentMostLikelyPath" ref="a4ab88acfd71654c293dc7d7193b07291" args="(std::deque< TPose3D > &outPath) const " --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">void mrpt::slam::CMetricMapBuilderRBPF::getCurrentMostLikelyPath </td> <td>(</td> <td class="paramtype"><a class="el" href="classstd_1_1deque.html">std::deque</a>< <a class="el" href="structmrpt_1_1math_1_1_t_pose3_d.html">TPose3D</a> > & </td> <td class="paramname"><em>outPath</em></td><td>)</td> <td> const</td> </tr> </table> </div> <div class="memdoc"> <p>Returns the current most-likely path estimation (the path associated to the most likely particle). </p> </div> </div> <a class="anchor" id="a93bf627a068b5b3ea299e8b729564edd"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderRBPF::getCurrentPoseEstimation" ref="a93bf627a068b5b3ea299e8b729564edd" 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::CMetricMapBuilderRBPF::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="a7e6cc1d4bdc90c2fd10e09aa0eca543b"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderRBPF::initialize" ref="a7e6cc1d4bdc90c2fd10e09aa0eca543b" args="(const CSimpleMap &initialMap=CSimpleMap(), CPosePDF *x0=NULL)" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">void mrpt::slam::CMetricMapBuilderRBPF::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>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::CMetricMapBuilderRBPF::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::CMetricMapBuilderRBPF::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::CMetricMapBuilderRBPF::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="a914dd7413e703c8c22093f340e6423ee"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderRBPF::processActionObservation" ref="a914dd7413e703c8c22093f340e6423ee" args="(CActionCollection &action, CSensoryFrame &observations)" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">void mrpt::slam::CMetricMapBuilderRBPF::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>observations</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 incremental 2D pose change in the robot pose. This value is deterministic. </td></tr> <tr><td class="paramname">observations</td><td>The set of observations that robot senses at the new pose. Statistics will be saved to statsLastIteration </td></tr> </table> </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="a244bdf1b8b839b572a8480082011cca4"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderRBPF::saveCurrentEstimationToImage" ref="a244bdf1b8b839b572a8480082011cca4" 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::CMetricMapBuilderRBPF::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::CMetricMapBuilderRBPF::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="ad6fe99ca086939ae20fda03e047f3092"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderRBPF::saveCurrentPathEstimationToTextFile" ref="ad6fe99ca086939ae20fda03e047f3092" args="(std::string fil)" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">void mrpt::slam::CMetricMapBuilderRBPF::saveCurrentPathEstimationToTextFile </td> <td>(</td> <td class="paramtype"><a class="el" href="classstd_1_1string.html">std::string</a> </td> <td class="paramname"><em>fil</em></td><td>)</td> <td></td> </tr> </table> </div> <div class="memdoc"> <p>A logging utility: saves the current path estimation for each particle in a text file (a row per particle, each 3-column-entry is a set [x,y,phi], respectively). </p> </div> </div> <hr/><h2>Member Data Documentation</h2> <a class="anchor" id="a2effa8714a43d5bdfd27b0e9fee09cb3"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderRBPF::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="a9ed28ff34b052e1a82cedc5fd70c3e6a"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderRBPF::currentMetricMapEstimation" ref="a9ed28ff34b052e1a82cedc5fd70c3e6a" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname"><a class="el" href="structmrpt_1_1utils_1_1non__copiable__ptr.html">non_copiable_ptr</a><<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_r_b_p_f.html#a9ed28ff34b052e1a82cedc5fd70c3e6a">mrpt::slam::CMetricMapBuilderRBPF::currentMetricMapEstimation</a><code> [protected]</code></td> </tr> </table> </div> <div class="memdoc"> <p>A buffer: memory is actually hold within "mapPDF". </p> <p>Definition at line <a class="el" href="_c_metric_map_builder_r_b_p_f_8h_source.html#l00091">91</a> of file <a class="el" href="_c_metric_map_builder_r_b_p_f_8h_source.html">CMetricMapBuilderRBPF.h</a>.</p> </div> </div> <a class="anchor" id="a6419d5c06cfe3b2d76b9a0d6f076d24f"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderRBPF::insertionAngDistance" ref="a6419d5c06cfe3b2d76b9a0d6f076d24f" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">float <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#a6419d5c06cfe3b2d76b9a0d6f076d24f">mrpt::slam::CMetricMapBuilderRBPF::insertionAngDistance</a><code> [protected]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Definition at line <a class="el" href="_c_metric_map_builder_r_b_p_f_8h_source.html#l00079">79</a> of file <a class="el" href="_c_metric_map_builder_r_b_p_f_8h_source.html">CMetricMapBuilderRBPF.h</a>.</p> </div> </div> <a class="anchor" id="ad0227fba9ff6b0e4b9ca491ed79b2f0e"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderRBPF::insertionLinDistance" ref="ad0227fba9ff6b0e4b9ca491ed79b2f0e" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">float <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#ad0227fba9ff6b0e4b9ca491ed79b2f0e">mrpt::slam::CMetricMapBuilderRBPF::insertionLinDistance</a><code> [protected]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Distances (linear and angular) for inserting a new observation into the map. </p> <p>Definition at line <a class="el" href="_c_metric_map_builder_r_b_p_f_8h_source.html#l00079">79</a> of file <a class="el" href="_c_metric_map_builder_r_b_p_f_8h_source.html">CMetricMapBuilderRBPF.h</a>.</p> </div> </div> <a class="anchor" id="a603c4090661af389ab52cc496965708e"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderRBPF::localizeAngDistance" ref="a603c4090661af389ab52cc496965708e" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">float <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#a603c4090661af389ab52cc496965708e">mrpt::slam::CMetricMapBuilderRBPF::localizeAngDistance</a><code> [protected]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Definition at line <a class="el" href="_c_metric_map_builder_r_b_p_f_8h_source.html#l00083">83</a> of file <a class="el" href="_c_metric_map_builder_r_b_p_f_8h_source.html">CMetricMapBuilderRBPF.h</a>.</p> </div> </div> <a class="anchor" id="ac23cc1def48847393932b55488103ac0"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderRBPF::localizeLinDistance" ref="ac23cc1def48847393932b55488103ac0" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname">float <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#ac23cc1def48847393932b55488103ac0">mrpt::slam::CMetricMapBuilderRBPF::localizeLinDistance</a><code> [protected]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Distances (linear and angular) for updating the robot pose estimate (and particles weighs, if applicable). </p> <p>Definition at line <a class="el" href="_c_metric_map_builder_r_b_p_f_8h_source.html#l00083">83</a> of file <a class="el" href="_c_metric_map_builder_r_b_p_f_8h_source.html">CMetricMapBuilderRBPF.h</a>.</p> </div> </div> <a class="anchor" id="a9653b9c2e9afe2de7cc619eda9323b3c"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderRBPF::m_PF_options" ref="a9653b9c2e9afe2de7cc619eda9323b3c" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname"><a class="el" href="structmrpt_1_1bayes_1_1_c_particle_filter_1_1_t_particle_filter_options.html">bayes::CParticleFilter::TParticleFilterOptions</a> <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#a9653b9c2e9afe2de7cc619eda9323b3c">mrpt::slam::CMetricMapBuilderRBPF::m_PF_options</a><code> [protected]</code></td> </tr> </table> </div> <div class="memdoc"> <p>The configuration of the particle filter: </p> <p>Definition at line <a class="el" href="_c_metric_map_builder_r_b_p_f_8h_source.html#l00075">75</a> of file <a class="el" href="_c_metric_map_builder_r_b_p_f_8h_source.html">CMetricMapBuilderRBPF.h</a>.</p> </div> </div> <a class="anchor" id="a7248f9700730c83e208f542f30899a3b"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderRBPF::m_statsLastIteration" ref="a7248f9700730c83e208f542f30899a3b" 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_r_b_p_f_1_1_t_stats.html">TStats</a> <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#a7248f9700730c83e208f542f30899a3b">mrpt::slam::CMetricMapBuilderRBPF::m_statsLastIteration</a></td> </tr> </table> </div> <div class="memdoc"> <p>This structure will hold stats after each execution of processActionObservation. </p> <p>Definition at line <a class="el" href="_c_metric_map_builder_r_b_p_f_8h_source.html#l00206">206</a> of file <a class="el" href="_c_metric_map_builder_r_b_p_f_8h_source.html">CMetricMapBuilderRBPF.h</a>.</p> </div> </div> <a class="anchor" id="a567e3937c2c51bb6c91c5f4370a2a9a9"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderRBPF::mapPDF" ref="a567e3937c2c51bb6c91c5f4370a2a9a9" 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_p_d_f.html">CMultiMetricMapPDF</a> <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#a567e3937c2c51bb6c91c5f4370a2a9a9">mrpt::slam::CMetricMapBuilderRBPF::mapPDF</a></td> </tr> </table> </div> <div class="memdoc"> <p>The map PDF: It includes a path and associated map for each particle. </p> <p>Definition at line <a class="el" href="_c_metric_map_builder_r_b_p_f_8h_source.html#l00070">70</a> of file <a class="el" href="_c_metric_map_builder_r_b_p_f_8h_source.html">CMetricMapBuilderRBPF.h</a>.</p> </div> </div> <a class="anchor" id="abdfcc141c475abd6ad54cf0b657c63b8"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderRBPF::odoIncrementSinceLastLocalization" ref="abdfcc141c475abd6ad54cf0b657c63b8" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname"><a class="el" href="classmrpt_1_1poses_1_1_c_pose3_d_p_d_f_gaussian.html">mrpt::poses::CPose3DPDFGaussian</a> <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#abdfcc141c475abd6ad54cf0b657c63b8">mrpt::slam::CMetricMapBuilderRBPF::odoIncrementSinceLastLocalization</a><code> [protected]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Traveled distance since last localization update. </p> <p>Definition at line <a class="el" href="_c_metric_map_builder_r_b_p_f_8h_source.html#l00086">86</a> of file <a class="el" href="_c_metric_map_builder_r_b_p_f_8h_source.html">CMetricMapBuilderRBPF.h</a>.</p> </div> </div> <a class="anchor" id="aad453e506dc2700b5c1d7ba9e652c39a"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderRBPF::odoIncrementSinceLastMapUpdate" ref="aad453e506dc2700b5c1d7ba9e652c39a" args="" --> <div class="memitem"> <div class="memproto"> <table class="memname"> <tr> <td class="memname"><a class="el" href="classmrpt_1_1poses_1_1_c_pose3_d.html">mrpt::poses::CPose3D</a> <a class="el" href="classmrpt_1_1slam_1_1_c_metric_map_builder_r_b_p_f.html#aad453e506dc2700b5c1d7ba9e652c39a">mrpt::slam::CMetricMapBuilderRBPF::odoIncrementSinceLastMapUpdate</a><code> [protected]</code></td> </tr> </table> </div> <div class="memdoc"> <p>Traveled distance since last map update. </p> <p>Definition at line <a class="el" href="_c_metric_map_builder_r_b_p_f_8h_source.html#l00087">87</a> of file <a class="el" href="_c_metric_map_builder_r_b_p_f_8h_source.html">CMetricMapBuilderRBPF.h</a>.</p> </div> </div> <a class="anchor" id="a8db543d082103e5300415d4139d9255a"></a><!-- doxytag: member="mrpt::slam::CMetricMapBuilderRBPF::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> </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>