poisson.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, Willow Garage, 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 Willow Garage, Inc. 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  * $Id: poisson.h 5036 2012-03-12 08:54:15Z rusu $
00035  *
00036  */
00037 
00038 #ifndef PCL_SURFACE_POISSON_H_
00039 #define PCL_SURFACE_POISSON_H_
00040 
00041 #include <pcl/surface/reconstruction.h>
00042 #include <pcl/surface/poisson/geometry.h>
00043 
00044 namespace pcl
00045 {
00054   template<typename PointNT>
00055   class Poisson : public SurfaceReconstruction<PointNT>
00056   {
00057     public:
00058       using SurfaceReconstruction<PointNT>::input_;
00059       using SurfaceReconstruction<PointNT>::tree_;
00060 
00061       typedef typename pcl::PointCloud<PointNT>::Ptr PointCloudPtr;
00062 
00063       typedef typename pcl::KdTree<PointNT> KdTree;
00064       typedef typename pcl::KdTree<PointNT>::Ptr KdTreePtr;
00065 
00067       Poisson ();
00068 
00070       ~Poisson ();
00071 
00075       void
00076       performReconstruction (pcl::PolygonMesh &output);
00077 
00082       void
00083       performReconstruction (pcl::PointCloud<PointNT> &points,
00084                              std::vector<pcl::Vertices> &polygons);
00085 
00091       inline void
00092       setConfidence (bool confidence) { confidence_ = confidence; }
00093 
00095       inline bool
00096       getConfidence () { return confidence_; }
00097 
00103       inline void
00104       setManifold (bool manifold) { manifold_ = manifold; }
00105 
00107       inline bool
00108       getManifold () { return manifold_; }
00109 
00114       inline void
00115       setOutputPolygons (bool output_polygons) { output_polygons_ = output_polygons; }
00116 
00118       inline bool
00119       getOutputPolygons () { return output_polygons_; }
00120 
00121 
00128       inline void
00129       setDepth (int depth) { depth_ = depth; }
00130 
00132       inline int
00133       getDepth () { return depth_; }
00134 
00141       inline void
00142       setSolverDivide (int solver_divide) { solver_divide_ = solver_divide; }
00143 
00145       inline int
00146       getSolverDivide () { return solver_divide_; }
00147 
00154       inline void
00155       setIsoDivide (int iso_divide) { iso_divide_ = iso_divide; }
00156 
00158       inline int
00159       getIsoDivide () { return iso_divide_; }
00160 
00167       inline void
00168       setSamplesPerNode (float samples_per_node) { samples_per_node_ = samples_per_node; }
00169 
00173       inline float
00174       getSamplesPerNode () { return samples_per_node_; }
00175 
00180       inline void
00181       setScale (float scale) { scale_ = scale; }
00182 
00186       inline float
00187       getScale () { return scale_; }
00188 
00192       inline void
00193       setDegree (int degree) { degree_ = degree; }
00194 
00196       inline int
00197       getDegree () { return degree_; }
00198 
00199 
00200     protected:
00202       PointCloudPtr data_;
00203 
00205       std::string
00206       getClassName () const { return ("Poisson"); }
00207 
00208     private:
00209       bool no_reset_samples_;
00210       bool no_clip_tree_;
00211       bool confidence_;
00212       bool manifold_;
00213       bool output_polygons_;
00214 
00215       int depth_;
00216       int solver_divide_;
00217       int iso_divide_;
00218       int refine_;
00219       int kernel_depth_;
00220       int degree_;
00221 
00222       float samples_per_node_;
00223       float scale_;
00224 
00225       template<int Degree> void
00226       execute (poisson::CoredMeshData &mesh,
00227                poisson::Point3D<float> &translate,
00228                float &scale);
00229 
00230     public:
00231       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00232   };
00233 }
00234 
00235 #endif  // PCL_SURFACE_POISSON_H_


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:17:20