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 #ifndef PCL_FILTERS_CROP_HULL_H_
00039 #define PCL_FILTERS_CROP_HULL_H_
00040
00041 #include <pcl/point_types.h>
00042 #include <pcl/Vertices.h>
00043 #include <pcl/filters/filter_indices.h>
00044
00045 namespace pcl
00046 {
00052 template<typename PointT>
00053 class CropHull: public FilterIndices<PointT>
00054 {
00055 using Filter<PointT>::filter_name_;
00056 using Filter<PointT>::indices_;
00057 using Filter<PointT>::input_;
00058
00059 typedef typename Filter<PointT>::PointCloud PointCloud;
00060 typedef typename PointCloud::Ptr PointCloudPtr;
00061 typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00062
00063 public:
00064
00065 typedef boost::shared_ptr< CropHull<PointT> > Ptr;
00066 typedef boost::shared_ptr< const CropHull<PointT> > ConstPtr;
00067
00069 CropHull () :
00070 hull_polygons_(),
00071 hull_cloud_(),
00072 dim_(3),
00073 crop_outside_(true)
00074 {
00075 filter_name_ = "CropHull";
00076 }
00077
00082 inline void
00083 setHullIndices (const std::vector<Vertices>& polygons)
00084 {
00085 hull_polygons_ = polygons;
00086 }
00087
00090 std::vector<Vertices>
00091 getHullIndices () const
00092 {
00093 return (hull_polygons_);
00094 }
00095
00099 inline void
00100 setHullCloud (PointCloudPtr points)
00101 {
00102 hull_cloud_ = points;
00103 }
00104
00106 PointCloudPtr
00107 getHullCloud () const
00108 {
00109 return (hull_cloud_);
00110 }
00111
00118 inline void
00119 setDim (int dim)
00120 {
00121 dim_ = dim;
00122 }
00123
00128 inline void
00129 setCropOutside(bool crop_outside)
00130 {
00131 crop_outside_ = crop_outside;
00132 }
00133
00134 protected:
00138 void
00139 applyFilter (PointCloud &output);
00140
00144 void
00145 applyFilter (std::vector<int> &indices);
00146
00147 private:
00152 Eigen::Vector3f
00153 getHullCloudRange ();
00154
00161 template<unsigned PlaneDim1, unsigned PlaneDim2> void
00162 applyFilter2D (PointCloud &output);
00163
00171 template<unsigned PlaneDim1, unsigned PlaneDim2> void
00172 applyFilter2D (std::vector<int> &indices);
00173
00182 void
00183 applyFilter3D (PointCloud &output);
00184
00193 void
00194 applyFilter3D (std::vector<int> &indices);
00195
00202 template<unsigned PlaneDim1, unsigned PlaneDim2> inline static bool
00203 isPointIn2DPolyWithVertIndices (const PointT& point,
00204 const Vertices& verts,
00205 const PointCloud& cloud);
00206
00215 inline static bool
00216 rayTriangleIntersect (const PointT& point,
00217 const Eigen::Vector3f& ray,
00218 const Vertices& verts,
00219 const PointCloud& cloud);
00220
00221
00223 std::vector<pcl::Vertices> hull_polygons_;
00224
00226 PointCloudPtr hull_cloud_;
00227
00229 int dim_;
00230
00234 bool crop_outside_;
00235 };
00236
00237 }
00238
00239 #ifdef PCL_NO_PRECOMPILE
00240 #include <pcl/filters/impl/crop_hull.hpp>
00241 #endif
00242
00243 #endif // ifndef PCL_FILTERS_CROP_HULL_H_