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_EXTRACT_POLYGONAL_PRISM_DATA_H_
00039 #define PCL_EXTRACT_POLYGONAL_PRISM_DATA_H_
00040
00041 #include <pcl/pcl_base.h>
00042 #include <pcl/sample_consensus/sac_model_plane.h>
00043
00044 namespace pcl
00045 {
00054 template <typename PointT> bool
00055 isPointIn2DPolygon (const PointT &point, const pcl::PointCloud<PointT> &polygon);
00056
00067 template <typename PointT> bool
00068 isXYPointIn2DXYPolygon (const PointT &point, const pcl::PointCloud<PointT> &polygon);
00069
00071
00082 template <typename PointT>
00083 class ExtractPolygonalPrismData : public PCLBase<PointT>
00084 {
00085 using PCLBase<PointT>::input_;
00086 using PCLBase<PointT>::indices_;
00087 using PCLBase<PointT>::initCompute;
00088 using PCLBase<PointT>::deinitCompute;
00089
00090 public:
00091 typedef pcl::PointCloud<PointT> PointCloud;
00092 typedef typename PointCloud::Ptr PointCloudPtr;
00093 typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00094
00095 typedef PointIndices::Ptr PointIndicesPtr;
00096 typedef PointIndices::ConstPtr PointIndicesConstPtr;
00097
00099 ExtractPolygonalPrismData () : planar_hull_ (), min_pts_hull_ (3),
00100 height_limit_min_ (0), height_limit_max_ (FLT_MAX),
00101 vpx_ (0), vpy_ (0), vpz_ (0)
00102 {};
00103
00107 inline void
00108 setInputPlanarHull (const PointCloudConstPtr &hull) { planar_hull_ = hull; }
00109
00111 inline PointCloudConstPtr
00112 getInputPlanarHull () const { return (planar_hull_); }
00113
00120 inline void
00121 setHeightLimits (double height_min, double height_max)
00122 {
00123 height_limit_min_ = height_min;
00124 height_limit_max_ = height_max;
00125 }
00126
00132 inline void
00133 getHeightLimits (double &height_min, double &height_max) const
00134 {
00135 height_min = height_limit_min_;
00136 height_max = height_limit_max_;
00137 }
00138
00144 inline void
00145 setViewPoint (float vpx, float vpy, float vpz)
00146 {
00147 vpx_ = vpx;
00148 vpy_ = vpy;
00149 vpz_ = vpz;
00150 }
00151
00153 inline void
00154 getViewPoint (float &vpx, float &vpy, float &vpz) const
00155 {
00156 vpx = vpx_;
00157 vpy = vpy_;
00158 vpz = vpz_;
00159 }
00160
00164 void
00165 segment (PointIndices &output);
00166
00167 protected:
00169 PointCloudConstPtr planar_hull_;
00170
00172 int min_pts_hull_;
00173
00177 double height_limit_min_;
00178
00182 double height_limit_max_;
00183
00185 float vpx_, vpy_, vpz_;
00186
00188 virtual std::string
00189 getClassName () const { return ("ExtractPolygonalPrismData"); }
00190 };
00191 }
00192
00193 #endif //#ifndef PCL_EXTRACT_POLYGONAL_PRISM_DATA_H_