<!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: ompl::base::ScopedState< T > Class Template Reference</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="namespaceompl.html">ompl</a> </li> <li class="navelem"><a class="el" href="namespaceompl_1_1base.html">base</a> </li> <li class="navelem"><a class="el" href="classompl_1_1base_1_1ScopedState.html">ScopedState</a> </li> </ul> </div> </div> <div class="header"> <div class="summary"> <a href="#pub-types">Public Types</a> | <a href="#pub-methods">Public Member Functions</a> </div> <div class="headertitle"> <div class="title">ompl::base::ScopedState< T > Class Template Reference</div> </div> </div> <div class="contents"> <!-- doxytag: class="ompl::base::ScopedState" --> <p>Definition of a scoped state. <a href="classompl_1_1base_1_1ScopedState.html#details">More...</a></p> <p><code>#include <<a class="el" href="ScopedState_8h_source.html">ScopedState.h</a>></code></p> <p><a href="classompl_1_1base_1_1ScopedState-members.html">List of all members.</a></p> <table class="memberdecls"> <tr><td colspan="2"><h2><a name="pub-types"></a> Public Types</h2></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a5a33e968e72f92b5e25bdf3e2feaa0c6"></a><!-- doxytag: member="ompl::base::ScopedState::StateType" ref="a5a33e968e72f92b5e25bdf3e2feaa0c6" args="" --> typedef T::StateType </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ScopedState.html#a5a33e968e72f92b5e25bdf3e2feaa0c6">StateType</a></td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">The type of the contained state. <br/></td></tr> <tr><td colspan="2"><h2><a name="pub-methods"></a> Public Member Functions</h2></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a7d5d0be9ab08141bdc4b896f6a0fcbfd"></a><!-- doxytag: member="ompl::base::ScopedState::ScopedState" ref="a7d5d0be9ab08141bdc4b896f6a0fcbfd" args="(const SpaceInformationPtr &si)" -->  </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ScopedState.html#a7d5d0be9ab08141bdc4b896f6a0fcbfd">ScopedState</a> (const <a class="el" href="classompl_1_1base_1_1SpaceInformationPtr.html">SpaceInformationPtr</a> &si)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Given the space that we are working with, allocate a state from the corresponding state space. <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a983420b093e57a2c3250e1b31c382047"></a><!-- doxytag: member="ompl::base::ScopedState::ScopedState" ref="a983420b093e57a2c3250e1b31c382047" args="(const StateSpacePtr &space)" -->  </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ScopedState.html#a983420b093e57a2c3250e1b31c382047">ScopedState</a> (const <a class="el" href="classompl_1_1base_1_1StateSpacePtr.html">StateSpacePtr</a> &space)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Given the state space that we are working with, allocate a state. <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="aa6f35a339ef5e31b0a163a829f80f5b1"></a><!-- doxytag: member="ompl::base::ScopedState::ScopedState" ref="aa6f35a339ef5e31b0a163a829f80f5b1" args="(const ScopedState< T > &other)" -->  </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ScopedState.html#aa6f35a339ef5e31b0a163a829f80f5b1">ScopedState</a> (const <a class="el" href="classompl_1_1base_1_1ScopedState.html">ScopedState</a>< T > &other)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Copy constructor. <br/></td></tr> <tr><td class="memTemplParams" colspan="2"><a class="anchor" id="a4cada6ab0b1126666ff59e17bf7cb629"></a><!-- doxytag: member="ompl::base::ScopedState::ScopedState" ref="a4cada6ab0b1126666ff59e17bf7cb629" args="(const ScopedState< O > &other)" --> template<class O > </td></tr> <tr><td class="memTemplItemLeft" align="right" valign="top"> </td><td class="memTemplItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ScopedState.html#a4cada6ab0b1126666ff59e17bf7cb629">ScopedState</a> (const <a class="el" href="classompl_1_1base_1_1ScopedState.html">ScopedState</a>< O > &other)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Copy constructor that allows instantiation from states of other type. <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a0d44eaea9444aba5c696c58187a755bd"></a><!-- doxytag: member="ompl::base::ScopedState::ScopedState" ref="a0d44eaea9444aba5c696c58187a755bd" args="(const StateSpacePtr &space, const State *state)" -->  </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ScopedState.html#a0d44eaea9444aba5c696c58187a755bd">ScopedState</a> (const <a class="el" href="classompl_1_1base_1_1StateSpacePtr.html">StateSpacePtr</a> &space, const <a class="el" href="classompl_1_1base_1_1State.html">State</a> *state)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Given the state space that we are working with, allocate a state and fill that state with a given value. <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ab79a4c8ea0b1af9fb58edebd77dbf6a0"></a><!-- doxytag: member="ompl::base::ScopedState::~ScopedState" ref="ab79a4c8ea0b1af9fb58edebd77dbf6a0" args="(void)" -->  </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ScopedState.html#ab79a4c8ea0b1af9fb58edebd77dbf6a0">~ScopedState</a> (void)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Free the memory of the internally allocated state. <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="abcc9537b30fb02b67f7e68dd82c07970"></a><!-- doxytag: member="ompl::base::ScopedState::getSpace" ref="abcc9537b30fb02b67f7e68dd82c07970" args="(void) const " --> const <a class="el" href="classompl_1_1base_1_1StateSpacePtr.html">StateSpacePtr</a> & </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ScopedState.html#abcc9537b30fb02b67f7e68dd82c07970">getSpace</a> (void) const </td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Get the state space that the state corresponds to. <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ac4fb27b32ef5e413b1a2ad8cfc84f7a4"></a><!-- doxytag: member="ompl::base::ScopedState::operator=" ref="ac4fb27b32ef5e413b1a2ad8cfc84f7a4" args="(const ScopedState< T > &other)" --> <a class="el" href="classompl_1_1base_1_1ScopedState.html">ScopedState</a>< T > & </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ScopedState.html#ac4fb27b32ef5e413b1a2ad8cfc84f7a4">operator=</a> (const <a class="el" href="classompl_1_1base_1_1ScopedState.html">ScopedState</a>< T > &other)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Assignment operator. <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="af81845da48cd2995b0786c1a2135e6a6"></a><!-- doxytag: member="ompl::base::ScopedState::operator=" ref="af81845da48cd2995b0786c1a2135e6a6" args="(const State *other)" --> <a class="el" href="classompl_1_1base_1_1ScopedState.html">ScopedState</a>< T > & </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ScopedState.html#af81845da48cd2995b0786c1a2135e6a6">operator=</a> (const <a class="el" href="classompl_1_1base_1_1State.html">State</a> *other)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Assignment operator. <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a2a942938fd27f567e50c882448a36249"></a><!-- doxytag: member="ompl::base::ScopedState::operator=" ref="a2a942938fd27f567e50c882448a36249" args="(const State &other)" --> <a class="el" href="classompl_1_1base_1_1ScopedState.html">ScopedState</a>< T > & </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ScopedState.html#a2a942938fd27f567e50c882448a36249">operator=</a> (const <a class="el" href="classompl_1_1base_1_1State.html">State</a> &other)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Assignment operator. <br/></td></tr> <tr><td class="memTemplParams" colspan="2"><a class="anchor" id="a3da3e6438bde92cad7d980c8801f4f1e"></a><!-- doxytag: member="ompl::base::ScopedState::operator=" ref="a3da3e6438bde92cad7d980c8801f4f1e" args="(const ScopedState< O > &other)" --> template<class O > </td></tr> <tr><td class="memTemplItemLeft" align="right" valign="top"><a class="el" href="classompl_1_1base_1_1ScopedState.html">ScopedState</a>< T > & </td><td class="memTemplItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ScopedState.html#a3da3e6438bde92cad7d980c8801f4f1e">operator=</a> (const <a class="el" href="classompl_1_1base_1_1ScopedState.html">ScopedState</a>< O > &other)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Assignment operator that allows conversion of states. <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a483e5d636b2955b73f4642e6b90cda9f"></a><!-- doxytag: member="ompl::base::ScopedState::operator=" ref="a483e5d636b2955b73f4642e6b90cda9f" args="(const std::vector< double > &reals)" --> <a class="el" href="classompl_1_1base_1_1ScopedState.html">ScopedState</a>< T > & </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ScopedState.html#a483e5d636b2955b73f4642e6b90cda9f">operator=</a> (const std::vector< double > &reals)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Partial assignment operator. Only sets the double values of the state to specified real values. <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a50cbd5b4ee7fca852b2e6279f0980f8a"></a><!-- doxytag: member="ompl::base::ScopedState::operator=" ref="a50cbd5b4ee7fca852b2e6279f0980f8a" args="(const double value)" --> <a class="el" href="classompl_1_1base_1_1ScopedState.html">ScopedState</a>< T > & </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ScopedState.html#a50cbd5b4ee7fca852b2e6279f0980f8a">operator=</a> (const double value)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Partial assignment operator. Only sets the double values of the state to a fixed value. <br/></td></tr> <tr><td class="memTemplParams" colspan="2"><a class="anchor" id="a70cc12c65d1a069362d79d22d09fc1f9"></a><!-- doxytag: member="ompl::base::ScopedState::operator==" ref="a70cc12c65d1a069362d79d22d09fc1f9" args="(const ScopedState< O > &other) const " --> template<class O > </td></tr> <tr><td class="memTemplItemLeft" align="right" valign="top">bool </td><td class="memTemplItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ScopedState.html#a70cc12c65d1a069362d79d22d09fc1f9">operator==</a> (const <a class="el" href="classompl_1_1base_1_1ScopedState.html">ScopedState</a>< O > &other) const </td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Checks equality of two states. <br/></td></tr> <tr><td class="memTemplParams" colspan="2"><a class="anchor" id="ae6f4c9e2d5d072aeda6fe5953c17ed64"></a><!-- doxytag: member="ompl::base::ScopedState::operator!=" ref="ae6f4c9e2d5d072aeda6fe5953c17ed64" args="(const ScopedState< O > &other) const " --> template<class O > </td></tr> <tr><td class="memTemplItemLeft" align="right" valign="top">bool </td><td class="memTemplItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ScopedState.html#ae6f4c9e2d5d072aeda6fe5953c17ed64">operator!=</a> (const <a class="el" href="classompl_1_1base_1_1ScopedState.html">ScopedState</a>< O > &other) const </td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Checks equality of two states. <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a19f24f28908474678e5fef9a9f64abf1"></a><!-- doxytag: member="ompl::base::ScopedState::operator[]" ref="a19f24f28908474678e5fef9a9f64abf1" args="(const StateSpacePtr &s) const " --> <a class="el" href="classompl_1_1base_1_1ScopedState.html">ScopedState</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ScopedState.html#a19f24f28908474678e5fef9a9f64abf1">operator[]</a> (const <a class="el" href="classompl_1_1base_1_1StateSpacePtr.html">StateSpacePtr</a> &s) const </td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Extract a state that corresponds to the components in state space <em>s</em>. Those components will have the same value as the current state (only the ones included in the current state; others will be uninitialised) <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a58359e139ad823db181bc12fbcf3aafd"></a><!-- doxytag: member="ompl::base::ScopedState::operator[]" ref="a58359e139ad823db181bc12fbcf3aafd" args="(const unsigned int index)" --> double & </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ScopedState.html#a58359e139ad823db181bc12fbcf3aafd">operator[]</a> (const unsigned int index)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Access the <em>index<sup>th</sup></em> double value this state contains. <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a780b9677561db41bcf935d2257bd3b44"></a><!-- doxytag: member="ompl::base::ScopedState::operator[]" ref="a780b9677561db41bcf935d2257bd3b44" args="(const unsigned int index) const " --> double </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ScopedState.html#a780b9677561db41bcf935d2257bd3b44">operator[]</a> (const unsigned int index) const </td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Access the <em>index<sup>th</sup></em> double value this state contains. <br/></td></tr> <tr><td class="memTemplParams" colspan="2"><a class="anchor" id="a9d8ea405c0cb1ffd7e143e15220f617c"></a><!-- doxytag: member="ompl::base::ScopedState::distance" ref="a9d8ea405c0cb1ffd7e143e15220f617c" args="(const ScopedState< O > &other) const " --> template<class O > </td></tr> <tr><td class="memTemplItemLeft" align="right" valign="top">double </td><td class="memTemplItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ScopedState.html#a9d8ea405c0cb1ffd7e143e15220f617c">distance</a> (const <a class="el" href="classompl_1_1base_1_1ScopedState.html">ScopedState</a>< O > &other) const </td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Compute the distance to another state. <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a533a7aba977907512e265270957626b7"></a><!-- doxytag: member="ompl::base::ScopedState::distance" ref="a533a7aba977907512e265270957626b7" args="(const State *state) const " --> double </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ScopedState.html#a533a7aba977907512e265270957626b7">distance</a> (const <a class="el" href="classompl_1_1base_1_1State.html">State</a> *state) const </td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Compute the distance to another state. <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a75426bd77afe65e28a70a64bf78ac8cb"></a><!-- doxytag: member="ompl::base::ScopedState::random" ref="a75426bd77afe65e28a70a64bf78ac8cb" args="(void)" --> void </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ScopedState.html#a75426bd77afe65e28a70a64bf78ac8cb">random</a> (void)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Set this state to a random value (uniform) <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a6f3ccf027ee8319e027b96d5da772414"></a><!-- doxytag: member="ompl::base::ScopedState::enforceBounds" ref="a6f3ccf027ee8319e027b96d5da772414" args="(void)" --> void </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ScopedState.html#a6f3ccf027ee8319e027b96d5da772414">enforceBounds</a> (void)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Enforce the bounds on the maintained state. <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="acf51db7a9416f79adaa06f9fa35e4976"></a><!-- doxytag: member="ompl::base::ScopedState::satisfiesBounds" ref="acf51db7a9416f79adaa06f9fa35e4976" args="(void) const " --> bool </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ScopedState.html#acf51db7a9416f79adaa06f9fa35e4976">satisfiesBounds</a> (void) const </td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Check if the maintained state satisfies bounds. <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="aef18b4a578e37cf4221e1835faa71e26"></a><!-- doxytag: member="ompl::base::ScopedState::reals" ref="aef18b4a578e37cf4221e1835faa71e26" args="(void) const " --> std::vector< double > </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ScopedState.html#aef18b4a578e37cf4221e1835faa71e26">reals</a> (void) const </td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Return the real values corresponding to this state. If a conversion is not possible, an exception is thrown. <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="ad3e8b7908ff5d912a6698654f2959a57"></a><!-- doxytag: member="ompl::base::ScopedState::print" ref="ad3e8b7908ff5d912a6698654f2959a57" args="(std::ostream &out=std::cout) const " --> void </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ScopedState.html#ad3e8b7908ff5d912a6698654f2959a57">print</a> (std::ostream &out=std::cout) const </td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Print this state to a stream. <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a77401118b5ce7e73800de21dbfdae755"></a><!-- doxytag: member="ompl::base::ScopedState::operator*" ref="a77401118b5ce7e73800de21dbfdae755" args="(void)" --> <a class="el" href="classompl_1_1base_1_1ScopedState.html#a5a33e968e72f92b5e25bdf3e2feaa0c6">StateType</a> & </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ScopedState.html#a77401118b5ce7e73800de21dbfdae755">operator*</a> (void)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">De-references to the contained state. <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a1979076ff08b70decdc6295ea8544953"></a><!-- doxytag: member="ompl::base::ScopedState::operator*" ref="a1979076ff08b70decdc6295ea8544953" args="(void) const " --> const <a class="el" href="classompl_1_1base_1_1ScopedState.html#a5a33e968e72f92b5e25bdf3e2feaa0c6">StateType</a> & </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ScopedState.html#a1979076ff08b70decdc6295ea8544953">operator*</a> (void) const </td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">De-references to the contained state. <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a83a1fa65a1e16144d76048d935a05f3c"></a><!-- doxytag: member="ompl::base::ScopedState::operator->" ref="a83a1fa65a1e16144d76048d935a05f3c" args="(void)" --> <a class="el" href="classompl_1_1base_1_1ScopedState.html#a5a33e968e72f92b5e25bdf3e2feaa0c6">StateType</a> * </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ScopedState.html#a83a1fa65a1e16144d76048d935a05f3c">operator-></a> (void)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Returns a pointer to the contained state. <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="adc86b0e73af68ad84e6d9dae5c993816"></a><!-- doxytag: member="ompl::base::ScopedState::operator->" ref="adc86b0e73af68ad84e6d9dae5c993816" args="(void) const " --> const <a class="el" href="classompl_1_1base_1_1ScopedState.html#a5a33e968e72f92b5e25bdf3e2feaa0c6">StateType</a> * </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ScopedState.html#adc86b0e73af68ad84e6d9dae5c993816">operator-></a> (void) const </td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Returns a pointer to the contained state. <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="afc13c57b8379540de664491aa7113c3a"></a><!-- doxytag: member="ompl::base::ScopedState::get" ref="afc13c57b8379540de664491aa7113c3a" args="(void)" --> <a class="el" href="classompl_1_1base_1_1ScopedState.html#a5a33e968e72f92b5e25bdf3e2feaa0c6">StateType</a> * </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ScopedState.html#afc13c57b8379540de664491aa7113c3a">get</a> (void)</td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Returns a pointer to the contained state. <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a7e7ddbe1ddc9ab35eec46677da16b6d1"></a><!-- doxytag: member="ompl::base::ScopedState::get" ref="a7e7ddbe1ddc9ab35eec46677da16b6d1" args="(void) const " --> const <a class="el" href="classompl_1_1base_1_1ScopedState.html#a5a33e968e72f92b5e25bdf3e2feaa0c6">StateType</a> * </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ScopedState.html#a7e7ddbe1ddc9ab35eec46677da16b6d1">get</a> (void) const </td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Returns a pointer to the contained state. <br/></td></tr> <tr><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="aac8391ea166a4e2ee89d274672224f2d"></a><!-- doxytag: member="ompl::base::ScopedState::operator()" ref="aac8391ea166a4e2ee89d274672224f2d" args="(void) const " --> <a class="el" href="classompl_1_1base_1_1ScopedState.html#a5a33e968e72f92b5e25bdf3e2feaa0c6">StateType</a> * </td><td class="memItemRight" valign="bottom"><a class="el" href="classompl_1_1base_1_1ScopedState.html#aac8391ea166a4e2ee89d274672224f2d">operator()</a> (void) const </td></tr> <tr><td class="mdescLeft"> </td><td class="mdescRight">Returns a pointer to the contained state (used for Python bindings) <br/></td></tr> </table> <hr/><a name="details" id="details"></a><h2>Detailed Description</h2> <div class="textblock"><h3>template<class T = StateSpace><br/> class ompl::base::ScopedState< T ></h3> <p>Definition of a scoped state. </p> <p>This class allocates a state of a desired type using the allocation mechanism of the corresponding state space. The state is then freed when the instance goes out of scope using the corresponding free mechanism. </p> <p>Definition at line <a class="el" href="ScopedState_8h_source.html#l00056">56</a> of file <a class="el" href="ScopedState_8h_source.html">ScopedState.h</a>.</p> </div><hr/>The documentation for this class was generated from the following file:<ul> <li>src/ompl/base/<a class="el" href="ScopedState_8h_source.html">ScopedState.h</a></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="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:42 by <a href="http://www.doxygen.org/index.html">doxygen</a> 1.7.4</div> </div> </div> </body> </html>