Go to the documentation of this file.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
00039
00040 #include <pcl/pcl_config.h>
00041 #ifdef HAVE_QHULL
00042
00043 #ifndef PCL_CONCAVE_HULL_H
00044 #define PCL_CONCAVE_HULL_H
00045
00046 #include <pcl/surface/convex_hull.h>
00047
00048 namespace pcl
00049 {
00051
00055 template<typename PointInT>
00056 class ConcaveHull : public MeshConstruction<PointInT>
00057 {
00058 protected:
00059 typedef boost::shared_ptr<ConcaveHull<PointInT> > Ptr;
00060 typedef boost::shared_ptr<const ConcaveHull<PointInT> > ConstPtr;
00061
00062 using PCLBase<PointInT>::input_;
00063 using PCLBase<PointInT>::indices_;
00064 using PCLBase<PointInT>::initCompute;
00065 using PCLBase<PointInT>::deinitCompute;
00066
00067 public:
00068 using MeshConstruction<PointInT>::reconstruct;
00069
00070 typedef pcl::PointCloud<PointInT> PointCloud;
00071 typedef typename PointCloud::Ptr PointCloudPtr;
00072 typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00073
00075 ConcaveHull () : alpha_ (0), keep_information_ (false), voronoi_centers_ (), dim_(0)
00076 {
00077 };
00078
00080 virtual ~ConcaveHull () {}
00081
00088 void
00089 reconstruct (PointCloud &points,
00090 std::vector<pcl::Vertices> &polygons);
00091
00095 void
00096 reconstruct (PointCloud &output);
00097
00104 inline void
00105 setAlpha (double alpha)
00106 {
00107 alpha_ = alpha;
00108 }
00109
00111 inline double
00112 getAlpha ()
00113 {
00114 return (alpha_);
00115 }
00116
00120 inline void
00121 setVoronoiCenters (PointCloudPtr voronoi_centers)
00122 {
00123 voronoi_centers_ = voronoi_centers;
00124 }
00125
00130 void
00131 setKeepInformation (bool value)
00132 {
00133 keep_information_ = value;
00134 }
00135
00137 PCL_DEPRECATED (int getDim () const, "[pcl::ConcaveHull::getDim] This method is deprecated. Please use getDimension () instead.");
00138
00140 inline int
00141 getDimension () const
00142 {
00143 return (dim_);
00144 }
00145
00149 void
00150 setDimension (int dimension)
00151 {
00152 if ((dimension == 2) || (dimension == 3))
00153 dim_ = dimension;
00154 else
00155 PCL_ERROR ("[pcl::%s::setDimension] Invalid input dimension specified!\n", getClassName ().c_str ());
00156 }
00157
00158 protected:
00160 std::string
00161 getClassName () const
00162 {
00163 return ("ConcaveHull");
00164 }
00165
00166 protected:
00173 void
00174 performReconstruction (PointCloud &points,
00175 std::vector<pcl::Vertices> &polygons);
00176
00177 virtual void
00178 performReconstruction (PolygonMesh &output);
00179
00180 virtual void
00181 performReconstruction (std::vector<pcl::Vertices> &polygons);
00182
00186 double alpha_;
00187
00191 bool keep_information_;
00192
00194 PointCloudPtr voronoi_centers_;
00195
00197 int dim_;
00198 };
00199 }
00200
00201 #ifdef PCL_NO_PRECOMPILE
00202 #include <pcl/surface/impl/concave_hull.hpp>
00203 #endif
00204
00205 #endif //#ifndef PCL_CONCAVE_HULL
00206 #endif