triangulation.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2012-, Open Perception, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the copyright holder(s) nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  * 
00035  *
00036  */
00037 
00038 #ifndef NURBS_TRIANGULATION_H
00039 #define NURBS_TRIANGULATION_H
00040 
00041 #include <pcl/pcl_exports.h>
00042 #include <pcl/point_cloud.h>
00043 #include <pcl/point_types.h>
00044 #include <pcl/surface/3rdparty/opennurbs/opennurbs.h>
00045 #include <pcl/PolygonMesh.h>
00046 
00047 #include <pcl/surface/on_nurbs/nurbs_data.h>
00048 
00049 namespace pcl
00050 {
00051   namespace on_nurbs
00052   {
00053 
00055     class PCL_EXPORTS Triangulation
00056     {
00057       protected:
00059         static void
00060         createIndices (std::vector<pcl::Vertices> &vertices, unsigned vidx, unsigned segX, unsigned segY);
00061 
00063         static void
00064         createVertices (pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud, float x0, float y0, float z0, float width,
00065                         float height, unsigned segX, unsigned segY);
00066 
00067       public:
00068         static bool
00069         isInside(const ON_NurbsCurve &curve, const pcl::PointXYZ &v);
00070 
00071         //      /** \brief Converts an NurbsObject to a pcl::PolygonMesh by sampling all NURBS according to the resolution specified.
00072         //       *  \param[in] object The NURBS object.
00073         //       *  \param[out] mesh The pcl::PolygonMesh
00074         //       *  \param[in] resolution mesh resolution (number of vertices along each of the two dimensions of the surface. */
00075         //      static void
00076         //      convertObject2PolygonMesh (const NurbsObject &object, PolygonMesh &mesh, unsigned resolution);
00077 
00082         static void
00083         convertSurface2PolygonMesh (const ON_NurbsSurface &nurbs, PolygonMesh &mesh, unsigned resolution);
00084 
00090         static void
00091         convertTrimmedSurface2PolygonMesh (const ON_NurbsSurface &nurbs, const ON_NurbsCurve &curve, PolygonMesh &mesh,
00092                                            unsigned resolution);
00093         static void
00094         convertTrimmedSurface2PolygonMesh (const ON_NurbsSurface &nurbs, const ON_NurbsCurve &curve, PolygonMesh &mesh,
00095                                            unsigned resolution, vector_vec3d &start, vector_vec3d &end);
00096 
00103         static void
00104         convertSurface2Vertices (const ON_NurbsSurface &nurbs, pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
00105                                  std::vector<pcl::Vertices> &vertices, unsigned resolution);
00106 
00112         static void
00113         convertCurve2PointCloud (const ON_NurbsCurve &nurbs, pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud,
00114                                  unsigned resolution);
00115 
00121         static void
00122         convertCurve2PointCloud (const ON_NurbsCurve &curve, const ON_NurbsSurface &surf,
00123                                  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud, unsigned resolution);
00124 
00125     };
00126   }
00127 }
00128 
00129 #endif


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:37:09