00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 
00038 import os
00039 
00040 filename  = os.path.join (os.path.dirname (__file__), 'mesh_circulators.h')
00041 
00042 class Class:
00043     def __init__ (self, value_prefix, value_type, around_type, current_he, deref, inc1, inc2, dec1, dec2):
00044         self.value_prefix  = value_prefix
00045         self.value_type  = value_type
00046         self.around_type = around_type
00047         self.current_he  = current_he
00048         self.deref       = deref
00049         self.inc1        = inc1
00050         self.inc2        = inc2
00051         self.dec1        = dec1
00052         self.dec2        = dec2
00053         self.docstring   = 'TODO: Add documentation!'
00054 
00055 classes = []
00056 classes.append (Class (''        , 'Vertex'  , 'Vertex', 'Outgoing', 'TerminatingVertex', 'Opposite', 'Next'    , 'Prev'    , 'Opposite')) 
00057 classes.append (Class ('Outgoing', 'HalfEdge', 'Vertex', 'Outgoing', ''                 , 'Opposite', 'Next'    , 'Prev'    , 'Opposite')) 
00058 classes.append (Class ('Incoming', 'HalfEdge', 'Vertex', 'Incoming', ''                 , 'Next'    , 'Opposite', 'Opposite', 'Prev'    )) 
00059 classes.append (Class (''        , 'Face'    , 'Vertex', 'Outgoing', 'Face'             , 'Opposite', 'Next'    , 'Prev'    , 'Opposite')) 
00060 classes.append (Class (''        , 'Vertex'  , 'Face'  , 'Inner'   , 'TerminatingVertex', 'Next'    , ''        , 'Prev'    , ''        )) 
00061 classes.append (Class ('Inner'   , 'HalfEdge', 'Face'  , 'Inner'   , ''                 , 'Next'    , ''        , 'Prev'    , ''        )) 
00062 classes.append (Class ('Outer'   , 'HalfEdge', 'Face'  , 'Inner'   , 'OppositeHalfEdge' , 'Next'    , ''        , 'Prev'    , ''        )) 
00063 classes.append (Class (''        , 'Face'    , 'Face'  , 'Inner'   , 'OppositeFace'     , 'Next'    , ''        , 'Prev'    , ''        )) 
00064 
00065 classes [0].docstring = 'Circulates counter-clockwise around a vertex and returns an index to the terminating vertex of the outgoing half-edge (the target).'
00066 classes [1].docstring = 'Circulates counter-clockwise around a vertex and returns an index to the outgoing half-edge (the target).'
00067 classes [2].docstring = 'Circulates counter-clockwise around a vertex and returns an index to the incoming half-edge (the target).'
00068 classes [3].docstring = 'Circulates counter-clockwise around a vertex and returns an index to the face of the outgoing half-edge (the target).'
00069 classes [4].docstring = 'Circulates clockwise around a face and returns an index to the terminating vertex of the inner half-edge (the target).'
00070 classes [5].docstring = 'Circulates clockwise around a face and returns an index to the inner half-edge (the target).'
00071 classes [6].docstring = 'Circulates clockwise around a face and returns an index to the outer half-edge (the target).'
00072 classes [7].docstring = 'Circulates clockwise around a face and returns an index to the face of the outer half-edge (the target).'
00073 
00074 
00075 
00076 f = open (filename, 'w')
00077 
00078 f.write ('/*\n')
00079 f.write (' * Software License Agreement (BSD License)\n')
00080 f.write (' *\n')
00081 f.write (' * Point Cloud Library (PCL) - www.pointclouds.org\n')
00082 f.write (' * Copyright (c) 2009-2012, Willow Garage, Inc.\n')
00083 f.write (' * Copyright (c) 2012-, Open Perception, Inc.\n')
00084 f.write (' *\n')
00085 f.write (' * All rights reserved.\n')
00086 f.write (' *\n')
00087 f.write (' * Redistribution and use in source and binary forms, with or without\n')
00088 f.write (' * modification, are permitted provided that the following conditions\n')
00089 f.write (' * are met:\n')
00090 f.write (' *\n')
00091 f.write (' *  * Redistributions of source code must retain the above copyright\n')
00092 f.write (' *    notice, this list of conditions and the following disclaimer.\n')
00093 f.write (' *  * Redistributions in binary form must reproduce the above\n')
00094 f.write (' *    copyright notice, this list of conditions and the following\n')
00095 f.write (' *    disclaimer in the documentation and/or other materials provided\n')
00096 f.write (' *    with the distribution.\n')
00097 f.write (' *  * Neither the name of the copyright holder(s) nor the names of its\n')
00098 f.write (' *    contributors may be used to endorse or promote products derived\n')
00099 f.write (' *    from this software without specific prior written permission.\n')
00100 f.write (' *\n')
00101 f.write (' * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n')
00102 f.write (' * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n')
00103 f.write (' * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n')
00104 f.write (' * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n')
00105 f.write (' * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n')
00106 f.write (' * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n')
00107 f.write (' * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n')
00108 f.write (' * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n')
00109 f.write (' * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n')
00110 f.write (' * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n')
00111 f.write (' * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n')
00112 f.write (' * POSSIBILITY OF SUCH DAMAGE.\n')
00113 f.write (' *\n')
00114 f.write (' * $Id$\n')
00115 f.write (' *\n')
00116 f.write (' */\n\n')
00117 
00118 f.write ("// NOTE: This file has been created with 'pcl_src/geometry/include/pcl/geometry/mesh_circulators.py'\n\n")
00119 
00120 f.write ('#ifndef PCL_GEOMETRY_MESH_CIRCULATORS_H\n')
00121 f.write ('#define PCL_GEOMETRY_MESH_CIRCULATORS_H\n\n')
00122 
00123 f.write ('#include <pcl/geometry/boost.h>\n')
00124 f.write ('#include <pcl/geometry/mesh_indices.h>\n\n')
00125 
00126 for c in classes:
00127 
00128     value_prefix    = c.value_prefix
00129     value_name      = c.value_prefix + c.value_type
00130     value_type      = c.value_type
00131     around_type     = c.around_type
00132     around_obj      = around_type.lower ()
00133     around_idx      = 'idx_' + around_obj
00134     current_he      = c.current_he
00135     current_he_idx  = 'idx_' + current_he.lower () + '_half_edge'
00136     current_he_idx_ = current_he_idx + '_'
00137     deref           = c.deref
00138     inc1            = c.inc1
00139     inc2            = c.inc2
00140     dec1            = c.dec1
00141     dec2            = c.dec2
00142 
00143     class_name      = value_name + 'Around' + around_type + 'Circulator'
00144 
00145     placeholder_at  = ' ' * (len (around_type) - 3)
00146     placeholder_cn  = ' ' *  len (class_name)
00147     placeholder_gt  = ' ' * (len (current_he_idx) - 5)
00148 
00149     f.write ('////////////////////////////////////////////////////////////////////////////////\n')
00150     f.write ('// ' + class_name + '\n')
00151     f.write ('////////////////////////////////////////////////////////////////////////////////\n\n')
00152 
00153     f.write ('namespace pcl\n')
00154     f.write ('{\n')
00155     f.write ('  namespace geometry\n')
00156     f.write ('  {\n')
00157 
00158     f.write ('    /** \\brief ' + c.docstring + ' The best way to declare the circulator is to use the method pcl::geometry::MeshBase::get' + class_name + ' ().\n')
00159     f.write ("      * \\tparam MeshT Mesh to which this circulator belongs to.\n")
00160     f.write ("      * \\note The circulator can't be used to change the connectivity in the mesh (only const circulators are valid).\n")
00161     f.write ('      * \\author Martin Saelzle\n')
00162     f.write ('      * \ingroup geometry\n')
00163     f.write ('      */\n')
00164 
00165     f.write ('    template <class MeshT>\n')
00166     f.write ('    class ' + class_name + '\n')
00167     f.write ('        : boost::equality_comparable <pcl::geometry::' + class_name + ' <MeshT>\n')
00168     f.write ('        , boost::unit_steppable      <pcl::geometry::' + class_name + ' <MeshT>\n')
00169     f.write ('        > >\n')
00170     f.write ('    {\n')
00171     f.write ('      public:\n\n')
00172 
00173     f.write ('        typedef boost::equality_comparable <pcl::geometry::' + class_name + ' <MeshT>\n')
00174     f.write ('              , boost::unit_steppable      <pcl::geometry::' + class_name + ' <MeshT> > > Base;\n')
00175     f.write ('        typedef pcl::geometry::' + class_name + ' <MeshT> Self;\n\n')
00176 
00177     f.write ('        typedef MeshT Mesh;\n')
00178     if value_type != 'HalfEdge':
00179         f.write ('        typedef typename Mesh::' + value_type + 'Index ' + value_type + 'Index;\n')
00180     if around_type != value_type:
00181         f.write ('        typedef typename Mesh::' + around_type + 'Index ' + around_type + 'Index;\n')
00182     f.write ('        typedef typename Mesh::HalfEdgeIndex HalfEdgeIndex;\n\n')
00183 
00184     f.write ('        /** \\brief Constructor resulting in an invalid circulator. */\n')
00185     f.write ('        ' + class_name + ' ()\n')
00186     f.write ('          : mesh_ ' + placeholder_gt + ' (NULL),\n')
00187     f.write ('            '       + current_he_idx_ + ' ()\n')
00188     f.write ('        {\n')
00189     f.write ('        }\n\n')
00190 
00191     f.write ('        /** \\brief Construct from the ' + around_obj + ' around which we want to circulate. */\n')
00192     f.write ('        ' + class_name     + ' (const '      + around_type    + 'Index& ' + around_idx + ',\n')
00193     f.write ('        ' + placeholder_cn + '  Mesh*const ' + placeholder_at + '     '   + 'mesh)\n')
00194     f.write ('          : mesh_ ' + placeholder_gt + ' (mesh),\n')
00195     f.write ('            '       + current_he_idx_ + ' (mesh->get' + current_he + 'HalfEdgeIndex (' + around_idx + '))\n')
00196     f.write ('        {\n')
00197     f.write ('        }\n\n')
00198 
00199     f.write ('        /** \\brief Construct directly from the ' + current_he.lower () + ' half-edge. */\n')
00200     f.write ('        ' + class_name     + ' (const HalfEdgeIndex& ' + current_he_idx  + ',\n')
00201     f.write ('        ' + placeholder_cn + '  Mesh*const           ' + 'mesh)\n')
00202     f.write ('          : mesh_ ' + placeholder_gt + ' (mesh),\n')
00203     f.write ('            '       + current_he_idx_ + ' (' + current_he_idx + ')\n')
00204     f.write ('        {\n')
00205     f.write ('        }\n\n')
00206 
00207     f.write ('        /** \\brief Check if the circulator is valid.\n')
00208     f.write ('          * \\warning Does NOT check if the stored mesh pointer is valid. You have to ensure this yourself when constructing the circulator. */\n')
00209     f.write ('        inline bool\n')
00210     f.write ('        isValid () const\n')
00211     f.write ('        {\n')
00212     f.write ('          return (' + current_he_idx_ + '.isValid ());\n')
00213     f.write ('        }\n\n')
00214 
00215     f.write ('        /** \\brief Comparison operators (with boost::operators): == !=\n')
00216     f.write ('          * \\warning Does NOT check if the circulators belong to the same mesh. Please check this yourself. */\n')
00217     f.write ('        inline bool\n')
00218     f.write ('        operator == (const Self& other) const\n')
00219     f.write ('        {\n')
00220     f.write ('          return (' + current_he_idx_ + ' == other.' + current_he_idx_ + ');\n')
00221     f.write ('        }\n\n')
00222 
00223     tmp = 'mesh_->get' + inc1 + 'HalfEdgeIndex (' + current_he_idx_ + ')'
00224     if inc2:
00225         tmp = 'mesh_->get' + inc2 + 'HalfEdgeIndex (' + tmp + ')'
00226 
00227     f.write ('        /** \\brief Increment operators (with boost::operators): ++ (pre and post) */\n')
00228     f.write ('        inline Self&\n')
00229     f.write ('        operator ++ ()\n')
00230     f.write ('        {\n')
00231     f.write ('          ' + current_he_idx_ + ' = ' + tmp + ';\n')
00232     f.write ('          return (*this);\n')
00233     f.write ('        }\n\n')
00234 
00235     tmp = 'mesh_->get' + dec1 + 'HalfEdgeIndex (' + current_he_idx_ + ')'
00236     if dec2:
00237         tmp = 'mesh_->get' + dec2 + 'HalfEdgeIndex (' + tmp + ')'
00238 
00239     f.write ('        /** \\brief Decrement operators (with boost::operators): -- (pre and post) */\n')
00240     f.write ('        inline Self&\n')
00241     f.write ('        operator -- ()\n')
00242     f.write ('        {\n')
00243     f.write ('          ' + current_he_idx_ + ' = ' + tmp + ';\n')
00244     f.write ('          return (*this);\n')
00245     f.write ('        }\n\n')
00246 
00247     if deref:
00248         tmp = 'mesh_->get' + deref + 'Index (' + current_he_idx_ + ')'
00249     else:
00250         tmp = current_he_idx_
00251     tgt = 'half-edge' if value_type=='HalfEdge' else value_type.lower ()
00252     tgt = value_prefix.lower () + (' ' if value_prefix else 'target ')  + tgt
00253 
00254     f.write ('        /** \\brief Get the index to the ' + tgt + '. */\n')
00255     f.write ('        inline ' + value_type + 'Index\n')
00256     f.write ('        getTargetIndex () const\n')
00257     f.write ('        {\n')
00258     f.write ('          return (' + tmp + ');\n')
00259     f.write ('        }\n\n')
00260 
00261     f.write ('        /** \\brief Get the half-edge that is currently stored in the circulator. */\n')
00262     f.write ('        inline HalfEdgeIndex\n')
00263     f.write ('        getCurrentHalfEdgeIndex () const\n')
00264     f.write ('        {\n')
00265     f.write ('          return (' + current_he_idx_ + ');\n')
00266     f.write ('        }\n\n')
00267 
00268     f.write ('        /** \\brief The mesh to which this circulator belongs to. */\n')
00269     f.write ('        Mesh* mesh_;\n\n')
00270 
00271     f.write ('        /** \\brief The ' + current_he.lower () + ' half-edge of the ' + around_obj + ' around which we want to circulate. */\n')
00272     f.write ('        HalfEdgeIndex ' + current_he_idx_ + ';\n')
00273     f.write ('    };\n')
00274 
00275     f.write ('  } // End namespace geometry\n')
00276     f.write ('} // End namespace pcl\n\n')
00277 
00278 f.write ('#endif // PCL_GEOMETRY_MESH_CIRCULATORS_H\n')
00279 
00280 f.close()