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 using MeshConstruction<PointInT>::reconstruct;
00082
00083 typedef pcl::PointCloud<PointInT> PointCloud;
00084 typedef typename PointCloud::Ptr PointCloudPtr;
00085 typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00086
00088 ConvexHull () : compute_area_ (false), total_area_ (0), total_volume_ (0), dimension_ (0),
00089 projection_angle_thresh_ (cos (0.174532925) ), qhull_flags ("qhull "),
00090 x_axis_ (1.0, 0.0, 0.0), y_axis_ (0.0, 1.0, 0.0), z_axis_ (0.0, 0.0, 1.0)
00091 {
00092 };
00093
00100 void
00101 reconstruct (PointCloud &points,
00102 std::vector<pcl::Vertices> &polygons);
00103
00107 void
00108 reconstruct (PointCloud &output);
00109
00114 void
00115 setComputeAreaVolume (bool value)
00116 {
00117 compute_area_ = value;
00118 if (compute_area_)
00119 qhull_flags = std::string ("qhull FA");
00120 else
00121 qhull_flags = std::string ("qhull ");
00122 }
00123
00125 double
00126 getTotalArea () const
00127 {
00128 return (total_area_);
00129 }
00130
00134 double
00135 getTotalVolume () const
00136 {
00137 return (total_volume_);
00138 }
00139
00143 void
00144 setDimension (int dimension)
00145 {
00146 if ((dimension == 2) || (dimension == 3))
00147 dimension_ = dimension;
00148 else
00149 PCL_ERROR ("[pcl::%s::setDimension] Invalid input dimension specified!\n", getClassName ().c_str ());
00150 }
00151
00153 inline int
00154 getDimension () const
00155 {
00156 return (dimension_);
00157 }
00158
00159 protected:
00167 void
00168 performReconstruction (PointCloud &points,
00169 std::vector<pcl::Vertices> &polygons,
00170 bool fill_polygon_data = false);
00171
00179 void
00180 performReconstruction2D (PointCloud &points,
00181 std::vector<pcl::Vertices> &polygons,
00182 bool fill_polygon_data = false);
00183
00191 void
00192 performReconstruction3D (PointCloud &points,
00193 std::vector<pcl::Vertices> &polygons,
00194 bool fill_polygon_data = false);
00195
00200 virtual void
00201 performReconstruction (PolygonMesh &output);
00202
00207 virtual void
00208 performReconstruction (std::vector<pcl::Vertices> &polygons);
00209
00211 void
00212 calculateInputDimension ();
00213
00215 std::string
00216 getClassName () const
00217 {
00218 return ("ConvexHull");
00219 }
00220
00221
00222 bool compute_area_;
00223
00224
00225 double total_area_;
00226
00227
00228 double total_volume_;
00229
00231 int dimension_;
00232
00234 double projection_angle_thresh_;
00235
00237 std::string qhull_flags;
00238
00239
00240 const Eigen::Vector3f x_axis_;
00241
00242
00243 const Eigen::Vector3f y_axis_;
00244
00245
00246 const Eigen::Vector3f z_axis_;
00247
00248 public:
00249 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00250 };
00251 }
00252
00253 #endif //#ifndef PCL_CONVEX_HULL_2D_H_
00254 #endif