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_CONVEX_HULL_2D_H_
00044 #define PCL_CONVEX_HULL_2D_H_
00045
00046
00047 #include <pcl/surface/reconstruction.h>
00048 #include <pcl/ModelCoefficients.h>
00049 #include <pcl/PolygonMesh.h>
00050
00051 namespace pcl
00052 {
00058 inline bool
00059 comparePoints2D (const std::pair<int, Eigen::Vector4f> & p1, const std::pair<int, Eigen::Vector4f> & p2)
00060 {
00061 double angle1 = atan2 (p1.second[1], p1.second[0]) + M_PI;
00062 double angle2 = atan2 (p2.second[1], p2.second[0]) + M_PI;
00063 return (angle1 > angle2);
00064 }
00065
00067
00071 template<typename PointInT>
00072 class ConvexHull : public MeshConstruction<PointInT>
00073 {
00074 protected:
00075 using PCLBase<PointInT>::input_;
00076 using PCLBase<PointInT>::indices_;
00077 using PCLBase<PointInT>::initCompute;
00078 using PCLBase<PointInT>::deinitCompute;
00079
00080 public:
00081 typedef boost::shared_ptr<ConvexHull<PointInT> > Ptr;
00082 typedef boost::shared_ptr<const ConvexHull<PointInT> > ConstPtr;
00083
00084 using MeshConstruction<PointInT>::reconstruct;
00085
00086 typedef pcl::PointCloud<PointInT> PointCloud;
00087 typedef typename PointCloud::Ptr PointCloudPtr;
00088 typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00089
00091 ConvexHull () : compute_area_ (false), total_area_ (0), total_volume_ (0), dimension_ (0),
00092 projection_angle_thresh_ (cos (0.174532925) ), qhull_flags ("qhull "),
00093 x_axis_ (1.0, 0.0, 0.0), y_axis_ (0.0, 1.0, 0.0), z_axis_ (0.0, 0.0, 1.0)
00094 {
00095 };
00096
00098 virtual ~ConvexHull () {}
00099
00110 void
00111 reconstruct (PointCloud &points,
00112 std::vector<pcl::Vertices> &polygons);
00113
00117 void
00118 reconstruct (PointCloud &points);
00119
00124 void
00125 setComputeAreaVolume (bool value)
00126 {
00127 compute_area_ = value;
00128 if (compute_area_)
00129 qhull_flags = std::string ("qhull FA");
00130 else
00131 qhull_flags = std::string ("qhull ");
00132 }
00133
00135 double
00136 getTotalArea () const
00137 {
00138 return (total_area_);
00139 }
00140
00144 double
00145 getTotalVolume () const
00146 {
00147 return (total_volume_);
00148 }
00149
00153 void
00154 setDimension (int dimension)
00155 {
00156 if ((dimension == 2) || (dimension == 3))
00157 dimension_ = dimension;
00158 else
00159 PCL_ERROR ("[pcl::%s::setDimension] Invalid input dimension specified!\n", getClassName ().c_str ());
00160 }
00161
00163 inline int
00164 getDimension () const
00165 {
00166 return (dimension_);
00167 }
00168
00169 protected:
00177 void
00178 performReconstruction (PointCloud &points,
00179 std::vector<pcl::Vertices> &polygons,
00180 bool fill_polygon_data = false);
00181
00189 void
00190 performReconstruction2D (PointCloud &points,
00191 std::vector<pcl::Vertices> &polygons,
00192 bool fill_polygon_data = false);
00193
00201 void
00202 performReconstruction3D (PointCloud &points,
00203 std::vector<pcl::Vertices> &polygons,
00204 bool fill_polygon_data = false);
00205
00210 virtual void
00211 performReconstruction (PolygonMesh &output);
00212
00217 virtual void
00218 performReconstruction (std::vector<pcl::Vertices> &polygons);
00219
00221 void
00222 calculateInputDimension ();
00223
00225 std::string
00226 getClassName () const
00227 {
00228 return ("ConvexHull");
00229 }
00230
00231
00232 bool compute_area_;
00233
00234
00235 double total_area_;
00236
00237
00238 double total_volume_;
00239
00241 int dimension_;
00242
00244 double projection_angle_thresh_;
00245
00247 std::string qhull_flags;
00248
00249
00250 const Eigen::Vector3d x_axis_;
00251
00252
00253 const Eigen::Vector3d y_axis_;
00254
00255
00256 const Eigen::Vector3d z_axis_;
00257
00258 public:
00259 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00260 };
00261 }
00262
00263 #ifdef PCL_NO_PRECOMPILE
00264 #include <pcl/surface/impl/convex_hull.hpp>
00265 #endif
00266
00267 #endif //#ifndef PCL_CONVEX_HULL_2D_H_
00268 #endif