Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
pcl::ExtractPolygonalPrismData< PointT > Class Template Reference

ExtractPolygonalPrismData uses a set of point indices that represent a planar model, and together with a given height, generates a 3D polygonal prism. The polygonal prism is then used to segment all points lying inside it. More...

#include <extract_polygonal_prism_data.h>

Inheritance diagram for pcl::ExtractPolygonalPrismData< PointT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef pcl::PointCloud< PointTPointCloud
typedef PointCloud::ConstPtr PointCloudConstPtr
typedef PointCloud::Ptr PointCloudPtr
typedef PointIndices::ConstPtr PointIndicesConstPtr
typedef PointIndices::Ptr PointIndicesPtr

Public Member Functions

 ExtractPolygonalPrismData ()
 Empty constructor.
void getHeightLimits (double &height_min, double &height_max) const
 Get the height limits (min/max) as set by the user. The default values are -FLT_MAX, FLT_MAX.
PointCloudConstPtr getInputPlanarHull () const
 Get a pointer the input planar hull dataset.
void getViewPoint (float &vpx, float &vpy, float &vpz) const
 Get the viewpoint.
void segment (PointIndices &output)
 Cluster extraction in a PointCloud given by <setInputCloud (), setIndices ()>
void setHeightLimits (double height_min, double height_max)
 Set the height limits. All points having distances to the model outside this interval will be discarded.
void setInputPlanarHull (const PointCloudConstPtr &hull)
 Provide a pointer to the input planar hull dataset.
void setViewPoint (float vpx, float vpy, float vpz)
 Set the viewpoint.

Protected Member Functions

virtual std::string getClassName () const
 Class getName method.

Protected Attributes

double height_limit_max_
 The maximum allowed height (distance to the model) a point will be considered from.
double height_limit_min_
 The minimum allowed height (distance to the model) a point will be considered from.
int min_pts_hull_
 The minimum number of points needed on the convex hull.
PointCloudConstPtr planar_hull_
 A pointer to the input planar hull dataset.
float vpx_
 Values describing the data acquisition viewpoint. Default: 0,0,0.
float vpy_
float vpz_

Detailed Description

template<typename PointT>
class pcl::ExtractPolygonalPrismData< PointT >

ExtractPolygonalPrismData uses a set of point indices that represent a planar model, and together with a given height, generates a 3D polygonal prism. The polygonal prism is then used to segment all points lying inside it.

An example of its usage is to extract the data lying within a set of 3D boundaries (e.g., objects supported by a plane).

Example usage:

 {.cpp}
 double z_min = 0., z_max = 0.05; // we want the points above the plane, no farther than 5 cm from the surface
 pcl::PointCloud<pcl::PointXYZ>::Ptr hull_points (new pcl::PointCloud<pcl::PointXYZ> ());
 pcl::ConvexHull<pcl::PointXYZ> hull;
 // hull.setDimension (2); // not necessarily needed, but we need to check the dimensionality of the output
 hull.setInputCloud (cloud);
 hull.reconstruct (hull_points);
 if (hull.getDimension () == 2)
 {
   pcl::ExtractPolygonalPrismData<pcl::PointXYZ> prism;
   prism.setInputCloud (point_cloud);
   prism.setInputPlanarHull (hull_points);
   prism.setHeightLimits (z_min, z_max);
   prism.segment (cloud_indices);
 }
 else
  PCL_ERROR ("The input cloud does not represent a planar surface.\n");
Author:
Radu Bogdan Rusu

Definition at line 102 of file extract_polygonal_prism_data.h.


Member Typedef Documentation

template<typename PointT>
typedef pcl::PointCloud<PointT> pcl::ExtractPolygonalPrismData< PointT >::PointCloud

Reimplemented from pcl::PCLBase< PointT >.

Definition at line 110 of file extract_polygonal_prism_data.h.

Reimplemented from pcl::PCLBase< PointT >.

Definition at line 112 of file extract_polygonal_prism_data.h.

template<typename PointT>
typedef PointCloud::Ptr pcl::ExtractPolygonalPrismData< PointT >::PointCloudPtr

Reimplemented from pcl::PCLBase< PointT >.

Definition at line 111 of file extract_polygonal_prism_data.h.

Reimplemented from pcl::PCLBase< PointT >.

Definition at line 115 of file extract_polygonal_prism_data.h.

Reimplemented from pcl::PCLBase< PointT >.

Definition at line 114 of file extract_polygonal_prism_data.h.


Constructor & Destructor Documentation

template<typename PointT>
pcl::ExtractPolygonalPrismData< PointT >::ExtractPolygonalPrismData ( ) [inline]

Empty constructor.

Definition at line 118 of file extract_polygonal_prism_data.h.


Member Function Documentation

template<typename PointT>
virtual std::string pcl::ExtractPolygonalPrismData< PointT >::getClassName ( ) const [inline, protected, virtual]

Class getName method.

Definition at line 209 of file extract_polygonal_prism_data.h.

template<typename PointT>
void pcl::ExtractPolygonalPrismData< PointT >::getHeightLimits ( double &  height_min,
double &  height_max 
) const [inline]

Get the height limits (min/max) as set by the user. The default values are -FLT_MAX, FLT_MAX.

Parameters:
[out]height_minthe resultant min height limit
[out]height_maxthe resultant max height limit

Definition at line 153 of file extract_polygonal_prism_data.h.

template<typename PointT>
PointCloudConstPtr pcl::ExtractPolygonalPrismData< PointT >::getInputPlanarHull ( ) const [inline]

Get a pointer the input planar hull dataset.

Definition at line 132 of file extract_polygonal_prism_data.h.

template<typename PointT>
void pcl::ExtractPolygonalPrismData< PointT >::getViewPoint ( float &  vpx,
float &  vpy,
float &  vpz 
) const [inline]

Get the viewpoint.

Definition at line 174 of file extract_polygonal_prism_data.h.

template<typename PointT >
void pcl::ExtractPolygonalPrismData< PointT >::segment ( pcl::PointIndices output)

Cluster extraction in a PointCloud given by <setInputCloud (), setIndices ()>

Parameters:
[out]outputthe resultant point indices that support the model found (inliers)

Definition at line 170 of file extract_polygonal_prism_data.hpp.

template<typename PointT>
void pcl::ExtractPolygonalPrismData< PointT >::setHeightLimits ( double  height_min,
double  height_max 
) [inline]

Set the height limits. All points having distances to the model outside this interval will be discarded.

Parameters:
[in]height_minthe minimum allowed distance to the plane model value
[in]height_maxthe maximum allowed distance to the plane model value

Definition at line 141 of file extract_polygonal_prism_data.h.

template<typename PointT>
void pcl::ExtractPolygonalPrismData< PointT >::setInputPlanarHull ( const PointCloudConstPtr hull) [inline]

Provide a pointer to the input planar hull dataset.

Note:
Please see the example in the class description for how to obtain this.
Parameters:
[in]hullthe input planar hull dataset

Definition at line 128 of file extract_polygonal_prism_data.h.

template<typename PointT>
void pcl::ExtractPolygonalPrismData< PointT >::setViewPoint ( float  vpx,
float  vpy,
float  vpz 
) [inline]

Set the viewpoint.

Parameters:
[in]vpxthe X coordinate of the viewpoint
[in]vpythe Y coordinate of the viewpoint
[in]vpzthe Z coordinate of the viewpoint

Definition at line 165 of file extract_polygonal_prism_data.h.


Member Data Documentation

template<typename PointT>
double pcl::ExtractPolygonalPrismData< PointT >::height_limit_max_ [protected]

The maximum allowed height (distance to the model) a point will be considered from.

Definition at line 202 of file extract_polygonal_prism_data.h.

template<typename PointT>
double pcl::ExtractPolygonalPrismData< PointT >::height_limit_min_ [protected]

The minimum allowed height (distance to the model) a point will be considered from.

Definition at line 197 of file extract_polygonal_prism_data.h.

template<typename PointT>
int pcl::ExtractPolygonalPrismData< PointT >::min_pts_hull_ [protected]

The minimum number of points needed on the convex hull.

Definition at line 192 of file extract_polygonal_prism_data.h.

template<typename PointT>
PointCloudConstPtr pcl::ExtractPolygonalPrismData< PointT >::planar_hull_ [protected]

A pointer to the input planar hull dataset.

Definition at line 189 of file extract_polygonal_prism_data.h.

template<typename PointT>
float pcl::ExtractPolygonalPrismData< PointT >::vpx_ [protected]

Values describing the data acquisition viewpoint. Default: 0,0,0.

Definition at line 205 of file extract_polygonal_prism_data.h.

template<typename PointT>
float pcl::ExtractPolygonalPrismData< PointT >::vpy_ [protected]

Definition at line 205 of file extract_polygonal_prism_data.h.

template<typename PointT>
float pcl::ExtractPolygonalPrismData< PointT >::vpz_ [protected]

Definition at line 205 of file extract_polygonal_prism_data.h.


The documentation for this class was generated from the following files:


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:40:33