<!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>CPRRTNavigator.h Source File</title> <link href="doxygen.css" rel="stylesheet" type="text/css"> <link href="tabs.css" rel="stylesheet" type="text/css"> </head><body> <div align="left"><a href="http://www.mrpt.org/">Main MRPT website</a> > <b>C++ reference</b> </div> <div align="right"> <a href="index.html"><img border="0" src="mrpt_logo.png" alt="MRPT logo"></a> </div> <!-- Generated by Doxygen 1.7.5 --> <script type="text/javascript"> var searchBox = new SearchBox("searchBox", "search",false,'Search'); </script> <div id="navrow1" class="tabs"> <ul class="tablist"> <li><a href="index.html"><span>Main Page</span></a></li> <li><a href="pages.html"><span>Related Pages</span></a></li> <li><a href="modules.html"><span>Modules</span></a></li> <li><a href="namespaces.html"><span>Namespaces</span></a></li> <li><a href="annotated.html"><span>Classes</span></a></li> <li class="current"><a href="files.html"><span>Files</span></a></li> <li> <div id="MSearchBox" class="MSearchBoxInactive"> <div class="left"> <form id="FSearchBox" action="search.php" method="get"> <img id="MSearchSelect" src="search/mag.png" alt=""/> <input type="text" id="MSearchField" name="query" value="Search" size="20" accesskey="S" onfocus="searchBox.OnSearchFieldFocus(true)" onblur="searchBox.OnSearchFieldFocus(false)"/> </form> </div><div class="right"></div> </div> </li> </ul> </div> <div id="navrow2" class="tabs2"> <ul class="tablist"> <li><a href="files.html"><span>File List</span></a></li> <li><a href="globals.html"><span>File Members</span></a></li> </ul> </div> <div class="header"> <div class="headertitle"> <div class="title">CPRRTNavigator.h</div> </div> </div> <div class="contents"> <a href="_c_p_r_r_t_navigator_8h.html">Go to the documentation of this file.</a><div class="fragment"><pre class="fragment"><a name="l00001"></a>00001 <span class="comment">/* +---------------------------------------------------------------------------+</span> <a name="l00002"></a>00002 <span class="comment"> | The Mobile Robot Programming Toolkit (MRPT) C++ library |</span> <a name="l00003"></a>00003 <span class="comment"> | |</span> <a name="l00004"></a>00004 <span class="comment"> | http://www.mrpt.org/ |</span> <a name="l00005"></a>00005 <span class="comment"> | |</span> <a name="l00006"></a>00006 <span class="comment"> | Copyright (C) 2005-2011 University of Malaga |</span> <a name="l00007"></a>00007 <span class="comment"> | |</span> <a name="l00008"></a>00008 <span class="comment"> | This software was written by the Machine Perception and Intelligent |</span> <a name="l00009"></a>00009 <span class="comment"> | Robotics Lab, University of Malaga (Spain). |</span> <a name="l00010"></a>00010 <span class="comment"> | Contact: Jose-Luis Blanco <jlblanco@ctima.uma.es> |</span> <a name="l00011"></a>00011 <span class="comment"> | |</span> <a name="l00012"></a>00012 <span class="comment"> | This file is part of the MRPT project. |</span> <a name="l00013"></a>00013 <span class="comment"> | |</span> <a name="l00014"></a>00014 <span class="comment"> | MRPT is free software: you can redistribute it and/or modify |</span> <a name="l00015"></a>00015 <span class="comment"> | it under the terms of the GNU General Public License as published by |</span> <a name="l00016"></a>00016 <span class="comment"> | the Free Software Foundation, either version 3 of the License, or |</span> <a name="l00017"></a>00017 <span class="comment"> | (at your option) any later version. |</span> <a name="l00018"></a>00018 <span class="comment"> | |</span> <a name="l00019"></a>00019 <span class="comment"> | MRPT is distributed in the hope that it will be useful, |</span> <a name="l00020"></a>00020 <span class="comment"> | but WITHOUT ANY WARRANTY; without even the implied warranty of |</span> <a name="l00021"></a>00021 <span class="comment"> | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the |</span> <a name="l00022"></a>00022 <span class="comment"> | GNU General Public License for more details. |</span> <a name="l00023"></a>00023 <span class="comment"> | |</span> <a name="l00024"></a>00024 <span class="comment"> | You should have received a copy of the GNU General Public License |</span> <a name="l00025"></a>00025 <span class="comment"> | along with MRPT. If not, see <http://www.gnu.org/licenses/>. |</span> <a name="l00026"></a>00026 <span class="comment"> | |</span> <a name="l00027"></a>00027 <span class="comment"> +---------------------------------------------------------------------------+ */</span> <a name="l00028"></a>00028 <span class="preprocessor">#ifndef CPRRTNavigator_H</span> <a name="l00029"></a>00029 <span class="preprocessor"></span><span class="preprocessor">#define CPRRTNavigator_H</span> <a name="l00030"></a>00030 <span class="preprocessor"></span> <a name="l00031"></a>00031 <span class="preprocessor">#include <<a class="code" href="maps_8h.html">mrpt/maps.h</a>></span> <a name="l00032"></a>00032 <span class="preprocessor">#include <<a class="code" href="poses_8h.html">mrpt/poses.h</a>></span> <a name="l00033"></a>00033 <span class="preprocessor">#include <<a class="code" href="synch_8h.html">mrpt/synch.h</a>></span> <a name="l00034"></a>00034 <span class="preprocessor">#include <<a class="code" href="threads_8h.html">mrpt/system/threads.h</a>></span> <a name="l00035"></a>00035 <span class="preprocessor">#include <<a class="code" href="_c_parameterized_trajectory_generator_8h.html">mrpt/reactivenav/CParameterizedTrajectoryGenerator.h</a>></span> <a name="l00036"></a>00036 <a name="l00037"></a>00037 <span class="preprocessor">#include <<a class="code" href="reactivenav_2include_2mrpt_2reactivenav_2link__pragmas_8h.html">mrpt/reactivenav/link_pragmas.h</a>></span> <a name="l00038"></a>00038 <a name="l00039"></a>00039 <span class="keyword">namespace </span>mrpt <a name="l00040"></a>00040 { <a name="l00041"></a>00041 <span class="keyword">namespace </span>reactivenav <a name="l00042"></a>00042 { <a name="l00043"></a>00043 <span class="keyword">using namespace </span>mrpt; <a name="l00044"></a>00044 <span class="keyword">using namespace </span>mrpt::slam; <a name="l00045"></a>00045 <span class="keyword">using namespace </span>mrpt::math; <a name="l00046"></a>00046 <span class="keyword">using namespace </span>mrpt::synch; <a name="l00047"></a>00047 <span class="keyword">using namespace </span>mrpt::poses; <a name="l00048"></a>00048 <span class="comment"></span> <a name="l00049"></a>00049 <span class="comment"> /** This class is a multi-threaded mobile robot navigator, implementing an (anytime) PTG-based Rapidly-exploring Random Tree (PRRT) search algorithm.</span> <a name="l00050"></a>00050 <span class="comment"> *</span> <a name="l00051"></a>00051 <span class="comment"> * <b>Usage:</b><br></span> <a name="l00052"></a>00052 <span class="comment"> * - Create an instance of the CPRRTNavigator class (an object on the heap, i.e. no 'new', is preferred, but just for the convenience of the user).</span> <a name="l00053"></a>00053 <span class="comment"> * - Set all the parameters in CPRRTNavigator::params</span> <a name="l00054"></a>00054 <span class="comment"> * - Call CPRRTNavigator::initialize. If all the params are OK, true is returned and you can go on.</span> <a name="l00055"></a>00055 <span class="comment"> * - Start a navigation by calling CPRRTNavigator::navigate.</span> <a name="l00056"></a>00056 <span class="comment"> * - From your application, you must update all the sensory data (from the real robot or a simulator) on a timely-fashion. The navigator will stop the robot if the last sensory data is too old.</span> <a name="l00057"></a>00057 <span class="comment"> *</span> <a name="l00058"></a>00058 <span class="comment"> * Note that all the public methods are thread-safe.</span> <a name="l00059"></a>00059 <span class="comment"> *</span> <a name="l00060"></a>00060 <span class="comment"> * <b>About the algorithm:</b><br></span> <a name="l00061"></a>00061 <span class="comment"> *</span> <a name="l00062"></a>00062 <span class="comment"> *</span> <a name="l00063"></a>00063 <span class="comment"> *</span> <a name="l00064"></a>00064 <span class="comment"> *</span> <a name="l00065"></a>00065 <span class="comment"> *</span> <a name="l00066"></a>00066 <span class="comment"> * <b>Changes history</b></span> <a name="l00067"></a>00067 <span class="comment"> * - 05/JUL/2009: Creation (JLBC). This is an evolution from leassons learnt from the pure reactive navigator based on PTGs.</span> <a name="l00068"></a>00068 <span class="comment"> * \ingroup mrpt_reactivenav_grp</span> <a name="l00069"></a>00069 <span class="comment"> */</span> <a name="l00070"></a>00070 <span class="keyword">class </span><a class="code" href="reactivenav_2include_2mrpt_2reactivenav_2link__pragmas_8h.html#aa2168e902b4c1dd548d6129461f0c519">REACTIVENAV_IMPEXP</a> CPRRTNavigator <a name="l00071"></a>00071 { <a name="l00072"></a>00072 <span class="keyword">public</span>: <a name="l00073"></a>00073 <a class="code" href="_core.html">EIGEN_MAKE_ALIGNED_OPERATOR_NEW</a> <a name="l00074"></a>00074 <a name="l00075"></a>00075 <span class="keyword">public</span>: <a name="l00076"></a>00076 CPRRTNavigator(); <span class="comment">//!< Constructor</span> <a name="l00077"></a>00077 <span class="comment"></span> <span class="keyword">virtual</span> ~CPRRTNavigator(); <span class="comment">//!< Destructor</span> <a name="l00078"></a>00078 <span class="comment"></span><span class="comment"></span> <a name="l00079"></a>00079 <span class="comment"> /** @name Navigation control methods</span> <a name="l00080"></a>00080 <span class="comment"> @{*/</span><span class="comment"></span> <a name="l00081"></a>00081 <span class="comment"> /** Initialize the navigator using the parameters in "params"; read the usage instructions in CPRRTNavigator.</span> <a name="l00082"></a>00082 <span class="comment"> * This method should be called only once at the beginning of the robot operation.</span> <a name="l00083"></a>00083 <span class="comment"> * \return true on sucess, false on any error preparing the navigator (and no navigation command will be processed until that's fixed).</span> <a name="l00084"></a>00084 <span class="comment"> */</span> <a name="l00085"></a>00085 <span class="keywordtype">bool</span> initialize(); <a name="l00086"></a>00086 <span class="comment"></span> <a name="l00087"></a>00087 <span class="comment"> /** Starts a navigation to a 2D pose (including a desired heading at the target).</span> <a name="l00088"></a>00088 <span class="comment"> * \note CPRRTNavigator::initialize must be called first.</span> <a name="l00089"></a>00089 <span class="comment"> */</span> <a name="l00090"></a>00090 <span class="keywordtype">void</span> navigate( <span class="keyword">const</span> <a class="code" href="structmrpt_1_1math_1_1_t_pose2_d.html" title="Lightweight 2D pose.">mrpt::math::TPose2D</a> &target_pose); <a name="l00091"></a>00091 <span class="comment"></span> <a name="l00092"></a>00092 <span class="comment"> /** Starts a navigation to a given 2D point (any heading at the target).</span> <a name="l00093"></a>00093 <span class="comment"> * \note CPRRTNavigator::initialize must be called first.</span> <a name="l00094"></a>00094 <span class="comment"> */</span> <a name="l00095"></a>00095 <span class="keywordtype">void</span> navigate( <span class="keyword">const</span> <a class="code" href="structmrpt_1_1math_1_1_t_point2_d.html" title="Lightweight 2D point.">mrpt::math::TPoint2D</a> &target_point); <a name="l00096"></a>00096 <span class="comment"></span> <a name="l00097"></a>00097 <span class="comment"> /** Cancel current navegacion.</span> <a name="l00098"></a>00098 <span class="comment"> * \note CPRRTNavigator::initialize must be called first.</span> <a name="l00099"></a>00099 <span class="comment"> */</span> <a name="l00100"></a>00100 <span class="keywordtype">void</span> cancel(); <a name="l00101"></a>00101 <span class="comment"></span> <a name="l00102"></a>00102 <span class="comment"> /** Continues with suspended navigation.</span> <a name="l00103"></a>00103 <span class="comment"> * \sa suspend</span> <a name="l00104"></a>00104 <span class="comment"> * \note CPRRTNavigator::initialize must be called first.</span> <a name="l00105"></a>00105 <span class="comment"> */</span> <a name="l00106"></a>00106 <span class="keywordtype">void</span> resume(); <a name="l00107"></a>00107 <span class="comment"></span> <a name="l00108"></a>00108 <span class="comment"> /** Suspend current navegation</span> <a name="l00109"></a>00109 <span class="comment"> * \sa resume</span> <a name="l00110"></a>00110 <span class="comment"> * \note CPRRTNavigator::initialize must be called first.</span> <a name="l00111"></a>00111 <span class="comment"> */</span> <a name="l00112"></a>00112 <span class="keywordtype">void</span> suspend(); <a name="l00113"></a>00113 <span class="comment"></span> <a name="l00114"></a>00114 <span class="comment"> /** @} */</span> <a name="l00115"></a>00115 <span class="comment"></span> <a name="l00116"></a>00116 <span class="comment"> /** @name Navigator data structures</span> <a name="l00117"></a>00117 <span class="comment"> @{*/</span><span class="comment"></span> <a name="l00118"></a>00118 <span class="comment"> /** Each data point in m_planned_path */</span> <a name="l00119"></a>00119 <span class="keyword">struct </span><a class="code" href="reactivenav_2include_2mrpt_2reactivenav_2link__pragmas_8h.html#aa2168e902b4c1dd548d6129461f0c519">REACTIVENAV_IMPEXP</a> TPathData <a name="l00120"></a>00120 { <a name="l00121"></a><a class="code" href="structmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_path_data.html#a21976fa8e92cbeb7f0c0879560ac31c8">00121</a> <a class="code" href="structmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_path_data.html" title="Each data point in m_planned_path.">TPathData</a>() : <a name="l00122"></a>00122 p(0,0,0), <a name="l00123"></a>00123 max_v(0.1),max_w(0.2), <a name="l00124"></a>00124 trg_v(0.1) <a name="l00125"></a>00125 {} <a name="l00126"></a>00126 <a name="l00127"></a><a class="code" href="structmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_path_data.html#a94b10f69f7343b1ab2b36b76f17fb204">00127</a> <a class="code" href="structmrpt_1_1math_1_1_t_pose2_d.html" title="Lightweight 2D pose.">TPose2D</a> <a class="code" href="structmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_path_data.html#a94b10f69f7343b1ab2b36b76f17fb204" title="Coordinates are "global".">p</a>; <span class="comment">//!< Coordinates are "global"</span> <a name="l00128"></a><a class="code" href="structmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_path_data.html#a55bd84dc0f321799f32ed7cf5b183551">00128</a> <span class="comment"></span> <span class="keywordtype">double</span> max_v, <a class="code" href="structmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_path_data.html#a55bd84dc0f321799f32ed7cf5b183551" title="Maximum velocities along this path segment.">max_w</a>; <span class="comment">//!< Maximum velocities along this path segment.</span> <a name="l00129"></a><a class="code" href="structmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_path_data.html#a2deae07c8003076b74b38e5436231896">00129</a> <span class="comment"></span> <span class="keywordtype">double</span> <a class="code" href="structmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_path_data.html#a2deae07c8003076b74b38e5436231896" title="Desired linear velocity at the target point, ie: the robot should program its velocities such as afte...">trg_v</a>; <span class="comment">//!< Desired linear velocity at the target point, ie: the robot should program its velocities such as after this arc the speeds are the given ones.</span> <a name="l00130"></a>00130 <span class="comment"></span> }; <a name="l00131"></a>00131 <a name="l00132"></a><a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#ac4759f9afdeaf6613fb5fec336938374">00132</a> <span class="keyword">typedef</span> std<a class="code" href="classstd_1_1list.html">::list<TPathData></a> <a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#ac4759f9afdeaf6613fb5fec336938374" title="An ordered list of path poses.">TPlannedPath</a>; <span class="comment">//!< An ordered list of path poses.</span> <a name="l00133"></a>00133 <span class="comment"></span> <a name="l00134"></a>00134 <span class="keyword">class </span><a class="code" href="reactivenav_2include_2mrpt_2reactivenav_2link__pragmas_8h.html#aa2168e902b4c1dd548d6129461f0c519">REACTIVENAV_IMPEXP</a> <a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_options.html">TOptions</a> : <span class="keyword">public</span> mrpt::utils::<a class="code" href="classmrpt_1_1utils_1_1_c_loadable_options.html" title="This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...">CLoadableOptions</a> <a name="l00135"></a>00135 { <a name="l00136"></a>00136 <span class="keyword">public</span>: <a name="l00137"></a>00137 <a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_options.html">TOptions</a>(); <span class="comment">//!< Initial values</span> <a name="l00138"></a>00138 <span class="comment"></span><span class="comment"></span> <a name="l00139"></a>00139 <span class="comment"> /** This method load the options from a ".ini"-like file or memory-stored string list.</span> <a name="l00140"></a>00140 <span class="comment"> */</span> <a name="l00141"></a>00141 <span class="keywordtype">void</span> loadFromConfigFile( <a name="l00142"></a>00142 <span class="keyword">const</span> <a class="code" href="classmrpt_1_1utils_1_1_c_config_file_base.html" title="This class allows loading and storing values and vectors of different types from a configuration text...">mrpt::utils::CConfigFileBase</a> &source, <a name="l00143"></a>00143 <span class="keyword">const</span> <a class="code" href="classstd_1_1string.html" title="STL class.">std::string</a> &section); <a name="l00144"></a>00144 <span class="comment"></span> <a name="l00145"></a>00145 <span class="comment"> /** This method displays clearly all the contents of the structure in textual form, sending it to a CStream. */</span> <a name="l00146"></a>00146 <span class="keywordtype">void</span> dumpToTextStream( <a class="code" href="classmrpt_1_1utils_1_1_c_stream.html" title="This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...">CStream</a> &out) <span class="keyword">const</span>; <a name="l00147"></a>00147 <a name="l00148"></a>00148 <span class="comment">// Data:</span> <a name="l00149"></a><a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_options.html#ae4968a725d3dabdb6c78a9746f74b54a">00149</a> <span class="keywordtype">double</span> <a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_options.html#ae4968a725d3dabdb6c78a9746f74b54a" title="Max linear speed (m/s)">absolute_max_v</a>; <span class="comment">//!< Max linear speed (m/s)</span> <a name="l00150"></a><a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_options.html#a305e60ad23cd69d196f118086340339c">00150</a> <span class="comment"></span> <span class="keywordtype">double</span> <a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_options.html#a305e60ad23cd69d196f118086340339c" title="Max angular speed (rad/s)">absolute_max_w</a>; <span class="comment">//!< Max angular speed (rad/s)</span> <a name="l00151"></a><a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_options.html#a6a0aa231f97407a7852f73802050a1f4">00151</a> <span class="comment"></span> <span class="keywordtype">double</span> <a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_options.html#a6a0aa231f97407a7852f73802050a1f4" title="Max desired linear speed acceleration (m/s^2)">max_accel_v</a>; <span class="comment">//!< Max desired linear speed acceleration (m/s^2)</span> <a name="l00152"></a><a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_options.html#a7a203f2588d120a978e164b5853f38ab">00152</a> <span class="comment"></span> <span class="keywordtype">double</span> <a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_options.html#a7a203f2588d120a978e164b5853f38ab" title="Max desired angular speed acceleration (rad/s^2)">max_accel_w</a>; <span class="comment">//!< Max desired angular speed acceleration (rad/s^2)</span> <a name="l00153"></a>00153 <span class="comment"></span> <a name="l00154"></a><a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_options.html#a054c61e3078d0de535b6c591f05d5b68">00154</a> <span class="keywordtype">double</span> <a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_options.html#a054c61e3078d0de535b6c591f05d5b68" title="Max age (in seconds) for an observation to be considered invalid for navigation purposes.">max_age_observations</a>; <span class="comment">//!< Max age (in seconds) for an observation to be considered invalid for navigation purposes.</span> <a name="l00155"></a>00155 <span class="comment"></span><span class="comment"></span> <a name="l00156"></a>00156 <span class="comment"> /** The robot shape used when computing collisions; it's loaded from the</span> <a name="l00157"></a>00157 <span class="comment"> * config file/text as a single 2xN matrix in MATLAB format, first row are Xs, second are Ys, e.g:</span> <a name="l00158"></a>00158 <span class="comment"> * \code</span> <a name="l00159"></a>00159 <span class="comment"> * robot_shape = [-0.2 0.2 0.2 -0.2; -0.1 -0.1 0.1 0.1]</span> <a name="l00160"></a>00160 <span class="comment"> * \endcode</span> <a name="l00161"></a>00161 <span class="comment"> */</span> <a name="l00162"></a><a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_options.html#a111b132e1025966ce582633c92f70b7b">00162</a> <a class="code" href="classmrpt_1_1math_1_1_t_polygon2_d.html" title="2D polygon, inheriting from std::vector<TPoint2D>.">TPolygon2D</a> <a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_options.html#a111b132e1025966ce582633c92f70b7b" title="The robot shape used when computing collisions; it's loaded from the config file/text as a single 2xN...">robot_shape</a>; <a name="l00163"></a>00163 <a name="l00164"></a>00164 <span class="keyword">struct </span><a class="code" href="reactivenav_2include_2mrpt_2reactivenav_2link__pragmas_8h.html#aa2168e902b4c1dd548d6129461f0c519">REACTIVENAV_IMPEXP</a> <a class="code" href="structmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_options_1_1_t_path_tracking_opts.html">TPathTrackingOpts</a> <a name="l00165"></a>00165 { <a name="l00166"></a><a class="code" href="structmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_options_1_1_t_path_tracking_opts.html#a5a80e50a38b9b5dd28169ec795e4fd4f">00166</a> <span class="keywordtype">double</span> <a class="code" href="structmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_options_1_1_t_path_tracking_opts.html#a5a80e50a38b9b5dd28169ec795e4fd4f" title="Radius of each checkpoint in the path, ie: when the robot get closer than this distance, the point is considered as visited and the next one is processed.">radius_checkpoints</a>; <span class="comment">//!< Radius of each checkpoint in the path, ie: when the robot get closer than this distance, the point is considered as visited and the next one is processed.</span> <a name="l00167"></a>00167 <span class="comment"></span> }; <a name="l00168"></a><a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_options.html#a9b06f9fd16d802063953b73cc1fb50ca">00168</a> <a class="code" href="structmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_options_1_1_t_path_tracking_opts.html">TPathTrackingOpts</a> <a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_options.html#a9b06f9fd16d802063953b73cc1fb50ca">pathtrack</a>; <a name="l00169"></a>00169 <a name="l00170"></a>00170 <span class="keyword">struct </span><a class="code" href="reactivenav_2include_2mrpt_2reactivenav_2link__pragmas_8h.html#aa2168e902b4c1dd548d6129461f0c519">REACTIVENAV_IMPEXP</a> <a class="code" href="structmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_options_1_1_t_planner_opts.html">TPlannerOpts</a> <a name="l00171"></a>00171 { <a name="l00172"></a><a class="code" href="structmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_options_1_1_t_planner_opts.html#ae747fd5c4ffcb3823e744a37a6a8f978">00172</a> <span class="keywordtype">double</span> <a class="code" href="structmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_options_1_1_t_planner_opts.html#ae747fd5c4ffcb3823e744a37a6a8f978" title="Maximum time to spend when planning, in seconds.">max_time_expend_planning</a>; <span class="comment">//!< Maximum time to spend when planning, in seconds.</span> <a name="l00173"></a>00173 <span class="comment"></span> }; <a name="l00174"></a><a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_options.html#a17ddcc95c294c4db16eaa96c8d24147f">00174</a> <a class="code" href="structmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_options_1_1_t_planner_opts.html">TPlannerOpts</a> <a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_options.html#a17ddcc95c294c4db16eaa96c8d24147f">planner</a>; <a name="l00175"></a>00175 <a name="l00176"></a>00176 }; <a name="l00177"></a>00177 <a name="l00178"></a><a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#aae065073b31838516e694308f926acfc">00178</a> <a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator_1_1_t_options.html">TOptions</a> <a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#aae065073b31838516e694308f926acfc" title="Change here all the parameters of the navigator.">params</a>; <span class="comment">//!< Change here all the parameters of the navigator.</span> <a name="l00179"></a>00179 <span class="comment"></span><span class="comment"></span> <a name="l00180"></a>00180 <span class="comment"> /** @} */</span> <a name="l00181"></a>00181 <span class="comment"></span> <a name="l00182"></a>00182 <span class="comment"> /** @name Debug and logging</span> <a name="l00183"></a>00183 <span class="comment"> @{*/</span><span class="comment"></span> <a name="l00184"></a>00184 <span class="comment"> /** Manually sets the short-time path to be followed by the robot (use 'navigate' instead, this method is for debugging mainly)</span> <a name="l00185"></a>00185 <span class="comment"> */</span> <a name="l00186"></a>00186 <span class="keywordtype">void</span> setPathToFollow(<span class="keyword">const</span> <a class="code" href="classstd_1_1list.html">TPlannedPath</a> &path ); <a name="l00187"></a>00187 <span class="comment"></span> <a name="l00188"></a>00188 <span class="comment"> /** Returns the current planned path the robot is following */</span> <a name="l00189"></a>00189 <span class="keywordtype">void</span> getCurrentPlannedPath(<a class="code" href="classstd_1_1list.html">TPlannedPath</a> &path ) <span class="keyword">const</span>; <a name="l00190"></a>00190 <a name="l00191"></a>00191 <span class="comment"></span> <a name="l00192"></a>00192 <span class="comment"> /** @} */</span> <a name="l00193"></a>00193 <a name="l00194"></a>00194 <span class="comment"></span> <a name="l00195"></a>00195 <span class="comment"> /** @name Sensory data methods: call them to update the navigator knowledge on the outside world.</span> <a name="l00196"></a>00196 <span class="comment"> @{*/</span><span class="comment"></span> <a name="l00197"></a>00197 <span class="comment"> /** Updates the navigator with a low or high-rate estimate from a localization (or SLAM) algorithm running somewhere else.</span> <a name="l00198"></a>00198 <span class="comment"> * \param new_robot_pose The (global) coordinates of the mean robot pose as estimated by some external module.</span> <a name="l00199"></a>00199 <span class="comment"> * \param new_robot_cov The 3x3 covariance matrix of that estimate.</span> <a name="l00200"></a>00200 <span class="comment"> * \param timestamp The associated timestamp of the data.</span> <a name="l00201"></a>00201 <span class="comment"> */</span> <a name="l00202"></a>00202 <span class="keywordtype">void</span> processNewLocalization(<span class="keyword">const</span> <a class="code" href="structmrpt_1_1math_1_1_t_pose2_d.html" title="Lightweight 2D pose.">TPose2D</a> &new_robot_pose, <span class="keyword">const</span> <a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html">CMatrixDouble33</a> &new_robot_cov, <a class="code" href="group__time__date.html#ga42674286d8d56afea013b6329bb7327a" title="A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...">TTimeStamp</a> timestamp ); <a name="l00203"></a>00203 <span class="comment"></span> <a name="l00204"></a>00204 <span class="comment"> /** Updates the navigator with high-rate odometry from the mobile base.</span> <a name="l00205"></a>00205 <span class="comment"> * The odometry poses are dealed internally as increments only, so there is no problem is</span> <a name="l00206"></a>00206 <span class="comment"> * arbitrary mismatches between localization (from a particle filter or SLAM) and the odometry.</span> <a name="l00207"></a>00207 <span class="comment"> * \param newOdoPose The global, cummulative odometry as computed by the robot.</span> <a name="l00208"></a>00208 <span class="comment"> * \param timestamp The associated timestamp of the measurement.</span> <a name="l00209"></a>00209 <span class="comment"> * \param hasVelocities If false, the next arguments are ignored.</span> <a name="l00210"></a>00210 <span class="comment"> * \param v Measured linear speed, in m/s.</span> <a name="l00211"></a>00211 <span class="comment"> * \param w Measured angular speed, in rad/s.</span> <a name="l00212"></a>00212 <span class="comment"> */</span> <a name="l00213"></a>00213 <span class="keywordtype">void</span> processNewOdometryInfo( <span class="keyword">const</span> <a class="code" href="structmrpt_1_1math_1_1_t_pose2_d.html" title="Lightweight 2D pose.">TPose2D</a> &newOdoPose, <a class="code" href="group__time__date.html#ga42674286d8d56afea013b6329bb7327a" title="A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...">TTimeStamp</a> timestamp, <span class="keywordtype">bool</span> hasVelocities =<span class="keyword">false</span>, <span class="keywordtype">float</span> v =0, <span class="keywordtype">float</span> w=0 ); <a name="l00214"></a>00214 <span class="comment"></span> <a name="l00215"></a>00215 <span class="comment"> /** Must be called in a timely fashion to let the navigator know about the obstacles in the environment.</span> <a name="l00216"></a>00216 <span class="comment"> * \param obstacles</span> <a name="l00217"></a>00217 <span class="comment"> * \param timestamp The associated timestamp of the sensed points.</span> <a name="l00218"></a>00218 <span class="comment"> */</span> <a name="l00219"></a>00219 <span class="keywordtype">void</span> processNewObstaclesData(<span class="keyword">const</span> <a class="code" href="classmrpt_1_1slam_1_1_c_points_map.html" title="A cloud of points in 2D or 3D, which can be built from a sequence of laser scans or other sensors...">mrpt::slam::CPointsMap</a>* obstacles, <a class="code" href="group__time__date.html#ga42674286d8d56afea013b6329bb7327a" title="A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...">TTimeStamp</a> timestamp ); <a name="l00220"></a>00220 <span class="comment"></span> <a name="l00221"></a>00221 <span class="comment"> /** @} */</span> <a name="l00222"></a>00222 <span class="comment"></span> <a name="l00223"></a>00223 <span class="comment"> /** @name Virtual methods to be implemented by the user.</span> <a name="l00224"></a>00224 <span class="comment"> @{*/</span><span class="comment"></span> <a name="l00225"></a>00225 <span class="comment"> /** This is the most important method the user must provide: to send an instantaneous velocity command to the robot.</span> <a name="l00226"></a>00226 <span class="comment"> * \param v Desired linear speed, in meters/second.</span> <a name="l00227"></a>00227 <span class="comment"> * \param w Desired angular speed, in rads/second.</span> <a name="l00228"></a>00228 <span class="comment"> * \return false on any error. In that case, the navigator will immediately stop the navigation and announce the error.</span> <a name="l00229"></a>00229 <span class="comment"> */</span> <a name="l00230"></a>00230 <span class="keyword">virtual</span> <span class="keywordtype">bool</span> onMotionCommand(<span class="keywordtype">float</span> v, <span class="keywordtype">float</span> w ) = 0; <a name="l00231"></a>00231 <span class="comment"></span> <a name="l00232"></a>00232 <span class="comment"> /** Re-implement this method if you want to know when a new navigation has started.</span> <a name="l00233"></a>00233 <span class="comment"> */</span> <a name="l00234"></a><a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#aa582e40ef55ad4a83687f380b1ebb28e">00234</a> <span class="keyword">virtual</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#aa582e40ef55ad4a83687f380b1ebb28e" title="Re-implement this method if you want to know when a new navigation has started.">onNavigationStart</a>( ) { } <a name="l00235"></a>00235 <span class="comment"></span> <a name="l00236"></a>00236 <span class="comment"> /** Re-implement this method if you want to know when and why a navigation has ended.</span> <a name="l00237"></a>00237 <span class="comment"> * \param targetReachedOK Will be false if the navigation failed.</span> <a name="l00238"></a>00238 <span class="comment"> */</span> <a name="l00239"></a><a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#a918557efcb18f959d2f5f2fe81587f63">00239</a> <span class="keyword">virtual</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#a918557efcb18f959d2f5f2fe81587f63" title="Re-implement this method if you want to know when and why a navigation has ended.">onNavigationEnd</a>( <span class="keywordtype">bool</span> targetReachedOK ) { } <a name="l00240"></a>00240 <span class="comment"></span> <a name="l00241"></a>00241 <span class="comment"> /** Re-implement this method if you want to know when the robot is approaching the target:</span> <a name="l00242"></a>00242 <span class="comment"> * this event is raised before onNavigationEnd, when the robot is closer than a certain distance to the target.</span> <a name="l00243"></a>00243 <span class="comment"> */</span> <a name="l00244"></a><a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#ab4a3c677d4f39f7579b21be27fc503b7">00244</a> <span class="keyword">virtual</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#ab4a3c677d4f39f7579b21be27fc503b7" title="Re-implement this method if you want to know when the robot is approaching the target: this event is ...">onApproachingTarget</a>( ) { } <a name="l00245"></a>00245 <span class="comment"></span> <a name="l00246"></a>00246 <span class="comment"> /** @} */</span> <a name="l00247"></a>00247 <a name="l00248"></a><a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#ad4ea80185f3a227c729cf83da3f6489b">00248</a> <span class="keyword">static</span> <span class="keyword">const</span> <span class="keywordtype">double</span> <a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#ad4ea80185f3a227c729cf83da3f6489b" title="Used to refer to undefined or "never mind" headings values.">INVALID_HEADING</a>; <span class="comment">//!< Used to refer to undefined or "never mind" headings values.</span> <a name="l00249"></a>00249 <span class="comment"></span> <a name="l00250"></a>00250 <span class="keyword">private</span>: <a name="l00251"></a>00251 <span class="comment">// ----------- Internal methods & threads -----------</span> <a name="l00252"></a>00252 <a name="l00253"></a><a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#a9f6dc216a23ce62bb3447218a7ad10f9">00253</a> <a class="code" href="structmrpt_1_1system_1_1_t_thread_handle.html" title="This structure contains the information needed to interface the threads API on each platform:...">TThreadHandle</a> <a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#a9f6dc216a23ce62bb3447218a7ad10f9" title="Thread handle.">m_thr_planner</a>; <span class="comment">//!< Thread handle</span> <a name="l00254"></a><a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#a65e8aab888ceadf7326e5c146e3bdc36">00254</a> <span class="comment"></span> <a class="code" href="structmrpt_1_1system_1_1_t_thread_handle.html" title="This structure contains the information needed to interface the threads API on each platform:...">TThreadHandle</a> <a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#a65e8aab888ceadf7326e5c146e3bdc36" title="Thread handle.">m_thr_testcol</a>; <span class="comment">//!< Thread handle</span> <a name="l00255"></a><a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#af8274ad039e262eecefbb20810af7e79">00255</a> <span class="comment"></span> <a class="code" href="structmrpt_1_1system_1_1_t_thread_handle.html" title="This structure contains the information needed to interface the threads API on each platform:...">TThreadHandle</a> <a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#af8274ad039e262eecefbb20810af7e79" title="Thread handle.">m_thr_pathtrack</a>; <span class="comment">//!< Thread handle</span> <a name="l00256"></a>00256 <span class="comment"></span> <a name="l00257"></a>00257 <span class="keywordtype">void</span> thread_planner(); <span class="comment">//!< Thread function</span> <a name="l00258"></a>00258 <span class="comment"></span> <span class="keywordtype">void</span> thread_test_collision(); <span class="comment">//!< Thread function</span> <a name="l00259"></a>00259 <span class="comment"></span> <span class="keywordtype">void</span> thread_path_tracking(); <span class="comment">//!< Thread function</span> <a name="l00260"></a>00260 <span class="comment"></span> <a name="l00261"></a>00261 <a name="l00262"></a>00262 <span class="comment">// ----------- Internal data -----------</span> <a name="l00263"></a>00263 <a name="l00264"></a><a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#ac0ce69545de3e651b050385a3da0f354">00264</a> <span class="keywordtype">bool</span> <a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#ac0ce69545de3e651b050385a3da0f354" title="The object is ready to navigate. Users must call "initialize" first.">m_initialized</a>; <span class="comment">//!< The object is ready to navigate. Users must call "initialize" first.</span> <a name="l00265"></a><a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#a10dbf8b8724bef6837022469bb67c59d">00265</a> <span class="comment"></span> <span class="keywordtype">bool</span> <a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#a10dbf8b8724bef6837022469bb67c59d" title="set to true at destructor.">m_closingThreads</a>; <span class="comment">//!< set to true at destructor.</span> <a name="l00266"></a>00266 <span class="comment"></span> <a name="l00267"></a><a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#a31a8b2b3f951a79251283b7b78a7801c">00267</a> <a class="code" href="structmrpt_1_1math_1_1_t_pose2_d.html" title="Lightweight 2D pose.">TPose2D</a> <a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#a31a8b2b3f951a79251283b7b78a7801c" title="Heading may be INVALID_HEADING to indicate "don't mind".">m_target_pose</a>; <span class="comment">//!< Heading may be INVALID_HEADING to indicate "don't mind"</span> <a name="l00268"></a><a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#a54e46b1065d6effc0c63b2a33b3e644c">00268</a> <span class="comment"></span> <a class="code" href="group__time__date.html#ga42674286d8d56afea013b6329bb7327a" title="A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...">TTimeStamp</a> <a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#a54e46b1065d6effc0c63b2a33b3e644c">m_target_pose_time</a>; <a name="l00269"></a><a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#a5819dc1781d4cf3ce6db0db78277a0a5">00269</a> <a class="code" href="classmrpt_1_1synch_1_1_c_critical_section.html" title="This class provides simple critical sections functionality.">CCriticalSection</a> <a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#a5819dc1781d4cf3ce6db0db78277a0a5">m_target_pose_cs</a>; <a name="l00270"></a>00270 <a name="l00271"></a>00271 <span class="comment">// Instead of a CSimplePointsMap, just store the X & Y vectors, since</span> <a name="l00272"></a>00272 <span class="comment">// this is a temporary variable. We'll let the planning thread to build</span> <a name="l00273"></a>00273 <span class="comment">// a CSimplePointsMap object with these points.</span> <a name="l00274"></a>00274 <span class="comment">//mrpt::slam::CSimplePointsMap m_last_obstacles;</span> <a name="l00275"></a><a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#a375e0b1fa177426b6175ff4ead2f9c0f">00275</a> std<a class="code" href="classstd_1_1vector.html">::vector<float></a> m_last_obstacles_x,<a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#a375e0b1fa177426b6175ff4ead2f9c0f">m_last_obstacles_y</a>; <a name="l00276"></a><a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#a8c73e87eca9abdc37f2755de2abcc02d">00276</a> <a class="code" href="group__time__date.html#ga42674286d8d56afea013b6329bb7327a" title="A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...">TTimeStamp</a> <a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#a8c73e87eca9abdc37f2755de2abcc02d">m_last_obstacles_time</a>; <a name="l00277"></a><a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#acac78122cbb624fd0d815dc289061636">00277</a> <a class="code" href="classmrpt_1_1synch_1_1_c_critical_section.html" title="This class provides simple critical sections functionality.">CCriticalSection</a> <a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#acac78122cbb624fd0d815dc289061636">m_last_obstacles_cs</a>; <a name="l00278"></a>00278 <a name="l00279"></a>00279 <span class="comment">// The planned path, to be followed:</span> <a name="l00280"></a><a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#aa91bf8d6a540c2eca3d7d61e7b9c3845">00280</a> <a class="code" href="classmrpt_1_1synch_1_1_c_critical_section.html" title="This class provides simple critical sections functionality.">CCriticalSection</a> <a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#aa91bf8d6a540c2eca3d7d61e7b9c3845">m_planned_path_cs</a>; <a name="l00281"></a><a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#a8c5ba43a18d2ab0d31ec68d26b593984">00281</a> <a class="code" href="group__time__date.html#ga42674286d8d56afea013b6329bb7327a" title="A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...">TTimeStamp</a> <a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#a8c5ba43a18d2ab0d31ec68d26b593984" title="The last modification time. INVALID_TIMESTAMP means there is no path.">m_planned_path_time</a>; <span class="comment">//!< The last modification time. INVALID_TIMESTAMP means there is no path.</span> <a name="l00282"></a><a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#a2cb1e3a1f06fcc3b06b7f2bffca6112d">00282</a> <span class="comment"></span> <a class="code" href="classstd_1_1list.html">TPlannedPath</a> <a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#a2cb1e3a1f06fcc3b06b7f2bffca6112d">m_planned_path</a>; <a name="l00283"></a>00283 <span class="comment"></span> <a name="l00284"></a>00284 <span class="comment"> /** The list of PTGs used by the anytime planner to explore the free-space. */</span> <a name="l00285"></a><a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#a2784ee37f3ad7f549197b5a282e3ef3b">00285</a> <a class="code" href="classstd_1_1vector.html">TListPTGs</a> <a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#a2784ee37f3ad7f549197b5a282e3ef3b" title="The list of PTGs used by the anytime planner to explore the free-space.">m_PTGs</a>; <a name="l00286"></a><a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#ac7cc5be2c9826aa0d262b571e346ae0c">00286</a> <a class="code" href="classmrpt_1_1synch_1_1_c_critical_section.html" title="This class provides simple critical sections functionality.">CCriticalSection</a> <a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#ac7cc5be2c9826aa0d262b571e346ae0c">m_PTGs_cs</a>; <a name="l00287"></a>00287 <a name="l00288"></a>00288 <span class="keyword">public</span>: <a name="l00289"></a>00289 <a name="l00290"></a><a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#af247a47a88dab4cc96b1cab2ed171f0b">00290</a> mrpt<a class="code" href="classmrpt_1_1poses_1_1_c_robot2_d_pose_estimator.html" title="A simple filter to estimate and extrapolate the robot 2D (x,y,phi) pose from asynchronous odometry an...">::poses::CRobot2DPoseEstimator</a> <a class="code" href="classmrpt_1_1reactivenav_1_1_c_p_r_r_t_navigator.html#af247a47a88dab4cc96b1cab2ed171f0b" title="Object maintained by the robot-tracking thread (All methods are thread-safe).">m_robotStateFilter</a>; <span class="comment">//!< Object maintained by the robot-tracking thread (All methods are thread-safe).</span> <a name="l00291"></a>00291 <span class="comment"></span> <a name="l00292"></a>00292 <a name="l00293"></a>00293 <a name="l00294"></a>00294 }; <a name="l00295"></a>00295 } <a name="l00296"></a>00296 } <a name="l00297"></a>00297 <a name="l00298"></a>00298 <a name="l00299"></a>00299 <span class="preprocessor">#endif</span> <a name="l00300"></a>00300 <span class="preprocessor"></span> </pre></div></div> </div> <br><hr><br> <table border="0" width="100%"> <tr> <td> Page generated by <a href="http://www.doxygen.org" target="_blank">Doxygen 1.7.5</a> for MRPT 0.9.5 SVN: at Sun Sep 25 17:20:18 UTC 2011</td><td></td> <td width="100"> </td> <td width="150"> </td></tr> </table> </body></html>