Sophie

Sophie

distrib > Fedora > 16 > i386 > by-pkgid > 4bc66056a634db26a1f4d0845dc41ca6 > files > 1541

mrpt-doc-0.9.5-0.1.20110925svn2670.fc16.i686.rpm

<!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>CPoint.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> &gt; <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&#160;Page</span></a></li>
      <li><a href="pages.html"><span>Related&#160;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&#160;List</span></a></li>
      <li><a href="globals.html"><span>File&#160;Members</span></a></li>
    </ul>
  </div>
<div class="header">
  <div class="headertitle">
<div class="title">CPoint.h</div>  </div>
</div>
<div class="contents">
<a href="_c_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  &lt;jlblanco@ctima.uma.es&gt;                     |</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 &lt;http://www.gnu.org/licenses/&gt;.         |</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 CPOINT_H</span>
<a name="l00029"></a>00029 <span class="preprocessor"></span><span class="preprocessor">#define CPOINT_H</span>
<a name="l00030"></a>00030 <span class="preprocessor"></span>
<a name="l00031"></a>00031 <span class="preprocessor">#include &lt;<a class="code" href="_c_pose_or_point_8h.html">mrpt/poses/CPoseOrPoint.h</a>&gt;</span>
<a name="l00032"></a>00032 
<a name="l00033"></a>00033 <span class="keyword">namespace </span>mrpt
<a name="l00034"></a>00034 {
<a name="l00035"></a>00035         <span class="keyword">namespace </span>poses
<a name="l00036"></a>00036         {<span class="comment"></span>
<a name="l00037"></a>00037 <span class="comment">                /** A base class for representing a point in 2D or 3D.</span>
<a name="l00038"></a>00038 <span class="comment">                 *   For more information refer to the &lt;a href=&quot;http://www.mrpt.org/2D_3D_Geometry&quot;&gt;2D/3D Geometry tutorial&lt;/a&gt; online.</span>
<a name="l00039"></a>00039 <span class="comment">                 * \note This class is based on the CRTP design pattern</span>
<a name="l00040"></a>00040 <span class="comment">                 * \sa CPoseOrPoint, CPose</span>
<a name="l00041"></a>00041 <span class="comment">                 * \ingroup poses_grp</span>
<a name="l00042"></a>00042 <span class="comment">                 */</span>
<a name="l00043"></a>00043                 <span class="keyword">template</span> &lt;<span class="keyword">class</span> DERIVEDCLASS&gt;
<a name="l00044"></a>00044                 <span class="keyword">class </span>CPoint : <span class="keyword">public</span> CPoseOrPoint&lt;DERIVEDCLASS&gt;
<a name="l00045"></a>00045                 {
<a name="l00046"></a>00046                 <span class="keyword">public</span>:<span class="comment"></span>
<a name="l00047"></a>00047 <span class="comment">                        /** @name Methods common to all 2D or 3D points</span>
<a name="l00048"></a>00048 <span class="comment">                            @{ */</span>
<a name="l00049"></a>00049 <span class="comment"></span>
<a name="l00050"></a>00050 <span class="comment">                        /** Scalar addition of all coordinates.</span>
<a name="l00051"></a>00051 <span class="comment">                          * This is diferent from poses/point composition, which is implemented as &quot;+&quot; operators in classes derived from &quot;CPose&quot;</span>
<a name="l00052"></a>00052 <span class="comment">                          */</span>
<a name="l00053"></a>00053                         <span class="keyword">template</span> &lt;<span class="keyword">class</span> OTHERCLASS&gt;
<a name="l00054"></a><a class="code" href="classmrpt_1_1poses_1_1_c_point.html#a3e4975121395a7c8f8efa6a2e536971e">00054</a>                         <span class="keyword">inline</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1poses_1_1_c_point.html#a3e4975121395a7c8f8efa6a2e536971e" title="Scalar addition of all coordinates.">AddComponents</a>(<span class="keyword">const</span> OTHERCLASS &amp;b)
<a name="l00055"></a>00055                         {
<a name="l00056"></a>00056                                 <span class="keyword">const</span> <span class="keywordtype">int</span> dims = std::min( <span class="keywordtype">size_t</span>(<a class="code" href="eigen__plugins_8h.html#a99fb83031ce9923c84392b4e92f956b5ad4a8f9f8c603d29a20ca6f9c056dd4da">DERIVEDCLASS::static_size</a>), <span class="keywordtype">size_t</span>(OTHERCLASS::is3DPoseOrPoint() ? 3:2));
<a name="l00057"></a>00057                                 <span class="keywordflow">for</span> (<span class="keywordtype">int</span> i=0;i&lt;dims;i++)
<a name="l00058"></a>00058                                         static_cast&lt;DERIVEDCLASS*&gt;(<span class="keyword">this</span>)-&gt;m_coords[i]+= <span class="keyword">static_cast&lt;</span><span class="keyword">const </span>OTHERCLASS*<span class="keyword">&gt;</span>(&amp;b)-&gt;m_coords[i];
<a name="l00059"></a>00059                         }
<a name="l00060"></a>00060 <span class="comment"></span>
<a name="l00061"></a>00061 <span class="comment">                        /** Scalar multiplication. */</span>
<a name="l00062"></a><a class="code" href="classmrpt_1_1poses_1_1_c_point.html#ad1c5229e7462c31eeb01e0ec7e002742">00062</a>                         <span class="keyword">inline</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1poses_1_1_c_point.html#ad1c5229e7462c31eeb01e0ec7e002742" title="Scalar multiplication.">operator *=</a>(<span class="keyword">const</span> <span class="keywordtype">double</span> s)
<a name="l00063"></a>00063                         {
<a name="l00064"></a>00064                                 <span class="keywordflow">for</span> (<span class="keywordtype">int</span> i=0;i&lt;DERIVEDCLASS<a class="code" href="eigen__plugins_8h.html#a99fb83031ce9923c84392b4e92f956b5ad4a8f9f8c603d29a20ca6f9c056dd4da">::static_size</a>;i++)
<a name="l00065"></a>00065                                         static_cast&lt;DERIVEDCLASS*&gt;(<span class="keyword">this</span>)-&gt;m_coords[i] *= s;
<a name="l00066"></a>00066                         }
<a name="l00067"></a>00067 <span class="comment"></span>
<a name="l00068"></a>00068 <span class="comment">                        /** Return the pose or point as a 1x2 or 1x3 vector [x y] or [x y z] */</span>
<a name="l00069"></a><a class="code" href="classmrpt_1_1poses_1_1_c_point.html#a1475f71cb06192af4a43d0f0ceb54a86">00069</a>                         <span class="keyword">inline</span> <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1poses_1_1_c_point.html#aa056055a3cbfe41c6ba3c79370c561ca">getAsVector</a>(<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> &amp;v)<span class="keyword"> const</span>
<a name="l00070"></a>00070 <span class="keyword">                        </span>{
<a name="l00071"></a>00071                                 v.<a class="code" href="structmrpt_1_1dynamicsize__vector.html#a8fd6a8b950613c9abbf6366bcc9d4e4c" title="Overloaded resize method that mimics std::vector::resize(SIZE,DEFAULT_VALUE) instead of resize(nrows...">resize</a>(<a class="code" href="eigen__plugins_8h.html#a99fb83031ce9923c84392b4e92f956b5ad4a8f9f8c603d29a20ca6f9c056dd4da">DERIVEDCLASS::static_size</a>);
<a name="l00072"></a>00072                                 <span class="keywordflow">for</span> (<span class="keywordtype">int</span> i=0;i&lt;DERIVEDCLASS<a class="code" href="eigen__plugins_8h.html#a99fb83031ce9923c84392b4e92f956b5ad4a8f9f8c603d29a20ca6f9c056dd4da">::static_size</a>;i++)
<a name="l00073"></a>00073                                         v[i] = static_cast&lt;const DERIVEDCLASS*&gt;(<span class="keyword">this</span>)-&gt;m_coords[i];
<a name="l00074"></a>00074                         }<span class="comment"></span>
<a name="l00075"></a>00075 <span class="comment">                        //! \overload</span>
<a name="l00076"></a><a class="code" href="classmrpt_1_1poses_1_1_c_point.html#aa056055a3cbfe41c6ba3c79370c561ca">00076</a> <span class="comment"></span>                        <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_point.html#aa056055a3cbfe41c6ba3c79370c561ca">getAsVector</a>()<span class="keyword"> const </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> v; <a class="code" href="classmrpt_1_1poses_1_1_c_point.html#aa056055a3cbfe41c6ba3c79370c561ca">getAsVector</a>(v); <span class="keywordflow">return</span> v; }
<a name="l00077"></a>00077 <span class="comment"></span>
<a name="l00078"></a>00078 <span class="comment">                        /** Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (translation+orientation).</span>
<a name="l00079"></a>00079 <span class="comment">                          * \sa getInverseHomogeneousMatrix</span>
<a name="l00080"></a>00080 <span class="comment">                          */</span>
<a name="l00081"></a><a class="code" href="classmrpt_1_1poses_1_1_c_point.html#a9feaa4392d225ef30569d927ea912cd8">00081</a>                         <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1poses_1_1_c_point.html#a9feaa4392d225ef30569d927ea912cd8" title="Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (t...">getHomogeneousMatrix</a>(<a class="code" href="classmrpt_1_1math_1_1_c_matrix_fixed_numeric.html">CMatrixDouble44</a> &amp; out_HM )<span class="keyword"> const</span>
<a name="l00082"></a>00082 <span class="keyword">                        </span>{
<a name="l00083"></a>00083                                 out_HM.unit(4,1.0);
<a name="l00084"></a>00084                                 out_HM.get_unsafe(0,3)= <span class="keyword">static_cast&lt;</span><span class="keyword">const </span>DERIVEDCLASS*<span class="keyword">&gt;</span>(<span class="keyword">this</span>)-&gt;<a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#af3506e31b659334e6992f5cd9ac657b7" title="Common members of all points &amp; poses classes.">x</a>();
<a name="l00085"></a>00085                                 out_HM.get_unsafe(1,3)= <span class="keyword">static_cast&lt;</span><span class="keyword">const </span>DERIVEDCLASS*<span class="keyword">&gt;</span>(<span class="keyword">this</span>)-&gt;<a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a912d9a0a05f236fdb947b6627e7349ba">y</a>();
<a name="l00086"></a>00086                                 <span class="keywordflow">if</span> (DERIVEDCLASS::is3DPoseOrPoint())
<a name="l00087"></a>00087                                         out_HM.get_unsafe(2,3)= <span class="keyword">static_cast&lt;</span><span class="keyword">const </span>DERIVEDCLASS*<span class="keyword">&gt;</span>(<span class="keyword">this</span>)-&gt;m_coords[2];
<a name="l00088"></a>00088                         }
<a name="l00089"></a>00089 <span class="comment"></span>
<a name="l00090"></a>00090 <span class="comment">                        /** Returns a human-readable textual representation of the object (eg: &quot;[0.02 1.04]&quot; )</span>
<a name="l00091"></a>00091 <span class="comment">                        * \sa fromString</span>
<a name="l00092"></a>00092 <span class="comment">                        */</span>
<a name="l00093"></a><a class="code" href="classmrpt_1_1poses_1_1_c_point.html#a62421d42705b4f7529f9140cf8f5e37f">00093</a>                         <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1poses_1_1_c_point.html#a73c90c209be9250b480aa9db19c6e37e">asString</a>(<a class="code" href="classstd_1_1string.html" title="STL class.">std::string</a> &amp;s)<span class="keyword"> const</span>
<a name="l00094"></a>00094 <span class="keyword">                        </span>{
<a name="l00095"></a>00095                                 s = (<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.">DERIVEDCLASS::is3DPoseOrPoint</a>()) ?
<a name="l00096"></a>00096                                         <a class="code" href="namespacemrpt.html#a3a27af794b658df5491e2b7678f8ccb8" title="A std::string version of C sprintf.">mrpt::format</a>(<span class="stringliteral">&quot;[%f %f]&quot;</span>, static_cast&lt;const DERIVEDCLASS*&gt;(<span class="keyword">this</span>)-&gt;x(), <span class="keyword">static_cast&lt;</span><span class="keyword">const </span>DERIVEDCLASS*<span class="keyword">&gt;</span>(<span class="keyword">this</span>)-&gt;<a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a912d9a0a05f236fdb947b6627e7349ba">y</a>()) :
<a name="l00097"></a>00097                                         <a class="code" href="namespacemrpt.html#a3a27af794b658df5491e2b7678f8ccb8" title="A std::string version of C sprintf.">mrpt::format</a>(<span class="stringliteral">&quot;[%f %f %f]&quot;</span>,static_cast&lt;const DERIVEDCLASS*&gt;(<span class="keyword">this</span>)-&gt;x(), <span class="keyword">static_cast&lt;</span><span class="keyword">const </span>DERIVEDCLASS*<span class="keyword">&gt;</span>(<span class="keyword">this</span>)-&gt;<a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a912d9a0a05f236fdb947b6627e7349ba">y</a>(), <span class="keyword">static_cast&lt;</span><span class="keyword">const </span>DERIVEDCLASS*<span class="keyword">&gt;</span>(<span class="keyword">this</span>)-&gt;m_coords[2]);
<a name="l00098"></a>00098                         }
<a name="l00099"></a><a class="code" href="classmrpt_1_1poses_1_1_c_point.html#a73c90c209be9250b480aa9db19c6e37e">00099</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_point.html#a73c90c209be9250b480aa9db19c6e37e">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_point.html#a73c90c209be9250b480aa9db19c6e37e">asString</a>(s); <span class="keywordflow">return</span> s; }
<a name="l00100"></a>00100 <span class="comment"></span>
<a name="l00101"></a>00101 <span class="comment">                        /** Set the current object value from a string generated by &#39;asString&#39; (eg: &quot;[0.02 1.04]&quot; )</span>
<a name="l00102"></a>00102 <span class="comment">                        * \sa asString</span>
<a name="l00103"></a>00103 <span class="comment">                        * \exception std::exception On invalid format</span>
<a name="l00104"></a>00104 <span class="comment">                        */</span>
<a name="l00105"></a><a class="code" href="classmrpt_1_1poses_1_1_c_point.html#a6bd476309950f08614b53293b3ba909c">00105</a>                         <span class="keywordtype">void</span> <a class="code" href="classmrpt_1_1poses_1_1_c_point.html#a6bd476309950f08614b53293b3ba909c" title="Set the current object value from a string generated by &#39;asString&#39; (eg: &quot;[0.02 1.04]&quot; )...">fromString</a>(<span class="keyword">const</span> <a class="code" href="classstd_1_1string.html" title="STL class.">std::string</a> &amp;s)
<a name="l00106"></a>00106                         {
<a name="l00107"></a>00107                                 <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="l00108"></a>00108                                 <span class="keywordflow">if</span> (!m.fromMatlabStringFormat(s)) <a class="code" href="mrpt__macros_8h.html#aaa3f404ea85a6575a7139f8d101370ba">THROW_EXCEPTION</a>(<span class="stringliteral">&quot;Malformed expression in ::fromString&quot;</span>);
<a name="l00109"></a>00109                                 <a class="code" href="mrpt__macros_8h.html#a02c6e78d47a0bae723824559846cc673">ASSERT_EQUAL_</a>(<a class="code" href="namespacemrpt_1_1math.html#a632ae0aecf78103f87f18f9ac33f7170">mrpt::math::size</a>(m,1),1)
<a name="l00110"></a>00110                                 <a class="code" href="mrpt__macros_8h.html#a02c6e78d47a0bae723824559846cc673">ASSERT_EQUAL_</a>(<a class="code" href="namespacemrpt_1_1math.html#a632ae0aecf78103f87f18f9ac33f7170">mrpt::math::size</a>(m,2),<a class="code" href="eigen__plugins_8h.html#a99fb83031ce9923c84392b4e92f956b5ad4a8f9f8c603d29a20ca6f9c056dd4da">DERIVEDCLASS::static_size</a>)
<a name="l00111"></a>00111                                 <span class="keywordflow">for</span> (<span class="keywordtype">int</span> i=0;i&lt;DERIVEDCLASS<a class="code" href="eigen__plugins_8h.html#a99fb83031ce9923c84392b4e92f956b5ad4a8f9f8c603d29a20ca6f9c056dd4da">::static_size</a>;i++)
<a name="l00112"></a>00112                                         static_cast&lt;DERIVEDCLASS*&gt;(<span class="keyword">this</span>)-&gt;m_coords[i] = m.get_unsafe(0,i);
<a name="l00113"></a>00113                         }
<a name="l00114"></a>00114 
<a name="l00115"></a><a class="code" href="classmrpt_1_1poses_1_1_c_point.html#a74cf5b85852318531e782ada372e2882">00115</a>                         <span class="keyword">inline</span> <span class="keyword">const</span> <span class="keywordtype">double</span> &amp;<a class="code" href="classmrpt_1_1poses_1_1_c_point.html#a74cf5b85852318531e782ada372e2882">operator[]</a>(<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i)<span class="keyword"> const </span>{ <span class="keywordflow">return</span> <span class="keyword">static_cast&lt;</span><span class="keyword">const </span>DERIVEDCLASS*<span class="keyword">&gt;</span>(<span class="keyword">this</span>)-&gt;m_coords[i]; }
<a name="l00116"></a><a class="code" href="classmrpt_1_1poses_1_1_c_point.html#a02db452a96be2068ec89b09e4963f1e4">00116</a>                         <span class="keyword">inline</span>       <span class="keywordtype">double</span> &amp;<a class="code" href="classmrpt_1_1poses_1_1_c_point.html#a02db452a96be2068ec89b09e4963f1e4">operator[]</a>(<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i)       { <span class="keywordflow">return</span> <span class="keyword">static_cast&lt;</span>DERIVEDCLASS*<span class="keyword">&gt;</span>(<span class="keyword">this</span>)-&gt;m_coords[i]; }
<a name="l00117"></a>00117 <span class="comment"></span>
<a name="l00118"></a>00118 <span class="comment">                        /** @} */</span>
<a name="l00119"></a>00119 
<a name="l00120"></a>00120                 }; <span class="comment">// End of class def.</span>
<a name="l00121"></a>00121 <span class="comment"></span>
<a name="l00122"></a>00122 <span class="comment">        /** Dumps a point as a string [x,y] or [x,y,z]  */</span>
<a name="l00123"></a>00123         <span class="keyword">template</span> &lt;<span class="keyword">class</span> DERIVEDCLASS&gt;
<a name="l00124"></a><a class="code" href="namespacemrpt_1_1poses.html#aa4247c4d793d20edb770e56f22b286f1">00124</a>         std<a class="code" href="classstd_1_1ostream.html" title="STL class.">::ostream</a> &amp;operator &lt;&lt; (std::ostream&amp; o, const CPoint&lt;DERIVEDCLASS&gt;&amp; p)
<a name="l00125"></a>00125         {
<a name="l00126"></a>00126                 o &lt;&lt; <span class="stringliteral">&quot;(&quot;</span> &lt;&lt; p[0] &lt;&lt; <span class="stringliteral">&quot;,&quot;</span> &lt;&lt; p[1];
<a name="l00127"></a>00127                 <span class="keywordflow">if</span> (p.is3DPoseOrPoint())        o &lt;&lt; <span class="stringliteral">&quot;,&quot;</span> &lt;&lt; p[2];
<a name="l00128"></a>00128                 o &lt;&lt;<span class="stringliteral">&quot;)&quot;</span>;
<a name="l00129"></a>00129                 <span class="keywordflow">return</span> o;
<a name="l00130"></a>00130         }
<a name="l00131"></a>00131 <span class="comment"></span>
<a name="l00132"></a>00132 <span class="comment">        /** Used by STL algorithms */</span>
<a name="l00133"></a>00133         <span class="keyword">template</span> &lt;<span class="keyword">class</span> DERIVEDCLASS&gt;
<a name="l00134"></a><a class="code" href="namespacemrpt_1_1poses.html#aff846586035182f99707712cb073a5d2">00134</a>         <span class="keywordtype">bool</span> operator &lt; (const CPoint&lt;DERIVEDCLASS&gt; &amp;a, <span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_point.html" title="A base class for representing a point in 2D or 3D.">CPoint&lt;DERIVEDCLASS&gt;</a> &amp;b)
<a name="l00135"></a>00135         {
<a name="l00136"></a>00136                 <span class="keywordflow">if</span> (a.x()&lt;b.x()) <span class="keywordflow">return</span> <span class="keyword">true</span>;
<a name="l00137"></a>00137                 <span class="keywordflow">else</span>
<a name="l00138"></a>00138                 {
<a name="l00139"></a>00139                         <span class="keywordflow">if</span> (!a.is3DPoseOrPoint())
<a name="l00140"></a>00140                                 <span class="keywordflow">return</span> a.<a class="code" href="classmrpt_1_1poses_1_1_c_pose_or_point.html#a912d9a0a05f236fdb947b6627e7349ba">y</a>()&lt;b.y();
<a name="l00141"></a>00141                         <span class="keywordflow">else</span>  <span class="keywordflow">if</span> (a.y()&lt;b.y())
<a name="l00142"></a>00142                                 <span class="keywordflow">return</span> <span class="keyword">true</span>;
<a name="l00143"></a>00143                         <span class="keywordflow">else</span> <span class="keywordflow">return</span> a[2]&lt;b[2];
<a name="l00144"></a>00144                 }
<a name="l00145"></a>00145         }
<a name="l00146"></a>00146 
<a name="l00147"></a>00147         <span class="keyword">template</span> &lt;<span class="keyword">class</span> DERIVEDCLASS&gt;
<a name="l00148"></a><a class="code" href="namespacemrpt_1_1poses.html#acd8c946fdfab1501027f3a9347181ebf">00148</a>         <span class="keywordtype">bool</span> <a class="code" href="namespacemrpt_1_1poses.html#acd8c946fdfab1501027f3a9347181ebf">operator==</a>(<span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_point.html" title="A base class for representing a point in 2D or 3D.">CPoint&lt;DERIVEDCLASS&gt;</a> &amp;p1,<span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_point.html" title="A base class for representing a point in 2D or 3D.">CPoint&lt;DERIVEDCLASS&gt;</a> &amp;p2)
<a name="l00149"></a>00149         {
<a name="l00150"></a>00150                 <span class="keywordflow">for</span> (<span class="keywordtype">int</span> i=0;i&lt;DERIVEDCLASS<a class="code" href="eigen__plugins_8h.html#a99fb83031ce9923c84392b4e92f956b5ad4a8f9f8c603d29a20ca6f9c056dd4da">::static_size</a>;i++)
<a name="l00151"></a>00151                         <span class="keywordflow">if</span> (p1[i]!=p2[i])       <span class="keywordflow">return</span> <span class="keyword">false</span>;
<a name="l00152"></a>00152                 <span class="keywordflow">return</span> <span class="keyword">true</span>;
<a name="l00153"></a>00153         }
<a name="l00154"></a>00154 
<a name="l00155"></a>00155         <span class="keyword">template</span> &lt;<span class="keyword">class</span> DERIVEDCLASS&gt;
<a name="l00156"></a><a class="code" href="namespacemrpt_1_1poses.html#a4a84f6907abc469f1bcadbf0ae3b485d">00156</a>         <span class="keywordtype">bool</span> <a class="code" href="namespacemrpt_1_1poses.html#a4a84f6907abc469f1bcadbf0ae3b485d">operator!=</a>(<span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_point.html" title="A base class for representing a point in 2D or 3D.">CPoint&lt;DERIVEDCLASS&gt;</a> &amp;p1,<span class="keyword">const</span> <a class="code" href="classmrpt_1_1poses_1_1_c_point.html" title="A base class for representing a point in 2D or 3D.">CPoint&lt;DERIVEDCLASS&gt;</a> &amp;p2)
<a name="l00157"></a>00157         {
<a name="l00158"></a>00158                 <span class="keywordflow">for</span> (<span class="keywordtype">int</span> i=0;i&lt;DERIVEDCLASS<a class="code" href="eigen__plugins_8h.html#a99fb83031ce9923c84392b4e92f956b5ad4a8f9f8c603d29a20ca6f9c056dd4da">::static_size</a>;i++)
<a name="l00159"></a>00159                         <span class="keywordflow">if</span> (p1[i]!=p2[i])       <span class="keywordflow">return</span> <span class="keyword">true</span>;
<a name="l00160"></a>00160                 <span class="keywordflow">return</span> <span class="keyword">false</span>;
<a name="l00161"></a>00161         }
<a name="l00162"></a>00162 
<a name="l00163"></a>00163 
<a name="l00164"></a>00164 
<a name="l00165"></a>00165         } <span class="comment">// End of namespace</span>
<a name="l00166"></a>00166 } <span class="comment">// End of namespace</span>
<a name="l00167"></a>00167 
<a name="l00168"></a>00168 <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>