<!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/spaces/src/SO3StateSpace.cpp 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> <li class="navelem"><a class="el" href="dir_7f116b207a3e42501f874f0585585053.html">spaces</a> </li> <li class="navelem"><a class="el" href="dir_8bacea68f46bad3796bf3f4dc8ff506f.html">src</a> </li> </ul> </div> </div> <div class="header"> <div class="headertitle"> <div class="title">SO3StateSpace.cpp</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">#include "ompl/base/spaces/SO3StateSpace.h"</span> <a name="l00038"></a>00038 <span class="preprocessor">#include <algorithm></span> <a name="l00039"></a>00039 <span class="preprocessor">#include <limits></span> <a name="l00040"></a>00040 <span class="preprocessor">#include <cmath></span> <a name="l00041"></a>00041 <span class="preprocessor">#include "ompl/tools/config/MagicConstants.h"</span> <a name="l00042"></a>00042 <span class="preprocessor">#include <boost/math/constants/constants.hpp></span> <a name="l00043"></a>00043 <a name="l00044"></a>00044 <span class="keyword">static</span> <span class="keyword">const</span> <span class="keywordtype">double</span> MAX_QUATERNION_NORM_ERROR = 1e-9; <a name="l00045"></a>00045 <a name="l00046"></a><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#af5a4d02906007a810e3bbe2b442d7a2f">00046</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#af5a4d02906007a810e3bbe2b442d7a2f" title="Set the quaternion from axis-angle representation.">ompl::base::SO3StateSpace::StateType::setAxisAngle</a>(<span class="keywordtype">double</span> ax, <span class="keywordtype">double</span> ay, <span class="keywordtype">double</span> az, <span class="keywordtype">double</span> angle) <a name="l00047"></a>00047 { <a name="l00048"></a>00048 <span class="keywordtype">double</span> <a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a43d994e1775140840b42a493d8b4d0e8" title="Compute the norm of a state.">norm</a> = sqrt(ax * ax + ay * ay + az * az); <a name="l00049"></a>00049 <span class="keywordflow">if</span> (norm < MAX_QUATERNION_NORM_ERROR) <a name="l00050"></a>00050 <a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a80c975328b052ed3e3ec5b3d457cbf08" title="Set the state to identity -- no rotation.">setIdentity</a>(); <a name="l00051"></a>00051 <span class="keywordflow">else</span> <a name="l00052"></a>00052 { <a name="l00053"></a>00053 <span class="keywordtype">double</span> s = sin(angle / 2.0); <a name="l00054"></a>00054 <a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a525d64ca3f68c8e6492c6e26199d4717" title="X component of quaternion vector.">x</a> = s * ax / <a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a43d994e1775140840b42a493d8b4d0e8" title="Compute the norm of a state.">norm</a>; <a name="l00055"></a>00055 <a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#ae9e99008a6b4448e6a5e53ba42430bcd" title="Y component of quaternion vector.">y</a> = s * ay / <a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a43d994e1775140840b42a493d8b4d0e8" title="Compute the norm of a state.">norm</a>; <a name="l00056"></a>00056 <a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#ae4b1013f96d9ad164e54c758711377d0" title="Z component of quaternion vector.">z</a> = s * az / <a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a43d994e1775140840b42a493d8b4d0e8" title="Compute the norm of a state.">norm</a>; <a name="l00057"></a>00057 <a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a819bd3faba4f19b9f2f58c310c5d6e3c" title="scalar component of quaternion">w</a> = cos(angle / 2.0); <a name="l00058"></a>00058 } <a name="l00059"></a>00059 } <a name="l00060"></a>00060 <a name="l00061"></a><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a80c975328b052ed3e3ec5b3d457cbf08">00061</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a80c975328b052ed3e3ec5b3d457cbf08" title="Set the state to identity -- no rotation.">ompl::base::SO3StateSpace::StateType::setIdentity</a>(<span class="keywordtype">void</span>) <a name="l00062"></a>00062 { <a name="l00063"></a>00063 x = y = z = 0.0; <a name="l00064"></a>00064 w = 1.0; <a name="l00065"></a>00065 } <a name="l00066"></a>00066 <a name="l00067"></a><a class="code" href="classompl_1_1base_1_1SO3StateSampler.html#a11673448fc45166c7535b87a5d2c4d40">00067</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1base_1_1SO3StateSampler.html#a11673448fc45166c7535b87a5d2c4d40" title="Sample a state.">ompl::base::SO3StateSampler::sampleUniform</a>(<a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *state) <a name="l00068"></a>00068 { <a name="l00069"></a>00069 rng_.quaternion(&state-><a class="code" href="classompl_1_1base_1_1State.html#ae4ed5c095a6b2d4a5c946b91bc65e9cb" title="Cast this instance to a desired type.">as</a><<a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html" title="The definition of a state in SO(3) represented as a unit quaternion.">SO3StateSpace::StateType</a>>()-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a525d64ca3f68c8e6492c6e26199d4717" title="X component of quaternion vector.">x</a>); <a name="l00070"></a>00070 } <a name="l00071"></a>00071 <a name="l00072"></a><a class="code" href="classompl_1_1base_1_1SO3StateSampler.html#ade4097ad565c31a70c83331f2243fb13">00072</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1base_1_1SO3StateSampler.html#ade4097ad565c31a70c83331f2243fb13" title="Sample a state near another, within specified distance.">ompl::base::SO3StateSampler::sampleUniformNear</a>(<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 class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> * <span class="comment">/* near */</span>, <span class="keyword">const</span> <span class="keywordtype">double</span> <span class="comment">/* distance */</span>) <a name="l00073"></a>00073 { <a name="l00075"></a>00075 sampleUniform(state); <a name="l00076"></a>00076 } <a name="l00077"></a>00077 <a name="l00078"></a><a class="code" href="classompl_1_1base_1_1SO3StateSampler.html#ad73f1f60597f294443fdd2f4af7dc9fe">00078</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1base_1_1SO3StateSampler.html#ad73f1f60597f294443fdd2f4af7dc9fe" title="Sample a state using a Gaussian distribution with given mean and standard deviation (stdDev)...">ompl::base::SO3StateSampler::sampleGaussian</a>(<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 class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> * <span class="comment">/* mean */</span>, <span class="keyword">const</span> <span class="keywordtype">double</span> <span class="comment">/* stdDev */</span>) <a name="l00079"></a>00079 { <a name="l00081"></a>00081 sampleUniform(state); <a name="l00082"></a>00082 } <a name="l00083"></a>00083 <a name="l00084"></a>00084 <a name="l00085"></a><a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a8b21b5e3cfcc3d66d892fb525e21911a">00085</a> <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> <a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a8b21b5e3cfcc3d66d892fb525e21911a" title="Get the dimension of the space (not the dimension of the surrounding ambient space)">ompl::base::SO3StateSpace::getDimension</a>(<span class="keywordtype">void</span>)<span class="keyword"> const</span> <a name="l00086"></a>00086 <span class="keyword"></span>{ <a name="l00087"></a>00087 <span class="keywordflow">return</span> 3; <a name="l00088"></a>00088 } <a name="l00089"></a>00089 <a name="l00090"></a><a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#ab2195bd3a08aeee6e3fad7e425eb9f26">00090</a> <span class="keywordtype">double</span> <a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#ab2195bd3a08aeee6e3fad7e425eb9f26" title="Get the maximum value a call to distance() can return (or an upper bound). For unbounded state spaces...">ompl::base::SO3StateSpace::getMaximumExtent</a>(<span class="keywordtype">void</span>)<span class="keyword"> const</span> <a name="l00091"></a>00091 <span class="keyword"></span>{ <a name="l00092"></a>00092 <span class="keywordflow">return</span> boost::math::constants::pi<double>(); <a name="l00093"></a>00093 } <a name="l00094"></a>00094 <a name="l00095"></a><a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a43d994e1775140840b42a493d8b4d0e8">00095</a> <span class="keywordtype">double</span> <a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a43d994e1775140840b42a493d8b4d0e8" title="Compute the norm of a state.">ompl::base::SO3StateSpace::norm</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html" title="The definition of a state in SO(3) represented as a unit quaternion.">StateType</a> *state)<span class="keyword"> const</span> <a name="l00096"></a>00096 <span class="keyword"></span>{ <a name="l00097"></a>00097 <span class="keywordtype">double</span> nrmSqr = state-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a525d64ca3f68c8e6492c6e26199d4717" title="X component of quaternion vector.">x</a> * state-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a525d64ca3f68c8e6492c6e26199d4717" title="X component of quaternion vector.">x</a> + state-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#ae9e99008a6b4448e6a5e53ba42430bcd" title="Y component of quaternion vector.">y</a> * state-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#ae9e99008a6b4448e6a5e53ba42430bcd" title="Y component of quaternion vector.">y</a> + state-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#ae4b1013f96d9ad164e54c758711377d0" title="Z component of quaternion vector.">z</a> * state-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#ae4b1013f96d9ad164e54c758711377d0" title="Z component of quaternion vector.">z</a> + state-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a819bd3faba4f19b9f2f58c310c5d6e3c" title="scalar component of quaternion">w</a> * state-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a819bd3faba4f19b9f2f58c310c5d6e3c" title="scalar component of quaternion">w</a>; <a name="l00098"></a>00098 <span class="keywordflow">return</span> (fabs(nrmSqr - 1.0) > std::numeric_limits<double>::epsilon()) ? sqrt(nrmSqr) : 1.0; <a name="l00099"></a>00099 } <a name="l00100"></a>00100 <a name="l00101"></a><a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a5b0be6b2327b3c8d3ef83b9368c0695a">00101</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a5b0be6b2327b3c8d3ef83b9368c0695a" title="Bring the state within the bounds of the state space. For unbounded spaces this function can be a no-...">ompl::base::SO3StateSpace::enforceBounds</a>(<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="l00102"></a>00102 <span class="keyword"></span>{ <a name="l00103"></a>00103 <a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html" title="The definition of a state in SO(3) represented as a unit quaternion.">StateType</a> *qstate = <span class="keyword">static_cast<</span><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html" title="The definition of a state in SO(3) represented as a unit quaternion.">StateType</a>*<span class="keyword">></span>(state); <a name="l00104"></a>00104 <span class="keywordtype">double</span> nrm = <a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a43d994e1775140840b42a493d8b4d0e8" title="Compute the norm of a state.">norm</a>(qstate); <a name="l00105"></a>00105 <span class="keywordflow">if</span> (fabs(nrm - 1.0) > MAX_QUATERNION_NORM_ERROR) <a name="l00106"></a>00106 { <a name="l00107"></a>00107 qstate-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a525d64ca3f68c8e6492c6e26199d4717" title="X component of quaternion vector.">x</a> /= nrm; <a name="l00108"></a>00108 qstate-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#ae9e99008a6b4448e6a5e53ba42430bcd" title="Y component of quaternion vector.">y</a> /= nrm; <a name="l00109"></a>00109 qstate-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#ae4b1013f96d9ad164e54c758711377d0" title="Z component of quaternion vector.">z</a> /= nrm; <a name="l00110"></a>00110 qstate-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a819bd3faba4f19b9f2f58c310c5d6e3c" title="scalar component of quaternion">w</a> /= nrm; <a name="l00111"></a>00111 } <a name="l00112"></a>00112 <span class="keywordflow">else</span> <a name="l00113"></a>00113 qstate-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a80c975328b052ed3e3ec5b3d457cbf08" title="Set the state to identity -- no rotation.">setIdentity</a>(); <a name="l00114"></a>00114 } <a name="l00115"></a>00115 <a name="l00116"></a><a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a601ae978dbde5d0ded039af4b87edda9">00116</a> <span class="keywordtype">bool</span> <a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a601ae978dbde5d0ded039af4b87edda9" title="Check if a state is inside the bounding box. For unbounded spaces this function can always return tru...">ompl::base::SO3StateSpace::satisfiesBounds</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="l00117"></a>00117 <span class="keyword"></span>{ <a name="l00118"></a>00118 <span class="keywordflow">return</span> fabs(<a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a43d994e1775140840b42a493d8b4d0e8" title="Compute the norm of a state.">norm</a>(static_cast<const StateType*>(state)) - 1.0) < MAX_QUATERNION_NORM_ERROR; <a name="l00119"></a>00119 } <a name="l00120"></a>00120 <a name="l00121"></a><a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a013547ae0375ec0a158cdefe71b670c3">00121</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a013547ae0375ec0a158cdefe71b670c3" title="Copy a state to another. The memory of source and destination should NOT overlap.">ompl::base::SO3StateSpace::copyState</a>(<a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *destination, <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *source)<span class="keyword"> const</span> <a name="l00122"></a>00122 <span class="keyword"></span>{ <a name="l00123"></a>00123 <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html" title="The definition of a state in SO(3) represented as a unit quaternion.">StateType</a> *qsource = <span class="keyword">static_cast<</span><span class="keyword">const </span><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html" title="The definition of a state in SO(3) represented as a unit quaternion.">StateType</a>*<span class="keyword">></span>(source); <a name="l00124"></a>00124 <a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html" title="The definition of a state in SO(3) represented as a unit quaternion.">StateType</a> *qdestination = <span class="keyword">static_cast<</span><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html" title="The definition of a state in SO(3) represented as a unit quaternion.">StateType</a>*<span class="keyword">></span>(destination); <a name="l00125"></a>00125 qdestination-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a525d64ca3f68c8e6492c6e26199d4717" title="X component of quaternion vector.">x</a> = qsource-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a525d64ca3f68c8e6492c6e26199d4717" title="X component of quaternion vector.">x</a>; <a name="l00126"></a>00126 qdestination-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#ae9e99008a6b4448e6a5e53ba42430bcd" title="Y component of quaternion vector.">y</a> = qsource-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#ae9e99008a6b4448e6a5e53ba42430bcd" title="Y component of quaternion vector.">y</a>; <a name="l00127"></a>00127 qdestination-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#ae4b1013f96d9ad164e54c758711377d0" title="Z component of quaternion vector.">z</a> = qsource-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#ae4b1013f96d9ad164e54c758711377d0" title="Z component of quaternion vector.">z</a>; <a name="l00128"></a>00128 qdestination-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a819bd3faba4f19b9f2f58c310c5d6e3c" title="scalar component of quaternion">w</a> = qsource-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a819bd3faba4f19b9f2f58c310c5d6e3c" title="scalar component of quaternion">w</a>; <a name="l00129"></a>00129 } <a name="l00130"></a>00130 <a name="l00131"></a>00131 <a name="l00132"></a>00132 <span class="comment">/*</span> <a name="l00133"></a>00133 <span class="comment">Based on code from :</span> <a name="l00134"></a>00134 <span class="comment"></span> <a name="l00135"></a>00135 <span class="comment">Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/</span> <a name="l00136"></a>00136 <span class="comment">*/</span> <a name="l00137"></a><a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a0c3bdda1e03c41965aea586cec605b7c">00137</a> <span class="keywordtype">double</span> <a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a0c3bdda1e03c41965aea586cec605b7c" title="Computes distance to between two states. This function satisfies the properties of a metric and its r...">ompl::base::SO3StateSpace::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> *state1, <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *state2)<span class="keyword"> const</span> <a name="l00138"></a>00138 <span class="keyword"></span>{ <a name="l00139"></a>00139 <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html" title="The definition of a state in SO(3) represented as a unit quaternion.">StateType</a> *qs1 = <span class="keyword">static_cast<</span><span class="keyword">const </span><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html" title="The definition of a state in SO(3) represented as a unit quaternion.">StateType</a>*<span class="keyword">></span>(state1); <a name="l00140"></a>00140 <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html" title="The definition of a state in SO(3) represented as a unit quaternion.">StateType</a> *qs2 = <span class="keyword">static_cast<</span><span class="keyword">const </span><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html" title="The definition of a state in SO(3) represented as a unit quaternion.">StateType</a>*<span class="keyword">></span>(state2); <a name="l00141"></a>00141 <span class="keywordtype">double</span> dq = fabs(qs1-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a525d64ca3f68c8e6492c6e26199d4717" title="X component of quaternion vector.">x</a> * qs2-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a525d64ca3f68c8e6492c6e26199d4717" title="X component of quaternion vector.">x</a> + qs1-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#ae9e99008a6b4448e6a5e53ba42430bcd" title="Y component of quaternion vector.">y</a> * qs2-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#ae9e99008a6b4448e6a5e53ba42430bcd" title="Y component of quaternion vector.">y</a> + qs1-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#ae4b1013f96d9ad164e54c758711377d0" title="Z component of quaternion vector.">z</a> * qs2-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#ae4b1013f96d9ad164e54c758711377d0" title="Z component of quaternion vector.">z</a> + qs1-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a819bd3faba4f19b9f2f58c310c5d6e3c" title="scalar component of quaternion">w</a> * qs2-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a819bd3faba4f19b9f2f58c310c5d6e3c" title="scalar component of quaternion">w</a>); <a name="l00142"></a>00142 <span class="keywordflow">if</span> (dq > 1.0 - MAX_QUATERNION_NORM_ERROR) <a name="l00143"></a>00143 <span class="keywordflow">return</span> 0.0; <a name="l00144"></a>00144 <span class="keywordflow">else</span> <a name="l00145"></a>00145 <span class="keywordflow">return</span> acos(dq) * 2.0; <a name="l00146"></a>00146 } <a name="l00147"></a>00147 <a name="l00148"></a><a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a25bdfa4f3262f348d228a119d81b9f30">00148</a> <span class="keywordtype">bool</span> <a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a25bdfa4f3262f348d228a119d81b9f30" title="Checks whether two states are equal.">ompl::base::SO3StateSpace::equalStates</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *state1, <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *state2)<span class="keyword"> const</span> <a name="l00149"></a>00149 <span class="keyword"></span>{ <a name="l00150"></a>00150 <span class="keywordflow">return</span> <a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a0c3bdda1e03c41965aea586cec605b7c" title="Computes distance to between two states. This function satisfies the properties of a metric and its r...">distance</a>(state1, state2) < std::numeric_limits<double>::epsilon() * 2.0; <a name="l00151"></a>00151 } <a name="l00152"></a>00152 <a name="l00153"></a>00153 <span class="comment">/*</span> <a name="l00154"></a>00154 <span class="comment">Based on code from :</span> <a name="l00155"></a>00155 <span class="comment"></span> <a name="l00156"></a>00156 <span class="comment">Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/</span> <a name="l00157"></a>00157 <span class="comment">*/</span> <a name="l00158"></a><a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#ab3926aa72315531e407aed2dc9d41541">00158</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#ab3926aa72315531e407aed2dc9d41541" title="Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state...">ompl::base::SO3StateSpace::interpolate</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *from, <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *to, <span class="keyword">const</span> <span class="keywordtype">double</span> t, <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="l00159"></a>00159 <span class="keyword"></span>{ <a name="l00160"></a>00160 assert(<a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a43d994e1775140840b42a493d8b4d0e8" title="Compute the norm of a state.">norm</a>(static_cast<const StateType*>(from)) - 1.0 < MAX_QUATERNION_NORM_ERROR); <a name="l00161"></a>00161 assert(<a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a43d994e1775140840b42a493d8b4d0e8" title="Compute the norm of a state.">norm</a>(static_cast<const StateType*>(to)) - 1.0 < MAX_QUATERNION_NORM_ERROR); <a name="l00162"></a>00162 <a name="l00163"></a>00163 <span class="keywordtype">double</span> theta = <a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a0c3bdda1e03c41965aea586cec605b7c" title="Computes distance to between two states. This function satisfies the properties of a metric and its r...">distance</a>(from, to) / 2.0; <a name="l00164"></a>00164 <span class="keywordflow">if</span> (theta > std::numeric_limits<double>::epsilon()) <a name="l00165"></a>00165 { <a name="l00166"></a>00166 <span class="keywordtype">double</span> d = 1.0 / sin(theta); <a name="l00167"></a>00167 <span class="keywordtype">double</span> s0 = sin((1.0 - t) * theta); <a name="l00168"></a>00168 <span class="keywordtype">double</span> s1 = sin(t * theta); <a name="l00169"></a>00169 <a name="l00170"></a>00170 <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html" title="The definition of a state in SO(3) represented as a unit quaternion.">StateType</a> *qs1 = <span class="keyword">static_cast<</span><span class="keyword">const </span><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html" title="The definition of a state in SO(3) represented as a unit quaternion.">StateType</a>*<span class="keyword">></span>(from); <a name="l00171"></a>00171 <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html" title="The definition of a state in SO(3) represented as a unit quaternion.">StateType</a> *qs2 = <span class="keyword">static_cast<</span><span class="keyword">const </span><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html" title="The definition of a state in SO(3) represented as a unit quaternion.">StateType</a>*<span class="keyword">></span>(to); <a name="l00172"></a>00172 <a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html" title="The definition of a state in SO(3) represented as a unit quaternion.">StateType</a> *qr = <span class="keyword">static_cast<</span><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html" title="The definition of a state in SO(3) represented as a unit quaternion.">StateType</a>*<span class="keyword">></span>(state); <a name="l00173"></a>00173 <span class="keywordtype">double</span> dq = qs1-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a525d64ca3f68c8e6492c6e26199d4717" title="X component of quaternion vector.">x</a> * qs2-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a525d64ca3f68c8e6492c6e26199d4717" title="X component of quaternion vector.">x</a> + qs1-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#ae9e99008a6b4448e6a5e53ba42430bcd" title="Y component of quaternion vector.">y</a> * qs2-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#ae9e99008a6b4448e6a5e53ba42430bcd" title="Y component of quaternion vector.">y</a> + qs1-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#ae4b1013f96d9ad164e54c758711377d0" title="Z component of quaternion vector.">z</a> * qs2-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#ae4b1013f96d9ad164e54c758711377d0" title="Z component of quaternion vector.">z</a> + qs1-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a819bd3faba4f19b9f2f58c310c5d6e3c" title="scalar component of quaternion">w</a> * qs2-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a819bd3faba4f19b9f2f58c310c5d6e3c" title="scalar component of quaternion">w</a>; <a name="l00174"></a>00174 <span class="keywordflow">if</span> (dq < 0) <span class="comment">// Take care of long angle case see http://en.wikipedia.org/wiki/Slerp</span> <a name="l00175"></a>00175 s1 = -s1; <a name="l00176"></a>00176 <a name="l00177"></a>00177 qr-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a525d64ca3f68c8e6492c6e26199d4717" title="X component of quaternion vector.">x</a> = (qs1-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a525d64ca3f68c8e6492c6e26199d4717" title="X component of quaternion vector.">x</a> * s0 + qs2-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a525d64ca3f68c8e6492c6e26199d4717" title="X component of quaternion vector.">x</a> * s1) * d; <a name="l00178"></a>00178 qr-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#ae9e99008a6b4448e6a5e53ba42430bcd" title="Y component of quaternion vector.">y</a> = (qs1-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#ae9e99008a6b4448e6a5e53ba42430bcd" title="Y component of quaternion vector.">y</a> * s0 + qs2-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#ae9e99008a6b4448e6a5e53ba42430bcd" title="Y component of quaternion vector.">y</a> * s1) * d; <a name="l00179"></a>00179 qr-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#ae4b1013f96d9ad164e54c758711377d0" title="Z component of quaternion vector.">z</a> = (qs1-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#ae4b1013f96d9ad164e54c758711377d0" title="Z component of quaternion vector.">z</a> * s0 + qs2-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#ae4b1013f96d9ad164e54c758711377d0" title="Z component of quaternion vector.">z</a> * s1) * d; <a name="l00180"></a>00180 qr-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a819bd3faba4f19b9f2f58c310c5d6e3c" title="scalar component of quaternion">w</a> = (qs1-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a819bd3faba4f19b9f2f58c310c5d6e3c" title="scalar component of quaternion">w</a> * s0 + qs2-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a819bd3faba4f19b9f2f58c310c5d6e3c" title="scalar component of quaternion">w</a> * s1) * d; <a name="l00181"></a>00181 } <a name="l00182"></a>00182 <span class="keywordflow">else</span> <a name="l00183"></a>00183 { <a name="l00184"></a>00184 <span class="keywordflow">if</span> (state != from) <a name="l00185"></a>00185 <a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a013547ae0375ec0a158cdefe71b670c3" title="Copy a state to another. The memory of source and destination should NOT overlap.">copyState</a>(state, from); <a name="l00186"></a>00186 } <a name="l00187"></a>00187 } <a name="l00188"></a>00188 <a name="l00189"></a><a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a54dbc7c689cf8bb3ecddd480205d1281">00189</a> <a class="code" href="classompl_1_1base_1_1StateSamplerPtr.html" title="A boost shared pointer wrapper for ompl::base::StateSampler.">ompl::base::StateSamplerPtr</a> <a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a54dbc7c689cf8bb3ecddd480205d1281" title="Allocate an instance of a uniform state sampler for this space.">ompl::base::SO3StateSpace::allocStateSampler</a>(<span class="keywordtype">void</span>)<span class="keyword"> const</span> <a name="l00190"></a>00190 <span class="keyword"></span>{ <a name="l00191"></a>00191 <span class="keywordflow">return</span> <a class="code" href="classompl_1_1base_1_1StateSamplerPtr.html" title="A boost shared pointer wrapper for ompl::base::StateSampler.">StateSamplerPtr</a>(<span class="keyword">new</span> <a class="code" href="classompl_1_1base_1_1SO3StateSampler.html" title="State space sampler for SO(3), using quaternion representation.">SO3StateSampler</a>(<span class="keyword">this</span>)); <a name="l00192"></a>00192 } <a name="l00193"></a>00193 <a name="l00194"></a><a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a279d39fb50eddc2e3a9b9f98335a2299">00194</a> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">ompl::base::State</a>* <a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a279d39fb50eddc2e3a9b9f98335a2299" title="Allocate a state that can store a point in the described space.">ompl::base::SO3StateSpace::allocState</a>(<span class="keywordtype">void</span>)<span class="keyword"> const</span> <a name="l00195"></a>00195 <span class="keyword"></span>{ <a name="l00196"></a>00196 <span class="keywordflow">return</span> <span class="keyword">new</span> <a class="code" href="classompl_1_1base_1_1StateSpace.html#aa995357fedb73879bc7f0bb946db76d1" title="Define the type of state allocated by this space.">StateType</a>(); <a name="l00197"></a>00197 } <a name="l00198"></a>00198 <a name="l00199"></a><a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a5cd2870506265d0f7475fe336680a220">00199</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a5cd2870506265d0f7475fe336680a220" title="Free the memory of the allocated state.">ompl::base::SO3StateSpace::freeState</a>(<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="l00200"></a>00200 <span class="keyword"></span>{ <a name="l00201"></a>00201 <span class="keyword">delete</span> <span class="keyword">static_cast<</span><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html" title="The definition of a state in SO(3) represented as a unit quaternion.">StateType</a>*<span class="keyword">></span>(state); <a name="l00202"></a>00202 } <a name="l00203"></a>00203 <a name="l00204"></a><a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a3bf3e86830acabec6f88cfd8a9958800">00204</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a3bf3e86830acabec6f88cfd8a9958800" title="Register the projections for this state space. Usually, this is at least the default projection...">ompl::base::SO3StateSpace::registerProjections</a>(<span class="keywordtype">void</span>) <a name="l00205"></a>00205 { <a name="l00206"></a>00206 <span class="keyword">class </span>SO3DefaultProjection : <span class="keyword">public</span> <a class="code" href="classompl_1_1base_1_1ProjectionEvaluator.html" title="Abstract definition for a class computing projections to Rn. Implicit integer grids are imposed on th...">ProjectionEvaluator</a> <a name="l00207"></a>00207 { <a name="l00208"></a>00208 <span class="keyword">public</span>: <a name="l00209"></a>00209 <a name="l00210"></a>00210 SO3DefaultProjection(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1StateSpace.html" title="Representation of a space in which planning can be performed. Topology specific sampling, interpolation and distance are defined.">StateSpace</a> *space) : <a class="code" href="classompl_1_1base_1_1ProjectionEvaluator.html" title="Abstract definition for a class computing projections to Rn. Implicit integer grids are imposed on th...">ProjectionEvaluator</a>(space) <a name="l00211"></a>00211 { <a name="l00212"></a>00212 } <a name="l00213"></a>00213 <a name="l00214"></a>00214 <span class="keyword">virtual</span> <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> <a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a8b21b5e3cfcc3d66d892fb525e21911a" title="Get the dimension of the space (not the dimension of the surrounding ambient space)">getDimension</a>(<span class="keywordtype">void</span>)<span class="keyword"> const</span> <a name="l00215"></a>00215 <span class="keyword"> </span>{ <a name="l00216"></a>00216 <span class="keywordflow">return</span> 3; <a name="l00217"></a>00217 } <a name="l00218"></a>00218 <a name="l00219"></a>00219 <span class="keyword">virtual</span> <span class="keywordtype">void</span> defaultCellSizes(<span class="keywordtype">void</span>) <a name="l00220"></a>00220 { <a name="l00221"></a>00221 cellSizes_.resize(3); <a name="l00222"></a>00222 cellSizes_[0] = boost::math::constants::pi<double>() / <a class="code" href="namespaceompl_1_1magic.html#a89c2a3791d4d4579c36593a70f00588d" title="When the cell sizes for a projection are automatically computed, this value defines the number of par...">magic::PROJECTION_DIMENSION_SPLITS</a>; <a name="l00223"></a>00223 cellSizes_[1] = boost::math::constants::pi<double>() / <a class="code" href="namespaceompl_1_1magic.html#a89c2a3791d4d4579c36593a70f00588d" title="When the cell sizes for a projection are automatically computed, this value defines the number of par...">magic::PROJECTION_DIMENSION_SPLITS</a>; <a name="l00224"></a>00224 cellSizes_[2] = boost::math::constants::pi<double>() / <a class="code" href="namespaceompl_1_1magic.html#a89c2a3791d4d4579c36593a70f00588d" title="When the cell sizes for a projection are automatically computed, this value defines the number of par...">magic::PROJECTION_DIMENSION_SPLITS</a>; <a name="l00225"></a>00225 } <a name="l00226"></a>00226 <a name="l00227"></a>00227 <span class="keyword">virtual</span> <span class="keywordtype">void</span> project(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *state, <a class="code" href="namespaceompl_1_1base.html#aa83f2e90d56884b236b1e400d116b10b" title="The datatype for state projections. This class contains a real vector.">EuclideanProjection</a> &projection)<span class="keyword"> const</span> <a name="l00228"></a>00228 <span class="keyword"> </span>{ <a name="l00229"></a>00229 projection(0) = state-><a class="code" href="classompl_1_1base_1_1State.html#ae4ed5c095a6b2d4a5c946b91bc65e9cb" title="Cast this instance to a desired type.">as</a><<a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html" title="The definition of a state in SO(3) represented as a unit quaternion.">SO3StateSpace::StateType</a>>()->x; <a name="l00230"></a>00230 projection(1) = state-><a class="code" href="classompl_1_1base_1_1State.html#ae4ed5c095a6b2d4a5c946b91bc65e9cb" title="Cast this instance to a desired type.">as</a><<a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html" title="The definition of a state in SO(3) represented as a unit quaternion.">SO3StateSpace::StateType</a>>()->y; <a name="l00231"></a>00231 projection(2) = state-><a class="code" href="classompl_1_1base_1_1State.html#ae4ed5c095a6b2d4a5c946b91bc65e9cb" title="Cast this instance to a desired type.">as</a><<a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html" title="The definition of a state in SO(3) represented as a unit quaternion.">SO3StateSpace::StateType</a>>()->z; <a name="l00232"></a>00232 } <a name="l00233"></a>00233 }; <a name="l00234"></a>00234 <a name="l00235"></a>00235 <a class="code" href="classompl_1_1base_1_1StateSpace.html#ac79f6342fb2d85f1c2c87bfff812fbbf" title="Register the default projection for this state space.">registerDefaultProjection</a>(<a class="code" href="classompl_1_1base_1_1ProjectionEvaluatorPtr.html" title="A boost shared pointer wrapper for ompl::base::ProjectionEvaluator.">ProjectionEvaluatorPtr</a>(dynamic_cast<ProjectionEvaluator*>(<span class="keyword">new</span> SO3DefaultProjection(<span class="keyword">this</span>)))); <a name="l00236"></a>00236 } <a name="l00237"></a>00237 <a name="l00238"></a><a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a01bdc2556f215089743cd8d0114dc0fa">00238</a> <span class="keywordtype">double</span>* <a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a01bdc2556f215089743cd8d0114dc0fa" title="Many states contain a number of double values. This function provides a means to get the memory addre...">ompl::base::SO3StateSpace::getValueAddressAtIndex</a>(<a class="code" href="classompl_1_1base_1_1State.html" title="Definition of an abstract state.">State</a> *state, <span class="keyword">const</span> <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> index)<span class="keyword"> const</span> <a name="l00239"></a>00239 <span class="keyword"></span>{ <a name="l00240"></a>00240 <span class="keywordflow">return</span> index < 4 ? &(state-><a class="code" href="classompl_1_1base_1_1State.html#ae4ed5c095a6b2d4a5c946b91bc65e9cb" title="Cast this instance to a desired type.">as</a><<a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html" title="The definition of a state in SO(3) represented as a unit quaternion.">StateType</a>>()->x) + index : NULL; <a name="l00241"></a>00241 } <a name="l00242"></a>00242 <a name="l00243"></a><a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a3d415c89084ad4270fcbae9d59c296fe">00243</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#a3d415c89084ad4270fcbae9d59c296fe" title="Print a state to a stream.">ompl::base::SO3StateSpace::printState</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, std::ostream &out)<span class="keyword"> const</span> <a name="l00244"></a>00244 <span class="keyword"></span>{ <a name="l00245"></a>00245 out << <span class="stringliteral">"SO3State ["</span>; <a name="l00246"></a>00246 <span class="keywordflow">if</span> (state) <a name="l00247"></a>00247 { <a name="l00248"></a>00248 <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html" title="The definition of a state in SO(3) represented as a unit quaternion.">StateType</a> *qstate = <span class="keyword">static_cast<</span><span class="keyword">const </span><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html" title="The definition of a state in SO(3) represented as a unit quaternion.">StateType</a>*<span class="keyword">></span>(state); <a name="l00249"></a>00249 out << qstate-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a525d64ca3f68c8e6492c6e26199d4717" title="X component of quaternion vector.">x</a> << <span class="stringliteral">" "</span> << qstate-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#ae9e99008a6b4448e6a5e53ba42430bcd" title="Y component of quaternion vector.">y</a> << <span class="stringliteral">" "</span> << qstate-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#ae4b1013f96d9ad164e54c758711377d0" title="Z component of quaternion vector.">z</a> << <span class="stringliteral">" "</span> << qstate-><a class="code" href="classompl_1_1base_1_1SO3StateSpace_1_1StateType.html#a819bd3faba4f19b9f2f58c310c5d6e3c" title="scalar component of quaternion">w</a>; <a name="l00250"></a>00250 } <a name="l00251"></a>00251 <span class="keywordflow">else</span> <a name="l00252"></a>00252 out << <span class="stringliteral">"NULL"</span>; <a name="l00253"></a>00253 out << <span class="charliteral">']'</span> << std::endl; <a name="l00254"></a>00254 } <a name="l00255"></a>00255 <a name="l00256"></a><a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#aaadc7e4634cfb489d3bc813a23094a08">00256</a> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1base_1_1SO3StateSpace.html#aaadc7e4634cfb489d3bc813a23094a08" title="Print the settings for this state space to a stream.">ompl::base::SO3StateSpace::printSettings</a>(std::ostream &out)<span class="keyword"> const</span> <a name="l00257"></a>00257 <span class="keyword"></span>{ <a name="l00258"></a>00258 out << <span class="stringliteral">"SO(3) state space '"</span> << <a class="code" href="classompl_1_1base_1_1StateSpace.html#a90015676df178b4406a8ab8399f0624c" title="Get the name of the state space.">getName</a>() << <span class="stringliteral">"' (represented using quaternions)"</span> << std::endl; <a name="l00259"></a>00259 } </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>