<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN"> <html><head><meta http-equiv="Content-Type" content="text/html;charset=iso-8859-1"> <title>CPoseOrPoint.h Source File</title> <link href="doxygen.css" rel="stylesheet" type="text/css"> <link href="tabs.css" rel="stylesheet" type="text/css"> </head><body> <div align="left"><a href="http://www.mrpt.org/">Main MRPT website</a> > <b>C++ reference</b> </div> <div align="right"> <a href="index.html"><img border="0" src="mrpt_logo.png" alt="MRPT logo"></a> </div> <!-- Generated by Doxygen 1.7.5 --> <script type="text/javascript"> var searchBox = new SearchBox("searchBox", "search",false,'Search'); </script> <div id="navrow1" class="tabs"> <ul class="tablist"> <li><a href="index.html"><span>Main Page</span></a></li> <li><a href="pages.html"><span>Related Pages</span></a></li> <li><a href="modules.html"><span>Modules</span></a></li> <li><a href="namespaces.html"><span>Namespaces</span></a></li> <li><a href="annotated.html"><span>Classes</span></a></li> <li class="current"><a href="files.html"><span>Files</span></a></li> <li> <div id="MSearchBox" class="MSearchBoxInactive"> <div class="left"> <form id="FSearchBox" action="search.php" method="get"> <img id="MSearchSelect" src="search/mag.png" alt=""/> <input type="text" id="MSearchField" name="query" value="Search" size="20" accesskey="S" onfocus="searchBox.OnSearchFieldFocus(true)" onblur="searchBox.OnSearchFieldFocus(false)"/> </form> </div><div class="right"></div> </div> </li> </ul> </div> <div id="navrow2" class="tabs2"> <ul class="tablist"> <li><a href="files.html"><span>File List</span></a></li> <li><a href="globals.html"><span>File Members</span></a></li> </ul> </div> <div class="header"> <div class="headertitle"> <div class="title">CPoseOrPoint.h</div> </div> </div> <div class="contents"> <a href="_c_pose_or_point_8h.html">Go to the documentation of this file.</a><div class="fragment"><pre class="fragment"><a name="l00001"></a>00001 <span class="comment">/* +---------------------------------------------------------------------------+</span> <a name="l00002"></a>00002 <span class="comment"> | The Mobile Robot Programming Toolkit (MRPT) C++ library |</span> <a name="l00003"></a>00003 <span class="comment"> | |</span> <a name="l00004"></a>00004 <span class="comment"> | http://www.mrpt.org/ |</span> <a name="l00005"></a>00005 <span class="comment"> | |</span> <a name="l00006"></a>00006 <span class="comment"> | Copyright (C) 2005-2011 University of Malaga |</span> <a name="l00007"></a>00007 <span class="comment"> | |</span> <a name="l00008"></a>00008 <span class="comment"> | This software was written by the Machine Perception and Intelligent |</span> <a name="l00009"></a>00009 <span class="comment"> | Robotics Lab, University of Malaga (Spain). |</span> <a name="l00010"></a>00010 <span class="comment"> | Contact: Jose-Luis Blanco <jlblanco@ctima.uma.es> |</span> <a name="l00011"></a>00011 <span class="comment"> | |</span> <a name="l00012"></a>00012 <span class="comment"> | This file is part of the MRPT project. |</span> <a name="l00013"></a>00013 <span class="comment"> | |</span> <a name="l00014"></a>00014 <span class="comment"> | MRPT is free software: you can redistribute it and/or modify |</span> <a name="l00015"></a>00015 <span class="comment"> | it under the terms of the GNU General Public License as published by |</span> <a name="l00016"></a>00016 <span class="comment"> | the Free Software Foundation, either version 3 of the License, or |</span> <a name="l00017"></a>00017 <span class="comment"> | (at your option) any later version. |</span> <a name="l00018"></a>00018 <span class="comment"> | |</span> <a name="l00019"></a>00019 <span class="comment"> | MRPT is distributed in the hope that it will be useful, |</span> <a name="l00020"></a>00020 <span class="comment"> | but WITHOUT ANY WARRANTY; without even the implied warranty of |</span> <a name="l00021"></a>00021 <span class="comment"> | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the |</span> <a name="l00022"></a>00022 <span class="comment"> | GNU General Public License for more details. |</span> <a name="l00023"></a>00023 <span class="comment"> | |</span> <a name="l00024"></a>00024 <span class="comment"> | You should have received a copy of the GNU General Public License |</span> <a name="l00025"></a>00025 <span class="comment"> | along with MRPT. If not, see <http://www.gnu.org/licenses/>. |</span> <a name="l00026"></a>00026 <span class="comment"> | |</span> <a name="l00027"></a>00027 <span class="comment"> +---------------------------------------------------------------------------+ */</span> <a name="l00028"></a>00028 <span class="preprocessor">#ifndef CPOSEORPOINT_H</span> <a name="l00029"></a>00029 <span class="preprocessor"></span><span class="preprocessor">#define CPOSEORPOINT_H</span> <a name="l00030"></a>00030 <span class="preprocessor"></span> <a name="l00031"></a>00031 <span class="preprocessor">#include <<a class="code" href="_c_matrix_fixed_numeric_8h.html">mrpt/math/CMatrixFixedNumeric.h</a>></span> <a name="l00032"></a>00032 <span class="preprocessor">#include <<a class="code" href="lightweight__geom__data_8h.html">mrpt/math/lightweight_geom_data.h</a>></span> <a name="l00033"></a>00033 <span class="preprocessor">#include <<a class="code" href="ops__matrices_8h.html" title="This file implements miscelaneous matrix and matrix/vector operations, plus internal functions in mrp...">mrpt/math/ops_matrices.h</a>></span> <span class="comment">// Added here so many classes have access to these templates</span> <a name="l00034"></a>00034 <span class="preprocessor">#include <<a class="code" href="base_2include_2mrpt_2math_2utils_8h.html">mrpt/math/utils.h</a>></span> <span class="comment">// For homogeneousMatrixInverse</span> <a name="l00035"></a>00035 <a name="l00036"></a>00036 <span class="preprocessor">#include <<a class="code" href="_c_pose_or_point__detail_8h.html">mrpt/poses/CPoseOrPoint_detail.h</a>></span> <a name="l00037"></a>00037 <a name="l00038"></a>00038 <span class="keyword">namespace </span>mrpt <a name="l00039"></a>00039 {<span class="comment"></span> <a name="l00040"></a>00040 <span class="comment"> /** \defgroup poses_grp 2D/3D points and poses</span> <a name="l00041"></a>00041 <span class="comment"> * \ingroup mrpt_base_grp */</span> <a name="l00042"></a>00042 <span class="comment"></span> <a name="l00043"></a>00043 <span class="comment"> /** \defgroup poses_pdf_grp 2D/3D point and pose PDFs</span> <a name="l00044"></a>00044 <span class="comment"> * \ingroup mrpt_base_grp */</span> <a name="l00045"></a>00045 <span class="comment"></span> <a name="l00046"></a>00046 <span class="comment"> /** Classes for 2D/3D geometry representation, both of single values and probability density distributions (PDFs) in many forms.</span> <a name="l00047"></a>00047 <span class="comment"> * \ingroup poses_grp poses_pdf_grp</span> <a name="l00048"></a>00048 <span class="comment"> */</span> <a name="l00049"></a>00049 <span class="keyword">namespace </span>poses <a name="l00050"></a>00050 { <a name="l00051"></a>00051 <span class="keyword">using namespace </span>mrpt::utils; <span class="comment">// For square</span> <a name="l00052"></a>00052 <span class="keyword">using namespace </span>mrpt::math; <span class="comment">// For ligh. geom data</span> <a name="l00053"></a>00053 <a name="l00054"></a>00054 <span class="comment">// For use in some constructors (eg. CPose3D)</span> <a name="l00055"></a><a class="code" href="namespacemrpt_1_1poses.html#ac46e1fb95d438a441b6f396d9c79f430">00055</a> <span class="keyword">enum</span> <a class="code" href="namespacemrpt_1_1poses.html#ac46e1fb95d438a441b6f396d9c79f430">TConstructorFlags_Poses</a> <a name="l00056"></a>00056 { <a name="l00057"></a><a class="code" href="namespacemrpt_1_1poses.html#ac46e1fb95d438a441b6f396d9c79f430aefbfdff7ad639a9a8019af9de5f3c592">00057</a> <a class="code" href="namespacemrpt_1_1poses.html#ac46e1fb95d438a441b6f396d9c79f430aefbfdff7ad639a9a8019af9de5f3c592">UNINITIALIZED_POSE</a> = 0 <a name="l00058"></a>00058 }; <a name="l00059"></a>00059 <span class="comment"></span> <a name="l00060"></a>00060 <span class="comment"> /** The base template class for 2D & 3D points and poses.</span> <a name="l00061"></a>00061 <span class="comment"> * This class use the Curiously Recurring Template Pattern (CRTP) to define</span> <a name="l00062"></a>00062 <span class="comment"> * a set of common methods to all the children classes without the cost</span> <a name="l00063"></a>00063 <span class="comment"> * of virtual methods. Since most important methods are inline, they will be expanded</span> <a name="l00064"></a>00064 <span class="comment"> * at compile time and optimized for every specific derived case.</span> <a name="l00065"></a>00065 <span class="comment"> *</span> <a name="l00066"></a>00066 <span class="comment"> * For more information and examples, refer</span> <a name="l00067"></a>00067 <span class="comment"> * to the <a href="http://www.mrpt.org/2D_3D_Geometry">2D/3D Geometry tutorial</a> online.</span> <a name="l00068"></a>00068 <span class="comment"> *</span> <a name="l00069"></a>00069 <span class="comment"> *</span> <a name="l00070"></a>00070 <span class="comment"> * <center><h2>Introduction to 2D and 3D representation classes</h2></center></span> <a name="l00071"></a>00071 <span class="comment"> * <hr></span> <a name="l00072"></a>00072 <span class="comment"> * <p></span> <a name="l00073"></a>00073 <span class="comment"> * There are two class of spatial representation classes:</span> <a name="l00074"></a>00074 <span class="comment"> * - Point: A point in the common mathematical sense, with no directional information.</span> <a name="l00075"></a>00075 <span class="comment"> * - 2D: A 2D point is represented just by its coordinates (x,y).</span> <a name="l00076"></a>00076 <span class="comment"> * - 3D: A 3D point is represented by its coordinates (x,y,z).</span> <a name="l00077"></a>00077 <span class="comment"> * - Pose: It is a point, plus a direction.</span> <a name="l00078"></a>00078 <span class="comment"> * - 2D: A 2D pose is a 2D point plus a single angle, the yaw or &#966; angle: the angle from the positive X angle.</span> <a name="l00079"></a>00079 <span class="comment"> * - 3D: A 3D point is a 3D point plus three orientation angles (More details above).</span> <a name="l00080"></a>00080 <span class="comment"> * </p></span> <a name="l00081"></a>00081 <span class="comment"> * In the case for a 3D orientation many representation angles can be used (Euler angles,yaw/pitch/roll,...)</span> <a name="l00082"></a>00082 <span class="comment"> * but all of them can be handled by a 4x4 matrix called "Homogeneous Matrix". This matrix includes both, the</span> <a name="l00083"></a>00083 <span class="comment"> * translation and the orientation for a point or a pose, and it can be obtained using</span> <a name="l00084"></a>00084 <span class="comment"> * the method getHomogeneousMatrix() which is defined for any pose or point. Note that when the YPR angles are</span> <a name="l00085"></a>00085 <span class="comment"> * used to define a 3D orientation, these three values can not be extracted from the matrix again.<br><br></span> <a name="l00086"></a>00086 <span class="comment"> *</span> <a name="l00087"></a>00087 <span class="comment"> * <b>Homogeneous matrices:</b> These are 4x4 matrices which can represent any translation or rotation in 2D & 3D.</span> <a name="l00088"></a>00088 <span class="comment"> * See the tutorial online for more details. *</span> <a name="l00089"></a>00089 <span class="comment"> *</span> <a name="l00090"></a>00090 <span class="comment"> * <b>Operators:</b> There are operators defined for the pose compounding \f$ \oplus \f$ and inverse pose</span> <a name="l00091"></a>00091 <span class="comment"> * compounding \f$ \ominus \f$ of poses and points. For example, let "a" and "b" be 2D or 3D poses. Then "a+b"</span> <a name="l00092"></a>00092 <span class="comment"> * returns the resulting pose of "moving b" from "a"; and "b-a" returns the pose of "b" as it is seen</span> <a name="l00093"></a>00093 <span class="comment"> * "from a". They can be mixed points and poses, being 2D or 3D, in these operators, with the following</span> <a name="l00094"></a>00094 <span class="comment"> * results: <br></span> <a name="l00095"></a>00095 <span class="comment"> *</span> <a name="l00096"></a>00096 <span class="comment"> * <div align="center" ></span> <a name="l00097"></a>00097 <span class="comment"> * <pre></span> <a name="l00098"></a>00098 <span class="comment"> * Does "a+b" return a Pose or a Point?</span> <a name="l00099"></a>00099 <span class="comment"> * +---------------------------------+</span> <a name="l00100"></a>00100 <span class="comment"> * | a \ b | Pose | Point |</span> <a name="l00101"></a>00101 <span class="comment"> * +----------+-----------+----------+</span> <a name="l00102"></a>00102 <span class="comment"> * | Pose | Pose | Point |</span> <a name="l00103"></a>00103 <span class="comment"> * | Point | Pose | Point |</span> <a name="l00104"></a>00104 <span class="comment"> * +---------------------------------+</span> <a name="l00105"></a>00105 <span class="comment"> *</span> <a name="l00106"></a>00106 <span class="comment"> * Does "a-b" return a Pose or a Point?</span> <a name="l00107"></a>00107 <span class="comment"> * +---------------------------------+</span> <a name="l00108"></a>00108 <span class="comment"> * | a \ b | Pose | Point |</span> <a name="l00109"></a>00109 <span class="comment"> * +----------+-----------+----------+</span> <a name="l00110"></a>00110 <span class="comment"> * | Pose | Pose | Pose |</span> <a name="l00111"></a>00111 <span class="comment"> * | Point | Point | Point |</span> <a name="l00112"></a>00112 <span class="comment"> * +---------------------------------+</span> <a name="l00113"></a>00113 <span class="comment"> *</span> <a name="l00114"></a>00114 <span class="comment"> * Does "a+b" and "a-b" return a 2D or 3D object?</span> <a name="l00115"></a>00115 <span class="comment"> * +-------------------------+</span> <a name="l00116"></a>00116 <span class="comment"> * | a \ b | 2D | 3D |</span> <a name="l00117"></a>00117 <span class="comment"> * +----------+--------------+</span> <a name="l00118"></a>00118 <span class="comment"> * | 2D | 2D | 3D |</span> <a name="l00119"></a>00119 <span class="comment"> * | 3D | 3D | 3D |</span> <a name="l00120"></a>00120 <span class="comment"> * +-------------------------+</span> <a name="l00121"></a>00121 <span class="comment"> *</span> <a name="l00122"></a>00122 <span class="comment"> * </pre></span> <a name="l00123"></a>00123 <span class="comment"> * </div></span> <a name="l00124"></a>00124 <span class="comment"> *</span> <a name="l00125"></a>00125 <span class="comment"> * \sa CPose,CPoint</span> <a name="l00126"></a>00126 <span class="comment"> * \ingroup poses_grp</span> <a name="l00127"></a>00127 <span class="comment"> */</span> <a name="l00128"></a>00128 <span class="keyword">template</span> <<span class="keyword">class</span> DERIVEDCLASS> <a name="l00129"></a>00129 <span class="keyword">class </span>CPoseOrPoint : <span class="keyword">public</span> mrpt::poses::detail::pose_point_impl<DERIVEDCLASS, mrpt::poses::detail::T3DTypeHelper<DERIVEDCLASS>::is_3D_val> <a name="l00130"></a>00130 { <a name="l00131"></a>00131 <span class="keyword">public</span>:<span class="comment"></span> <a name="l00132"></a>00132 <span class="comment"> /** Common members of all points & poses classes.</span> <a name="l00133"></a>00133 <span class="comment"> @{ */</span> <a name="l00134"></a>00134 <span class="comment">// Note: the access to "z" is implemented (only for 3D data types), in detail::pose_point_impl<></span> <a name="l00135"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#af3506e31b659334e6992f5cd9ac657b7">00135</a> <span class="keyword">inline</span> <span class="keywordtype">double</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#af3506e31b659334e6992f5cd9ac657b7" title="Common members of all points & poses classes.">x</a>() const <span class="comment">/*!< Get X coord. */</span> { <span class="keywordflow">return</span> <span class="keyword">static_cast<</span><span class="keyword">const </span>DERIVEDCLASS*<span class="keyword">></span>(<span class="keyword">this</span>)->m_coords[0]; } <a name="l00136"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a912d9a0a05f236fdb947b6627e7349ba">00136</a> <span class="keyword">inline</span> <span class="keywordtype">double</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a912d9a0a05f236fdb947b6627e7349ba">y</a>() const <span class="comment">/*!< Get Y coord. */</span> { <span class="keywordflow">return</span> <span class="keyword">static_cast<</span><span class="keyword">const </span>DERIVEDCLASS*<span class="keyword">></span>(<span class="keyword">this</span>)->m_coords[1]; } <a name="l00137"></a>00137 <a name="l00138"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#ad83a13c613e3a571d38ecf0c5bbaf14e">00138</a> <span class="keyword">inline</span> <span class="keywordtype">double</span> &<a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#ad83a13c613e3a571d38ecf0c5bbaf14e">x</a>() <span class="comment">/*!< Get ref to X coord. */</span> { <span class="keywordflow">return</span> <span class="keyword">static_cast<</span>DERIVEDCLASS*<span class="keyword">></span>(<span class="keyword">this</span>)->m_coords[0]; } <a name="l00139"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#afc45043b9e86558dac17091787cc8546">00139</a> <span class="keyword">inline</span> <span class="keywordtype">double</span> &<a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#afc45043b9e86558dac17091787cc8546">y</a>() <span class="comment">/*!< Get ref to Y coord. */</span> { <span class="keywordflow">return</span> <span class="keyword">static_cast<</span>DERIVEDCLASS*<span class="keyword">></span>(<span class="keyword">this</span>)->m_coords[1]; } <a name="l00140"></a>00140 <a name="l00141"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#abd0edead14bf974e3573635db0649b8b">00141</a> <span class="keyword">inline</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#abd0edead14bf974e3573635db0649b8b">x</a>(<span class="keyword">const</span> <span class="keywordtype">double</span> v) <span class="comment">/*!< Set X coord. */</span> { <span class="keyword">static_cast<</span>DERIVEDCLASS*<span class="keyword">></span>(<span class="keyword">this</span>)->m_coords[0]=v; } <a name="l00142"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a40f5b89235381d395cf6ed933e3456b4">00142</a> <span class="keyword">inline</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a40f5b89235381d395cf6ed933e3456b4">y</a>(<span class="keyword">const</span> <span class="keywordtype">double</span> v) <span class="comment">/*!< Set Y coord. */</span> { <span class="keyword">static_cast<</span>DERIVEDCLASS*<span class="keyword">></span>(<span class="keyword">this</span>)->m_coords[1]=v; } <a name="l00143"></a>00143 <a name="l00144"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a988b5d127feca6fcc17c5fc9c5617a32">00144</a> <span class="keyword">inline</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a988b5d127feca6fcc17c5fc9c5617a32">x_incr</a>(<span class="keyword">const</span> <span class="keywordtype">double</span> v) <span class="comment">/*!< X+=v */</span> { <span class="keyword">static_cast<</span>DERIVEDCLASS*<span class="keyword">></span>(<span class="keyword">this</span>)->m_coords[0]+=v; } <a name="l00145"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a2c96d47bfe4f9666bf5816a5d5f030ec">00145</a> <span class="keyword">inline</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a2c96d47bfe4f9666bf5816a5d5f030ec">y_incr</a>(<span class="keyword">const</span> <span class="keywordtype">double</span> v) <span class="comment">/*!< Y+=v */</span> { <span class="keyword">static_cast<</span>DERIVEDCLASS*<span class="keyword">></span>(<span class="keyword">this</span>)->m_coords[1]+=v; } <a name="l00146"></a>00146 <a name="l00147"></a>00147 <span class="comment"></span> <a name="l00148"></a>00148 <span class="comment"> /** Return true for poses or points with a Z component, false otherwise. */</span> <a name="l00149"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a4d63d1364f37b48c83d36f4f2e5fb20a">00149</a> <span class="keyword">static</span> <span class="keyword">inline</span> <span class="keywordtype">bool</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a4d63d1364f37b48c83d36f4f2e5fb20a" title="Return true for poses or points with a Z component, false otherwise.">is3DPoseOrPoint</a>() { <span class="keywordflow">return</span> DERIVEDCLASS::is_3D_val!=0; } <a name="l00150"></a>00150 <span class="comment"></span> <a name="l00151"></a>00151 <span class="comment"> /** Returns the squared euclidean distance to another pose/point: */</span> <a name="l00152"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a2b9df9477af343743486cc4811d82357">00152</a> <span class="keyword">template</span> <<span class="keyword">class</span> OTHERCLASS> <span class="keyword">inline</span> <span class="keywordtype">double</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a2b9df9477af343743486cc4811d82357" title="Returns the squared euclidean distance to another pose/point:">sqrDistanceTo</a>(<span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html" title="The base template class for 2D & 3D points and poses.">CPoseOrPoint<OTHERCLASS></a> &b)<span class="keyword"> const</span> <a name="l00153"></a>00153 <span class="keyword"> </span>{ <a name="l00154"></a>00154 <span class="keywordflow">if</span> (b.is3DPoseOrPoint()) <a name="l00155"></a>00155 { <a name="l00156"></a>00156 <span class="keywordflow">if</span> (<a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a4d63d1364f37b48c83d36f4f2e5fb20a" title="Return true for poses or points with a Z component, false otherwise.">is3DPoseOrPoint</a>()) <a name="l00157"></a>00157 <span class="keywordflow">return</span> <a class="code" href="namespacemrpt_1_1utils.html#a67cb05bb8ad4e725875a7ee54b7042ae" title="Inline function for the square of a number.">square</a>(<a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#af3506e31b659334e6992f5cd9ac657b7" title="Common members of all points & poses classes.">x</a>()-b.x()) + <a class="code" href="namespacemrpt_1_1utils.html#a67cb05bb8ad4e725875a7ee54b7042ae" title="Inline function for the square of a number.">square</a>(<a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a912d9a0a05f236fdb947b6627e7349ba">y</a>()-b.y()) + <a class="code" href="namespacemrpt_1_1utils.html#a67cb05bb8ad4e725875a7ee54b7042ae" title="Inline function for the square of a number.">square</a>(static_cast<const DERIVEDCLASS*>(<span class="keyword">this</span>)->m_coords[2]-<span class="keyword">static_cast<</span><span class="keyword">const </span>OTHERCLASS*<span class="keyword">></span>(&b)->m_coords[2]); <a name="l00158"></a>00158 <span class="keywordflow">else</span> <span class="keywordflow">return</span> <a class="code" href="namespacemrpt_1_1utils.html#a67cb05bb8ad4e725875a7ee54b7042ae" title="Inline function for the square of a number.">square</a>(<a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#af3506e31b659334e6992f5cd9ac657b7" title="Common members of all points & poses classes.">x</a>()-b.x()) + <a class="code" href="namespacemrpt_1_1utils.html#a67cb05bb8ad4e725875a7ee54b7042ae" title="Inline function for the square of a number.">square</a>(<a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a912d9a0a05f236fdb947b6627e7349ba">y</a>()-b.y()) + <a class="code" href="namespacemrpt_1_1utils.html#a67cb05bb8ad4e725875a7ee54b7042ae" title="Inline function for the square of a number.">square</a>(static_cast<const OTHERCLASS*>(&b)->m_coords[2]); <a name="l00159"></a>00159 } <a name="l00160"></a>00160 <span class="keywordflow">else</span> <a name="l00161"></a>00161 { <a name="l00162"></a>00162 <span class="keywordflow">if</span> (<a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a4d63d1364f37b48c83d36f4f2e5fb20a" title="Return true for poses or points with a Z component, false otherwise.">is3DPoseOrPoint</a>()) <a name="l00163"></a>00163 <span class="keywordflow">return</span> <a class="code" href="namespacemrpt_1_1utils.html#a67cb05bb8ad4e725875a7ee54b7042ae" title="Inline function for the square of a number.">square</a>(<a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#af3506e31b659334e6992f5cd9ac657b7" title="Common members of all points & poses classes.">x</a>()-b.x()) + <a class="code" href="namespacemrpt_1_1utils.html#a67cb05bb8ad4e725875a7ee54b7042ae" title="Inline function for the square of a number.">square</a>(<a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a912d9a0a05f236fdb947b6627e7349ba">y</a>()-b.y()) + <a class="code" href="namespacemrpt_1_1utils.html#a67cb05bb8ad4e725875a7ee54b7042ae" title="Inline function for the square of a number.">square</a>(static_cast<const OTHERCLASS*>(&b)->m_coords[2]); <a name="l00164"></a>00164 <span class="keywordflow">else</span> <span class="keywordflow">return</span> <a class="code" href="namespacemrpt_1_1utils.html#a67cb05bb8ad4e725875a7ee54b7042ae" title="Inline function for the square of a number.">square</a>(<a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#af3506e31b659334e6992f5cd9ac657b7" title="Common members of all points & poses classes.">x</a>()-b.x()) + <a class="code" href="namespacemrpt_1_1utils.html#a67cb05bb8ad4e725875a7ee54b7042ae" title="Inline function for the square of a number.">square</a>(<a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a912d9a0a05f236fdb947b6627e7349ba">y</a>()-b.y()); <a name="l00165"></a>00165 } <a name="l00166"></a>00166 } <a name="l00167"></a>00167 <span class="comment"></span> <a name="l00168"></a>00168 <span class="comment"> /** Returns the Euclidean distance to another pose/point: */</span> <a name="l00169"></a>00169 <span class="keyword">template</span> <<span class="keyword">class</span> OTHERCLASS> <a name="l00170"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#aafaf13c20929700f3cd1688374bb9999">00170</a> <span class="keyword">inline</span> <span class="keywordtype">double</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#aafaf13c20929700f3cd1688374bb9999" title="Returns the Euclidean distance to another pose/point:">distanceTo</a>(<span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html" title="The base template class for 2D & 3D points and poses.">CPoseOrPoint<OTHERCLASS></a> &b)<span class="keyword"> const</span> <a name="l00171"></a>00171 <span class="keyword"> </span>{ <a name="l00172"></a>00172 <span class="keywordflow">return</span> std::sqrt( <a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a2b9df9477af343743486cc4811d82357" title="Returns the squared euclidean distance to another pose/point:">sqrDistanceTo</a>(b)); <a name="l00173"></a>00173 } <a name="l00174"></a>00174 <span class="comment"></span> <a name="l00175"></a>00175 <span class="comment"> /** Returns the squared 2D distance from this pose/point to a 2D point (ignores Z, if it exists). */</span> <a name="l00176"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a4dd58b18bb7d5a7da1d38ee1a5feab5e">00176</a> <span class="keyword">inline</span> <span class="keywordtype">double</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a4dd58b18bb7d5a7da1d38ee1a5feab5e" title="Returns the squared 2D distance from this pose/point to a 2D point (ignores Z, if it exists)...">distance2DToSquare</a>( <span class="keywordtype">double</span> ax, <span class="keywordtype">double</span> ay )<span class="keyword"> const </span>{ <span class="keywordflow">return</span> <a class="code" href="namespacemrpt_1_1utils.html#a67cb05bb8ad4e725875a7ee54b7042ae" title="Inline function for the square of a number.">square</a>(ax-<a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#af3506e31b659334e6992f5cd9ac657b7" title="Common members of all points & poses classes.">x</a>())+<a class="code" href="namespacemrpt_1_1utils.html#a67cb05bb8ad4e725875a7ee54b7042ae" title="Inline function for the square of a number.">square</a>(ay-<a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a912d9a0a05f236fdb947b6627e7349ba">y</a>()); } <a name="l00177"></a>00177 <span class="comment"></span> <a name="l00178"></a>00178 <span class="comment"> /** Returns the squared 3D distance from this pose/point to a 3D point */</span> <a name="l00179"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#af9801e32904a1a4fe11fd2ab1a8eb8a4">00179</a> <span class="keyword">inline</span> <span class="keywordtype">double</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#af9801e32904a1a4fe11fd2ab1a8eb8a4" title="Returns the squared 3D distance from this pose/point to a 3D point.">distance3DToSquare</a>( <span class="keywordtype">double</span> ax, <span class="keywordtype">double</span> ay, <span class="keywordtype">double</span> az )<span class="keyword"> const </span>{ <a name="l00180"></a>00180 <span class="keywordflow">return</span> <a class="code" href="namespacemrpt_1_1utils.html#a67cb05bb8ad4e725875a7ee54b7042ae" title="Inline function for the square of a number.">square</a>(ax-<a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#af3506e31b659334e6992f5cd9ac657b7" title="Common members of all points & poses classes.">x</a>())+<a class="code" href="namespacemrpt_1_1utils.html#a67cb05bb8ad4e725875a7ee54b7042ae" title="Inline function for the square of a number.">square</a>(ay-<a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a912d9a0a05f236fdb947b6627e7349ba">y</a>())+<a class="code" href="namespacemrpt_1_1utils.html#a67cb05bb8ad4e725875a7ee54b7042ae" title="Inline function for the square of a number.">square</a>(az-(<a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a4d63d1364f37b48c83d36f4f2e5fb20a" title="Return true for poses or points with a Z component, false otherwise.">is3DPoseOrPoint</a>() ? static_cast<const DERIVEDCLASS*>(<span class="keyword">this</span>)->m_coords[2] : 0) ); <a name="l00181"></a>00181 } <a name="l00182"></a>00182 <span class="comment"></span> <a name="l00183"></a>00183 <span class="comment"> /** Returns the 2D distance from this pose/point to a 2D point (ignores Z, if it exists). */</span> <a name="l00184"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#abcd313017da1f9f0a2837ff89b9f0f8b">00184</a> <span class="keyword">inline</span> <span class="keywordtype">double</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#abcd313017da1f9f0a2837ff89b9f0f8b" title="Returns the 2D distance from this pose/point to a 2D point (ignores Z, if it exists).">distance2DTo</a>( <span class="keywordtype">double</span> ax, <span class="keywordtype">double</span> ay )<span class="keyword"> const </span>{ <span class="keywordflow">return</span> std::sqrt(<a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a4dd58b18bb7d5a7da1d38ee1a5feab5e" title="Returns the squared 2D distance from this pose/point to a 2D point (ignores Z, if it exists)...">distance2DToSquare</a>(ax,ay)); } <a name="l00185"></a>00185 <span class="comment"></span> <a name="l00186"></a>00186 <span class="comment"> /** Returns the 3D distance from this pose/point to a 3D point */</span> <a name="l00187"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a509a80a9a64db02142688f648e5f5f67">00187</a> <span class="keyword">inline</span> <span class="keywordtype">double</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a509a80a9a64db02142688f648e5f5f67" title="Returns the 3D distance from this pose/point to a 3D point.">distance3DTo</a>( <span class="keywordtype">double</span> ax, <span class="keywordtype">double</span> ay, <span class="keywordtype">double</span> az )<span class="keyword"> const </span>{ <span class="keywordflow">return</span> std::sqrt(<a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#af9801e32904a1a4fe11fd2ab1a8eb8a4" title="Returns the squared 3D distance from this pose/point to a 3D point.">distance3DToSquare</a>(ax,ay,az)); } <a name="l00188"></a>00188 <span class="comment"></span> <a name="l00189"></a>00189 <span class="comment"> /** Returns the euclidean distance to a 3D point: */</span> <a name="l00190"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a7dc4616a2d4ecef34d38ccb3da948d98">00190</a> <span class="keyword">inline</span> <span class="keywordtype">double</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a7dc4616a2d4ecef34d38ccb3da948d98" title="Returns the euclidean distance to a 3D point:">distanceTo</a>(<span class="keyword">const</span> <a class="code" href="structmrpt_1_1math_1_1_t_point3_d.html" title="Lightweight 3D point.">mrpt::math::TPoint3D</a> &b)<span class="keyword"> const </span>{ <span class="keywordflow">return</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a509a80a9a64db02142688f648e5f5f67" title="Returns the 3D distance from this pose/point to a 3D point.">distance3DTo</a>(b.<a class="code" href="structmrpt_1_1math_1_1_t_point3_d.html#a5014ee49d97866d293568300b619a7e2" title="X coordinate.">x</a>,b.<a class="code" href="structmrpt_1_1math_1_1_t_point3_d.html#aec879c0d61d8446e93b7d09344931d37" title="Y coordinate.">y</a>,b.<a class="code" href="structmrpt_1_1math_1_1_t_point3_d.html#a61df04839b9146696e696fc7af3bc307" title="Z coordinate.">z</a>); } <a name="l00191"></a>00191 <span class="comment"></span> <a name="l00192"></a>00192 <span class="comment"> /** Returns the euclidean norm of vector: \f$ ||\mathbf{x}|| = \sqrt{x^2+y^2+z^2} \f$ */</span> <a name="l00193"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a24ea0fd503c68ce305247573583f5284">00193</a> <span class="keyword">inline</span> <span class="keywordtype">double</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a24ea0fd503c68ce305247573583f5284" title="Returns the euclidean norm of vector: .">norm</a>()<span class="keyword"> const</span> <a name="l00194"></a>00194 <span class="keyword"> </span>{ <a name="l00195"></a>00195 <span class="keywordflow">return</span> std::sqrt( <a class="code" href="namespacemrpt_1_1utils.html#a67cb05bb8ad4e725875a7ee54b7042ae" title="Inline function for the square of a number.">square</a>(<a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#af3506e31b659334e6992f5cd9ac657b7" title="Common members of all points & poses classes.">x</a>())+<a class="code" href="namespacemrpt_1_1utils.html#a67cb05bb8ad4e725875a7ee54b7042ae" title="Inline function for the square of a number.">square</a>(<a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a912d9a0a05f236fdb947b6627e7349ba">y</a>())+ (!<a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a4d63d1364f37b48c83d36f4f2e5fb20a" title="Return true for poses or points with a Z component, false otherwise.">is3DPoseOrPoint</a>() ? 0 : <a class="code" href="namespacemrpt_1_1utils.html#a67cb05bb8ad4e725875a7ee54b7042ae" title="Inline function for the square of a number.">square</a>(static_cast<const DERIVEDCLASS*>(<span class="keyword">this</span>)->m_coords[2]) ) ); <a name="l00196"></a>00196 } <a name="l00197"></a>00197 <span class="comment"></span> <a name="l00198"></a>00198 <span class="comment"> /** Return the pose or point as a 1xN vector with all the components (see derived classes for each implementation) */</span> <a name="l00199"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#af6cebd2b9558f7e6624ef2e8965c4d20">00199</a> <span class="keyword">inline</span> <a class="code" href="structmrpt_1_1dynamicsize__vector.html" title="The base class of MRPT vectors, actually, Eigen column matrices of dynamic size with specialized cons...">vector_double</a> <a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#af6cebd2b9558f7e6624ef2e8965c4d20" title="Return the pose or point as a 1xN vector with all the components (see derived classes for each implem...">getAsVectorVal</a>()<span class="keyword"> const</span> <a name="l00200"></a>00200 <span class="keyword"> </span>{ <a name="l00201"></a>00201 <a class="code" href="structmrpt_1_1dynamicsize__vector.html" title="The base class of MRPT vectors, actually, Eigen column matrices of dynamic size with specialized cons...">vector_double</a> v; <a name="l00202"></a>00202 <span class="keyword">static_cast<</span><span class="keyword">const </span>DERIVEDCLASS*<span class="keyword">></span>(<span class="keyword">this</span>)->getAsVector(v); <a name="l00203"></a>00203 <span class="keywordflow">return</span> v; <a name="l00204"></a>00204 } <a name="l00205"></a>00205 <span class="comment"></span> <a name="l00206"></a>00206 <span class="comment"> /** Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (translation+orientation).</span> <a name="l00207"></a>00207 <span class="comment"> * \sa getInverseHomogeneousMatrix</span> <a name="l00208"></a>00208 <span class="comment"> */</span> <a name="l00209"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#af4008d5353e9349be18baeb82d4701e3">00209</a> <span class="keyword">inline</span> <a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html">CMatrixDouble44</a> <a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#af4008d5353e9349be18baeb82d4701e3" title="Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (t...">getHomogeneousMatrixVal</a>()<span class="keyword"> const</span> <a name="l00210"></a>00210 <span class="keyword"> </span>{ <a name="l00211"></a>00211 <a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html">CMatrixDouble44</a> m(<a class="code" href="namespacemrpt_1_1math.html#a27e8ae8971ff5aa1c39f1f9be334d73aa28acc66160006cb691487ec89f8d266d">UNINITIALIZED_MATRIX</a>); <a name="l00212"></a>00212 <span class="keyword">static_cast<</span><span class="keyword">const </span>DERIVEDCLASS*<span class="keyword">></span>(<span class="keyword">this</span>)->getHomogeneousMatrix(m); <a name="l00213"></a>00213 <span class="keywordflow">return</span> m; <a name="l00214"></a>00214 } <a name="l00215"></a>00215 <span class="comment"></span> <a name="l00216"></a>00216 <span class="comment"> /** Returns the corresponding 4x4 inverse homogeneous transformation matrix for this point or pose.</span> <a name="l00217"></a>00217 <span class="comment"> * \sa getHomogeneousMatrix</span> <a name="l00218"></a>00218 <span class="comment"> */</span> <a name="l00219"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a573fbc8166aa8c2ee04ff229a178fb10">00219</a> <span class="keyword">inline</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#add70f40f0ead699d706779c07123cd90">getInverseHomogeneousMatrix</a>( <a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html">math::CMatrixDouble44</a> &out_HM )<span class="keyword"> const</span> <a name="l00220"></a>00220 <span class="keyword"> </span>{ <span class="comment">// Get current HM & inverse in-place:</span> <a name="l00221"></a>00221 <span class="keyword">static_cast<</span><span class="keyword">const </span>DERIVEDCLASS*<span class="keyword">></span>(<span class="keyword">this</span>)->getHomogeneousMatrix(out_HM); <a name="l00222"></a>00222 <a class="code" href="group__container__ops__grp.html#ga65a4cb93289c9373a8830102a2296e2d" title="Efficiently compute the inverse of a 4x4 homogeneous matrix by only transposing the rotation 3x3 part...">mrpt::math::homogeneousMatrixInverse</a>(out_HM); <a name="l00223"></a>00223 } <a name="l00224"></a>00224 <span class="comment"></span> <a name="l00225"></a>00225 <span class="comment"> //! \overload</span> <a name="l00226"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#add70f40f0ead699d706779c07123cd90">00226</a> <span class="comment"></span> <span class="keyword">inline</span> mrpt<a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html">::math::CMatrixDouble44</a> <a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#add70f40f0ead699d706779c07123cd90">getInverseHomogeneousMatrix</a>()<span class="keyword"> const</span> <a name="l00227"></a>00227 <span class="keyword"> </span>{ <a name="l00228"></a>00228 mrpt<a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html">::math::CMatrixDouble44</a> M(<a class="code" href="namespacemrpt_1_1math.html#a27e8ae8971ff5aa1c39f1f9be334d73aa28acc66160006cb691487ec89f8d266d">UNINITIALIZED_MATRIX</a>); <a name="l00229"></a>00229 <a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#add70f40f0ead699d706779c07123cd90">getInverseHomogeneousMatrix</a>(M); <a name="l00230"></a>00230 <span class="keywordflow">return</span> M; <a name="l00231"></a>00231 } <a name="l00232"></a>00232 <span class="comment"></span> <a name="l00233"></a>00233 <span class="comment"> /** @} */</span> <a name="l00234"></a>00234 }; <span class="comment">// End of class def.</span> <a name="l00235"></a>00235 <a name="l00236"></a>00236 <a name="l00237"></a>00237 } <span class="comment">// End of namespace</span> <a name="l00238"></a>00238 } <span class="comment">// End of namespace</span> <a name="l00239"></a>00239 <a name="l00240"></a>00240 <span class="preprocessor">#endif</span> </pre></div></div> </div> <br><hr><br> <table border="0" width="100%"> <tr> <td> Page generated by <a href="http://www.doxygen.org" target="_blank">Doxygen 1.7.5</a> for MRPT 0.9.5 SVN: at Sun Sep 25 17:20:18 UTC 2011</td><td></td> <td width="100"> </td> <td width="150"> </td></tr> </table> </body></html>