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
00101 template <typename PointT>
00102 class ExtractPolygonalPrismData : public PCLBase<PointT>
00103 {
00104 using PCLBase<PointT>::input_;
00105 using PCLBase<PointT>::indices_;
00106 using PCLBase<PointT>::initCompute;
00107 using PCLBase<PointT>::deinitCompute;
00108
00109 public:
00110 typedef pcl::PointCloud<PointT> PointCloud;
00111 typedef typename PointCloud::Ptr PointCloudPtr;
00112 typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00113
00114 typedef PointIndices::Ptr PointIndicesPtr;
00115 typedef PointIndices::ConstPtr PointIndicesConstPtr;
00116
00118 ExtractPolygonalPrismData () : planar_hull_ (), min_pts_hull_ (3),
00119 height_limit_min_ (0), height_limit_max_ (FLT_MAX),
00120 vpx_ (0), vpy_ (0), vpz_ (0)
00121 {};
00122
00127 inline void
00128 setInputPlanarHull (const PointCloudConstPtr &hull) { planar_hull_ = hull; }
00129
00131 inline PointCloudConstPtr
00132 getInputPlanarHull () const { return (planar_hull_); }
00133
00140 inline void
00141 setHeightLimits (double height_min, double height_max)
00142 {
00143 height_limit_min_ = height_min;
00144 height_limit_max_ = height_max;
00145 }
00146
00152 inline void
00153 getHeightLimits (double &height_min, double &height_max) const
00154 {
00155 height_min = height_limit_min_;
00156 height_max = height_limit_max_;
00157 }
00158
00164 inline void
00165 setViewPoint (float vpx, float vpy, float vpz)
00166 {
00167 vpx_ = vpx;
00168 vpy_ = vpy;
00169 vpz_ = vpz;
00170 }
00171
00173 inline void
00174 getViewPoint (float &vpx, float &vpy, float &vpz) const
00175 {
00176 vpx = vpx_;
00177 vpy = vpy_;
00178 vpz = vpz_;
00179 }
00180
00184 void
00185 segment (PointIndices &output);
00186
00187 protected:
00189 PointCloudConstPtr planar_hull_;
00190
00192 int min_pts_hull_;
00193
00197 double height_limit_min_;
00198
00202 double height_limit_max_;
00203
00205 float vpx_, vpy_, vpz_;
00206
00208 virtual std::string
00209 getClassName () const { return ("ExtractPolygonalPrismData"); }
00210 };
00211 }
00212
00213 #ifdef PCL_NO_PRECOMPILE
00214 #include <pcl/segmentation/impl/extract_polygonal_prism_data.hpp>
00215 #endif
00216
00217 #endif //#ifndef PCL_EXTRACT_POLYGONAL_PRISM_DATA_H_