mesh_indices.py
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 
00038 import os
00039 
00040 filename    = os.path.join (os.path.dirname (__file__), 'mesh_indices.h')
00041 class_names = ['VertexIndex', 'HalfEdgeIndex', 'EdgeIndex', 'FaceIndex']
00042 
00043 ################################################################################
00044 
00045 f = open (filename, 'w')
00046 
00047 f.write ('/*\n')
00048 f.write (' * Software License Agreement (BSD License)\n')
00049 f.write (' *\n')
00050 f.write (' * Point Cloud Library (PCL) - www.pointclouds.org\n')
00051 f.write (' * Copyright (c) 2009-2012, Willow Garage, Inc.\n')
00052 f.write (' * Copyright (c) 2012-, Open Perception, Inc.\n')
00053 f.write (' *\n')
00054 f.write (' * All rights reserved.\n')
00055 f.write (' *\n')
00056 f.write (' * Redistribution and use in source and binary forms, with or without\n')
00057 f.write (' * modification, are permitted provided that the following conditions\n')
00058 f.write (' * are met:\n')
00059 f.write (' *\n')
00060 f.write (' *  * Redistributions of source code must retain the above copyright\n')
00061 f.write (' *    notice, this list of conditions and the following disclaimer.\n')
00062 f.write (' *  * Redistributions in binary form must reproduce the above\n')
00063 f.write (' *    copyright notice, this list of conditions and the following\n')
00064 f.write (' *    disclaimer in the documentation and/or other materials provided\n')
00065 f.write (' *    with the distribution.\n')
00066 f.write (' *  * Neither the name of the copyright holder(s) nor the names of its\n')
00067 f.write (' *    contributors may be used to endorse or promote products derived\n')
00068 f.write (' *    from this software without specific prior written permission.\n')
00069 f.write (' *\n')
00070 f.write (' * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n')
00071 f.write (' * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n')
00072 f.write (' * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n')
00073 f.write (' * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n')
00074 f.write (' * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n')
00075 f.write (' * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n')
00076 f.write (' * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n')
00077 f.write (' * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n')
00078 f.write (' * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n')
00079 f.write (' * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n')
00080 f.write (' * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n')
00081 f.write (' * POSSIBILITY OF SUCH DAMAGE.\n')
00082 f.write (' *\n')
00083 f.write (' * $Id$\n')
00084 f.write (' *\n')
00085 f.write (' */\n\n')
00086 
00087 f.write ("// NOTE: This file has been created with 'pcl_src/geometry/include/pcl/geometry/mesh_indices.py'\n\n")
00088 
00089 f.write ('#ifndef PCL_GEOMETRY_MESH_INDICES_H\n')
00090 f.write ('#define PCL_GEOMETRY_MESH_INDICES_H\n\n')
00091 
00092 f.write ('#include <iostream>\n\n')
00093 
00094 f.write ('#include <pcl/geometry/boost.h>\n\n')
00095 
00096 for cn in class_names:
00097 
00098     f.write ('////////////////////////////////////////////////////////////////////////////////\n')
00099     f.write ('// ' + cn + '\n')
00100     f.write ('////////////////////////////////////////////////////////////////////////////////\n\n')
00101 
00102     f.write ('namespace pcl\n')
00103     f.write ('{\n')
00104     f.write ('  namespace geometry\n')
00105     f.write ('  {\n')
00106     f.write ('    /** \\brief Index used to access elements in the half-edge mesh. It is basically just a wrapper around an integer with a few added methods.\n')
00107     f.write ('      * \\author Martin Saelzle\n')
00108     f.write ('      * \ingroup geometry\n')
00109     f.write ('      */\n')
00110     f.write ('    class ' + cn + '\n')
00111     f.write ('        : boost::totally_ordered <pcl::geometry::' + cn + ' // < > <= >= == !=\n')
00112     f.write ('        , boost::unit_steppable  <pcl::geometry::' + cn + ' // ++ -- (pre and post)\n')
00113     f.write ('        , boost::additive        <pcl::geometry::' + cn + ' // += + -= -\n')
00114     f.write ('        > > >\n')
00115     f.write ('    {\n')
00116     f.write ('      public:\n\n')
00117 
00118     f.write ('        typedef boost::totally_ordered <pcl::geometry::' + cn + ',\n')
00119     f.write ('                boost::unit_steppable  <pcl::geometry::' + cn + ',\n')
00120     f.write ('                boost::additive        <pcl::geometry::' + cn + '> > > Base;\n')
00121     f.write ('        typedef pcl::geometry::' + cn + '                              Self;\n\n')
00122 
00123     f.write ('        /** \\brief Constructor. Initializes with an invalid index. */\n')
00124     f.write ('        ' + cn + ' ()\n')
00125     f.write ('          : index_ (-1)\n')
00126     f.write ('        {\n')
00127     f.write ('        }\n\n')
00128 
00129     f.write ('        /** \\brief Constructor.\n')
00130     f.write ('          * \param[in] index The integer index.\n')
00131     f.write ('          */\n')
00132     f.write ('        explicit ' + cn + ' (const int index)\n')
00133     f.write ('          : index_ (index)\n')
00134     f.write ('        {\n')
00135     f.write ('        }\n\n')
00136 
00137     f.write ('        /** \\brief Returns true if the index is valid. */\n')
00138     f.write ('        inline bool\n')
00139     f.write ('        isValid () const\n')
00140     f.write ('        {\n')
00141     f.write ('          return (index_ >= 0);\n')
00142     f.write ('        }\n\n')
00143 
00144     f.write ('        /** \\brief Invalidate the index. */\n')
00145     f.write ('        inline void\n')
00146     f.write ('        invalidate ()\n')
00147     f.write ('        {\n')
00148     f.write ('          index_ = -1;\n')
00149     f.write ('        }\n\n')
00150 
00151     f.write ('        /** \\brief Get the index. */\n')
00152     f.write ('        inline int\n')
00153     f.write ('        get () const\n')
00154     f.write ('        {\n')
00155     f.write ('          return (index_);\n')
00156     f.write ('        }\n\n')
00157 
00158     f.write ('        /** \\brief Set the index. */\n')
00159     f.write ('        inline void\n')
00160     f.write ('        set (const int index)\n')
00161     f.write ('        {\n')
00162     f.write ('          index_ = index;\n')
00163     f.write ('        }\n\n')
00164 
00165     f.write ('        /** \\brief Comparison operators (with boost::operators): < > <= >= */\n')
00166     f.write ('        inline bool\n')
00167     f.write ('        operator < (const Self& other) const\n')
00168     f.write ('        {\n')
00169     f.write ('          return (this->get () < other.get ());\n')
00170     f.write ('        }\n\n')
00171 
00172     f.write ('        /** \\brief Comparison operators (with boost::operators): == != */\n')
00173     f.write ('        inline bool\n')
00174     f.write ('        operator == (const Self& other) const\n')
00175     f.write ('        {\n')
00176     f.write ('          return (this->get () == other.get ());\n')
00177     f.write ('        }\n\n')
00178 
00179     f.write ('        /** \\brief Increment operators (with boost::operators): ++ (pre and post) */\n')
00180     f.write ('        inline Self&\n')
00181     f.write ('        operator ++ ()\n')
00182     f.write ('        {\n')
00183     f.write ('          ++index_;\n')
00184     f.write ('          return (*this);\n')
00185     f.write ('        }\n\n')
00186 
00187     f.write ('        /** \\brief Decrement operators (with boost::operators): \-\- (pre and post) */\n')
00188     f.write ('        inline Self&\n')
00189     f.write ('        operator -- ()\n')
00190     f.write ('        {\n')
00191     f.write ('          --index_;\n')
00192     f.write ('          return (*this);\n')
00193     f.write ('        }\n\n')
00194 
00195     f.write ('        /** \\brief Addition operators (with boost::operators): + += */\n')
00196     f.write ('        inline Self&\n')
00197     f.write ('        operator += (const Self& other)\n')
00198     f.write ('        {\n')
00199     f.write ('          index_ += other.get ();\n')
00200     f.write ('          return (*this);\n')
00201     f.write ('        }\n\n')
00202 
00203     f.write ('        /** \\brief Subtraction operators (with boost::operators): - -= */\n')
00204     f.write ('        inline Self&\n')
00205     f.write ('        operator -= (const Self& other)\n')
00206     f.write ('        {\n')
00207     f.write ('          index_ -= other.get ();\n')
00208     f.write ('          return (*this);\n')
00209     f.write ('        }\n\n')
00210 
00211     f.write ('      private:\n\n')
00212 
00213     f.write ('        /** \\brief Stored index. */\n')
00214     f.write ('        int index_;\n\n')
00215 
00216     f.write ('        friend std::istream&\n')
00217     f.write ('        operator >> (std::istream& is, pcl::geometry::' + cn + '& index);\n')
00218     f.write ('    };\n\n')
00219 
00220     f.write ('    /** \\brief ostream operator. */\n')
00221     f.write ('    inline std::ostream&\n')
00222     f.write ('    operator << (std::ostream& os, const pcl::geometry::' + cn + '& index)\n')
00223     f.write ('    {\n')
00224     f.write ('      return (os << index.get ());\n')
00225     f.write ('    }\n\n')
00226 
00227     f.write ('    /** \\brief istream operator. */\n')
00228     f.write ('    inline std::istream&\n')
00229     f.write ('    operator >> (std::istream& is, pcl::geometry::' + cn + '& index)\n')
00230     f.write ('    {\n')
00231     f.write ('      return (is >> index.index_);\n')
00232     f.write ('    }\n\n')
00233 
00234     f.write ('  } // End namespace geometry\n')
00235     f.write ('} // End namespace pcl\n\n')
00236 
00237 f.write ('////////////////////////////////////////////////////////////////////////////////\n')
00238 f.write ('// Conversions\n')
00239 f.write ('////////////////////////////////////////////////////////////////////////////////\n\n')
00240 
00241 f.write ('namespace pcl\n')
00242 f.write ('{\n')
00243 f.write ('  namespace geometry\n')
00244 f.write ('  {\n')
00245 f.write ('    /** \\brief Convert the given half-edge index to an edge index. */\n')
00246 f.write ('    inline pcl::geometry::EdgeIndex\n')
00247 f.write ('    toEdgeIndex (const HalfEdgeIndex& index)\n')
00248 f.write ('    {\n')
00249 f.write ('      return (index.isValid () ? EdgeIndex (index.get () / 2) : EdgeIndex ());\n')
00250 f.write ('    }\n\n')
00251 
00252 f.write ('    /** \\brief Convert the given edge index to a half-edge index.\n')
00253 f.write ('      * \\param[in] get_first The first half-edge of the edge is returned if this variable is true; elsewise the second.\n')
00254 f.write ('      */\n')
00255 f.write ('    inline pcl::geometry::HalfEdgeIndex\n')
00256 f.write ('    toHalfEdgeIndex (const EdgeIndex& index, const bool get_first=true)\n')
00257 f.write ('    {\n')
00258 f.write ('      return (index.isValid () ? HalfEdgeIndex (index.get () * 2 + static_cast <int> (!get_first)) : HalfEdgeIndex ());\n')
00259 f.write ('    }\n')
00260 f.write ('  } // End namespace geometry\n')
00261 f.write ('} // End namespace pcl\n\n')
00262 
00263 f.write ('#endif // PCL_GEOMETRY_MESH_INDICES_H\n')
00264 
00265 f.close()


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