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$
00035  *
00036  */
00037 
00038 #ifndef PCL_SURFACE_POISSON_H_
00039 #define PCL_SURFACE_POISSON_H_
00040 
00041 #include <pcl/surface/reconstruction.h>
00042 
00043 namespace pcl
00044 {
00045   namespace poisson
00046   {
00047     class CoredVectorMeshData;
00048     template <class Real> struct Point3D;
00049   }
00050 
00059   template<typename PointNT>
00060   class Poisson : public SurfaceReconstruction<PointNT>
00061   {
00062     public:
00063       typedef boost::shared_ptr<Poisson<PointNT> > Ptr;
00064       typedef boost::shared_ptr<const Poisson<PointNT> > ConstPtr;
00065 
00066       using SurfaceReconstruction<PointNT>::input_;
00067       using SurfaceReconstruction<PointNT>::tree_;
00068 
00069       typedef typename pcl::PointCloud<PointNT>::Ptr PointCloudPtr;
00070 
00071       typedef typename pcl::KdTree<PointNT> KdTree;
00072       typedef typename pcl::KdTree<PointNT>::Ptr KdTreePtr;
00073 
00075       Poisson ();
00076 
00078       ~Poisson ();
00079 
00083       void
00084       performReconstruction (pcl::PolygonMesh &output);
00085 
00090       void
00091       performReconstruction (pcl::PointCloud<PointNT> &points,
00092                              std::vector<pcl::Vertices> &polygons);
00093 
00100       inline void
00101       setDepth (int depth) { depth_ = depth; }
00102 
00104       inline int
00105       getDepth () { return depth_; }
00106 
00107       inline void
00108       setMinDepth (int min_depth) { min_depth_ = min_depth; }
00109 
00110       inline int
00111       getMinDepth () { return min_depth_; }
00112 
00113       inline void
00114       setPointWeight (float point_weight) { point_weight_ = point_weight; }
00115 
00116       inline float
00117       getPointWeight () { return point_weight_; }
00118 
00123       inline void
00124       setScale (float scale) { scale_ = scale; }
00125 
00129       inline float
00130       getScale () { return scale_; }
00131 
00138       inline void
00139       setSolverDivide (int solver_divide) { solver_divide_ = solver_divide; }
00140 
00142       inline int
00143       getSolverDivide () { return solver_divide_; }
00144 
00151       inline void
00152       setIsoDivide (int iso_divide) { iso_divide_ = iso_divide; }
00153 
00155       inline int
00156       getIsoDivide () { return iso_divide_; }
00157 
00164       inline void
00165       setSamplesPerNode (float samples_per_node) { samples_per_node_ = samples_per_node; }
00166 
00170       inline float
00171       getSamplesPerNode () { return samples_per_node_; }
00172 
00178       inline void
00179       setConfidence (bool confidence) { confidence_ = confidence; }
00180 
00182       inline bool
00183       getConfidence () { return confidence_; }
00184 
00189       inline void
00190       setOutputPolygons (bool output_polygons) { output_polygons_ = output_polygons; }
00191 
00193       inline bool
00194       getOutputPolygons () { return output_polygons_; }
00195 
00199       inline void
00200       setDegree (int degree) { degree_ = degree; }
00201 
00203       inline int
00204       getDegree () { return degree_; }
00205 
00211       inline void
00212       setManifold (bool manifold) { manifold_ = manifold; }
00213 
00215       inline bool
00216       getManifold () { return manifold_; }
00217 
00218     protected:
00220       std::string
00221       getClassName () const { return ("Poisson"); }
00222 
00223     private:
00224       int depth_;
00225       int min_depth_;
00226       float point_weight_;
00227       float scale_;
00228       int solver_divide_;
00229       int iso_divide_;
00230       float samples_per_node_;
00231       bool confidence_;
00232       bool output_polygons_;
00233 
00234       bool no_reset_samples_;
00235       bool no_clip_tree_;
00236       bool manifold_;
00237 
00238       int refine_;
00239       int kernel_depth_;
00240       int degree_;
00241       bool non_adaptive_weights_;
00242       bool show_residual_;
00243       int min_iterations_;
00244       float solver_accuracy_;
00245 
00246       template<int Degree> void
00247       execute (poisson::CoredVectorMeshData &mesh,
00248                poisson::Point3D<float> &translate,
00249                float &scale);
00250 
00251     public:
00252       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00253   };
00254 }
00255 
00256 #endif  // PCL_SURFACE_POISSON_H_


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:31:04