<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd"> <html xmlns="http://www.w3.org/1999/xhtml"> <head> <meta http-equiv="Content-Type" content="text/xhtml; charset=UTF-8"/> <title>OMPL: src/ompl/base/ScopedState.h Source File</title> <meta name="author" content="Ioan A. Șucan, Mark Moll, Lydia E. Kavraki"> <link rel="stylesheet" href="../css/screen.css" type="text/css" media="screen, projection"> <link rel="stylesheet" href="../css/print.css" type="text/css" media="print"> <!--[if lt IE 7]> <script type="text/javascript" src="../js/jquery/jquery.js"></script> <script type="text/javascript" src="../js/jquery/jquery.dropdown.js"></script> <![endif]--> <script type="text/javaScript" src="search/search.js"></script> <script type="text/javascript"> var _gaq = _gaq || []; _gaq.push(['_setAccount', 'UA-9156598-2']); _gaq.push(['_trackPageview']); (function() { var ga = document.createElement('script'); ga.type = 'text/javascript'; ga.async = true; ga.src = ('https:' == document.location.protocol ? 'https://ssl' : 'http://www') + '.google-analytics.com/ga.js'; var s = document.getElementsByTagName('script')[0]; s.parentNode.insertBefore(ga, s); })(); </script> </head> <body onload='searchBox.OnSelectItem(0);'> <script type="text/javascript"><!-- var searchBox = new SearchBox("searchBox", "search",false,'Search API'); --></script> <div class="navigation" id="top"> <div class="tabs" id="ompltitle"> <ul class="tablist"> <li>The Open Motion Planning Library</li> <li id="searchli"> <div id="MSearchBox" class="MSearchBoxInactive"> <span class="left"> <img id="MSearchSelect" src="search/mag_sel.png" onmouseover="return searchBox.OnSearchSelectShow()" onmouseout="return searchBox.OnSearchSelectHide()" alt=""/> <input type="text" id="MSearchField" value="Search API" accesskey="S" onfocus="searchBox.OnSearchFieldFocus(true)" onblur="searchBox.OnSearchFieldFocus(false)" onkeyup="searchBox.OnSearchFieldChange(event)"/> </span><span class="right"> <a id="MSearchClose" href="javascript:searchBox.CloseResultsWindow()"><img id="MSearchCloseImg" border="0" src="search/close.png" alt=""/></a> </span> </div> </li> </ul> </div> <ul id="nav" class="dropdown"> <li class="first"><a href="index.html">Home</a></li> <li><a href="download.html">Download</a></li> <li><a href="documentation.html">Documentation</a></li> <li><span class="dir">Code API</span> <ul> <li><a href="api_overview.html">API Overview</a></li> <li><a href="namespaces.html">Namespaces</a></li> <li><a href="annotated.html">Classes</a></li> <li><a href="files.html">Files</a></li> <li><a href="dirs.html">Directories</a></li> </ul> </li> <li><span class="dir">Community</span> <ul> <li><a href="developers.html">Developers</a></li> <li><a href="thirdparty.html">Contributions</a></li> <li><a href="education.html">Education</a></li> <li><a href="gallery.html">Gallery</a></li> </ul> </li> <li><span class="dir">About</span> <ul> <li><a href="license.html">License</a></li> <li><a href="citations.html">Citations</a></li> <li><a href="acknowledgements.html">Acknowledgments</a></li> <li><a href="contact.html">Contact Us</a></li> </ul> </li> </ul> </div> <!--- window showing the filter options --> <div id="MSearchSelectWindow" onmouseover="return searchBox.OnSearchSelectShow()" onmouseout="return searchBox.OnSearchSelectHide()" onkeydown="return searchBox.OnSearchSelectKey(event)"> <a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(0)"><span class="SelectionMark"> </span>All</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(1)"><span class="SelectionMark"> </span>Classes</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(2)"><span class="SelectionMark"> </span>Namespaces</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(3)"><span class="SelectionMark"> </span>Functions</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(4)"><span class="SelectionMark"> </span>Variables</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(5)"><span class="SelectionMark"> </span>Typedefs</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(6)"><span class="SelectionMark"> </span>Enumerations</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(7)"><span class="SelectionMark"> </span>Enumerator</a></div> <!-- iframe showing the search results (closed by default) --> <div id="MSearchResultsWindow"> <iframe src="" frameborder="0"name="MSearchResults" id="MSearchResults"></iframe> </div> <div class="container"> <div class="span-22 push-2 first last"> <div> <!-- Generated by Doxygen 1.7.4 --> <script type="text/javascript"><!-- var searchBox = new SearchBox("searchBox", "search",false,'Search'); --></script> <div id="nav-path" class="navpath"> <ul> <li class="navelem"><a class="el" href="dir_f5421e52a658cd938113ed6044324834.html">src</a> </li> <li class="navelem"><a class="el" href="dir_ae92c2ff78847f0cb49b545f9089bbbc.html">ompl</a> </li> <li class="navelem"><a class="el" href="dir_40bc83a902349ad67ef9d1cb49964511.html">base</a> </li> </ul> </div> </div> <div class="header"> <div class="headertitle"> <div class="title">ScopedState.h</div> </div> </div> <div class="contents"> <div class="fragment"><pre class="fragment"><a name="l00001"></a>00001 <span class="comment">/*********************************************************************</span> <a name="l00002"></a>00002 <span class="comment">* Software License Agreement (BSD License)</span> <a name="l00003"></a>00003 <span class="comment">*</span> <a name="l00004"></a>00004 <span class="comment">* Copyright (c) 2010, Rice University</span> <a name="l00005"></a>00005 <span class="comment">* All rights reserved.</span> <a name="l00006"></a>00006 <span class="comment">*</span> <a name="l00007"></a>00007 <span class="comment">* Redistribution and use in source and binary forms, with or without</span> <a name="l00008"></a>00008 <span class="comment">* modification, are permitted provided that the following conditions</span> <a name="l00009"></a>00009 <span class="comment">* are met:</span> <a name="l00010"></a>00010 <span class="comment">*</span> <a name="l00011"></a>00011 <span class="comment">* * Redistributions of source code must retain the above copyright</span> <a name="l00012"></a>00012 <span class="comment">* notice, this list of conditions and the following disclaimer.</span> <a name="l00013"></a>00013 <span class="comment">* * Redistributions in binary form must reproduce the above</span> <a name="l00014"></a>00014 <span class="comment">* copyright notice, this list of conditions and the following</span> <a name="l00015"></a>00015 <span class="comment">* disclaimer in the documentation and/or other materials provided</span> <a name="l00016"></a>00016 <span class="comment">* with the distribution.</span> <a name="l00017"></a>00017 <span class="comment">* * Neither the name of the Rice University nor the names of its</span> <a name="l00018"></a>00018 <span class="comment">* contributors may be used to endorse or promote products derived</span> <a name="l00019"></a>00019 <span class="comment">* from this software without specific prior written permission.</span> <a name="l00020"></a>00020 <span class="comment">*</span> <a name="l00021"></a>00021 <span class="comment">* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS</span> <a name="l00022"></a>00022 <span class="comment">* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT</span> <a name="l00023"></a>00023 <span class="comment">* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS</span> <a name="l00024"></a>00024 <span class="comment">* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE</span> <a name="l00025"></a>00025 <span class="comment">* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,</span> <a name="l00026"></a>00026 <span class="comment">* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,</span> <a name="l00027"></a>00027 <span class="comment">* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;</span> <a name="l00028"></a>00028 <span class="comment">* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER</span> <a name="l00029"></a>00029 <span class="comment">* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT</span> <a name="l00030"></a>00030 <span class="comment">* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN</span> <a name="l00031"></a>00031 <span class="comment">* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE</span> <a name="l00032"></a>00032 <span class="comment">* POSSIBILITY OF SUCH DAMAGE.</span> <a name="l00033"></a>00033 <span class="comment">*********************************************************************/</span> <a name="l00034"></a>00034 <a name="l00035"></a>00035 <span class="comment">/* Author: Ioan Sucan */</span> <a name="l00036"></a>00036 <a name="l00037"></a>00037 <span class="preprocessor">#ifndef OMPL_BASE_SCOPED_STATE_</span> <a name="l00038"></a>00038 <span class="preprocessor"></span><span class="preprocessor">#define OMPL_BASE_SCOPED_STATE_</span> <a name="l00039"></a>00039 <span class="preprocessor"></span> <a name="l00040"></a>00040 <span class="preprocessor">#include "ompl/base/SpaceInformation.h"</span> <a name="l00041"></a>00041 <span class="preprocessor">#include <boost/concept_check.hpp></span> <a name="l00042"></a>00042 <span class="preprocessor">#include <iostream></span> <a name="l00043"></a>00043 <a name="l00044"></a>00044 <span class="keyword">namespace </span>ompl <a name="l00045"></a>00045 { <a name="l00046"></a>00046 <span class="keyword">namespace </span>base <a name="l00047"></a>00047 { <a name="l00048"></a>00048 <a name="l00055"></a>00055 <span class="keyword">template</span><<span class="keyword">class</span> T = StateSpace> <a name="l00056"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html">00056</a> <span class="keyword">class </span><a class="code" href="classompl_1_1base_1_1ScopedState.html" title="Definition of a scoped state.">ScopedState</a> <a name="l00057"></a>00057 { <a name="l00059"></a>00059 BOOST_CONCEPT_ASSERT((boost::Convertible<T*, StateSpace*>)); <a name="l00060"></a>00060 <a name="l00062"></a>00062 BOOST_CONCEPT_ASSERT((boost::Convertible<typename T::StateType*, State*>)); <a name="l00063"></a>00063 <a name="l00064"></a>00064 <span class="keyword">public</span>: <a name="l00065"></a>00065 <a name="l00067"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html#a5a33e968e72f92b5e25bdf3e2feaa0c6">00067</a> <span class="keyword">typedef</span> <span class="keyword">typename</span> T::StateType <a class="code" href="classompl_1_1base_1_1ScopedState.html#a5a33e968e72f92b5e25bdf3e2feaa0c6" title="The type of the contained state.">StateType</a>; <a name="l00068"></a>00068 <a name="l00072"></a>00072 <span class="keyword">explicit</span> <a name="l00073"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html#a7d5d0be9ab08141bdc4b896f6a0fcbfd">00073</a> <a class="code" href="classompl_1_1base_1_1ScopedState.html#a7d5d0be9ab08141bdc4b896f6a0fcbfd" title="Given the space that we are working with, allocate a state from the corresponding state space...">ScopedState</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1SpaceInformationPtr.html" title="A boost shared pointer wrapper for ompl::base::SpaceInformation.">SpaceInformationPtr</a> &si) : space_(si->getStateSpace()) <a name="l00074"></a>00074 { <a name="l00075"></a>00075 <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *s = space_->allocState(); <a name="l00076"></a>00076 <a name="l00077"></a>00077 <span class="comment">// ideally, this should be a dynamic_cast and we</span> <a name="l00078"></a>00078 <span class="comment">// should throw an exception in case of</span> <a name="l00079"></a>00079 <span class="comment">// failure. However, RTTI may not be available across</span> <a name="l00080"></a>00080 <span class="comment">// shared library boundaries, so we do not use it</span> <a name="l00081"></a>00081 state_ = <span class="keyword">static_cast<</span><a class="code" href="classompl_1_1base_1_1ScopedState.html#a5a33e968e72f92b5e25bdf3e2feaa0c6" title="The type of the contained state.">StateType</a>*<span class="keyword">></span>(s); <a name="l00082"></a>00082 } <a name="l00083"></a>00083 <a name="l00086"></a>00086 <span class="keyword">explicit</span> <a name="l00087"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html#a983420b093e57a2c3250e1b31c382047">00087</a> <a class="code" href="classompl_1_1base_1_1ScopedState.html#a7d5d0be9ab08141bdc4b896f6a0fcbfd" title="Given the space that we are working with, allocate a state from the corresponding state space...">ScopedState</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1StateSpacePtr.html" title="A boost shared pointer wrapper for ompl::base::StateSpace.">StateSpacePtr</a> &space) : space_(space) <a name="l00088"></a>00088 { <a name="l00089"></a>00089 <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *s = space_->allocState(); <a name="l00090"></a>00090 <a name="l00091"></a>00091 <span class="comment">// ideally, this should be a dynamic_cast and we</span> <a name="l00092"></a>00092 <span class="comment">// should throw an exception in case of</span> <a name="l00093"></a>00093 <span class="comment">// failure. However, RTTI may not be available across</span> <a name="l00094"></a>00094 <span class="comment">// shared library boundaries, so we do not use it</span> <a name="l00095"></a>00095 state_ = <span class="keyword">static_cast<</span><a class="code" href="classompl_1_1base_1_1ScopedState.html#a5a33e968e72f92b5e25bdf3e2feaa0c6" title="The type of the contained state.">StateType</a>*<span class="keyword">></span>(s); <a name="l00096"></a>00096 } <a name="l00097"></a>00097 <a name="l00099"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html#aa6f35a339ef5e31b0a163a829f80f5b1">00099</a> <a class="code" href="classompl_1_1base_1_1ScopedState.html#a7d5d0be9ab08141bdc4b896f6a0fcbfd" title="Given the space that we are working with, allocate a state from the corresponding state space...">ScopedState</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1ScopedState.html" title="Definition of a scoped state.">ScopedState<T></a> &other) : space_(other.<a class="code" href="classompl_1_1base_1_1ScopedState.html#abcc9537b30fb02b67f7e68dd82c07970" title="Get the state space that the state corresponds to.">getSpace</a>()) <a name="l00100"></a>00100 { <a name="l00101"></a>00101 <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *s = space_->allocState(); <a name="l00102"></a>00102 state_ = <span class="keyword">static_cast<</span><a class="code" href="classompl_1_1base_1_1ScopedState.html#a5a33e968e72f92b5e25bdf3e2feaa0c6" title="The type of the contained state.">StateType</a>*<span class="keyword">></span>(s); <a name="l00103"></a>00103 space_->copyState(s, static_cast<const State*>(other.<a class="code" href="classompl_1_1base_1_1ScopedState.html#afc13c57b8379540de664491aa7113c3a" title="Returns a pointer to the contained state.">get</a>())); <a name="l00104"></a>00104 } <a name="l00105"></a>00105 <a name="l00107"></a>00107 <span class="keyword">template</span><<span class="keyword">class</span> O> <a name="l00108"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html#a4cada6ab0b1126666ff59e17bf7cb629">00108</a> <a class="code" href="classompl_1_1base_1_1ScopedState.html#a7d5d0be9ab08141bdc4b896f6a0fcbfd" title="Given the space that we are working with, allocate a state from the corresponding state space...">ScopedState</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1ScopedState.html" title="Definition of a scoped state.">ScopedState<O></a> &other) : space_(other.<a class="code" href="classompl_1_1base_1_1ScopedState.html#abcc9537b30fb02b67f7e68dd82c07970" title="Get the state space that the state corresponds to.">getSpace</a>()) <a name="l00109"></a>00109 { <a name="l00110"></a>00110 BOOST_CONCEPT_ASSERT((boost::Convertible<O*, StateSpace*>)); <a name="l00111"></a>00111 BOOST_CONCEPT_ASSERT((boost::Convertible<typename O::StateType*, State*>)); <a name="l00112"></a>00112 <a name="l00113"></a>00113 <span class="comment">// ideally, we should use a dynamic_cast and throw an</span> <a name="l00114"></a>00114 <span class="comment">// exception in case other.get() does not cast to</span> <a name="l00115"></a>00115 <span class="comment">// const StateType*. However, RTTI may not be</span> <a name="l00116"></a>00116 <span class="comment">// available across shared library boundaries, so we</span> <a name="l00117"></a>00117 <span class="comment">// do not use it</span> <a name="l00118"></a>00118 <a name="l00119"></a>00119 <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *s = space_->allocState(); <a name="l00120"></a>00120 state_ = <span class="keyword">static_cast<</span><a class="code" href="classompl_1_1base_1_1ScopedState.html#a5a33e968e72f92b5e25bdf3e2feaa0c6" title="The type of the contained state.">StateType</a>*<span class="keyword">></span>(s); <a name="l00121"></a>00121 space_->copyState(s, static_cast<const State*>(other.<a class="code" href="classompl_1_1base_1_1ScopedState.html#afc13c57b8379540de664491aa7113c3a" title="Returns a pointer to the contained state.">get</a>())); <a name="l00122"></a>00122 } <a name="l00123"></a>00123 <a name="l00126"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html#a0d44eaea9444aba5c696c58187a755bd">00126</a> <a class="code" href="classompl_1_1base_1_1ScopedState.html#a7d5d0be9ab08141bdc4b896f6a0fcbfd" title="Given the space that we are working with, allocate a state from the corresponding state space...">ScopedState</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1StateSpacePtr.html" title="A boost shared pointer wrapper for ompl::base::StateSpace.">StateSpacePtr</a> &space, <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *state) : space_(space) <a name="l00127"></a>00127 { <a name="l00128"></a>00128 <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *s = space_->allocState(); <a name="l00129"></a>00129 space_->copyState(s, state); <a name="l00130"></a>00130 <a name="l00131"></a>00131 <span class="comment">// ideally, this should be a dynamic_cast and we</span> <a name="l00132"></a>00132 <span class="comment">// should throw an exception in case of</span> <a name="l00133"></a>00133 <span class="comment">// failure. However, RTTI may not be available across</span> <a name="l00134"></a>00134 <span class="comment">// shared library boundaries, so we do not use it</span> <a name="l00135"></a>00135 state_ = <span class="keyword">static_cast<</span><a class="code" href="classompl_1_1base_1_1ScopedState.html#a5a33e968e72f92b5e25bdf3e2feaa0c6" title="The type of the contained state.">StateType</a>*<span class="keyword">></span>(s); <a name="l00136"></a>00136 } <a name="l00137"></a>00137 <a name="l00139"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html#ab79a4c8ea0b1af9fb58edebd77dbf6a0">00139</a> <a class="code" href="classompl_1_1base_1_1ScopedState.html#ab79a4c8ea0b1af9fb58edebd77dbf6a0" title="Free the memory of the internally allocated state.">~ScopedState</a>(<span class="keywordtype">void</span>) <a name="l00140"></a>00140 { <a name="l00141"></a>00141 space_->freeState(state_); <a name="l00142"></a>00142 } <a name="l00143"></a>00143 <a name="l00145"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html#abcc9537b30fb02b67f7e68dd82c07970">00145</a> <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1StateSpacePtr.html" title="A boost shared pointer wrapper for ompl::base::StateSpace.">StateSpacePtr</a>& <a class="code" href="classompl_1_1base_1_1ScopedState.html#abcc9537b30fb02b67f7e68dd82c07970" title="Get the state space that the state corresponds to.">getSpace</a>(<span class="keywordtype">void</span>)<span class="keyword"> const</span> <a name="l00146"></a>00146 <span class="keyword"> </span>{ <a name="l00147"></a>00147 <span class="keywordflow">return</span> space_; <a name="l00148"></a>00148 } <a name="l00149"></a>00149 <a name="l00151"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html#ac4fb27b32ef5e413b1a2ad8cfc84f7a4">00151</a> <a class="code" href="classompl_1_1base_1_1ScopedState.html" title="Definition of a scoped state.">ScopedState<T></a>& <a class="code" href="classompl_1_1base_1_1ScopedState.html#ac4fb27b32ef5e413b1a2ad8cfc84f7a4" title="Assignment operator.">operator=</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1ScopedState.html" title="Definition of a scoped state.">ScopedState<T></a> &other) <a name="l00152"></a>00152 { <a name="l00153"></a>00153 <span class="keywordflow">if</span> (&other != <span class="keyword">this</span>) <a name="l00154"></a>00154 { <a name="l00155"></a>00155 space_->freeState(state_); <a name="l00156"></a>00156 space_ = other.<a class="code" href="classompl_1_1base_1_1ScopedState.html#abcc9537b30fb02b67f7e68dd82c07970" title="Get the state space that the state corresponds to.">getSpace</a>(); <a name="l00157"></a>00157 <a name="l00158"></a>00158 <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *s = space_->allocState(); <a name="l00159"></a>00159 state_ = <span class="keyword">static_cast<</span><a class="code" href="classompl_1_1base_1_1ScopedState.html#a5a33e968e72f92b5e25bdf3e2feaa0c6" title="The type of the contained state.">StateType</a>*<span class="keyword">></span>(s); <a name="l00160"></a>00160 space_->copyState(s, static_cast<const State*>(other.<a class="code" href="classompl_1_1base_1_1ScopedState.html#afc13c57b8379540de664491aa7113c3a" title="Returns a pointer to the contained state.">get</a>())); <a name="l00161"></a>00161 } <a name="l00162"></a>00162 <span class="keywordflow">return</span> *<span class="keyword">this</span>; <a name="l00163"></a>00163 } <a name="l00164"></a>00164 <a name="l00166"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html#af81845da48cd2995b0786c1a2135e6a6">00166</a> <a class="code" href="classompl_1_1base_1_1ScopedState.html" title="Definition of a scoped state.">ScopedState<T></a>& <a class="code" href="classompl_1_1base_1_1ScopedState.html#ac4fb27b32ef5e413b1a2ad8cfc84f7a4" title="Assignment operator.">operator=</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *other) <a name="l00167"></a>00167 { <a name="l00168"></a>00168 <span class="keywordflow">if</span> (other != static_cast<State*>(state_)) <a name="l00169"></a>00169 { <a name="l00170"></a>00170 <span class="comment">// ideally, we should use a dynamic_cast and throw an</span> <a name="l00171"></a>00171 <span class="comment">// exception in case other does not cast to</span> <a name="l00172"></a>00172 <span class="comment">// const StateType*. However, RTTI may not be</span> <a name="l00173"></a>00173 <span class="comment">// available across shared library boundaries, so we</span> <a name="l00174"></a>00174 <span class="comment">// do not use it</span> <a name="l00175"></a>00175 <a name="l00176"></a>00176 space_->copyState(static_cast<State*>(state_), other); <a name="l00177"></a>00177 } <a name="l00178"></a>00178 <span class="keywordflow">return</span> *<span class="keyword">this</span>; <a name="l00179"></a>00179 } <a name="l00180"></a>00180 <a name="l00182"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html#a2a942938fd27f567e50c882448a36249">00182</a> <a class="code" href="classompl_1_1base_1_1ScopedState.html" title="Definition of a scoped state.">ScopedState<T></a>& <a class="code" href="classompl_1_1base_1_1ScopedState.html#ac4fb27b32ef5e413b1a2ad8cfc84f7a4" title="Assignment operator.">operator=</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> &other) <a name="l00183"></a>00183 { <a name="l00184"></a>00184 <span class="keywordflow">if</span> (&other != static_cast<State*>(state_)) <a name="l00185"></a>00185 { <a name="l00186"></a>00186 <span class="comment">// ideally, we should use a dynamic_cast and throw an</span> <a name="l00187"></a>00187 <span class="comment">// exception in case &other does not cast to</span> <a name="l00188"></a>00188 <span class="comment">// const StateType*. However, RTTI may not be</span> <a name="l00189"></a>00189 <span class="comment">// available across shared library boundaries, so we</span> <a name="l00190"></a>00190 <span class="comment">// do not use it</span> <a name="l00191"></a>00191 <a name="l00192"></a>00192 space_->copyState(static_cast<State*>(state_), &other); <a name="l00193"></a>00193 } <a name="l00194"></a>00194 <span class="keywordflow">return</span> *<span class="keyword">this</span>; <a name="l00195"></a>00195 } <a name="l00196"></a>00196 <a name="l00198"></a>00198 <span class="keyword">template</span><<span class="keyword">class</span> O> <a name="l00199"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html#a3da3e6438bde92cad7d980c8801f4f1e">00199</a> <a class="code" href="classompl_1_1base_1_1ScopedState.html" title="Definition of a scoped state.">ScopedState<T></a>& <a class="code" href="classompl_1_1base_1_1ScopedState.html#ac4fb27b32ef5e413b1a2ad8cfc84f7a4" title="Assignment operator.">operator=</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1ScopedState.html" title="Definition of a scoped state.">ScopedState<O></a> &other) <a name="l00200"></a>00200 { <a name="l00201"></a>00201 BOOST_CONCEPT_ASSERT((boost::Convertible<O*, StateSpace*>)); <a name="l00202"></a>00202 BOOST_CONCEPT_ASSERT((boost::Convertible<typename O::StateType*, State*>)); <a name="l00203"></a>00203 <a name="l00204"></a>00204 <span class="comment">// ideally, we should use a dynamic_cast and throw an</span> <a name="l00205"></a>00205 <span class="comment">// exception in case other.get() does not cast to</span> <a name="l00206"></a>00206 <span class="comment">// const StateType*. However, RTTI may not be</span> <a name="l00207"></a>00207 <span class="comment">// available across shared library boundaries, so we</span> <a name="l00208"></a>00208 <span class="comment">// do not use it</span> <a name="l00209"></a>00209 <a name="l00210"></a>00210 <span class="keywordflow">if</span> (reinterpret_cast<const void*>(&other) != reinterpret_cast<const void*>(<span class="keyword">this</span>)) <a name="l00211"></a>00211 { <a name="l00212"></a>00212 space_->freeState(state_); <a name="l00213"></a>00213 space_ = other.<a class="code" href="classompl_1_1base_1_1ScopedState.html#abcc9537b30fb02b67f7e68dd82c07970" title="Get the state space that the state corresponds to.">getSpace</a>(); <a name="l00214"></a>00214 <a name="l00215"></a>00215 <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *s = space_->allocState(); <a name="l00216"></a>00216 state_ = <span class="keyword">static_cast<</span><a class="code" href="classompl_1_1base_1_1ScopedState.html#a5a33e968e72f92b5e25bdf3e2feaa0c6" title="The type of the contained state.">StateType</a>*<span class="keyword">></span>(s); <a name="l00217"></a>00217 space_->copyState(s, static_cast<const State*>(other.<a class="code" href="classompl_1_1base_1_1ScopedState.html#afc13c57b8379540de664491aa7113c3a" title="Returns a pointer to the contained state.">get</a>())); <a name="l00218"></a>00218 } <a name="l00219"></a>00219 <span class="keywordflow">return</span> *<span class="keyword">this</span>; <a name="l00220"></a>00220 } <a name="l00221"></a>00221 <a name="l00223"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html#a483e5d636b2955b73f4642e6b90cda9f">00223</a> <a class="code" href="classompl_1_1base_1_1ScopedState.html" title="Definition of a scoped state.">ScopedState<T></a>& <a class="code" href="classompl_1_1base_1_1ScopedState.html#ac4fb27b32ef5e413b1a2ad8cfc84f7a4" title="Assignment operator.">operator=</a>(<span class="keyword">const</span> std::vector<double> &<a class="code" href="classompl_1_1base_1_1ScopedState.html#aef18b4a578e37cf4221e1835faa71e26" title="Return the real values corresponding to this state. If a conversion is not possible, an exception is thrown.">reals</a>) <a name="l00224"></a>00224 { <a name="l00225"></a>00225 <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0 ; i < reals.size() ; ++i) <a name="l00226"></a>00226 <span class="keywordflow">if</span> (<span class="keywordtype">double</span> *va = space_->getValueAddressAtIndex(state_, i)) <a name="l00227"></a>00227 *va = reals[i]; <a name="l00228"></a>00228 <span class="keywordflow">else</span> <a name="l00229"></a>00229 <span class="keywordflow">break</span>; <a name="l00230"></a>00230 <span class="keywordflow">return</span> *<span class="keyword">this</span>; <a name="l00231"></a>00231 } <a name="l00232"></a>00232 <a name="l00234"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html#a50cbd5b4ee7fca852b2e6279f0980f8a">00234</a> <a class="code" href="classompl_1_1base_1_1ScopedState.html" title="Definition of a scoped state.">ScopedState<T></a>& <a class="code" href="classompl_1_1base_1_1ScopedState.html#ac4fb27b32ef5e413b1a2ad8cfc84f7a4" title="Assignment operator.">operator=</a>(<span class="keyword">const</span> <span class="keywordtype">double</span> value) <a name="l00235"></a>00235 { <a name="l00236"></a>00236 <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> index = 0; <a name="l00237"></a>00237 <span class="keywordflow">while</span> (<span class="keywordtype">double</span> *va = space_->getValueAddressAtIndex(state_, index++)) <a name="l00238"></a>00238 *va = value; <a name="l00239"></a>00239 <span class="keywordflow">return</span> *<span class="keyword">this</span>; <a name="l00240"></a>00240 } <a name="l00241"></a>00241 <a name="l00243"></a>00243 <span class="keyword">template</span><<span class="keyword">class</span> O> <a name="l00244"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html#a70cc12c65d1a069362d79d22d09fc1f9">00244</a> <span class="keywordtype">bool</span> <a class="code" href="classompl_1_1base_1_1ScopedState.html#a70cc12c65d1a069362d79d22d09fc1f9" title="Checks equality of two states.">operator==</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1ScopedState.html" title="Definition of a scoped state.">ScopedState<O></a> &other)<span class="keyword"> const</span> <a name="l00245"></a>00245 <span class="keyword"> </span>{ <a name="l00246"></a>00246 BOOST_CONCEPT_ASSERT((boost::Convertible<O*, StateSpace*>)); <a name="l00247"></a>00247 BOOST_CONCEPT_ASSERT((boost::Convertible<typename O::StateType*, State*>)); <a name="l00248"></a>00248 <a name="l00249"></a>00249 <span class="comment">// ideally, we should use a dynamic_cast and throw an</span> <a name="l00250"></a>00250 <span class="comment">// exception in case other.get() does not cast to</span> <a name="l00251"></a>00251 <span class="comment">// const StateType*. However, RTTI may not be</span> <a name="l00252"></a>00252 <span class="comment">// available across shared library boundaries, so we</span> <a name="l00253"></a>00253 <span class="comment">// do not use it</span> <a name="l00254"></a>00254 <a name="l00255"></a>00255 <span class="keywordflow">return</span> space_->equalStates(static_cast<const State*>(state_), static_cast<const State*>(other.<a class="code" href="classompl_1_1base_1_1ScopedState.html#afc13c57b8379540de664491aa7113c3a" title="Returns a pointer to the contained state.">get</a>())); <a name="l00256"></a>00256 } <a name="l00257"></a>00257 <a name="l00259"></a>00259 <span class="keyword">template</span><<span class="keyword">class</span> O> <a name="l00260"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html#ae6f4c9e2d5d072aeda6fe5953c17ed64">00260</a> <span class="keywordtype">bool</span> <a class="code" href="classompl_1_1base_1_1ScopedState.html#ae6f4c9e2d5d072aeda6fe5953c17ed64" title="Checks equality of two states.">operator!=</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1ScopedState.html" title="Definition of a scoped state.">ScopedState<O></a> &other)<span class="keyword"> const</span> <a name="l00261"></a>00261 <span class="keyword"> </span>{ <a name="l00262"></a>00262 <span class="keywordflow">return</span> !(*<span class="keyword">this</span> == other); <a name="l00263"></a>00263 } <a name="l00264"></a>00264 <a name="l00270"></a>00270 <a class="code" href="classompl_1_1base_1_1ScopedState.html" title="Definition of a scoped state.">ScopedState<></a> <a class="code" href="classompl_1_1base_1_1ScopedState.html#a19f24f28908474678e5fef9a9f64abf1" title="Extract a state that corresponds to the components in state space s. Those components will have the s...">operator[]</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1StateSpacePtr.html" title="A boost shared pointer wrapper for ompl::base::StateSpace.">StateSpacePtr</a> &s) <span class="keyword">const</span>; <a name="l00271"></a>00271 <a name="l00273"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html#a58359e139ad823db181bc12fbcf3aafd">00273</a> <span class="keywordtype">double</span>& <a class="code" href="classompl_1_1base_1_1ScopedState.html#a19f24f28908474678e5fef9a9f64abf1" title="Extract a state that corresponds to the components in state space s. Those components will have the s...">operator[]</a>(<span class="keyword">const</span> <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> index) <a name="l00274"></a>00274 { <a name="l00275"></a>00275 <span class="keywordtype">double</span> *val = space_->getValueAddressAtIndex(state_, index); <a name="l00276"></a>00276 <span class="keywordflow">if</span> (!val) <a name="l00277"></a>00277 <span class="keywordflow">throw</span> <a class="code" href="classompl_1_1Exception.html" title="The exception type for ompl.">Exception</a>(<span class="stringliteral">"Index out of bounds"</span>); <a name="l00278"></a>00278 <span class="keywordflow">return</span> *val; <a name="l00279"></a>00279 } <a name="l00280"></a>00280 <a name="l00282"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html#a780b9677561db41bcf935d2257bd3b44">00282</a> <span class="keywordtype">double</span> <a class="code" href="classompl_1_1base_1_1ScopedState.html#a19f24f28908474678e5fef9a9f64abf1" title="Extract a state that corresponds to the components in state space s. Those components will have the s...">operator[]</a>(<span class="keyword">const</span> <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> index)<span class="keyword"> const</span> <a name="l00283"></a>00283 <span class="keyword"> </span>{ <a name="l00284"></a>00284 <span class="keyword">const</span> <span class="keywordtype">double</span> *val = space_->getValueAddressAtIndex(state_, index); <a name="l00285"></a>00285 <span class="keywordflow">if</span> (!val) <a name="l00286"></a>00286 <span class="keywordflow">throw</span> <a class="code" href="classompl_1_1Exception.html" title="The exception type for ompl.">Exception</a>(<span class="stringliteral">"Index out of bounds"</span>); <a name="l00287"></a>00287 <span class="keywordflow">return</span> *val; <a name="l00288"></a>00288 } <a name="l00289"></a>00289 <a name="l00291"></a>00291 <span class="keyword">template</span><<span class="keyword">class</span> O> <a name="l00292"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html#a9d8ea405c0cb1ffd7e143e15220f617c">00292</a> <span class="keywordtype">double</span> <a class="code" href="classompl_1_1base_1_1ScopedState.html#a9d8ea405c0cb1ffd7e143e15220f617c" title="Compute the distance to another state.">distance</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1ScopedState.html" title="Definition of a scoped state.">ScopedState<O></a> &other)<span class="keyword"> const</span> <a name="l00293"></a>00293 <span class="keyword"> </span>{ <a name="l00294"></a>00294 BOOST_CONCEPT_ASSERT((boost::Convertible<O*, StateSpace*>)); <a name="l00295"></a>00295 BOOST_CONCEPT_ASSERT((boost::Convertible<typename O::StateType*, State*>)); <a name="l00296"></a>00296 <span class="keywordflow">return</span> <a class="code" href="classompl_1_1base_1_1ScopedState.html#a9d8ea405c0cb1ffd7e143e15220f617c" title="Compute the distance to another state.">distance</a>(other.<a class="code" href="classompl_1_1base_1_1ScopedState.html#afc13c57b8379540de664491aa7113c3a" title="Returns a pointer to the contained state.">get</a>()); <a name="l00297"></a>00297 } <a name="l00298"></a>00298 <a name="l00300"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html#a533a7aba977907512e265270957626b7">00300</a> <span class="keywordtype">double</span> <a class="code" href="classompl_1_1base_1_1ScopedState.html#a9d8ea405c0cb1ffd7e143e15220f617c" title="Compute the distance to another state.">distance</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *state)<span class="keyword"> const</span> <a name="l00301"></a>00301 <span class="keyword"> </span>{ <a name="l00302"></a>00302 <span class="keywordflow">return</span> space_->distance(static_cast<const State*>(state_), state); <a name="l00303"></a>00303 } <a name="l00304"></a>00304 <a name="l00306"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html#a75426bd77afe65e28a70a64bf78ac8cb">00306</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1base_1_1ScopedState.html#a75426bd77afe65e28a70a64bf78ac8cb" title="Set this state to a random value (uniform)">random</a>(<span class="keywordtype">void</span>) <a name="l00307"></a>00307 { <a name="l00308"></a>00308 <span class="keywordflow">if</span> (!sampler_) <a name="l00309"></a>00309 sampler_ = space_->allocStateSampler(); <a name="l00310"></a>00310 sampler_->sampleUniform(state_); <a name="l00311"></a>00311 } <a name="l00312"></a>00312 <a name="l00314"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html#a6f3ccf027ee8319e027b96d5da772414">00314</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1base_1_1ScopedState.html#a6f3ccf027ee8319e027b96d5da772414" title="Enforce the bounds on the maintained state.">enforceBounds</a>(<span class="keywordtype">void</span>) <a name="l00315"></a>00315 { <a name="l00316"></a>00316 space_->enforceBounds(state_); <a name="l00317"></a>00317 } <a name="l00318"></a>00318 <a name="l00320"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html#acf51db7a9416f79adaa06f9fa35e4976">00320</a> <span class="keywordtype">bool</span> <a class="code" href="classompl_1_1base_1_1ScopedState.html#acf51db7a9416f79adaa06f9fa35e4976" title="Check if the maintained state satisfies bounds.">satisfiesBounds</a>(<span class="keywordtype">void</span>)<span class="keyword"> const</span> <a name="l00321"></a>00321 <span class="keyword"> </span>{ <a name="l00322"></a>00322 <span class="keywordflow">return</span> space_->satisfiesBounds(state_); <a name="l00323"></a>00323 } <a name="l00324"></a>00324 <a name="l00328"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html#aef18b4a578e37cf4221e1835faa71e26">00328</a> std::vector<double> <a class="code" href="classompl_1_1base_1_1ScopedState.html#aef18b4a578e37cf4221e1835faa71e26" title="Return the real values corresponding to this state. If a conversion is not possible, an exception is thrown.">reals</a>(<span class="keywordtype">void</span>)<span class="keyword"> const</span> <a name="l00329"></a>00329 <span class="keyword"> </span>{ <a name="l00330"></a>00330 std::vector<double> r; <a name="l00331"></a>00331 <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> index = 0; <a name="l00332"></a>00332 <span class="keywordflow">while</span> (<span class="keywordtype">double</span> *va = space_->getValueAddressAtIndex(state_, index++)) <a name="l00333"></a>00333 r.push_back(*va); <a name="l00334"></a>00334 <span class="keywordflow">return</span> r; <a name="l00335"></a>00335 } <a name="l00336"></a>00336 <a name="l00338"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html#ad3e8b7908ff5d912a6698654f2959a57">00338</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1base_1_1ScopedState.html#ad3e8b7908ff5d912a6698654f2959a57" title="Print this state to a stream.">print</a>(std::ostream &out = std::cout)<span class="keyword"> const</span> <a name="l00339"></a>00339 <span class="keyword"> </span>{ <a name="l00340"></a>00340 space_->printState(state_, out); <a name="l00341"></a>00341 } <a name="l00342"></a>00342 <a name="l00344"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html#a77401118b5ce7e73800de21dbfdae755">00344</a> <a class="code" href="classompl_1_1base_1_1ScopedState.html#a5a33e968e72f92b5e25bdf3e2feaa0c6" title="The type of the contained state.">StateType</a>& <a class="code" href="classompl_1_1base_1_1ScopedState.html#a77401118b5ce7e73800de21dbfdae755" title="De-references to the contained state.">operator*</a>(<span class="keywordtype">void</span>) <a name="l00345"></a>00345 { <a name="l00346"></a>00346 <span class="keywordflow">return</span> *state_; <a name="l00347"></a>00347 } <a name="l00348"></a>00348 <a name="l00350"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html#a1979076ff08b70decdc6295ea8544953">00350</a> <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1ScopedState.html#a5a33e968e72f92b5e25bdf3e2feaa0c6" title="The type of the contained state.">StateType</a>& <a class="code" href="classompl_1_1base_1_1ScopedState.html#a77401118b5ce7e73800de21dbfdae755" title="De-references to the contained state.">operator*</a>(<span class="keywordtype">void</span>)<span class="keyword"> const</span> <a name="l00351"></a>00351 <span class="keyword"> </span>{ <a name="l00352"></a>00352 <span class="keywordflow">return</span> *state_; <a name="l00353"></a>00353 } <a name="l00354"></a>00354 <a name="l00356"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html#a83a1fa65a1e16144d76048d935a05f3c">00356</a> <a class="code" href="classompl_1_1base_1_1ScopedState.html#a5a33e968e72f92b5e25bdf3e2feaa0c6" title="The type of the contained state.">StateType</a>* <a class="code" href="classompl_1_1base_1_1ScopedState.html#a83a1fa65a1e16144d76048d935a05f3c" title="Returns a pointer to the contained state.">operator-></a>(<span class="keywordtype">void</span>) <a name="l00357"></a>00357 { <a name="l00358"></a>00358 <span class="keywordflow">return</span> state_; <a name="l00359"></a>00359 } <a name="l00360"></a>00360 <a name="l00362"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html#adc86b0e73af68ad84e6d9dae5c993816">00362</a> <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1ScopedState.html#a5a33e968e72f92b5e25bdf3e2feaa0c6" title="The type of the contained state.">StateType</a>* <a class="code" href="classompl_1_1base_1_1ScopedState.html#a83a1fa65a1e16144d76048d935a05f3c" title="Returns a pointer to the contained state.">operator-></a>(<span class="keywordtype">void</span>)<span class="keyword"> const</span> <a name="l00363"></a>00363 <span class="keyword"> </span>{ <a name="l00364"></a>00364 <span class="keywordflow">return</span> state_; <a name="l00365"></a>00365 } <a name="l00366"></a>00366 <a name="l00368"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html#afc13c57b8379540de664491aa7113c3a">00368</a> <a class="code" href="classompl_1_1base_1_1ScopedState.html#a5a33e968e72f92b5e25bdf3e2feaa0c6" title="The type of the contained state.">StateType</a>* <span class="keyword">get</span>(void) <a name="l00369"></a>00369 { <a name="l00370"></a>00370 <span class="keywordflow">return</span> state_; <a name="l00371"></a>00371 } <a name="l00372"></a>00372 <a name="l00374"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html#a7e7ddbe1ddc9ab35eec46677da16b6d1">00374</a> <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1ScopedState.html#a5a33e968e72f92b5e25bdf3e2feaa0c6" title="The type of the contained state.">StateType</a>* <span class="keyword">get</span>(void) <span class="keyword">const</span> <a name="l00375"></a>00375 { <a name="l00376"></a>00376 <span class="keywordflow">return</span> state_; <a name="l00377"></a>00377 } <a name="l00378"></a>00378 <a name="l00380"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html#aac8391ea166a4e2ee89d274672224f2d">00380</a> <a class="code" href="classompl_1_1base_1_1ScopedState.html#a5a33e968e72f92b5e25bdf3e2feaa0c6" title="The type of the contained state.">StateType</a>* <a class="code" href="classompl_1_1base_1_1ScopedState.html#aac8391ea166a4e2ee89d274672224f2d" title="Returns a pointer to the contained state (used for Python bindings)">operator()</a>(<span class="keywordtype">void</span>)<span class="keyword"> const</span> <a name="l00381"></a>00381 <span class="keyword"> </span>{ <a name="l00382"></a>00382 <span class="keywordflow">return</span> state_; <a name="l00383"></a>00383 } <a name="l00384"></a>00384 <a name="l00385"></a>00385 <span class="keyword">private</span>: <a name="l00386"></a>00386 <a name="l00387"></a>00387 <a class="code" href="classompl_1_1base_1_1StateSpacePtr.html" title="A boost shared pointer wrapper for ompl::base::StateSpace.">StateSpacePtr</a> space_; <a name="l00388"></a>00388 <a class="code" href="classompl_1_1base_1_1StateSamplerPtr.html" title="A boost shared pointer wrapper for ompl::base::StateSampler.">StateSamplerPtr</a> sampler_; <a name="l00389"></a>00389 <a class="code" href="classompl_1_1base_1_1ScopedState.html#a5a33e968e72f92b5e25bdf3e2feaa0c6" title="The type of the contained state.">StateType</a> *state_; <a name="l00390"></a>00390 }; <a name="l00391"></a>00391 <a name="l00467"></a>00467 <span class="keyword">template</span><<span class="keyword">class</span> T> <a name="l00468"></a>00468 <span class="keyword">inline</span> <a name="l00469"></a><a class="code" href="group__stateAndSpaceOperators.html#ga17c5c6bebdc795305757693385c0593a">00469</a> std::ostream& operator<<(std::ostream &out, const ScopedState<T> &state) <a name="l00470"></a>00470 { <a name="l00471"></a>00471 state.print(out); <a name="l00472"></a>00472 <span class="keywordflow">return</span> out; <a name="l00473"></a>00473 } <a name="l00474"></a>00474 <a name="l00483"></a>00483 <span class="keyword">template</span><<span class="keyword">class</span> T, <span class="keyword">class</span> Y> <a name="l00484"></a>00484 <span class="keyword">inline</span> <a name="l00485"></a><a class="code" href="group__stateAndSpaceOperators.html#gaf8a616d4ac7f5f856d8a5fe95bb6ae73">00485</a> <a class="code" href="classompl_1_1base_1_1ScopedState.html" title="Definition of a scoped state.">ScopedState<T></a>& operator<<(ScopedState<T> &to, <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1ScopedState.html" title="Definition of a scoped state.">ScopedState<Y></a> &from) <a name="l00486"></a>00486 { <a name="l00487"></a>00487 <a class="code" href="namespaceompl_1_1base.html#a28f47f0634ddee5c73674b5e0fb2d9aa" title="Copy data from source (state from space sourceS) to dest (state from space destS) on a component by c...">copyStateData</a>(to.getSpace(), to.get(), from.getSpace(), from.get()); <a name="l00488"></a>00488 <span class="keywordflow">return</span> to; <a name="l00489"></a>00489 } <a name="l00490"></a>00490 <a name="l00499"></a>00499 <span class="keyword">template</span><<span class="keyword">class</span> T, <span class="keyword">class</span> Y> <a name="l00500"></a>00500 <span class="keyword">inline</span> <a name="l00501"></a><a class="code" href="group__stateAndSpaceOperators.html#ga5d41ba2026ef0c1de62ac81813ca7046">00501</a> <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1ScopedState.html" title="Definition of a scoped state.">ScopedState<T></a>& <a class="code" href="group__stateAndSpaceOperators.html#ga5d41ba2026ef0c1de62ac81813ca7046" title="This is a fancy version of the assignment operator. It is a partial assignment, in some sense...">operator>></a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1ScopedState.html" title="Definition of a scoped state.">ScopedState<T></a> &from, <a class="code" href="classompl_1_1base_1_1ScopedState.html" title="Definition of a scoped state.">ScopedState<Y></a> &to) <a name="l00502"></a>00502 { <a name="l00503"></a>00503 <a class="code" href="namespaceompl_1_1base.html#a28f47f0634ddee5c73674b5e0fb2d9aa" title="Copy data from source (state from space sourceS) to dest (state from space destS) on a component by c...">copyStateData</a>(to.<a class="code" href="classompl_1_1base_1_1ScopedState.html#abcc9537b30fb02b67f7e68dd82c07970" title="Get the state space that the state corresponds to.">getSpace</a>(), to.<a class="code" href="classompl_1_1base_1_1ScopedState.html#afc13c57b8379540de664491aa7113c3a" title="Returns a pointer to the contained state.">get</a>(), from.<a class="code" href="classompl_1_1base_1_1ScopedState.html#abcc9537b30fb02b67f7e68dd82c07970" title="Get the state space that the state corresponds to.">getSpace</a>(), from.<a class="code" href="classompl_1_1base_1_1ScopedState.html#afc13c57b8379540de664491aa7113c3a" title="Returns a pointer to the contained state.">get</a>()); <a name="l00504"></a>00504 <span class="keywordflow">return</span> from; <a name="l00505"></a>00505 } <a name="l00506"></a>00506 <a name="l00511"></a>00511 <span class="keyword">template</span><<span class="keyword">class</span> T, <span class="keyword">class</span> Y> <a name="l00512"></a>00512 <span class="keyword">inline</span> <a name="l00513"></a><a class="code" href="group__stateAndSpaceOperators.html#ga6db8232ebedcab3a50779bc50a6b495c">00513</a> <a class="code" href="classompl_1_1base_1_1ScopedState.html" title="Definition of a scoped state.">ScopedState<></a> <a class="code" href="group__stateAndSpaceOperators.html#ga6db8232ebedcab3a50779bc50a6b495c" title="Given state a from state space A and state b from state space B, construct a state from state space A...">operator^</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1ScopedState.html" title="Definition of a scoped state.">ScopedState<T></a> &a, <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1ScopedState.html" title="Definition of a scoped state.">ScopedState<Y></a> &b) <a name="l00514"></a>00514 { <a name="l00515"></a>00515 <a class="code" href="classompl_1_1base_1_1ScopedState.html" title="Definition of a scoped state.">ScopedState<></a> r(a.<a class="code" href="classompl_1_1base_1_1ScopedState.html#abcc9537b30fb02b67f7e68dd82c07970" title="Get the state space that the state corresponds to.">getSpace</a>() + b.<a class="code" href="classompl_1_1base_1_1ScopedState.html#abcc9537b30fb02b67f7e68dd82c07970" title="Get the state space that the state corresponds to.">getSpace</a>()); <a name="l00516"></a>00516 <span class="keywordflow">return</span> r << a << b; <a name="l00517"></a>00517 } <a name="l00518"></a>00518 <a name="l00521"></a>00521 <span class="keyword">template</span><<span class="keyword">class</span> T> <a name="l00522"></a><a class="code" href="classompl_1_1base_1_1ScopedState.html#a19f24f28908474678e5fef9a9f64abf1">00522</a> <a class="code" href="classompl_1_1base_1_1ScopedState.html" title="Definition of a scoped state.">ScopedState<></a> <a class="code" href="classompl_1_1base_1_1ScopedState.html#a19f24f28908474678e5fef9a9f64abf1" title="Extract a state that corresponds to the components in state space s. Those components will have the s...">ScopedState<T>::operator[]</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1StateSpacePtr.html" title="A boost shared pointer wrapper for ompl::base::StateSpace.">StateSpacePtr</a> &s)<span class="keyword"> const</span> <a name="l00523"></a>00523 <span class="keyword"> </span>{ <a name="l00524"></a>00524 <a class="code" href="classompl_1_1base_1_1ScopedState.html" title="Definition of a scoped state.">ScopedState<></a> r(s); <a name="l00525"></a>00525 <span class="keywordflow">return</span> r << *<span class="keyword">this</span>; <a name="l00526"></a>00526 } <a name="l00527"></a>00527 <a name="l00529"></a><a class="code" href="namespaceompl_1_1base.html#a2366ab3e3b91738fe0b51bafabf50a83">00529</a> <span class="keyword">typedef</span> boost::shared_ptr< ScopedState<> > <a class="code" href="namespaceompl_1_1base.html#a2366ab3e3b91738fe0b51bafabf50a83" title="Shared pointer to a ScopedState<>">ScopedStatePtr</a>; <a name="l00530"></a>00530 } <a name="l00531"></a>00531 } <a name="l00532"></a>00532 <a name="l00533"></a>00533 <span class="preprocessor">#endif</span> </pre></div></div> </div> <!-- window showing the filter options --> <div id="MSearchSelectWindow" onmouseover="return searchBox.OnSearchSelectShow()" onmouseout="return searchBox.OnSearchSelectHide()" onkeydown="return searchBox.OnSearchSelectKey(event)"> <a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(0)"><span class="SelectionMark"> </span>All</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(1)"><span class="SelectionMark"> </span>Classes</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(2)"><span class="SelectionMark"> </span>Namespaces</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(3)"><span class="SelectionMark"> </span>Functions</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(4)"><span class="SelectionMark"> </span>Variables</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(5)"><span class="SelectionMark"> </span>Typedefs</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(6)"><span class="SelectionMark"> </span>Enumerations</a><a class="SelectItem" href="javascript:void(0)" onclick="searchBox.OnSelectItem(7)"><span class="SelectionMark"> </span>Enumerator</a></div> <!-- iframe showing the search results (closed by default) --> <div id="MSearchResultsWindow"> <iframe src="javascript:void(0)" frameborder="0" name="MSearchResults" id="MSearchResults"> </iframe> </div> </div> <div class="footer span-22 push-2 last"> <a href="http://www.kavrakilab.org">Physical and Biological Computing Group</a> • <a href="http://www.cs.rice.edu">Department of Computer Science</a> • <a href="http://www.rice.edu">Rice University</a><br> <div class="gray">Generated on Sun Oct 9 2011 23:04:39 by <a href="http://www.doxygen.org/index.html">doxygen</a> 1.7.4</div> </div> </div> </body> </html>