mesh_indices.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  * Point Cloud Library (PCL) - www.pointclouds.org
00005  * Copyright (c) 2009-2012, Willow Garage, Inc.
00006  * Copyright (c) 2012-, Open Perception, Inc.
00007  *
00008  * All rights reserved.
00009  *
00010  * Redistribution and use in source and binary forms, with or without
00011  * modification, are permitted provided that the following conditions
00012  * are met:
00013  *
00014  *  * Redistributions of source code must retain the above copyright
00015  *    notice, this list of conditions and the following disclaimer.
00016  *  * Redistributions in binary form must reproduce the above
00017  *    copyright notice, this list of conditions and the following
00018  *    disclaimer in the documentation and/or other materials provided
00019  *    with the distribution.
00020  *  * Neither the name of the copyright holder(s) nor the names of its
00021  *    contributors may be used to endorse or promote products derived
00022  *    from this software without specific prior written permission.
00023  *
00024  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00025  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00026  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00027  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00028  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00029  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00030  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00031  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00032  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00033  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00034  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00035  * POSSIBILITY OF SUCH DAMAGE.
00036  *
00037  * $Id$
00038  *
00039  */
00040 
00041 // NOTE: This file has been created with 'pcl_src/geometry/include/pcl/geometry/mesh_indices.py'
00042 
00043 #ifndef PCL_GEOMETRY_MESH_INDICES_H
00044 #define PCL_GEOMETRY_MESH_INDICES_H
00045 
00046 #include <iostream>
00047 
00048 #include <pcl/geometry/boost.h>
00049 
00051 // VertexIndex
00053 
00054 namespace pcl
00055 {
00056   namespace geometry
00057   {
00062     class VertexIndex
00063         : boost::totally_ordered <pcl::geometry::VertexIndex // < > <= >= == !=
00064         , boost::unit_steppable  <pcl::geometry::VertexIndex // ++ -- (pre and post)
00065         , boost::additive        <pcl::geometry::VertexIndex // += + -= -
00066         > > >
00067     {
00068       public:
00069 
00070         typedef boost::totally_ordered <pcl::geometry::VertexIndex,
00071                 boost::unit_steppable  <pcl::geometry::VertexIndex,
00072                 boost::additive        <pcl::geometry::VertexIndex> > > Base;
00073         typedef pcl::geometry::VertexIndex                              Self;
00074 
00076         VertexIndex ()
00077           : index_ (-1)
00078         {
00079         }
00080 
00084         explicit VertexIndex (const int index)
00085           : index_ (index)
00086         {
00087         }
00088 
00090         inline bool
00091         isValid () const
00092         {
00093           return (index_ >= 0);
00094         }
00095 
00097         inline void
00098         invalidate ()
00099         {
00100           index_ = -1;
00101         }
00102 
00104         inline int
00105         get () const
00106         {
00107           return (index_);
00108         }
00109 
00111         inline void
00112         set (const int index)
00113         {
00114           index_ = index;
00115         }
00116 
00118         inline bool
00119         operator < (const Self& other) const
00120         {
00121           return (this->get () < other.get ());
00122         }
00123 
00125         inline bool
00126         operator == (const Self& other) const
00127         {
00128           return (this->get () == other.get ());
00129         }
00130 
00132         inline Self&
00133         operator ++ ()
00134         {
00135           ++index_;
00136           return (*this);
00137         }
00138 
00140         inline Self&
00141         operator -- ()
00142         {
00143           --index_;
00144           return (*this);
00145         }
00146 
00148         inline Self&
00149         operator += (const Self& other)
00150         {
00151           index_ += other.get ();
00152           return (*this);
00153         }
00154 
00156         inline Self&
00157         operator -= (const Self& other)
00158         {
00159           index_ -= other.get ();
00160           return (*this);
00161         }
00162 
00163       private:
00164 
00166         int index_;
00167 
00168         friend std::istream&
00169         operator >> (std::istream& is, pcl::geometry::VertexIndex& index);
00170     };
00171 
00173     inline std::ostream&
00174     operator << (std::ostream& os, const pcl::geometry::VertexIndex& index)
00175     {
00176       return (os << index.get ());
00177     }
00178 
00180     inline std::istream&
00181     operator >> (std::istream& is, pcl::geometry::VertexIndex& index)
00182     {
00183       return (is >> index.index_);
00184     }
00185 
00186   } // End namespace geometry
00187 } // End namespace pcl
00188 
00190 // HalfEdgeIndex
00192 
00193 namespace pcl
00194 {
00195   namespace geometry
00196   {
00201     class HalfEdgeIndex
00202         : boost::totally_ordered <pcl::geometry::HalfEdgeIndex // < > <= >= == !=
00203         , boost::unit_steppable  <pcl::geometry::HalfEdgeIndex // ++ -- (pre and post)
00204         , boost::additive        <pcl::geometry::HalfEdgeIndex // += + -= -
00205         > > >
00206     {
00207       public:
00208 
00209         typedef boost::totally_ordered <pcl::geometry::HalfEdgeIndex,
00210                 boost::unit_steppable  <pcl::geometry::HalfEdgeIndex,
00211                 boost::additive        <pcl::geometry::HalfEdgeIndex> > > Base;
00212         typedef pcl::geometry::HalfEdgeIndex                              Self;
00213 
00215         HalfEdgeIndex ()
00216           : index_ (-1)
00217         {
00218         }
00219 
00223         explicit HalfEdgeIndex (const int index)
00224           : index_ (index)
00225         {
00226         }
00227 
00229         inline bool
00230         isValid () const
00231         {
00232           return (index_ >= 0);
00233         }
00234 
00236         inline void
00237         invalidate ()
00238         {
00239           index_ = -1;
00240         }
00241 
00243         inline int
00244         get () const
00245         {
00246           return (index_);
00247         }
00248 
00250         inline void
00251         set (const int index)
00252         {
00253           index_ = index;
00254         }
00255 
00257         inline bool
00258         operator < (const Self& other) const
00259         {
00260           return (this->get () < other.get ());
00261         }
00262 
00264         inline bool
00265         operator == (const Self& other) const
00266         {
00267           return (this->get () == other.get ());
00268         }
00269 
00271         inline Self&
00272         operator ++ ()
00273         {
00274           ++index_;
00275           return (*this);
00276         }
00277 
00279         inline Self&
00280         operator -- ()
00281         {
00282           --index_;
00283           return (*this);
00284         }
00285 
00287         inline Self&
00288         operator += (const Self& other)
00289         {
00290           index_ += other.get ();
00291           return (*this);
00292         }
00293 
00295         inline Self&
00296         operator -= (const Self& other)
00297         {
00298           index_ -= other.get ();
00299           return (*this);
00300         }
00301 
00302       private:
00303 
00305         int index_;
00306 
00307         friend std::istream&
00308         operator >> (std::istream& is, pcl::geometry::HalfEdgeIndex& index);
00309     };
00310 
00312     inline std::ostream&
00313     operator << (std::ostream& os, const pcl::geometry::HalfEdgeIndex& index)
00314     {
00315       return (os << index.get ());
00316     }
00317 
00319     inline std::istream&
00320     operator >> (std::istream& is, pcl::geometry::HalfEdgeIndex& index)
00321     {
00322       return (is >> index.index_);
00323     }
00324 
00325   } // End namespace geometry
00326 } // End namespace pcl
00327 
00329 // EdgeIndex
00331 
00332 namespace pcl
00333 {
00334   namespace geometry
00335   {
00340     class EdgeIndex
00341         : boost::totally_ordered <pcl::geometry::EdgeIndex // < > <= >= == !=
00342         , boost::unit_steppable  <pcl::geometry::EdgeIndex // ++ -- (pre and post)
00343         , boost::additive        <pcl::geometry::EdgeIndex // += + -= -
00344         > > >
00345     {
00346       public:
00347 
00348         typedef boost::totally_ordered <pcl::geometry::EdgeIndex,
00349                 boost::unit_steppable  <pcl::geometry::EdgeIndex,
00350                 boost::additive        <pcl::geometry::EdgeIndex> > > Base;
00351         typedef pcl::geometry::EdgeIndex                              Self;
00352 
00354         EdgeIndex ()
00355           : index_ (-1)
00356         {
00357         }
00358 
00362         explicit EdgeIndex (const int index)
00363           : index_ (index)
00364         {
00365         }
00366 
00368         inline bool
00369         isValid () const
00370         {
00371           return (index_ >= 0);
00372         }
00373 
00375         inline void
00376         invalidate ()
00377         {
00378           index_ = -1;
00379         }
00380 
00382         inline int
00383         get () const
00384         {
00385           return (index_);
00386         }
00387 
00389         inline void
00390         set (const int index)
00391         {
00392           index_ = index;
00393         }
00394 
00396         inline bool
00397         operator < (const Self& other) const
00398         {
00399           return (this->get () < other.get ());
00400         }
00401 
00403         inline bool
00404         operator == (const Self& other) const
00405         {
00406           return (this->get () == other.get ());
00407         }
00408 
00410         inline Self&
00411         operator ++ ()
00412         {
00413           ++index_;
00414           return (*this);
00415         }
00416 
00418         inline Self&
00419         operator -- ()
00420         {
00421           --index_;
00422           return (*this);
00423         }
00424 
00426         inline Self&
00427         operator += (const Self& other)
00428         {
00429           index_ += other.get ();
00430           return (*this);
00431         }
00432 
00434         inline Self&
00435         operator -= (const Self& other)
00436         {
00437           index_ -= other.get ();
00438           return (*this);
00439         }
00440 
00441       private:
00442 
00444         int index_;
00445 
00446         friend std::istream&
00447         operator >> (std::istream& is, pcl::geometry::EdgeIndex& index);
00448     };
00449 
00451     inline std::ostream&
00452     operator << (std::ostream& os, const pcl::geometry::EdgeIndex& index)
00453     {
00454       return (os << index.get ());
00455     }
00456 
00458     inline std::istream&
00459     operator >> (std::istream& is, pcl::geometry::EdgeIndex& index)
00460     {
00461       return (is >> index.index_);
00462     }
00463 
00464   } // End namespace geometry
00465 } // End namespace pcl
00466 
00468 // FaceIndex
00470 
00471 namespace pcl
00472 {
00473   namespace geometry
00474   {
00479     class FaceIndex
00480         : boost::totally_ordered <pcl::geometry::FaceIndex // < > <= >= == !=
00481         , boost::unit_steppable  <pcl::geometry::FaceIndex // ++ -- (pre and post)
00482         , boost::additive        <pcl::geometry::FaceIndex // += + -= -
00483         > > >
00484     {
00485       public:
00486 
00487         typedef boost::totally_ordered <pcl::geometry::FaceIndex,
00488                 boost::unit_steppable  <pcl::geometry::FaceIndex,
00489                 boost::additive        <pcl::geometry::FaceIndex> > > Base;
00490         typedef pcl::geometry::FaceIndex                              Self;
00491 
00493         FaceIndex ()
00494           : index_ (-1)
00495         {
00496         }
00497 
00501         explicit FaceIndex (const int index)
00502           : index_ (index)
00503         {
00504         }
00505 
00507         inline bool
00508         isValid () const
00509         {
00510           return (index_ >= 0);
00511         }
00512 
00514         inline void
00515         invalidate ()
00516         {
00517           index_ = -1;
00518         }
00519 
00521         inline int
00522         get () const
00523         {
00524           return (index_);
00525         }
00526 
00528         inline void
00529         set (const int index)
00530         {
00531           index_ = index;
00532         }
00533 
00535         inline bool
00536         operator < (const Self& other) const
00537         {
00538           return (this->get () < other.get ());
00539         }
00540 
00542         inline bool
00543         operator == (const Self& other) const
00544         {
00545           return (this->get () == other.get ());
00546         }
00547 
00549         inline Self&
00550         operator ++ ()
00551         {
00552           ++index_;
00553           return (*this);
00554         }
00555 
00557         inline Self&
00558         operator -- ()
00559         {
00560           --index_;
00561           return (*this);
00562         }
00563 
00565         inline Self&
00566         operator += (const Self& other)
00567         {
00568           index_ += other.get ();
00569           return (*this);
00570         }
00571 
00573         inline Self&
00574         operator -= (const Self& other)
00575         {
00576           index_ -= other.get ();
00577           return (*this);
00578         }
00579 
00580       private:
00581 
00583         int index_;
00584 
00585         friend std::istream&
00586         operator >> (std::istream& is, pcl::geometry::FaceIndex& index);
00587     };
00588 
00590     inline std::ostream&
00591     operator << (std::ostream& os, const pcl::geometry::FaceIndex& index)
00592     {
00593       return (os << index.get ());
00594     }
00595 
00597     inline std::istream&
00598     operator >> (std::istream& is, pcl::geometry::FaceIndex& index)
00599     {
00600       return (is >> index.index_);
00601     }
00602 
00603   } // End namespace geometry
00604 } // End namespace pcl
00605 
00607 // Conversions
00609 
00610 namespace pcl
00611 {
00612   namespace geometry
00613   {
00615     inline pcl::geometry::EdgeIndex
00616     toEdgeIndex (const HalfEdgeIndex& index)
00617     {
00618       return (index.isValid () ? EdgeIndex (index.get () / 2) : EdgeIndex ());
00619     }
00620 
00624     inline pcl::geometry::HalfEdgeIndex
00625     toHalfEdgeIndex (const EdgeIndex& index, const bool get_first=true)
00626     {
00627       return (index.isValid () ? HalfEdgeIndex (index.get () * 2 + static_cast <int> (!get_first)) : HalfEdgeIndex ());
00628     }
00629   } // End namespace geometry
00630 } // End namespace pcl
00631 
00632 #endif // PCL_GEOMETRY_MESH_INDICES_H


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:25:32