mesh_circulators.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_circulators.py'
00042 
00043 #ifndef PCL_GEOMETRY_MESH_CIRCULATORS_H
00044 #define PCL_GEOMETRY_MESH_CIRCULATORS_H
00045 
00046 #include <pcl/geometry/boost.h>
00047 #include <pcl/geometry/mesh_indices.h>
00048 
00050 // VertexAroundVertexCirculator
00052 
00053 namespace pcl
00054 {
00055   namespace geometry
00056   {
00063     template <class MeshT>
00064     class VertexAroundVertexCirculator
00065         : boost::equality_comparable <pcl::geometry::VertexAroundVertexCirculator <MeshT>
00066         , boost::unit_steppable      <pcl::geometry::VertexAroundVertexCirculator <MeshT>
00067         > >
00068     {
00069       public:
00070 
00071         typedef boost::equality_comparable <pcl::geometry::VertexAroundVertexCirculator <MeshT>
00072               , boost::unit_steppable      <pcl::geometry::VertexAroundVertexCirculator <MeshT> > > Base;
00073         typedef pcl::geometry::VertexAroundVertexCirculator <MeshT> Self;
00074 
00075         typedef MeshT Mesh;
00076         typedef typename Mesh::VertexIndex VertexIndex;
00077         typedef typename Mesh::HalfEdgeIndex HalfEdgeIndex;
00078 
00080         VertexAroundVertexCirculator ()
00081           : mesh_                   (NULL),
00082             idx_outgoing_half_edge_ ()
00083         {
00084         }
00085 
00087         VertexAroundVertexCirculator (const VertexIndex& idx_vertex,
00088                                       Mesh*const         mesh)
00089           : mesh_                   (mesh),
00090             idx_outgoing_half_edge_ (mesh->getOutgoingHalfEdgeIndex (idx_vertex))
00091         {
00092         }
00093 
00095         VertexAroundVertexCirculator (const HalfEdgeIndex& idx_outgoing_half_edge,
00096                                       Mesh*const           mesh)
00097           : mesh_                   (mesh),
00098             idx_outgoing_half_edge_ (idx_outgoing_half_edge)
00099         {
00100         }
00101 
00104         inline bool
00105         isValid () const
00106         {
00107           return (idx_outgoing_half_edge_.isValid ());
00108         }
00109 
00112         inline bool
00113         operator == (const Self& other) const
00114         {
00115           return (idx_outgoing_half_edge_ == other.idx_outgoing_half_edge_);
00116         }
00117 
00119         inline Self&
00120         operator ++ ()
00121         {
00122           idx_outgoing_half_edge_ = mesh_->getNextHalfEdgeIndex (mesh_->getOppositeHalfEdgeIndex (idx_outgoing_half_edge_));
00123           return (*this);
00124         }
00125 
00127         inline Self&
00128         operator -- ()
00129         {
00130           idx_outgoing_half_edge_ = mesh_->getOppositeHalfEdgeIndex (mesh_->getPrevHalfEdgeIndex (idx_outgoing_half_edge_));
00131           return (*this);
00132         }
00133 
00135         inline VertexIndex
00136         getTargetIndex () const
00137         {
00138           return (mesh_->getTerminatingVertexIndex (idx_outgoing_half_edge_));
00139         }
00140 
00142         inline HalfEdgeIndex
00143         getCurrentHalfEdgeIndex () const
00144         {
00145           return (idx_outgoing_half_edge_);
00146         }
00147 
00149         Mesh* mesh_;
00150 
00152         HalfEdgeIndex idx_outgoing_half_edge_;
00153     };
00154   } // End namespace geometry
00155 } // End namespace pcl
00156 
00158 // OutgoingHalfEdgeAroundVertexCirculator
00160 
00161 namespace pcl
00162 {
00163   namespace geometry
00164   {
00171     template <class MeshT>
00172     class OutgoingHalfEdgeAroundVertexCirculator
00173         : boost::equality_comparable <pcl::geometry::OutgoingHalfEdgeAroundVertexCirculator <MeshT>
00174         , boost::unit_steppable      <pcl::geometry::OutgoingHalfEdgeAroundVertexCirculator <MeshT>
00175         > >
00176     {
00177       public:
00178 
00179         typedef boost::equality_comparable <pcl::geometry::OutgoingHalfEdgeAroundVertexCirculator <MeshT>
00180               , boost::unit_steppable      <pcl::geometry::OutgoingHalfEdgeAroundVertexCirculator <MeshT> > > Base;
00181         typedef pcl::geometry::OutgoingHalfEdgeAroundVertexCirculator <MeshT> Self;
00182 
00183         typedef MeshT Mesh;
00184         typedef typename Mesh::VertexIndex VertexIndex;
00185         typedef typename Mesh::HalfEdgeIndex HalfEdgeIndex;
00186 
00188         OutgoingHalfEdgeAroundVertexCirculator ()
00189           : mesh_                   (NULL),
00190             idx_outgoing_half_edge_ ()
00191         {
00192         }
00193 
00195         OutgoingHalfEdgeAroundVertexCirculator (const VertexIndex& idx_vertex,
00196                                                 Mesh*const         mesh)
00197           : mesh_                   (mesh),
00198             idx_outgoing_half_edge_ (mesh->getOutgoingHalfEdgeIndex (idx_vertex))
00199         {
00200         }
00201 
00203         OutgoingHalfEdgeAroundVertexCirculator (const HalfEdgeIndex& idx_outgoing_half_edge,
00204                                                 Mesh*const           mesh)
00205           : mesh_                   (mesh),
00206             idx_outgoing_half_edge_ (idx_outgoing_half_edge)
00207         {
00208         }
00209 
00212         inline bool
00213         isValid () const
00214         {
00215           return (idx_outgoing_half_edge_.isValid ());
00216         }
00217 
00220         inline bool
00221         operator == (const Self& other) const
00222         {
00223           return (idx_outgoing_half_edge_ == other.idx_outgoing_half_edge_);
00224         }
00225 
00227         inline Self&
00228         operator ++ ()
00229         {
00230           idx_outgoing_half_edge_ = mesh_->getNextHalfEdgeIndex (mesh_->getOppositeHalfEdgeIndex (idx_outgoing_half_edge_));
00231           return (*this);
00232         }
00233 
00235         inline Self&
00236         operator -- ()
00237         {
00238           idx_outgoing_half_edge_ = mesh_->getOppositeHalfEdgeIndex (mesh_->getPrevHalfEdgeIndex (idx_outgoing_half_edge_));
00239           return (*this);
00240         }
00241 
00243         inline HalfEdgeIndex
00244         getTargetIndex () const
00245         {
00246           return (idx_outgoing_half_edge_);
00247         }
00248 
00250         inline HalfEdgeIndex
00251         getCurrentHalfEdgeIndex () const
00252         {
00253           return (idx_outgoing_half_edge_);
00254         }
00255 
00257         Mesh* mesh_;
00258 
00260         HalfEdgeIndex idx_outgoing_half_edge_;
00261     };
00262   } // End namespace geometry
00263 } // End namespace pcl
00264 
00266 // IncomingHalfEdgeAroundVertexCirculator
00268 
00269 namespace pcl
00270 {
00271   namespace geometry
00272   {
00279     template <class MeshT>
00280     class IncomingHalfEdgeAroundVertexCirculator
00281         : boost::equality_comparable <pcl::geometry::IncomingHalfEdgeAroundVertexCirculator <MeshT>
00282         , boost::unit_steppable      <pcl::geometry::IncomingHalfEdgeAroundVertexCirculator <MeshT>
00283         > >
00284     {
00285       public:
00286 
00287         typedef boost::equality_comparable <pcl::geometry::IncomingHalfEdgeAroundVertexCirculator <MeshT>
00288               , boost::unit_steppable      <pcl::geometry::IncomingHalfEdgeAroundVertexCirculator <MeshT> > > Base;
00289         typedef pcl::geometry::IncomingHalfEdgeAroundVertexCirculator <MeshT> Self;
00290 
00291         typedef MeshT Mesh;
00292         typedef typename Mesh::VertexIndex VertexIndex;
00293         typedef typename Mesh::HalfEdgeIndex HalfEdgeIndex;
00294 
00296         IncomingHalfEdgeAroundVertexCirculator ()
00297           : mesh_                   (NULL),
00298             idx_incoming_half_edge_ ()
00299         {
00300         }
00301 
00303         IncomingHalfEdgeAroundVertexCirculator (const VertexIndex& idx_vertex,
00304                                                 Mesh*const         mesh)
00305           : mesh_                   (mesh),
00306             idx_incoming_half_edge_ (mesh->getIncomingHalfEdgeIndex (idx_vertex))
00307         {
00308         }
00309 
00311         IncomingHalfEdgeAroundVertexCirculator (const HalfEdgeIndex& idx_incoming_half_edge,
00312                                                 Mesh*const           mesh)
00313           : mesh_                   (mesh),
00314             idx_incoming_half_edge_ (idx_incoming_half_edge)
00315         {
00316         }
00317 
00320         inline bool
00321         isValid () const
00322         {
00323           return (idx_incoming_half_edge_.isValid ());
00324         }
00325 
00328         inline bool
00329         operator == (const Self& other) const
00330         {
00331           return (idx_incoming_half_edge_ == other.idx_incoming_half_edge_);
00332         }
00333 
00335         inline Self&
00336         operator ++ ()
00337         {
00338           idx_incoming_half_edge_ = mesh_->getOppositeHalfEdgeIndex (mesh_->getNextHalfEdgeIndex (idx_incoming_half_edge_));
00339           return (*this);
00340         }
00341 
00343         inline Self&
00344         operator -- ()
00345         {
00346           idx_incoming_half_edge_ = mesh_->getPrevHalfEdgeIndex (mesh_->getOppositeHalfEdgeIndex (idx_incoming_half_edge_));
00347           return (*this);
00348         }
00349 
00351         inline HalfEdgeIndex
00352         getTargetIndex () const
00353         {
00354           return (idx_incoming_half_edge_);
00355         }
00356 
00358         inline HalfEdgeIndex
00359         getCurrentHalfEdgeIndex () const
00360         {
00361           return (idx_incoming_half_edge_);
00362         }
00363 
00365         Mesh* mesh_;
00366 
00368         HalfEdgeIndex idx_incoming_half_edge_;
00369     };
00370   } // End namespace geometry
00371 } // End namespace pcl
00372 
00374 // FaceAroundVertexCirculator
00376 
00377 namespace pcl
00378 {
00379   namespace geometry
00380   {
00387     template <class MeshT>
00388     class FaceAroundVertexCirculator
00389         : boost::equality_comparable <pcl::geometry::FaceAroundVertexCirculator <MeshT>
00390         , boost::unit_steppable      <pcl::geometry::FaceAroundVertexCirculator <MeshT>
00391         > >
00392     {
00393       public:
00394 
00395         typedef boost::equality_comparable <pcl::geometry::FaceAroundVertexCirculator <MeshT>
00396               , boost::unit_steppable      <pcl::geometry::FaceAroundVertexCirculator <MeshT> > > Base;
00397         typedef pcl::geometry::FaceAroundVertexCirculator <MeshT> Self;
00398 
00399         typedef MeshT Mesh;
00400         typedef typename Mesh::FaceIndex FaceIndex;
00401         typedef typename Mesh::VertexIndex VertexIndex;
00402         typedef typename Mesh::HalfEdgeIndex HalfEdgeIndex;
00403 
00405         FaceAroundVertexCirculator ()
00406           : mesh_                   (NULL),
00407             idx_outgoing_half_edge_ ()
00408         {
00409         }
00410 
00412         FaceAroundVertexCirculator (const VertexIndex& idx_vertex,
00413                                     Mesh*const         mesh)
00414           : mesh_                   (mesh),
00415             idx_outgoing_half_edge_ (mesh->getOutgoingHalfEdgeIndex (idx_vertex))
00416         {
00417         }
00418 
00420         FaceAroundVertexCirculator (const HalfEdgeIndex& idx_outgoing_half_edge,
00421                                     Mesh*const           mesh)
00422           : mesh_                   (mesh),
00423             idx_outgoing_half_edge_ (idx_outgoing_half_edge)
00424         {
00425         }
00426 
00429         inline bool
00430         isValid () const
00431         {
00432           return (idx_outgoing_half_edge_.isValid ());
00433         }
00434 
00437         inline bool
00438         operator == (const Self& other) const
00439         {
00440           return (idx_outgoing_half_edge_ == other.idx_outgoing_half_edge_);
00441         }
00442 
00444         inline Self&
00445         operator ++ ()
00446         {
00447           idx_outgoing_half_edge_ = mesh_->getNextHalfEdgeIndex (mesh_->getOppositeHalfEdgeIndex (idx_outgoing_half_edge_));
00448           return (*this);
00449         }
00450 
00452         inline Self&
00453         operator -- ()
00454         {
00455           idx_outgoing_half_edge_ = mesh_->getOppositeHalfEdgeIndex (mesh_->getPrevHalfEdgeIndex (idx_outgoing_half_edge_));
00456           return (*this);
00457         }
00458 
00460         inline FaceIndex
00461         getTargetIndex () const
00462         {
00463           return (mesh_->getFaceIndex (idx_outgoing_half_edge_));
00464         }
00465 
00467         inline HalfEdgeIndex
00468         getCurrentHalfEdgeIndex () const
00469         {
00470           return (idx_outgoing_half_edge_);
00471         }
00472 
00474         Mesh* mesh_;
00475 
00477         HalfEdgeIndex idx_outgoing_half_edge_;
00478     };
00479   } // End namespace geometry
00480 } // End namespace pcl
00481 
00483 // VertexAroundFaceCirculator
00485 
00486 namespace pcl
00487 {
00488   namespace geometry
00489   {
00496     template <class MeshT>
00497     class VertexAroundFaceCirculator
00498         : boost::equality_comparable <pcl::geometry::VertexAroundFaceCirculator <MeshT>
00499         , boost::unit_steppable      <pcl::geometry::VertexAroundFaceCirculator <MeshT>
00500         > >
00501     {
00502       public:
00503 
00504         typedef boost::equality_comparable <pcl::geometry::VertexAroundFaceCirculator <MeshT>
00505               , boost::unit_steppable      <pcl::geometry::VertexAroundFaceCirculator <MeshT> > > Base;
00506         typedef pcl::geometry::VertexAroundFaceCirculator <MeshT> Self;
00507 
00508         typedef MeshT Mesh;
00509         typedef typename Mesh::VertexIndex VertexIndex;
00510         typedef typename Mesh::FaceIndex FaceIndex;
00511         typedef typename Mesh::HalfEdgeIndex HalfEdgeIndex;
00512 
00514         VertexAroundFaceCirculator ()
00515           : mesh_                (NULL),
00516             idx_inner_half_edge_ ()
00517         {
00518         }
00519 
00521         VertexAroundFaceCirculator (const FaceIndex& idx_face,
00522                                     Mesh*const       mesh)
00523           : mesh_                (mesh),
00524             idx_inner_half_edge_ (mesh->getInnerHalfEdgeIndex (idx_face))
00525         {
00526         }
00527 
00529         VertexAroundFaceCirculator (const HalfEdgeIndex& idx_inner_half_edge,
00530                                     Mesh*const           mesh)
00531           : mesh_                (mesh),
00532             idx_inner_half_edge_ (idx_inner_half_edge)
00533         {
00534         }
00535 
00538         inline bool
00539         isValid () const
00540         {
00541           return (idx_inner_half_edge_.isValid ());
00542         }
00543 
00546         inline bool
00547         operator == (const Self& other) const
00548         {
00549           return (idx_inner_half_edge_ == other.idx_inner_half_edge_);
00550         }
00551 
00553         inline Self&
00554         operator ++ ()
00555         {
00556           idx_inner_half_edge_ = mesh_->getNextHalfEdgeIndex (idx_inner_half_edge_);
00557           return (*this);
00558         }
00559 
00561         inline Self&
00562         operator -- ()
00563         {
00564           idx_inner_half_edge_ = mesh_->getPrevHalfEdgeIndex (idx_inner_half_edge_);
00565           return (*this);
00566         }
00567 
00569         inline VertexIndex
00570         getTargetIndex () const
00571         {
00572           return (mesh_->getTerminatingVertexIndex (idx_inner_half_edge_));
00573         }
00574 
00576         inline HalfEdgeIndex
00577         getCurrentHalfEdgeIndex () const
00578         {
00579           return (idx_inner_half_edge_);
00580         }
00581 
00583         Mesh* mesh_;
00584 
00586         HalfEdgeIndex idx_inner_half_edge_;
00587     };
00588   } // End namespace geometry
00589 } // End namespace pcl
00590 
00592 // InnerHalfEdgeAroundFaceCirculator
00594 
00595 namespace pcl
00596 {
00597   namespace geometry
00598   {
00605     template <class MeshT>
00606     class InnerHalfEdgeAroundFaceCirculator
00607         : boost::equality_comparable <pcl::geometry::InnerHalfEdgeAroundFaceCirculator <MeshT>
00608         , boost::unit_steppable      <pcl::geometry::InnerHalfEdgeAroundFaceCirculator <MeshT>
00609         > >
00610     {
00611       public:
00612 
00613         typedef boost::equality_comparable <pcl::geometry::InnerHalfEdgeAroundFaceCirculator <MeshT>
00614               , boost::unit_steppable      <pcl::geometry::InnerHalfEdgeAroundFaceCirculator <MeshT> > > Base;
00615         typedef pcl::geometry::InnerHalfEdgeAroundFaceCirculator <MeshT> Self;
00616 
00617         typedef MeshT Mesh;
00618         typedef typename Mesh::FaceIndex FaceIndex;
00619         typedef typename Mesh::HalfEdgeIndex HalfEdgeIndex;
00620 
00622         InnerHalfEdgeAroundFaceCirculator ()
00623           : mesh_                (NULL),
00624             idx_inner_half_edge_ ()
00625         {
00626         }
00627 
00629         InnerHalfEdgeAroundFaceCirculator (const FaceIndex& idx_face,
00630                                            Mesh*const       mesh)
00631           : mesh_                (mesh),
00632             idx_inner_half_edge_ (mesh->getInnerHalfEdgeIndex (idx_face))
00633         {
00634         }
00635 
00637         InnerHalfEdgeAroundFaceCirculator (const HalfEdgeIndex& idx_inner_half_edge,
00638                                            Mesh*const           mesh)
00639           : mesh_                (mesh),
00640             idx_inner_half_edge_ (idx_inner_half_edge)
00641         {
00642         }
00643 
00646         inline bool
00647         isValid () const
00648         {
00649           return (idx_inner_half_edge_.isValid ());
00650         }
00651 
00654         inline bool
00655         operator == (const Self& other) const
00656         {
00657           return (idx_inner_half_edge_ == other.idx_inner_half_edge_);
00658         }
00659 
00661         inline Self&
00662         operator ++ ()
00663         {
00664           idx_inner_half_edge_ = mesh_->getNextHalfEdgeIndex (idx_inner_half_edge_);
00665           return (*this);
00666         }
00667 
00669         inline Self&
00670         operator -- ()
00671         {
00672           idx_inner_half_edge_ = mesh_->getPrevHalfEdgeIndex (idx_inner_half_edge_);
00673           return (*this);
00674         }
00675 
00677         inline HalfEdgeIndex
00678         getTargetIndex () const
00679         {
00680           return (idx_inner_half_edge_);
00681         }
00682 
00684         inline HalfEdgeIndex
00685         getCurrentHalfEdgeIndex () const
00686         {
00687           return (idx_inner_half_edge_);
00688         }
00689 
00691         Mesh* mesh_;
00692 
00694         HalfEdgeIndex idx_inner_half_edge_;
00695     };
00696   } // End namespace geometry
00697 } // End namespace pcl
00698 
00700 // OuterHalfEdgeAroundFaceCirculator
00702 
00703 namespace pcl
00704 {
00705   namespace geometry
00706   {
00713     template <class MeshT>
00714     class OuterHalfEdgeAroundFaceCirculator
00715         : boost::equality_comparable <pcl::geometry::OuterHalfEdgeAroundFaceCirculator <MeshT>
00716         , boost::unit_steppable      <pcl::geometry::OuterHalfEdgeAroundFaceCirculator <MeshT>
00717         > >
00718     {
00719       public:
00720 
00721         typedef boost::equality_comparable <pcl::geometry::OuterHalfEdgeAroundFaceCirculator <MeshT>
00722               , boost::unit_steppable      <pcl::geometry::OuterHalfEdgeAroundFaceCirculator <MeshT> > > Base;
00723         typedef pcl::geometry::OuterHalfEdgeAroundFaceCirculator <MeshT> Self;
00724 
00725         typedef MeshT Mesh;
00726         typedef typename Mesh::FaceIndex FaceIndex;
00727         typedef typename Mesh::HalfEdgeIndex HalfEdgeIndex;
00728 
00730         OuterHalfEdgeAroundFaceCirculator ()
00731           : mesh_                (NULL),
00732             idx_inner_half_edge_ ()
00733         {
00734         }
00735 
00737         OuterHalfEdgeAroundFaceCirculator (const FaceIndex& idx_face,
00738                                            Mesh*const       mesh)
00739           : mesh_                (mesh),
00740             idx_inner_half_edge_ (mesh->getInnerHalfEdgeIndex (idx_face))
00741         {
00742         }
00743 
00745         OuterHalfEdgeAroundFaceCirculator (const HalfEdgeIndex& idx_inner_half_edge,
00746                                            Mesh*const           mesh)
00747           : mesh_                (mesh),
00748             idx_inner_half_edge_ (idx_inner_half_edge)
00749         {
00750         }
00751 
00754         inline bool
00755         isValid () const
00756         {
00757           return (idx_inner_half_edge_.isValid ());
00758         }
00759 
00762         inline bool
00763         operator == (const Self& other) const
00764         {
00765           return (idx_inner_half_edge_ == other.idx_inner_half_edge_);
00766         }
00767 
00769         inline Self&
00770         operator ++ ()
00771         {
00772           idx_inner_half_edge_ = mesh_->getNextHalfEdgeIndex (idx_inner_half_edge_);
00773           return (*this);
00774         }
00775 
00777         inline Self&
00778         operator -- ()
00779         {
00780           idx_inner_half_edge_ = mesh_->getPrevHalfEdgeIndex (idx_inner_half_edge_);
00781           return (*this);
00782         }
00783 
00785         inline HalfEdgeIndex
00786         getTargetIndex () const
00787         {
00788           return (mesh_->getOppositeHalfEdgeIndex (idx_inner_half_edge_));
00789         }
00790 
00792         inline HalfEdgeIndex
00793         getCurrentHalfEdgeIndex () const
00794         {
00795           return (idx_inner_half_edge_);
00796         }
00797 
00799         Mesh* mesh_;
00800 
00802         HalfEdgeIndex idx_inner_half_edge_;
00803     };
00804   } // End namespace geometry
00805 } // End namespace pcl
00806 
00808 // FaceAroundFaceCirculator
00810 
00811 namespace pcl
00812 {
00813   namespace geometry
00814   {
00821     template <class MeshT>
00822     class FaceAroundFaceCirculator
00823         : boost::equality_comparable <pcl::geometry::FaceAroundFaceCirculator <MeshT>
00824         , boost::unit_steppable      <pcl::geometry::FaceAroundFaceCirculator <MeshT>
00825         > >
00826     {
00827       public:
00828 
00829         typedef boost::equality_comparable <pcl::geometry::FaceAroundFaceCirculator <MeshT>
00830               , boost::unit_steppable      <pcl::geometry::FaceAroundFaceCirculator <MeshT> > > Base;
00831         typedef pcl::geometry::FaceAroundFaceCirculator <MeshT> Self;
00832 
00833         typedef MeshT Mesh;
00834         typedef typename Mesh::FaceIndex FaceIndex;
00835         typedef typename Mesh::HalfEdgeIndex HalfEdgeIndex;
00836 
00838         FaceAroundFaceCirculator ()
00839           : mesh_                (NULL),
00840             idx_inner_half_edge_ ()
00841         {
00842         }
00843 
00845         FaceAroundFaceCirculator (const FaceIndex& idx_face,
00846                                   Mesh*const       mesh)
00847           : mesh_                (mesh),
00848             idx_inner_half_edge_ (mesh->getInnerHalfEdgeIndex (idx_face))
00849         {
00850         }
00851 
00853         FaceAroundFaceCirculator (const HalfEdgeIndex& idx_inner_half_edge,
00854                                   Mesh*const           mesh)
00855           : mesh_                (mesh),
00856             idx_inner_half_edge_ (idx_inner_half_edge)
00857         {
00858         }
00859 
00862         inline bool
00863         isValid () const
00864         {
00865           return (idx_inner_half_edge_.isValid ());
00866         }
00867 
00870         inline bool
00871         operator == (const Self& other) const
00872         {
00873           return (idx_inner_half_edge_ == other.idx_inner_half_edge_);
00874         }
00875 
00877         inline Self&
00878         operator ++ ()
00879         {
00880           idx_inner_half_edge_ = mesh_->getNextHalfEdgeIndex (idx_inner_half_edge_);
00881           return (*this);
00882         }
00883 
00885         inline Self&
00886         operator -- ()
00887         {
00888           idx_inner_half_edge_ = mesh_->getPrevHalfEdgeIndex (idx_inner_half_edge_);
00889           return (*this);
00890         }
00891 
00893         inline FaceIndex
00894         getTargetIndex () const
00895         {
00896           return (mesh_->getOppositeFaceIndex (idx_inner_half_edge_));
00897         }
00898 
00900         inline HalfEdgeIndex
00901         getCurrentHalfEdgeIndex () const
00902         {
00903           return (idx_inner_half_edge_);
00904         }
00905 
00907         Mesh* mesh_;
00908 
00910         HalfEdgeIndex idx_inner_half_edge_;
00911     };
00912   } // End namespace geometry
00913 } // End namespace pcl
00914 
00915 #endif // PCL_GEOMETRY_MESH_CIRCULATORS_H


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