<!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>CPose3D.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">CPose3D.h</div> </div> </div> <div class="contents"> <a href="_c_pose3_d_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 CPOSE3D_H</span> <a name="l00029"></a>00029 <span class="preprocessor"></span><span class="preprocessor">#define CPOSE3D_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_pose_8h.html">mrpt/poses/CPose.h</a>></span> <a name="l00032"></a>00032 <span class="preprocessor">#include <<a class="code" href="_c_matrix_fixed_numeric_8h.html">mrpt/math/CMatrixFixedNumeric.h</a>></span> <a name="l00033"></a>00033 <span class="preprocessor">#include <<a class="code" href="_c_quaternion_8h.html">mrpt/math/CQuaternion.h</a>></span> <a name="l00034"></a>00034 <a name="l00035"></a>00035 <span class="keyword">namespace </span>mrpt <a name="l00036"></a>00036 { <a name="l00037"></a>00037 <span class="keyword">namespace </span>poses <a name="l00038"></a>00038 { <a name="l00039"></a>00039 <span class="keyword">using namespace </span>mrpt::math; <a name="l00040"></a>00040 <a name="l00041"></a><a class="code" href="namespacemrpt_1_1poses.html#a1d4ae634d5f0417a36ca15a4d928300d">00041</a> <span class="keyword">class </span><a class="code" href="base_2include_2mrpt_2base_2link__pragmas_8h.html#a6045fa0129b1a3d6c8bf895470e66574">BASE_IMPEXP</a> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_quat.html" title="A class used to store a 3D pose as a translation (x,y,z) and a quaternion (qr,qx,qy,qz).">CPose3DQuat</a>; <a name="l00042"></a>00042 <a name="l00043"></a><a class="code" href="structmrpt_1_1poses_1_1_c_pose3_d_ptr.html#a818c76be6c3f1b66c948da795a1b72f2">00043</a> <a class="code" href="_c_serializable_8h.html#a5155da97198db5986e6369e2fe7a3539" title="This declaration must be inserted in all CSerializable classes definition, before the class declarati...">DEFINE_SERIALIZABLE_PRE</a>( <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html" title="A class used to store a 3D pose (a 3D translation + a rotation in 3D).">CPose3D</a> ) <a name="l00044"></a>00044 <a name="l00045"></a>00045 <span class="comment">/** A class used to store a 3D pose (a 3D translation + a rotation in 3D).</span> <a name="l00046"></a>00046 <span class="comment"> * The 6D transformation in SE(3) stored in this class is kept in two</span> <a name="l00047"></a>00047 <span class="comment"> * separate containers: a 3-array for the translation, and a 3x3 rotation matrix.</span> <a name="l00048"></a>00048 <span class="comment"> *</span> <a name="l00049"></a>00049 <span class="comment"> * The 6D pose is parameterized as a 6-vector: [x y z yaw pitch roll]. Note however,</span> <a name="l00050"></a>00050 <span class="comment"> * that the yaw/pitch/roll angles are only computed (on-demand and transparently)</span> <a name="l00051"></a>00051 <span class="comment"> * when the user requests them. Normally, rotations are handled via the 3x3 rotation matrix only.</span> <a name="l00052"></a>00052 <span class="comment"> *</span> <a name="l00053"></a>00053 <span class="comment"> * For a complete descriptionan of Points/Poses, see mrpt::poses::CPoseOrPoint, or refer</span> <a name="l00054"></a>00054 <span class="comment"> * to the <a href="http://www.mrpt.org/2D_3D_Geometry"> 2D/3D Geometry tutorial</a> in the wiki.</span> <a name="l00055"></a>00055 <span class="comment"> *</span> <a name="l00056"></a>00056 <span class="comment"> * To change the individual components of the pose, use CPose3D::setFromValues. This class assures that the internal</span> <a name="l00057"></a>00057 <span class="comment"> * 3x3 rotation matrix is always up-to-date with the "yaw pitch roll" members.</span> <a name="l00058"></a>00058 <span class="comment"> *</span> <a name="l00059"></a>00059 <span class="comment"> * Rotations in 3D can be also represented by quaternions. See mrpt::math::CQuaternion, and method CPose3D::getAsQuaternion.</span> <a name="l00060"></a>00060 <span class="comment"> *</span> <a name="l00061"></a>00061 <span class="comment"> * This class and CPose3DQuat are very similar, and they can be converted to the each other automatically via transformation constructors.</span> <a name="l00062"></a>00062 <span class="comment"> *</span> <a name="l00063"></a>00063 <span class="comment"> * There are Lie algebra methods: \a exp and \a ln (see the methods for documentation).</span> <a name="l00064"></a>00064 <span class="comment"> *</span> <a name="l00065"></a>00065 <span class="comment"> * <div align=center></span> <a name="l00066"></a>00066 <span class="comment"> * <img src="CPose3D.gif"></span> <a name="l00067"></a>00067 <span class="comment"> * </div></span> <a name="l00068"></a>00068 <span class="comment"> *</span> <a name="l00069"></a>00069 <span class="comment"> * \ingroup poses_grp</span> <a name="l00070"></a>00070 <span class="comment"> * \sa CPoseOrPoint,CPoint3D, mrpt::math::CQuaternion</span> <a name="l00071"></a>00071 <span class="comment"> */</span> <a name="l00072"></a>00072 class <a class="code" href="base_2include_2mrpt_2base_2link__pragmas_8h.html#a6045fa0129b1a3d6c8bf895470e66574">BASE_IMPEXP</a> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html" title="A class used to store a 3D pose (a 3D translation + a rotation in 3D).">CPose3D</a> : public <a class="code" href="classmrpt_1_1poses_1_1_c_pose.html" title="A base class for representing a pose in 2D or 3D.">CPose</a><<a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html" title="A class used to store a 3D pose (a 3D translation + a rotation in 3D).">CPose3D</a>>, public mrpt::utils::<a class="code" href="classmrpt_1_1utils_1_1_c_serializable.html" title="The virtual base class which provides a unified interface for all persistent objects in MRPT...">CSerializable</a> <a name="l00073"></a>00073 { <a name="l00074"></a>00074 <span class="comment">// This must be added to any CSerializable derived class:</span> <a name="l00075"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#ae5cd379b52adb73ced744a4f8ef8f01f">00075</a> <a class="code" href="_c_serializable_8h.html#a72ab55bf7ae009c89b75715cfa21e84d" title="This declaration must be inserted in all CSerializable classes definition, within the class declarati...">DEFINE_SERIALIZABLE</a>( CPose3D ) <a name="l00076"></a>00076 <a name="l00077"></a>00077 public: <a name="l00078"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#ac30f085bf7693a5703af39ff3a28d4e8">00078</a> <a class="code" href="classmrpt_1_1math_1_1_c_array_double.html" title="A partial specialization of CArrayNumeric for double numbers.">CArrayDouble</a><3> m_coords; <span class="comment">//!< The translation vector [x,y,z]</span> <a name="l00079"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a64f8c16d8bc0eb236f375b1be9b8dfb5">00079</a> <span class="comment"></span> <a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html">CMatrixDouble33</a> m_ROT; <span class="comment">//!< The 3x3 rotation matrix</span> <a name="l00080"></a>00080 <span class="comment"></span> <a name="l00081"></a>00081 protected: <a name="l00082"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a9dae99aa623dc99e280db22f5633bb17">00082</a> mutable <span class="keywordtype">bool</span> m_ypr_uptodate; <span class="comment">//!< Whether yaw/pitch/roll members are up-to-date since the last rotation matrix update.</span> <a name="l00083"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a1f6071c84070cbcb8864616b945566fc">00083</a> <span class="comment"></span> mutable <span class="keywordtype">double</span> m_yaw, m_pitch, m_roll; <span class="comment">//!< These variables are updated every time that the object rotation matrix is modified (construction, loading from values, pose composition, etc )</span> <a name="l00084"></a>00084 <span class="comment"></span><span class="comment"></span> <a name="l00085"></a>00085 <span class="comment"> /** Rebuild the homog matrix from the angles. */</span> <a name="l00086"></a>00086 <span class="keywordtype">void</span> rebuildRotationMatrix(); <a name="l00087"></a>00087 <span class="comment"></span> <a name="l00088"></a>00088 <span class="comment"> /** Updates Yaw/pitch/roll members from the m_ROT */</span> <a name="l00089"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#ab8e1ad56668e9dff5a22185c7bc5adc5">00089</a> inline <span class="keywordtype">void</span> updateYawPitchRoll()<span class="keyword"> const </span>{ <span class="keywordflow">if</span> (!m_ypr_uptodate) { m_ypr_uptodate=<span class="keyword">true</span>; getYawPitchRoll( m_yaw, m_pitch, m_roll ); } } <a name="l00090"></a>00090 <a name="l00091"></a>00091 <span class="keyword">public</span>:<span class="comment"></span> <a name="l00092"></a>00092 <span class="comment"> /** @name Constructors</span> <a name="l00093"></a>00093 <span class="comment"> @{ */</span> <a name="l00094"></a>00094 <span class="comment"></span> <a name="l00095"></a>00095 <span class="comment"> /** Default constructor, with all the coordinates set to zero. */</span> <a name="l00096"></a>00096 CPose3D(); <a name="l00097"></a>00097 <span class="comment"></span> <a name="l00098"></a>00098 <span class="comment"> /** Constructor with initilization of the pose; (remember that angles are always given in radians!) */</span> <a name="l00099"></a>00099 CPose3D(<span class="keyword">const</span> <span class="keywordtype">double</span> x,<span class="keyword">const</span> <span class="keywordtype">double</span> <a class="code" href="namespace_eigen_1_1internal.html#a3d7a581aeb951248dc6fe114e9e05f07">y</a>,<span class="keyword">const</span> <span class="keywordtype">double</span> z,<span class="keyword">const</span> <span class="keywordtype">double</span> yaw=0, <span class="keyword">const</span> <span class="keywordtype">double</span> pitch=0, <span class="keyword">const</span> <span class="keywordtype">double</span> roll=0); <a name="l00100"></a>00100 <span class="comment"></span> <a name="l00101"></a>00101 <span class="comment"> /** Constructor from a 4x4 homogeneous matrix - the passed matrix can be actually of any size larger than or equal 3x4, since only those first values are used (the last row of a homogeneous 4x4 matrix are always fixed). */</span> <a name="l00102"></a>00102 <span class="keyword">explicit</span> CPose3D(<span class="keyword">const</span> <a class="code" href="classmrpt_1_1math_1_1_c_matrix_template_numeric.html" title="A matrix of dynamic size.">math::CMatrixDouble</a> &m); <a name="l00103"></a>00103 <span class="comment"></span> <a name="l00104"></a>00104 <span class="comment"> /** Constructor from a 4x4 homogeneous matrix: */</span> <a name="l00105"></a>00105 <span class="keyword">explicit</span> CPose3D(<span class="keyword">const</span> <a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html">math::CMatrixDouble44</a> &m); <a name="l00106"></a>00106 <span class="comment"></span> <a name="l00107"></a>00107 <span class="comment"> /** Constructor from a 3x3 rotation matrix and a the translation given as a 3-vector, a 3-array, a CPoint3D or a TPoint3D */</span> <a name="l00108"></a>00108 <span class="keyword">template</span> <<span class="keyword">class</span> MATRIX33,<span class="keyword">class</span> VECTOR3> <a name="l00109"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a5ee4cb6013f742cdc2bf7f71ee43e2b2">00109</a> <span class="keyword">inline</span> CPose3D(<span class="keyword">const</span> MATRIX33 &rot, <span class="keyword">const</span> VECTOR3& xyz) : m_ROT(<a class="code" href="namespacemrpt_1_1math.html#a27e8ae8971ff5aa1c39f1f9be334d73aa28acc66160006cb691487ec89f8d266d">UNINITIALIZED_MATRIX</a>), m_ypr_uptodate(false) <a name="l00110"></a>00110 { <a name="l00111"></a>00111 <a class="code" href="mrpt__macros_8h.html#a02c6e78d47a0bae723824559846cc673">ASSERT_EQUAL_</a>(<a class="code" href="namespacemrpt_1_1math.html#a632ae0aecf78103f87f18f9ac33f7170">size</a>(rot,1),3); <a class="code" href="mrpt__macros_8h.html#a02c6e78d47a0bae723824559846cc673">ASSERT_EQUAL_</a>(<a class="code" href="namespacemrpt_1_1math.html#a632ae0aecf78103f87f18f9ac33f7170">size</a>(rot,2),3);<a class="code" href="mrpt__macros_8h.html#a02c6e78d47a0bae723824559846cc673">ASSERT_EQUAL_</a>(xyz.size(),3) <a name="l00112"></a>00112 <span class="keywordflow">for</span> (<span class="keywordtype">int</span> r=0;r<3;r++) <a name="l00113"></a>00113 <span class="keywordflow">for</span> (<span class="keywordtype">int</span> c=0;c<3;c++) <a name="l00114"></a>00114 m_ROT(r,c)=rot.get_unsafe(r,c); <a name="l00115"></a>00115 <span class="keywordflow">for</span> (<span class="keywordtype">int</span> r=0;r<3;r++) m_coords[r]=xyz[r]; <a name="l00116"></a>00116 }<span class="comment"></span> <a name="l00117"></a>00117 <span class="comment"> //! \overload</span> <a name="l00118"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a45334da03ae59d776f5b9ebde4b49b3f">00118</a> <span class="comment"></span> <span class="keyword">inline</span> CPose3D(<span class="keyword">const</span> <a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html">CMatrixDouble33</a> &rot, <span class="keyword">const</span> <a class="code" href="classmrpt_1_1math_1_1_c_array_double.html">CArrayDouble<3></a>& xyz) : m_coords(xyz),m_ROT(rot), m_ypr_uptodate(false) <a name="l00119"></a>00119 { } <a name="l00120"></a>00120 <span class="comment"></span> <a name="l00121"></a>00121 <span class="comment"> /** Constructor from a CPose2D object.</span> <a name="l00122"></a>00122 <span class="comment"> */</span> <a name="l00123"></a>00123 CPose3D(<span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose2_d.html" title="A class used to store a 2D pose.">CPose2D</a> &); <a name="l00124"></a>00124 <span class="comment"></span> <a name="l00125"></a>00125 <span class="comment"> /** Constructor from a CPoint3D object.</span> <a name="l00126"></a>00126 <span class="comment"> */</span> <a name="l00127"></a>00127 CPose3D(<span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_point3_d.html" title="A class used to store a 3D point.">CPoint3D</a> &); <a name="l00128"></a>00128 <span class="comment"></span> <a name="l00129"></a>00129 <span class="comment"> /** Constructor from lightweight object.</span> <a name="l00130"></a>00130 <span class="comment"> */</span> <a name="l00131"></a>00131 CPose3D(<span class="keyword">const</span> <a class="code" href="structmrpt_1_1math_1_1_t_pose3_d.html" title="Lightweight 3D pose (three spatial coordinates, plus three angular coordinates).">mrpt::math::TPose3D</a> &); <a name="l00132"></a>00132 <span class="comment"></span> <a name="l00133"></a>00133 <span class="comment"> /** Constructor from a quaternion (which only represents the 3D rotation part) and a 3D displacement. */</span> <a name="l00134"></a>00134 CPose3D(<span class="keyword">const</span> <a class="code" href="classmrpt_1_1math_1_1_c_quaternion.html">mrpt::math::CQuaternionDouble</a> &q, <span class="keyword">const</span> <span class="keywordtype">double</span> x, <span class="keyword">const</span> <span class="keywordtype">double</span> <a class="code" href="namespace_eigen_1_1internal.html#a3d7a581aeb951248dc6fe114e9e05f07">y</a>, <span class="keyword">const</span> <span class="keywordtype">double</span> z ); <a name="l00135"></a>00135 <span class="comment"></span> <a name="l00136"></a>00136 <span class="comment"> /** Constructor from a CPose3DQuat. */</span> <a name="l00137"></a>00137 CPose3D(<span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d_quat.html" title="A class used to store a 3D pose as a translation (x,y,z) and a quaternion (qr,qx,qy,qz).">CPose3DQuat</a> &); <a name="l00138"></a>00138 <span class="comment"></span> <a name="l00139"></a>00139 <span class="comment"> /** Fast constructor that leaves all the data uninitialized - call with UNINITIALIZED_POSE as argument */</span> <a name="l00140"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#af245a30779e1d574021933a3c9d5d6ce">00140</a> <span class="keyword">inline</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#af245a30779e1d574021933a3c9d5d6ce" title="Fast constructor that leaves all the data uninitialized - call with UNINITIALIZED_POSE as argument...">CPose3D</a>(<a class="code" href="namespacemrpt_1_1poses.html#ac46e1fb95d438a441b6f396d9c79f430">TConstructorFlags_Poses</a> constructor_dummy_param) : m_ROT(<a class="code" href="namespacemrpt_1_1math.html#a27e8ae8971ff5aa1c39f1f9be334d73aa28acc66160006cb691487ec89f8d266d">UNINITIALIZED_MATRIX</a>), m_ypr_uptodate(false) { } <a name="l00141"></a>00141 <span class="comment"></span> <a name="l00142"></a>00142 <span class="comment"> /** Constructor from an array with these 12 elements: [r11 r21 r31 r12 r22 r32 r13 r23 r33 tx ty tz]</span> <a name="l00143"></a>00143 <span class="comment"> * where r{ij} are the entries of the 3x3 rotation matrix and t{x,y,z} are the 3D translation of the pose</span> <a name="l00144"></a>00144 <span class="comment"> * \sa setFrom12Vector, getAs12Vector</span> <a name="l00145"></a>00145 <span class="comment"> */</span> <a name="l00146"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a59214f588539f5b584b2ba4e02d13c10">00146</a> <span class="keyword">inline</span> <span class="keyword">explicit</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a59214f588539f5b584b2ba4e02d13c10" title="Constructor from an array with these 12 elements: [r11 r21 r31 r12 r22 r32 r13 r23 r33 tx ty tz] wher...">CPose3D</a>(<span class="keyword">const</span> <a class="code" href="classmrpt_1_1math_1_1_c_array_double.html" title="A partial specialization of CArrayNumeric for double numbers.">CArrayDouble<12></a> &vec12) : m_ROT( <a class="code" href="namespacemrpt_1_1math.html#a27e8ae8971ff5aa1c39f1f9be334d73aa28acc66160006cb691487ec89f8d266d">UNINITIALIZED_MATRIX</a> ), m_ypr_uptodate(false) { <a name="l00147"></a>00147 setFrom12Vector(vec12); <a name="l00148"></a>00148 } <a name="l00149"></a>00149 <span class="comment"></span> <a name="l00150"></a>00150 <span class="comment"> /** @} */</span> <span class="comment">// end Constructors</span> <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"> /** @name Access 3x3 rotation and 4x4 homogeneous matrices</span> <a name="l00155"></a>00155 <span class="comment"> @{ */</span> <a name="l00156"></a>00156 <span class="comment"></span> <a name="l00157"></a>00157 <span class="comment"> /** Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (translation+orientation).</span> <a name="l00158"></a>00158 <span class="comment"> * \sa getInverseHomogeneousMatrix, getRotationMatrix</span> <a name="l00159"></a>00159 <span class="comment"> */</span> <a name="l00160"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a2d9680cfd637c142dcd0d5523815254a">00160</a> <span class="keyword">inline</span> <span class="keywordtype">void</span> getHomogeneousMatrix(<a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html">CMatrixDouble44</a> & out_HM )<span class="keyword"> const</span> <a name="l00161"></a>00161 <span class="keyword"> </span>{ <a name="l00162"></a>00162 out_HM.insertMatrix(0,0,m_ROT); <a name="l00163"></a>00163 <span class="keywordflow">for</span> (<span class="keywordtype">int</span> i=0;i<3;i++) out_HM(i,3)=m_coords[i]; <a name="l00164"></a>00164 out_HM(3,0)=out_HM(3,1)=out_HM(3,2)=0.; out_HM(3,3)=1.; <a name="l00165"></a>00165 } <a name="l00166"></a>00166 <a name="l00167"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#aa0f69bb9174e66f3196420e53b97fbed">00167</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_pose3_d.html#aa0f69bb9174e66f3196420e53b97fbed">getHomogeneousMatrixVal</a>()<span class="keyword"> const </span>{ <a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html">CMatrixDouble44</a> M; getHomogeneousMatrix(M); <span class="keywordflow">return</span> M;} <a name="l00168"></a>00168 <span class="comment"></span> <a name="l00169"></a>00169 <span class="comment"> /** Get the 3x3 rotation matrix \sa getHomogeneousMatrix */</span> <a name="l00170"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a67131b7bf5250250cf37ed1f8acdf73e">00170</a> <span class="keyword">inline</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a67131b7bf5250250cf37ed1f8acdf73e" title="Get the 3x3 rotation matrix.">getRotationMatrix</a>( <a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html">mrpt::math::CMatrixDouble33</a> & ROT )<span class="keyword"> const </span>{ ROT = m_ROT; }<span class="comment"></span> <a name="l00171"></a>00171 <span class="comment"> //! \overload</span> <a name="l00172"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a007521f8a1d6ac7c2f72dd4b014c00fa">00172</a> <span class="comment"></span> <span class="keyword">inline</span> <span class="keyword">const</span> mrpt<a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html">::math::CMatrixDouble33</a> & <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a007521f8a1d6ac7c2f72dd4b014c00fa">getRotationMatrix</a>()<span class="keyword"> const </span>{ <span class="keywordflow">return</span> m_ROT; } <a name="l00173"></a>00173 <span class="comment"></span> <a name="l00174"></a>00174 <span class="comment"> /** @} */</span> <span class="comment">// end rot and HM</span> <a name="l00175"></a>00175 <a name="l00176"></a>00176 <span class="comment"></span> <a name="l00177"></a>00177 <span class="comment"> /** @name Pose-pose and pose-point compositions and operators</span> <a name="l00178"></a>00178 <span class="comment"> @{ */</span> <a name="l00179"></a>00179 <span class="comment"></span> <a name="l00180"></a>00180 <span class="comment"> /** The operator \f$ a \oplus b \f$ is the pose compounding operator. */</span> <a name="l00181"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a3ccd24581f78b116c1955ff621ceeae9">00181</a> <span class="keyword">inline</span> CPose3D <a class="code" href="namespacemrpt_1_1poses.html#afb287beee02202a14b09f1011b648e6f" title="Compose a 2D point from a new coordinate base given by a 2D pose.">operator + </a>(<span class="keyword">const</span> CPose3D& b)<span class="keyword"> const</span> <a name="l00182"></a>00182 <span class="keyword"> </span>{ <a name="l00183"></a>00183 CPose3D ret(<a class="code" href="namespacemrpt_1_1poses.html#ac46e1fb95d438a441b6f396d9c79f430aefbfdff7ad639a9a8019af9de5f3c592">UNINITIALIZED_POSE</a>); <a name="l00184"></a>00184 ret.<a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a88f72fa352303454295616213fc10c2d" title="Makes "this = A (+) B"; this method is slightly more efficient than "this= A + B;" since it avoids th...">composeFrom</a>(*<span class="keyword">this</span>,b); <a name="l00185"></a>00185 <span class="keywordflow">return</span> ret; <a name="l00186"></a>00186 } <a name="l00187"></a>00187 <span class="comment"></span> <a name="l00188"></a>00188 <span class="comment"> /** The operator \f$ a \oplus b \f$ is the pose compounding operator. */</span> <a name="l00189"></a>00189 <a class="code" href="classmrpt_1_1poses_1_1_c_point3_d.html" title="A class used to store a 3D point.">CPoint3D</a> <a class="code" href="namespacemrpt_1_1poses.html#afb287beee02202a14b09f1011b648e6f" title="Compose a 2D point from a new coordinate base given by a 2D pose.">operator + </a>(<span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_point3_d.html" title="A class used to store a 3D point.">CPoint3D</a>& b) <span class="keyword">const</span>; <a name="l00190"></a>00190 <span class="comment"></span> <a name="l00191"></a>00191 <span class="comment"> /** The operator \f$ a \oplus b \f$ is the pose compounding operator. */</span> <a name="l00192"></a>00192 <a class="code" href="classmrpt_1_1poses_1_1_c_point3_d.html" title="A class used to store a 3D point.">CPoint3D</a> <a class="code" href="namespacemrpt_1_1poses.html#afb287beee02202a14b09f1011b648e6f" title="Compose a 2D point from a new coordinate base given by a 2D pose.">operator + </a>(<span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_point2_d.html" title="A class used to store a 2D point.">CPoint2D</a>& b) <span class="keyword">const</span>; <a name="l00193"></a>00193 <span class="comment"></span> <a name="l00194"></a>00194 <span class="comment"> /** Computes the spherical coordinates of a 3D point as seen from the 6D pose specified by this object. For the coordinate system see the top of this page. */</span> <a name="l00195"></a>00195 <span class="keywordtype">void</span> sphericalCoordinates( <a name="l00196"></a>00196 <span class="keyword">const</span> <a class="code" href="structmrpt_1_1math_1_1_t_point3_d.html" title="Lightweight 3D point.">TPoint3D</a> &point, <a name="l00197"></a>00197 <span class="keywordtype">double</span> &out_range, <a name="l00198"></a>00198 <span class="keywordtype">double</span> &out_yaw, <a name="l00199"></a>00199 <span class="keywordtype">double</span> &out_pitch ) <span class="keyword">const</span>; <a name="l00200"></a>00200 <span class="comment"></span> <a name="l00201"></a>00201 <span class="comment"> /** An alternative, slightly more efficient way of doing \f$ G = P \oplus L \f$ with G and L being 3D points and P this 6D pose.</span> <a name="l00202"></a>00202 <span class="comment"> * If pointers are provided, the corresponding Jacobians are returned.</span> <a name="l00203"></a>00203 <span class="comment"> * "out_jacobian_df_dse3" stands for the Jacobian with respect to the 6D locally Euclidean vector in the tangent space of SE(3).</span> <a name="l00204"></a>00204 <span class="comment"> * See <a href="http://www.mrpt.org/6D_poses:equivalences_compositions_and_uncertainty" >this report</a> for mathematical details.</span> <a name="l00205"></a>00205 <span class="comment"> * \param If set to true, the Jacobian "out_jacobian_df_dpose" uses a fastest linearized appoximation (valid only for small rotations!).</span> <a name="l00206"></a>00206 <span class="comment"> */</span> <a name="l00207"></a>00207 <span class="keywordtype">void</span> composePoint(<span class="keywordtype">double</span> lx,<span class="keywordtype">double</span> ly,<span class="keywordtype">double</span> lz, <span class="keywordtype">double</span> &gx, <span class="keywordtype">double</span> &gy, <span class="keywordtype">double</span> &gz, <a name="l00208"></a>00208 <a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html">mrpt::math::CMatrixFixedNumeric<double,3,3></a> *out_jacobian_df_dpoint=NULL, <a name="l00209"></a>00209 <a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html" title="A numeric matrix of compile-time fixed size.">mrpt::math::CMatrixFixedNumeric<double,3,6></a> *out_jacobian_df_dpose=NULL, <a name="l00210"></a>00210 <a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html" title="A numeric matrix of compile-time fixed size.">mrpt::math::CMatrixFixedNumeric<double,3,6></a> *out_jacobian_df_dse3=NULL, <a name="l00211"></a>00211 <span class="keywordtype">bool</span> use_small_rot_approx = <span class="keyword">false</span>) <span class="keyword">const</span>; <a name="l00212"></a>00212 <span class="comment"></span> <a name="l00213"></a>00213 <span class="comment"> /** An alternative, slightly more efficient way of doing \f$ G = P \oplus L \f$ with G and L being 3D points and P this 6D pose.</span> <a name="l00214"></a>00214 <span class="comment"> * \note local_point is passed by value to allow global and local point to be the same variable</span> <a name="l00215"></a>00215 <span class="comment"> */</span> <a name="l00216"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a979861f7272eaa41953403e39588fe9e">00216</a> <span class="keyword">inline</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a979861f7272eaa41953403e39588fe9e" title="An alternative, slightly more efficient way of doing with G and L being 3D points and P this 6D pose...">composePoint</a>(<span class="keyword">const</span> <a class="code" href="structmrpt_1_1math_1_1_t_point3_d.html" title="Lightweight 3D point.">TPoint3D</a> local_point, <a class="code" href="structmrpt_1_1math_1_1_t_point3_d.html" title="Lightweight 3D point.">TPoint3D</a> &global_point)<span class="keyword"> const </span>{ <a name="l00217"></a>00217 composePoint(local_point.<a class="code" href="structmrpt_1_1math_1_1_t_point3_d.html#a5014ee49d97866d293568300b619a7e2" title="X coordinate.">x</a>,local_point.<a class="code" href="structmrpt_1_1math_1_1_t_point3_d.html#aec879c0d61d8446e93b7d09344931d37" title="Y coordinate.">y</a>,local_point.<a class="code" href="structmrpt_1_1math_1_1_t_point3_d.html#a61df04839b9146696e696fc7af3bc307" title="Z coordinate.">z</a>, global_point.<a class="code" href="structmrpt_1_1math_1_1_t_point3_d.html#a5014ee49d97866d293568300b619a7e2" title="X coordinate.">x</a>,global_point.<a class="code" href="structmrpt_1_1math_1_1_t_point3_d.html#aec879c0d61d8446e93b7d09344931d37" title="Y coordinate.">y</a>,global_point.<a class="code" href="structmrpt_1_1math_1_1_t_point3_d.html#a61df04839b9146696e696fc7af3bc307" title="Z coordinate.">z</a> ); <a name="l00218"></a>00218 } <a name="l00219"></a>00219 <span class="comment"></span> <a name="l00220"></a>00220 <span class="comment"> /** An alternative, slightly more efficient way of doing \f$ G = P \oplus L \f$ with G and L being 3D points and P this 6D pose. */</span> <a name="l00221"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#ab4cd48076205450895d0666c748bd983">00221</a> <span class="keyword">inline</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#ab4cd48076205450895d0666c748bd983" title="An alternative, slightly more efficient way of doing with G and L being 3D points and P this 6D pose...">composePoint</a>(<span class="keywordtype">double</span> lx,<span class="keywordtype">double</span> ly,<span class="keywordtype">double</span> lz, <span class="keywordtype">float</span> &gx, <span class="keywordtype">float</span> &gy, <span class="keywordtype">float</span> &gz )<span class="keyword"> const </span>{ <a name="l00222"></a>00222 <span class="keywordtype">double</span> ggx, ggy,ggz; <a name="l00223"></a>00223 composePoint(lx,ly,lz,ggx,ggy,ggz); <a name="l00224"></a>00224 gx = ggx; gy = ggy; gz = ggz; <a name="l00225"></a>00225 } <a name="l00226"></a>00226 <span class="comment"></span> <a name="l00227"></a>00227 <span class="comment"> /** Computes the 3D point L such as \f$ L = G \ominus this \f$.</span> <a name="l00228"></a>00228 <span class="comment"> * If pointers are provided, the corresponding Jacobians are returned.</span> <a name="l00229"></a>00229 <span class="comment"> * "out_jacobian_df_dse3" stands for the Jacobian with respect to the 6D locally Euclidean vector in the tangent space of SE(3).</span> <a name="l00230"></a>00230 <span class="comment"> * See <a href="http://www.mrpt.org/6D_poses:equivalences_compositions_and_uncertainty" >this report</a> for mathematical details.</span> <a name="l00231"></a>00231 <span class="comment"> * \sa composePoint, composeFrom</span> <a name="l00232"></a>00232 <span class="comment"> */</span> <a name="l00233"></a>00233 <span class="keywordtype">void</span> inverseComposePoint(<span class="keyword">const</span> <span class="keywordtype">double</span> gx,<span class="keyword">const</span> <span class="keywordtype">double</span> gy,<span class="keyword">const</span> <span class="keywordtype">double</span> gz,<span class="keywordtype">double</span> &lx,<span class="keywordtype">double</span> &ly,<span class="keywordtype">double</span> &lz, <a name="l00234"></a>00234 <a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html">mrpt::math::CMatrixFixedNumeric<double,3,3></a> *out_jacobian_df_dpoint=NULL, <a name="l00235"></a>00235 <a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html" title="A numeric matrix of compile-time fixed size.">mrpt::math::CMatrixFixedNumeric<double,3,6></a> *out_jacobian_df_dpose=NULL, <a name="l00236"></a>00236 <a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html" title="A numeric matrix of compile-time fixed size.">mrpt::math::CMatrixFixedNumeric<double,3,6></a> *out_jacobian_df_dse3=NULL ) <span class="keyword">const</span>; <a name="l00237"></a>00237 <span class="comment"></span> <a name="l00238"></a>00238 <span class="comment"> /** Makes "this = A (+) B"; this method is slightly more efficient than "this= A + B;" since it avoids the temporary object.</span> <a name="l00239"></a>00239 <span class="comment"> * \note A or B can be "this" without problems.</span> <a name="l00240"></a>00240 <span class="comment"> */</span> <a name="l00241"></a>00241 <span class="keywordtype">void</span> composeFrom(<span class="keyword">const</span> CPose3D& A, <span class="keyword">const</span> CPose3D& B ); <a name="l00242"></a>00242 <span class="comment"></span> <a name="l00243"></a>00243 <span class="comment"> /** Make \f$ this = this \oplus b \f$ (\a b can be "this" without problems) */</span> <a name="l00244"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a01f67ad787fdf9db41cf6de00b8f7c25">00244</a> <span class="keyword">inline</span> CPose3D& <a class="code" href="group__container__ops__grp.html#ga28127b8dfe78fea7644c4f2a3517cdef" title="a+=b (element-wise sum)">operator += </a>(<span class="keyword">const</span> CPose3D& b) <a name="l00245"></a>00245 { <a name="l00246"></a>00246 composeFrom(*<span class="keyword">this</span>,b); <a name="l00247"></a>00247 <span class="keywordflow">return</span> *<span class="keyword">this</span>; <a name="l00248"></a>00248 } <a name="l00249"></a>00249 <span class="comment"></span> <a name="l00250"></a>00250 <span class="comment"> /** Makes \f$ this = A \ominus B \f$ this method is slightly more efficient than "this= A - B;" since it avoids the temporary object.</span> <a name="l00251"></a>00251 <span class="comment"> * \note A or B can be "this" without problems.</span> <a name="l00252"></a>00252 <span class="comment"> * \sa composeFrom, composePoint</span> <a name="l00253"></a>00253 <span class="comment"> */</span> <a name="l00254"></a>00254 <span class="keywordtype">void</span> inverseComposeFrom(<span class="keyword">const</span> CPose3D& A, <span class="keyword">const</span> CPose3D& B ); <a name="l00255"></a>00255 <span class="comment"></span> <a name="l00256"></a>00256 <span class="comment"> /** Compute \f$ RET = this \oplus b \f$ */</span> <a name="l00257"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#aa96efca4ba4952c71a4eb8cf07f6ad20">00257</a> <span class="keyword">inline</span> CPose3D <a class="code" href="namespacemrpt_1_1poses.html#a678c1606b35876eae036755599a22d84" title="Unary - operator: return the inverse pose "-p" (Note that is NOT the same than a pose with negative x...">operator - </a>(<span class="keyword">const</span> CPose3D& b)<span class="keyword"> const</span> <a name="l00258"></a>00258 <span class="keyword"> </span>{ <a name="l00259"></a>00259 CPose3D ret(<a class="code" href="namespacemrpt_1_1poses.html#ac46e1fb95d438a441b6f396d9c79f430aefbfdff7ad639a9a8019af9de5f3c592">UNINITIALIZED_POSE</a>); <a name="l00260"></a>00260 ret.<a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a98f83d65d659a40fddff750983e5ed22" title="Makes this method is slightly more efficient than "this= A - B;" since it avoids the temporary objec...">inverseComposeFrom</a>(*<span class="keyword">this</span>,b); <a name="l00261"></a>00261 <span class="keywordflow">return</span> ret; <a name="l00262"></a>00262 } <a name="l00263"></a>00263 <span class="comment"></span> <a name="l00264"></a>00264 <span class="comment"> /** Convert this pose into its inverse, saving the result in itself. \sa operator- */</span> <a name="l00265"></a>00265 <span class="keywordtype">void</span> inverse(); <a name="l00266"></a>00266 <span class="comment"></span> <a name="l00267"></a>00267 <span class="comment"> /** makes: this = p (+) this */</span> <a name="l00268"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a9739a039b36061413cdb85bbb41491bb">00268</a> <span class="keyword">inline</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a9739a039b36061413cdb85bbb41491bb" title="makes: this = p (+) this">changeCoordinatesReference</a>( <span class="keyword">const</span> CPose3D & p ) { composeFrom(p,CPose3D(*<span class="keyword">this</span>)); } <a name="l00269"></a>00269 <span class="comment"></span> <a name="l00270"></a>00270 <span class="comment"> /** @} */</span> <span class="comment">// compositions</span> <a name="l00271"></a>00271 <a name="l00272"></a>00272 <span class="comment"></span> <a name="l00273"></a>00273 <span class="comment"> /** @name Access and modify contents</span> <a name="l00274"></a>00274 <span class="comment"> @{ */</span> <a name="l00275"></a>00275 <span class="comment"></span> <a name="l00276"></a>00276 <span class="comment"> /** Scalar sum of all 6 components: This is diferent from poses composition, which is implemented as "+" operators.</span> <a name="l00277"></a>00277 <span class="comment"> * \sa normalizeAngles</span> <a name="l00278"></a>00278 <span class="comment"> */</span> <a name="l00279"></a>00279 <span class="keywordtype">void</span> addComponents(<span class="keyword">const</span> CPose3D &p); <a name="l00280"></a>00280 <span class="comment"></span> <a name="l00281"></a>00281 <span class="comment"> /** Rebuild the internal matrix & update the yaw/pitch/roll angles within the ]-PI,PI] range (Must be called after using addComponents)</span> <a name="l00282"></a>00282 <span class="comment"> * \sa addComponents</span> <a name="l00283"></a>00283 <span class="comment"> */</span> <a name="l00284"></a>00284 <span class="keywordtype">void</span> normalizeAngles(); <a name="l00285"></a>00285 <span class="comment"></span> <a name="l00286"></a>00286 <span class="comment"> /** Scalar multiplication of x,y,z,yaw,pitch & roll (angles will be wrapped to the ]-pi,pi] interval). */</span> <a name="l00287"></a>00287 <span class="keywordtype">void</span> <a class="code" href="group__container__ops__grp.html#gabc43a80aa18fe8ffdfe69fed3ad115a9" title="a*=b (element-wise multiplication)">operator *=</a>(<span class="keyword">const</span> <span class="keywordtype">double</span> s); <a name="l00288"></a>00288 <span class="comment"></span> <a name="l00289"></a>00289 <span class="comment"> /** Set the pose from a 3D position (meters) and yaw/pitch/roll angles (radians) - This method recomputes the internal rotation matrix.</span> <a name="l00290"></a>00290 <span class="comment"> * \sa getYawPitchRoll, setYawPitchRoll</span> <a name="l00291"></a>00291 <span class="comment"> */</span> <a name="l00292"></a>00292 <span class="keywordtype">void</span> setFromValues( <a name="l00293"></a>00293 <span class="keyword">const</span> <span class="keywordtype">double</span> x0, <a name="l00294"></a>00294 <span class="keyword">const</span> <span class="keywordtype">double</span> y0, <a name="l00295"></a>00295 <span class="keyword">const</span> <span class="keywordtype">double</span> z0, <a name="l00296"></a>00296 <span class="keyword">const</span> <span class="keywordtype">double</span> yaw=0, <a name="l00297"></a>00297 <span class="keyword">const</span> <span class="keywordtype">double</span> pitch=0, <a name="l00298"></a>00298 <span class="keyword">const</span> <span class="keywordtype">double</span> roll=0); <a name="l00299"></a>00299 <span class="comment"></span> <a name="l00300"></a>00300 <span class="comment"> /** Set the pose from a 3D position (meters) and a quaternion, stored as [x y z qr qx qy qz] in a 7-element vector.</span> <a name="l00301"></a>00301 <span class="comment"> * \sa setFromValues, getYawPitchRoll, setYawPitchRoll, CQuaternion, getAsQuaternion</span> <a name="l00302"></a>00302 <span class="comment"> */</span> <a name="l00303"></a>00303 <span class="keyword">template</span> <<span class="keyword">typename</span> VECTORLIKE> <a name="l00304"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a349849154d1add656c936ad4323f28dd">00304</a> <span class="keyword">inline</span> <span class="keywordtype">void</span> setFromXYZQ( <a name="l00305"></a>00305 <span class="keyword">const</span> VECTORLIKE &v, <a name="l00306"></a>00306 <span class="keyword">const</span> <span class="keywordtype">size_t</span> index_offset = 0) <a name="l00307"></a>00307 { <a name="l00308"></a>00308 <a class="code" href="mrpt__macros_8h.html#ad8765ef1dc961d49450d95338d283386">ASSERT_ABOVEEQ_</a>(v.size(), 7+index_offset) <a name="l00309"></a>00309 <span class="comment">// The 3x3 rotation part:</span> <a name="l00310"></a>00310 <a class="code" href="classmrpt_1_1math_1_1_c_quaternion.html" title="A quaternion, which can represent a 3D rotation as pair , with a real part "r" and a 3D vector ...">mrpt::math::CQuaternion<typename VECTORLIKE::value_type></a> q( v[index_offset+3],v[index_offset+4],v[index_offset+5],v[index_offset+6] ); <a name="l00311"></a>00311 q.rotationMatrixNoResize(m_ROT); <a name="l00312"></a>00312 m_ypr_uptodate=<span class="keyword">false</span>; <a name="l00313"></a>00313 m_coords[0] = v[index_offset+0]; <a name="l00314"></a>00314 m_coords[1] = v[index_offset+1]; <a name="l00315"></a>00315 m_coords[2] = v[index_offset+2]; <a name="l00316"></a>00316 } <a name="l00317"></a>00317 <span class="comment"></span> <a name="l00318"></a>00318 <span class="comment"> /** Set the 3 angles of the 3D pose (in radians) - This method recomputes the internal rotation coordinates matrix.</span> <a name="l00319"></a>00319 <span class="comment"> * \sa getYawPitchRoll, setFromValues</span> <a name="l00320"></a>00320 <span class="comment"> */</span> <a name="l00321"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#acdd487677f00ab2378e3fa27d08ff651">00321</a> <span class="keyword">inline</span> <span class="keywordtype">void</span> setYawPitchRoll( <a name="l00322"></a>00322 <span class="keyword">const</span> <span class="keywordtype">double</span> yaw_, <a name="l00323"></a>00323 <span class="keyword">const</span> <span class="keywordtype">double</span> pitch_, <a name="l00324"></a>00324 <span class="keyword">const</span> <span class="keywordtype">double</span> roll_) <a name="l00325"></a>00325 { <a name="l00326"></a>00326 setFromValues(x(),<a class="code" href="namespace_eigen_1_1internal.html#a3d7a581aeb951248dc6fe114e9e05f07">y</a>(),z(),yaw_,pitch_,roll_); <a name="l00327"></a>00327 } <a name="l00328"></a>00328 <span class="comment"></span> <a name="l00329"></a>00329 <span class="comment"> /** Set pose from an array with these 12 elements: [r11 r21 r31 r12 r22 r32 r13 r23 r33 tx ty tz]</span> <a name="l00330"></a>00330 <span class="comment"> * where r{ij} are the entries of the 3x3 rotation matrix and t{x,y,z} are the 3D translation of the pose</span> <a name="l00331"></a>00331 <span class="comment"> * \sa getAs12Vector</span> <a name="l00332"></a>00332 <span class="comment"> */</span> <a name="l00333"></a>00333 <span class="keyword">template</span> <<span class="keyword">class</span> ARRAYORVECTOR> <a name="l00334"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a9c75a2bf26cc7ef56931497c900f8ab1">00334</a> <span class="keyword">inline</span> <span class="keywordtype">void</span> setFrom12Vector(<span class="keyword">const</span> ARRAYORVECTOR &vec12) <a name="l00335"></a>00335 { <a name="l00336"></a>00336 m_ROT.set_unsafe(0,0, vec12[0]); m_ROT.set_unsafe(0,1, vec12[3]); m_ROT.set_unsafe(0,2, vec12[6]); <a name="l00337"></a>00337 m_ROT.set_unsafe(1,0, vec12[1]); m_ROT.set_unsafe(1,1, vec12[4]); m_ROT.set_unsafe(1,2, vec12[7]); <a name="l00338"></a>00338 m_ROT.set_unsafe(2,0, vec12[2]); m_ROT.set_unsafe(2,1, vec12[5]); m_ROT.set_unsafe(2,2, vec12[8]); <a name="l00339"></a>00339 m_coords[0] = vec12[ 9]; <a name="l00340"></a>00340 m_coords[1] = vec12[10]; <a name="l00341"></a>00341 m_coords[2] = vec12[11]; <a name="l00342"></a>00342 } <a name="l00343"></a>00343 <span class="comment"></span> <a name="l00344"></a>00344 <span class="comment"> /** Get the pose representation as an array with these 12 elements: [r11 r21 r31 r12 r22 r32 r13 r23 r33 tx ty tz]</span> <a name="l00345"></a>00345 <span class="comment"> * where r{ij} are the entries of the 3x3 rotation matrix and t{x,y,z} are the 3D translation of the pose</span> <a name="l00346"></a>00346 <span class="comment"> * \sa setFrom12Vector</span> <a name="l00347"></a>00347 <span class="comment"> */</span> <a name="l00348"></a>00348 <span class="keyword">template</span> <<span class="keyword">class</span> ARRAYORVECTOR> <a name="l00349"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a5d3d820e9f85d64902c9d24e6bf3cff1">00349</a> <span class="keyword">inline</span> <span class="keywordtype">void</span> getAs12Vector(ARRAYORVECTOR &vec12)<span class="keyword"> const</span> <a name="l00350"></a>00350 <span class="keyword"> </span>{ <a name="l00351"></a>00351 vec12[0] = m_ROT.get_unsafe(0,0); vec12[3] = m_ROT.get_unsafe(0,1); vec12[6] = m_ROT.get_unsafe(0,2); <a name="l00352"></a>00352 vec12[1] = m_ROT.get_unsafe(1,0); vec12[4] = m_ROT.get_unsafe(1,1); vec12[7] = m_ROT.get_unsafe(1,2); <a name="l00353"></a>00353 vec12[2] = m_ROT.get_unsafe(2,0); vec12[5] = m_ROT.get_unsafe(2,1); vec12[8] = m_ROT.get_unsafe(2,2); <a name="l00354"></a>00354 vec12[ 9] = m_coords[0]; <a name="l00355"></a>00355 vec12[10] = m_coords[1]; <a name="l00356"></a>00356 vec12[11] = m_coords[2]; <a name="l00357"></a>00357 } <a name="l00358"></a>00358 <span class="comment"></span> <a name="l00359"></a>00359 <span class="comment"> /** Returns the three angles (yaw, pitch, roll), in radians, from the rotation matrix.</span> <a name="l00360"></a>00360 <span class="comment"> * \sa setFromValues, yaw, pitch, roll</span> <a name="l00361"></a>00361 <span class="comment"> */</span> <a name="l00362"></a>00362 <span class="keywordtype">void</span> getYawPitchRoll( <span class="keywordtype">double</span> &yaw, <span class="keywordtype">double</span> &pitch, <span class="keywordtype">double</span> &roll ) <span class="keyword">const</span>; <a name="l00363"></a>00363 <a name="l00364"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#ae6df3cca6719010c12d5d70f7059cb3f">00364</a> <span class="keyword">inline</span> <span class="keywordtype">double</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#ae6df3cca6719010c12d5d70f7059cb3f" title="Get the YAW angle (in radians)">yaw</a>()<span class="keyword"> const </span>{ updateYawPitchRoll(); <span class="keywordflow">return</span> m_yaw; } <span class="comment">//!< Get the YAW angle (in radians) \sa setFromValues</span> <a name="l00365"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#abed455c10a98c4b7463e49ca73dd1ac1">00365</a> <span class="comment"></span> <span class="keyword">inline</span> <span class="keywordtype">double</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#abed455c10a98c4b7463e49ca73dd1ac1" title="Get the PITCH angle (in radians)">pitch</a>()<span class="keyword"> const </span>{ updateYawPitchRoll(); <span class="keywordflow">return</span> m_pitch; } <span class="comment">//!< Get the PITCH angle (in radians) \sa setFromValues</span> <a name="l00366"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a47c00788772e211ca9efa4a59153b19b">00366</a> <span class="comment"></span> <span class="keyword">inline</span> <span class="keywordtype">double</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a47c00788772e211ca9efa4a59153b19b" title="Get the ROLL angle (in radians)">roll</a>()<span class="keyword"> const </span>{ updateYawPitchRoll(); <span class="keywordflow">return</span> m_roll; } <span class="comment">//!< Get the ROLL angle (in radians) \sa setFromValues</span> <a name="l00367"></a>00367 <span class="comment"></span><span class="comment"></span> <a name="l00368"></a>00368 <span class="comment"> /** Returns a 1x6 vector with [x y z yaw pitch roll] */</span> <a name="l00369"></a>00369 <span class="keywordtype">void</span> getAsVector(<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) <span class="keyword">const</span>; <a name="l00370"></a>00370 <span class="comment"></span> <a name="l00371"></a>00371 <span class="comment"> /** Returns the quaternion associated to the rotation of this object (NOTE: XYZ translation is ignored)</span> <a name="l00372"></a>00372 <span class="comment"> * \f[ \mathbf{q} = \left( \begin{array}{c} \cos (\phi /2) \cos (\theta /2) \cos (\psi /2) + \sin (\phi /2) \sin (\theta /2) \sin (\psi /2) \\ \sin (\phi /2) \cos (\theta /2) \cos (\psi /2) - \cos (\phi /2) \sin (\theta /2) \sin (\psi /2) \\ \cos (\phi /2) \sin (\theta /2) \cos (\psi /2) + \sin (\phi /2) \cos (\theta /2) \sin (\psi /2) \\ \cos (\phi /2) \cos (\theta /2) \sin (\psi /2) - \sin (\phi /2) \sin (\theta /2) \cos (\psi /2) \\ \end{array}\right) \f]</span> <a name="l00373"></a>00373 <span class="comment"> * With : \f$ \phi = roll \f$, \f$ \theta = pitch \f$ and \f$ \psi = yaw \f$.</span> <a name="l00374"></a>00374 <span class="comment"> * \param out_dq_dr If provided, the 4x3 Jacobian of the transformation will be computed and stored here. It's the Jacobian of the transformation from (yaw pitch roll) to (qr qx qy qz).</span> <a name="l00375"></a>00375 <span class="comment"> */</span> <a name="l00376"></a>00376 <span class="keywordtype">void</span> getAsQuaternion( <a name="l00377"></a>00377 <a class="code" href="classmrpt_1_1math_1_1_c_quaternion.html">mrpt::math::CQuaternionDouble</a> &q, <a name="l00378"></a>00378 <a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html" title="A numeric matrix of compile-time fixed size.">mrpt::math::CMatrixFixedNumeric<double,4,3></a> *out_dq_dr = NULL <a name="l00379"></a>00379 ) <span class="keyword">const</span>; <a name="l00380"></a>00380 <a name="l00381"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#aa7783b4cf19e6c2f3a653a07159784e8">00381</a> <span class="keyword">inline</span> <span class="keyword">const</span> <span class="keywordtype">double</span> &operator[](<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i)<span class="keyword"> const</span> <a name="l00382"></a>00382 <span class="keyword"> </span>{ <a name="l00383"></a>00383 updateYawPitchRoll(); <a name="l00384"></a>00384 <span class="keywordflow">switch</span>(i) <a name="l00385"></a>00385 { <a name="l00386"></a>00386 <span class="keywordflow">case</span> 0:<span class="keywordflow">return</span> m_coords[0]; <a name="l00387"></a>00387 <span class="keywordflow">case</span> 1:<span class="keywordflow">return</span> m_coords[1]; <a name="l00388"></a>00388 <span class="keywordflow">case</span> 2:<span class="keywordflow">return</span> m_coords[2]; <a name="l00389"></a>00389 <span class="keywordflow">case</span> 3:<span class="keywordflow">return</span> m_yaw; <a name="l00390"></a>00390 <span class="keywordflow">case</span> 4:<span class="keywordflow">return</span> m_pitch; <a name="l00391"></a>00391 <span class="keywordflow">case</span> 5:<span class="keywordflow">return</span> m_roll; <a name="l00392"></a>00392 <span class="keywordflow">default</span>: <a name="l00393"></a>00393 <span class="keywordflow">throw</span> <a class="code" href="classstd_1_1runtime__error.html" title="STL class.">std::runtime_error</a>(<span class="stringliteral">"CPose3D::operator[]: Index of bounds."</span>); <a name="l00394"></a>00394 } <a name="l00395"></a>00395 } <a name="l00396"></a>00396 <span class="comment">// CPose3D CANNOT have a write [] operator, since it'd leave the object in an inconsistent state (outdated rotation matrix).</span> <a name="l00397"></a>00397 <span class="comment">// Use setFromValues() instead.</span> <a name="l00398"></a>00398 <span class="comment">// inline double &operator[](unsigned int i)</span> <a name="l00399"></a>00399 <span class="comment"></span> <a name="l00400"></a>00400 <span class="comment"> /** Returns a human-readable textual representation of the object (eg: "[x y z yaw pitch roll]", angles in degrees.)</span> <a name="l00401"></a>00401 <span class="comment"> * \sa fromString</span> <a name="l00402"></a>00402 <span class="comment"> */</span> <a name="l00403"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#afe62a83323312708b9820a56d940b8d2">00403</a> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#afe62a83323312708b9820a56d940b8d2" title="Returns a human-readable textual representation of the object (eg: "[x y z yaw pitch roll]"...">asString</a>(<a class="code" href="classstd_1_1string.html" title="STL class.">std::string</a> &s)<span class="keyword"> const </span>{ updateYawPitchRoll(); s = <a class="code" href="namespacemrpt.html#a3a27af794b658df5491e2b7678f8ccb8" title="A std::string version of C sprintf.">mrpt::format</a>(<span class="stringliteral">"[%f %f %f %f %f %f]"</span>,m_coords[0],m_coords[1],m_coords[2],<a class="code" href="namespacemrpt_1_1utils.html#a62aea6de6157d52c54ae4251c871cfc1" title="Radians to degrees.">RAD2DEG</a>(m_yaw),<a class="code" href="namespacemrpt_1_1utils.html#a62aea6de6157d52c54ae4251c871cfc1" title="Radians to degrees.">RAD2DEG</a>(m_pitch),<a class="code" href="namespacemrpt_1_1utils.html#a62aea6de6157d52c54ae4251c871cfc1" title="Radians to degrees.">RAD2DEG</a>(m_roll)); } <a name="l00404"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#ab1f1e0b056ccc73e7746b65dab025a89">00404</a> <span class="keyword">inline</span> std<a class="code" href="classstd_1_1string.html" title="STL class.">::string</a> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#ab1f1e0b056ccc73e7746b65dab025a89">asString</a>()<span class="keyword"> const </span>{ std<a class="code" href="classstd_1_1string.html" title="STL class.">::string</a> s; <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#ab1f1e0b056ccc73e7746b65dab025a89">asString</a>(s); <span class="keywordflow">return</span> s; } <a name="l00405"></a>00405 <span class="comment"></span> <a name="l00406"></a>00406 <span class="comment"> /** Set the current object value from a string generated by 'asString' (eg: "[x y z yaw pitch roll]", angles in deg. )</span> <a name="l00407"></a>00407 <span class="comment"> * \sa asString</span> <a name="l00408"></a>00408 <span class="comment"> * \exception std::exception On invalid format</span> <a name="l00409"></a>00409 <span class="comment"> */</span> <a name="l00410"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#aaf6a240fec5da07b3eb8b6c5e45e1f3d">00410</a> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#aaf6a240fec5da07b3eb8b6c5e45e1f3d" title="Set the current object value from a string generated by 'asString' (eg: "[x y z yaw pitch roll]"...">fromString</a>(<span class="keyword">const</span> <a class="code" href="classstd_1_1string.html" title="STL class.">std::string</a> &s) { <a name="l00411"></a>00411 <a class="code" href="classmrpt_1_1math_1_1_c_matrix_template_numeric.html" title="A matrix of dynamic size.">CMatrixDouble</a> m; <a name="l00412"></a>00412 <span class="keywordflow">if</span> (!m.fromMatlabStringFormat(s)) <a class="code" href="mrpt__macros_8h.html#aaa3f404ea85a6575a7139f8d101370ba">THROW_EXCEPTION</a>(<span class="stringliteral">"Malformed expression in ::fromString"</span>); <a name="l00413"></a>00413 <a class="code" href="mrpt__macros_8h.html#ad30ea0382c594c0e2efe88212e9352b0">ASSERTMSG_</a>(<a class="code" href="namespacemrpt_1_1math.html#a632ae0aecf78103f87f18f9ac33f7170">mrpt::math::size</a>(m,1)==1 && <a class="code" href="namespacemrpt_1_1math.html#a632ae0aecf78103f87f18f9ac33f7170">mrpt::math::size</a>(m,2)==6, <span class="stringliteral">"Wrong size of vector in ::fromString"</span>); <a name="l00414"></a>00414 this->setFromValues(m.get_unsafe(0,0),m.get_unsafe(0,1),m.get_unsafe(0,2),<a class="code" href="namespacemrpt_1_1utils.html#a186dc19748953878f7be5e9b0c345dfd" title="Degrees to radians.">DEG2RAD</a>(m.get_unsafe(0,3)),<a class="code" href="namespacemrpt_1_1utils.html#a186dc19748953878f7be5e9b0c345dfd" title="Degrees to radians.">DEG2RAD</a>(m.get_unsafe(0,4)),<a class="code" href="namespacemrpt_1_1utils.html#a186dc19748953878f7be5e9b0c345dfd" title="Degrees to radians.">DEG2RAD</a>(m.get_unsafe(0,5))); <a name="l00415"></a>00415 } <a name="l00416"></a>00416 <span class="comment"></span> <a name="l00417"></a>00417 <span class="comment"> /** Return true if the 6D pose represents a Z axis almost exactly vertical (upwards or downwards), with a given tolerance (if set to 0 exact horizontality is tested). */</span> <a name="l00418"></a>00418 <span class="keywordtype">bool</span> isHorizontal( <span class="keyword">const</span> <span class="keywordtype">double</span> tolerance=0) <span class="keyword">const</span>; <a name="l00419"></a>00419 <span class="comment"></span> <a name="l00420"></a>00420 <span class="comment"> /** The euclidean distance between two poses taken as two 6-length vectors (angles in radians). */</span> <a name="l00421"></a>00421 <span class="keywordtype">double</span> distanceEuclidean6D( <span class="keyword">const</span> CPose3D &o ) <span class="keyword">const</span>; <a name="l00422"></a>00422 <span class="comment"></span> <a name="l00423"></a>00423 <span class="comment"> /** @} */</span> <span class="comment">// modif. components</span> <a name="l00424"></a>00424 <a name="l00425"></a>00425 <a name="l00426"></a>00426 <span class="comment"></span> <a name="l00427"></a>00427 <span class="comment"> /** @name Lie Algebra methods</span> <a name="l00428"></a>00428 <span class="comment"> @{ */</span> <a name="l00429"></a>00429 <span class="comment"></span> <a name="l00430"></a>00430 <span class="comment"> /** Exponentiate a Vector in the SE(3) Lie Algebra to generate a new CPose3D (static method).</span> <a name="l00431"></a>00431 <span class="comment"> * \note Method from TooN (C) Tom Drummond (GNU GPL) */</span> <a name="l00432"></a>00432 <span class="keyword">static</span> CPose3D exp(<span class="keyword">const</span> <a class="code" href="classmrpt_1_1math_1_1_c_array_numeric.html" title="CArrayNumeric is an array for numeric types supporting several mathematical operations (actually...">mrpt::math::CArrayNumeric<double,6></a> & vect); <a name="l00433"></a>00433 <span class="comment"></span> <a name="l00434"></a>00434 <span class="comment"> /** Exponentiate a vector in the Lie algebra to generate a new SO(3) (a 3x3 rotation matrix).</span> <a name="l00435"></a>00435 <span class="comment"> * \note Method from TooN (C) Tom Drummond (GNU GPL) */</span> <a name="l00436"></a>00436 <span class="keyword">static</span> <a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html">CMatrixDouble33</a> exp_rotation(<span class="keyword">const</span> <a class="code" href="classmrpt_1_1math_1_1_c_array_numeric.html" title="CArrayNumeric is an array for numeric types supporting several mathematical operations (actually...">mrpt::math::CArrayNumeric<double,3></a> & vect); <a name="l00437"></a>00437 <a name="l00438"></a>00438 <span class="comment"></span> <a name="l00439"></a>00439 <span class="comment"> /** Take the logarithm of the 3x4 matrix defined by this pose, generating the corresponding vector in the SE(3) Lie Algebra.</span> <a name="l00440"></a>00440 <span class="comment"> * \note Method from TooN (C) Tom Drummond (GNU GPL)</span> <a name="l00441"></a>00441 <span class="comment"> * \sa ln_jacob</span> <a name="l00442"></a>00442 <span class="comment"> */</span> <a name="l00443"></a>00443 <span class="keywordtype">void</span> ln(<a class="code" href="classmrpt_1_1math_1_1_c_array_double.html" title="A partial specialization of CArrayNumeric for double numbers.">mrpt::math::CArrayDouble<6></a> &out_ln) <span class="keyword">const</span>; <a name="l00444"></a>00444 <span class="comment"></span> <a name="l00445"></a>00445 <span class="comment"> /// \overload</span> <a name="l00446"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a11bb54f0ca1ccbdd6a8cd74d0ed223bc">00446</a> <span class="comment"></span> <span class="keyword">inline</span> mrpt<a class="code" href="classmrpt_1_1math_1_1_c_array_double.html" title="A partial specialization of CArrayNumeric for double numbers.">::math::CArrayDouble<6></a> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a11bb54f0ca1ccbdd6a8cd74d0ed223bc">ln</a>()<span class="keyword"> const </span>{ mrpt<a class="code" href="classmrpt_1_1math_1_1_c_array_double.html" title="A partial specialization of CArrayNumeric for double numbers.">::math::CArrayDouble<6></a> ret; <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a11bb54f0ca1ccbdd6a8cd74d0ed223bc">ln</a>(ret); <span class="keywordflow">return</span> ret; } <a name="l00447"></a>00447 <span class="comment"></span> <a name="l00448"></a>00448 <span class="comment"> /** Jacobian of the logarithm of the 3x4 matrix defined by this pose.</span> <a name="l00449"></a>00449 <span class="comment"> * \note Method from TooN (C) Tom Drummond (GNU GPL)</span> <a name="l00450"></a>00450 <span class="comment"> * \sa ln</span> <a name="l00451"></a>00451 <span class="comment"> */</span> <a name="l00452"></a>00452 <span class="keywordtype">void</span> ln_jacob(<a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html" title="A numeric matrix of compile-time fixed size.">mrpt::math::CMatrixFixedNumeric<double,6,12></a> &J) <span class="keyword">const</span>; <a name="l00453"></a>00453 <span class="comment"></span> <a name="l00454"></a>00454 <span class="comment"> /** Static function to compute the Jacobian of the SO(3) Logarithm function, evaluated at a given 3x3 rotation matrix R.</span> <a name="l00455"></a>00455 <span class="comment"> * \sa ln, ln_jacob</span> <a name="l00456"></a>00456 <span class="comment"> */</span> <a name="l00457"></a>00457 <span class="keyword">static</span> <span class="keywordtype">void</span> ln_rot_jacob(<span class="keyword">const</span> <a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html">CMatrixDouble33</a> &R, <a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html" title="A numeric matrix of compile-time fixed size.">CMatrixFixedNumeric<double,3,9></a> &M); <a name="l00458"></a>00458 <span class="comment"></span> <a name="l00459"></a>00459 <span class="comment"> /** Take the logarithm of the 3x3 rotation matrix, generating the corresponding vector in the Lie Algebra.</span> <a name="l00460"></a>00460 <span class="comment"> * \note Method from TooN (C) Tom Drummond (GNU GPL) */</span> <a name="l00461"></a>00461 <a class="code" href="classmrpt_1_1math_1_1_c_array_double.html">CArrayDouble<3></a> ln_rotation() <span class="keyword">const</span>; <a name="l00462"></a>00462 <span class="comment"></span> <a name="l00463"></a>00463 <span class="comment"> /** @} */</span> <a name="l00464"></a>00464 <a name="l00465"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a1c4d407c9e8c212bdcc073ea35a54346">00465</a> <span class="keyword">typedef</span> CPose3D <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a1c4d407c9e8c212bdcc073ea35a54346" title="Used to emulate CPosePDF types, for example, in mrpt::graphs::CNetworkOfPoses.">type_value</a>; <span class="comment">//!< Used to emulate CPosePDF types, for example, in mrpt::graphs::CNetworkOfPoses</span> <a name="l00466"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a394e2a642190e43d1eb268e2e70e53f2a5012cf5fc292528fbc0e69005acf5575">00466</a> <span class="comment"></span> <span class="keyword">enum</span> { is_3D_val = 1 }; <a name="l00467"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a81952d3f7366165f230f7daf1320150b">00467</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_pose3_d.html#a81952d3f7366165f230f7daf1320150b">is_3D</a>() { <span class="keywordflow">return</span> is_3D_val!=0; } <a name="l00468"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#ac66027644c05d47595076f339ea1f2f4a8fff27ddcd69881cd9bceb069d13f267">00468</a> <span class="keyword">enum</span> { rotation_dimensions = 3 }; <a name="l00469"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a67b629d161f9a8d195e296d80919658ea871ec113d2723d04b7bb906c3ddb8ce5">00469</a> <span class="keyword">enum</span> { is_PDF_val = 0 }; <a name="l00470"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#ac7cd59fb4a79b6e8a0096a46475d2e06">00470</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_pose3_d.html#ac7cd59fb4a79b6e8a0096a46475d2e06">is_PDF</a>() { <span class="keywordflow">return</span> is_PDF_val!=0; } <a name="l00471"></a>00471 <a name="l00472"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a6aeff154d8769aaa8ac951ba77c826f6">00472</a> <span class="keyword">inline</span> <span class="keyword">const</span> type_value & <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a6aeff154d8769aaa8ac951ba77c826f6">getPoseMean</a>()<span class="keyword"> const </span>{ <span class="keywordflow">return</span> *<span class="keyword">this</span>; } <a name="l00473"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a06e76192ed6f9c6a50a38db01def382b">00473</a> <span class="keyword">inline</span> type_value & <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a06e76192ed6f9c6a50a38db01def382b">getPoseMean</a>() { <span class="keywordflow">return</span> *<span class="keyword">this</span>; } <a name="l00474"></a>00474 <span class="comment"></span> <a name="l00475"></a>00475 <span class="comment"> /** @name STL-like methods and typedefs</span> <a name="l00476"></a>00476 <span class="comment"> @{ */</span> <a name="l00477"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#aab4e20e77a678d2c1052b6bd247d1f15">00477</a> <span class="keyword">typedef</span> <span class="keywordtype">double</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#aab4e20e77a678d2c1052b6bd247d1f15" title="The type of the elements.">value_type</a>; <span class="comment">//!< The type of the elements</span> <a name="l00478"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#aa3444675d49735770c93fec4e629553a">00478</a> <span class="comment"></span> <span class="keyword">typedef</span> <span class="keywordtype">double</span>& <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#aa3444675d49735770c93fec4e629553a">reference</a>; <a name="l00479"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a85a132c3e8cc81c4278b0f2c81d42f45">00479</a> <span class="keyword">typedef</span> <span class="keyword">const</span> <span class="keywordtype">double</span>& <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a85a132c3e8cc81c4278b0f2c81d42f45">const_reference</a>; <a name="l00480"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a06e2fd1cec22470a92c6ac05f30bb081">00480</a> <span class="keyword">typedef</span> std::size_t <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a06e2fd1cec22470a92c6ac05f30bb081">size_type</a>; <a name="l00481"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a3bdad630aa1cb766cff54a03a2e836d9">00481</a> <span class="keyword">typedef</span> std::ptrdiff_t <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a3bdad630aa1cb766cff54a03a2e836d9">difference_type</a>; <a name="l00482"></a>00482 <a name="l00483"></a>00483 <a name="l00484"></a>00484 <span class="comment">// size is constant</span> <a name="l00485"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#ab33765aadfb6c5430f79797981818f17a0778fd43755c7c4b0dcbfdfdbae70c64">00485</a> <span class="keyword">enum</span> { <a class="code" href="eigen__plugins_8h.html#a99fb83031ce9923c84392b4e92f956b5ad4a8f9f8c603d29a20ca6f9c056dd4da">static_size</a> = 6 }; <a name="l00486"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a3681727a91ff321244de2f0f48fdddb4">00486</a> <span class="keyword">static</span> <span class="keyword">inline</span> size_type <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a3681727a91ff321244de2f0f48fdddb4">size</a>() { <span class="keywordflow">return</span> <a class="code" href="eigen__plugins_8h.html#a99fb83031ce9923c84392b4e92f956b5ad4a8f9f8c603d29a20ca6f9c056dd4da">static_size</a>; } <a name="l00487"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a0f0b3e4038e5812e30e9da43e48c5c26">00487</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_pose3_d.html#a0f0b3e4038e5812e30e9da43e48c5c26">empty</a>() { <span class="keywordflow">return</span> <span class="keyword">false</span>; } <a name="l00488"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#ae0374ea77ba01589d29cd0f1c8218d4c">00488</a> <span class="keyword">static</span> <span class="keyword">inline</span> size_type <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#ae0374ea77ba01589d29cd0f1c8218d4c">max_size</a>() { <span class="keywordflow">return</span> <a class="code" href="eigen__plugins_8h.html#a99fb83031ce9923c84392b4e92f956b5ad4a8f9f8c603d29a20ca6f9c056dd4da">static_size</a>; } <a name="l00489"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a8f52c8785c46382346e516b6934eb949">00489</a> <span class="keyword">static</span> <span class="keyword">inline</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html#a8f52c8785c46382346e516b6934eb949">resize</a>(<span class="keyword">const</span> <span class="keywordtype">size_t</span> n) { <span class="keywordflow">if</span> (n!=<a class="code" href="eigen__plugins_8h.html#a99fb83031ce9923c84392b4e92f956b5ad4a8f9f8c603d29a20ca6f9c056dd4da">static_size</a>) <span class="keywordflow">throw</span> <a class="code" href="classstd_1_1logic__error.html" title="STL class.">std::logic_error</a>(<a class="code" href="namespacemrpt.html#a3a27af794b658df5491e2b7678f8ccb8" title="A std::string version of C sprintf.">format</a>(<span class="stringliteral">"Try to change the size of CPose3D to %u."</span>,static_cast<unsigned>(n))); }<span class="comment"></span> <a name="l00490"></a>00490 <span class="comment"> /** @} */</span> <a name="l00491"></a>00491 <a name="l00492"></a>00492 }; <span class="comment">// End of class def.</span> <a name="l00493"></a>00493 <a name="l00494"></a>00494 <a name="l00495"></a>00495 std::ostream <a class="code" href="base_2include_2mrpt_2base_2link__pragmas_8h.html#a6045fa0129b1a3d6c8bf895470e66574">BASE_IMPEXP</a> & <a class="code" href="namespacemrpt_1_1poses.html#aa4247c4d793d20edb770e56f22b286f1" title="Dumps a point as a string [x,y] or [x,y,z].">operator << </a>(<a class="code" href="classstd_1_1ostream.html" title="STL class.">std::ostream</a>& o, <span class="keyword">const</span> CPose3D& p); <a name="l00496"></a>00496 <span class="comment"></span> <a name="l00497"></a>00497 <span class="comment"> /** Unary - operator: return the inverse pose "-p" (Note that is NOT the same than a pose with negative x y z yaw pitch roll) */</span> <a name="l00498"></a>00498 CPose3D <a class="code" href="base_2include_2mrpt_2base_2link__pragmas_8h.html#a6045fa0129b1a3d6c8bf895470e66574">BASE_IMPEXP</a> <a class="code" href="namespacemrpt_1_1poses.html#a678c1606b35876eae036755599a22d84" title="Unary - operator: return the inverse pose "-p" (Note that is NOT the same than a pose with negative x...">operator -</a>(<span class="keyword">const</span> CPose3D &p); <a name="l00499"></a>00499 <a name="l00500"></a>00500 <span class="keywordtype">bool</span> <a class="code" href="base_2include_2mrpt_2base_2link__pragmas_8h.html#a6045fa0129b1a3d6c8bf895470e66574">BASE_IMPEXP</a> <a class="code" href="namespacemrpt_1_1poses.html#acd8c946fdfab1501027f3a9347181ebf">operator==</a>(<span class="keyword">const</span> CPose3D &p1,<span class="keyword">const</span> CPose3D &p2); <a name="l00501"></a>00501 <span class="keywordtype">bool</span> <a class="code" href="base_2include_2mrpt_2base_2link__pragmas_8h.html#a6045fa0129b1a3d6c8bf895470e66574">BASE_IMPEXP</a> <a class="code" href="namespacemrpt_1_1poses.html#a4a84f6907abc469f1bcadbf0ae3b485d">operator!=</a>(<span class="keyword">const</span> CPose3D &p1,<span class="keyword">const</span> CPose3D &p2); <a name="l00502"></a>00502 <a name="l00503"></a>00503 <a name="l00504"></a>00504 <span class="comment">// This is a member of CPose<>, but has to be defined here since in its header CPose3D is not declared yet.</span><span class="comment"></span> <a name="l00505"></a>00505 <span class="comment"> /** The operator \f$ a \ominus b \f$ is the pose inverse compounding operator. */</span> <a name="l00506"></a><a class="code" href="classmrpt_1_1poses_1_1_c_pose.html#ac3f6fe9de1bf9a16b2f27013997e6b68">00506</a> <span class="keyword">template</span> <<span class="keyword">class</span> DERIVEDCLASS> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html" title="A class used to store a 3D pose (a 3D translation + a rotation in 3D).">CPose3D</a> <a class="code" href="classmrpt_1_1poses_1_1_c_pose.html#ac3f6fe9de1bf9a16b2f27013997e6b68" title="The operator is the pose inverse compounding operator.">CPose<DERIVEDCLASS>::operator -</a>(<span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html" title="A class used to store a 3D pose (a 3D translation + a rotation in 3D).">CPose3D</a>& b)<span class="keyword"> const</span> <a name="l00507"></a>00507 <span class="keyword"> </span>{ <a name="l00508"></a>00508 <a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html">CMatrixDouble44</a> B_INV(<a class="code" href="namespacemrpt_1_1math.html#a27e8ae8971ff5aa1c39f1f9be334d73aa28acc66160006cb691487ec89f8d266d">UNINITIALIZED_MATRIX</a>); <a name="l00509"></a>00509 b.getInverseHomogeneousMatrix( B_INV ); <a name="l00510"></a>00510 <a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html">CMatrixDouble44</a> HM(<a class="code" href="namespacemrpt_1_1math.html#a27e8ae8971ff5aa1c39f1f9be334d73aa28acc66160006cb691487ec89f8d266d">UNINITIALIZED_MATRIX</a>); <a name="l00511"></a>00511 <span class="keyword">static_cast<</span><span class="keyword">const </span>DERIVEDCLASS*<span class="keyword">></span>(<span class="keyword">this</span>)->getHomogeneousMatrix(HM); <a name="l00512"></a>00512 <a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html">CMatrixDouble44</a> RES(<a class="code" href="namespacemrpt_1_1math.html#a27e8ae8971ff5aa1c39f1f9be334d73aa28acc66160006cb691487ec89f8d266d">UNINITIALIZED_MATRIX</a>); <a name="l00513"></a>00513 RES.multiply(B_INV,HM); <a name="l00514"></a>00514 <span class="keywordflow">return</span> <a class="code" href="classmrpt_1_1poses_1_1_c_pose3_d.html" title="A class used to store a 3D pose (a 3D translation + a rotation in 3D).">CPose3D</a>( RES ); <a name="l00515"></a>00515 } <a name="l00516"></a>00516 <a name="l00517"></a>00517 <a name="l00518"></a>00518 } <span class="comment">// End of namespace</span> <a name="l00519"></a>00519 } <span class="comment">// End of namespace</span> <a name="l00520"></a>00520 <a name="l00521"></a>00521 <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>