Public Types | Public Member Functions | Private Member Functions | Private Attributes
pcl::apps::DominantPlaneSegmentation< PointType > Class Template Reference

DominantPlaneSegmentation performs euclidean segmentation on a scene assuming that a dominant plane exists. More...

#include <dominant_plane_segmentation.h>

List of all members.

Public Types

typedef pcl::PointCloud
< PointType
Cloud
typedef Cloud::ConstPtr CloudConstPtr
typedef Cloud::Ptr CloudPtr
typedef pcl::search::KdTree
< PointType >::Ptr 
KdTreePtr

Public Member Functions

void compute (std::vector< CloudPtr > &clusters)
void compute_fast (std::vector< CloudPtr > &clusters)
void compute_full (std::vector< CloudPtr > &clusters)
void compute_table_plane ()
 DominantPlaneSegmentation ()
void getIndicesClusters (std::vector< pcl::PointIndices > &indices)
void getTableCoefficients (Eigen::Vector4f &model)
void setDistanceBetweenClusters (float d)
void setDownsamplingSize (float d)
void setInputCloud (CloudPtr &cloud_in)
void setKNeighbors (int k)
void setMaxZBounds (double z)
void setMinClusterSize (int size)
void setMinZBounds (double z)
void setObjectMaxHeight (double h)
void setObjectMinHeight (double h)
void setSACThreshold (double d)
void setWSize (int w)

Private Member Functions

int check (pcl::PointXYZI &p1, pcl::PointXYZI &p2, float, float max_dist)

Private Attributes

pcl::ProjectInliers< PointTypebb_cluster_proj_
pcl::EuclideanClusterExtraction
< PointType
cluster_
float downsample_leaf_
 Downsampling resolution.
pcl::VoxelGrid< PointTypegrid_
pcl::ConvexHull< PointTypehull_
std::vector< pcl::PointIndices > indices_clusters_
 Indices of the clusters to the main cloud found by the segmentation.
CloudPtr input_
 Input cloud from which to extract clusters.
int k_
 Number of neighbors for normal estimation.
double max_z_bounds_
 Keep points closer than max_z_bounds.
double min_z_bounds_
 Keep points farther away than min_z_bounds.
pcl::NormalEstimation
< PointType, pcl::Normal
n3d_
int object_cluster_min_size_
 Minimum size for a cluster, clusters smaller than this won't be returned.
float object_cluster_tolerance_
 Tolerance between different clusters.
double object_max_height_
 Max height from the table plane.
double object_min_height_
 Min height from the table plane object points will be considered from.
pcl::PassThrough< PointTypepass_
pcl::ExtractPolygonalPrismData
< PointType
prism_
pcl::ProjectInliers< PointTypeproj_
double sac_distance_threshold_
 Threshold for SAC plane segmentation.
pcl::SACSegmentationFromNormals
< PointType, pcl::Normal
seg_
Eigen::Vector4f table_coeffs_
 Table coefficients (a,b,c,d)
int wsize_
 Window size in pixels for CC in compute_fast method.

Detailed Description

template<typename PointType>
class pcl::apps::DominantPlaneSegmentation< PointType >

DominantPlaneSegmentation performs euclidean segmentation on a scene assuming that a dominant plane exists.

Author:
Aitor Aldoma

Definition at line 66 of file dominant_plane_segmentation.h.


Member Typedef Documentation

Definition at line 69 of file dominant_plane_segmentation.h.

Definition at line 71 of file dominant_plane_segmentation.h.

template<typename PointType >
typedef Cloud::Ptr pcl::apps::DominantPlaneSegmentation< PointType >::CloudPtr

Definition at line 70 of file dominant_plane_segmentation.h.

Definition at line 72 of file dominant_plane_segmentation.h.


Constructor & Destructor Documentation

template<typename PointType >
pcl::apps::DominantPlaneSegmentation< PointType >::DominantPlaneSegmentation ( ) [inline]

Definition at line 74 of file dominant_plane_segmentation.h.


Member Function Documentation

template<typename PointType >
int pcl::apps::DominantPlaneSegmentation< PointType >::check ( pcl::PointXYZI p1,
pcl::PointXYZI p2,
float  ,
float  max_dist 
) [inline, private]

Definition at line 227 of file dominant_plane_segmentation.h.

template<typename PointType >
void pcl::apps::DominantPlaneSegmentation< PointType >::compute ( std::vector< CloudPtr > &  clusters)

Definition at line 534 of file dominant_plane_segmentation.hpp.

template<typename PointType >
void pcl::apps::DominantPlaneSegmentation< PointType >::compute_fast ( std::vector< CloudPtr > &  clusters)

Definition at line 157 of file dominant_plane_segmentation.hpp.

template<typename PointType >
void pcl::apps::DominantPlaneSegmentation< PointType >::compute_full ( std::vector< CloudPtr > &  clusters)

Definition at line 697 of file dominant_plane_segmentation.hpp.

template<typename PointType >
void pcl::apps::DominantPlaneSegmentation< PointType >::compute_table_plane ( )

Definition at line 45 of file dominant_plane_segmentation.hpp.

template<typename PointType >
void pcl::apps::DominantPlaneSegmentation< PointType >::getIndicesClusters ( std::vector< pcl::PointIndices > &  indices) [inline]

Definition at line 220 of file dominant_plane_segmentation.h.

template<typename PointType >
void pcl::apps::DominantPlaneSegmentation< PointType >::getTableCoefficients ( Eigen::Vector4f &  model) [inline]

Definition at line 128 of file dominant_plane_segmentation.h.

template<typename PointType >
void pcl::apps::DominantPlaneSegmentation< PointType >::setDistanceBetweenClusters ( float  d) [inline]

Definition at line 137 of file dominant_plane_segmentation.h.

template<typename PointType >
void pcl::apps::DominantPlaneSegmentation< PointType >::setDownsamplingSize ( float  d) [inline]

Definition at line 204 of file dominant_plane_segmentation.h.

template<typename PointType >
void pcl::apps::DominantPlaneSegmentation< PointType >::setInputCloud ( CloudPtr cloud_in) [inline]

Definition at line 119 of file dominant_plane_segmentation.h.

template<typename PointType >
void pcl::apps::DominantPlaneSegmentation< PointType >::setKNeighbors ( int  k) [inline]

Definition at line 189 of file dominant_plane_segmentation.h.

template<typename PointType >
void pcl::apps::DominantPlaneSegmentation< PointType >::setMaxZBounds ( double  z) [inline]

Definition at line 181 of file dominant_plane_segmentation.h.

template<typename PointType >
void pcl::apps::DominantPlaneSegmentation< PointType >::setMinClusterSize ( int  size) [inline]

Definition at line 146 of file dominant_plane_segmentation.h.

template<typename PointType >
void pcl::apps::DominantPlaneSegmentation< PointType >::setMinZBounds ( double  z) [inline]

Definition at line 173 of file dominant_plane_segmentation.h.

template<typename PointType >
void pcl::apps::DominantPlaneSegmentation< PointType >::setObjectMaxHeight ( double  h) [inline]

Definition at line 164 of file dominant_plane_segmentation.h.

template<typename PointType >
void pcl::apps::DominantPlaneSegmentation< PointType >::setObjectMinHeight ( double  h) [inline]

Definition at line 155 of file dominant_plane_segmentation.h.

template<typename PointType >
void pcl::apps::DominantPlaneSegmentation< PointType >::setSACThreshold ( double  d) [inline]

Definition at line 196 of file dominant_plane_segmentation.h.

template<typename PointType >
void pcl::apps::DominantPlaneSegmentation< PointType >::setWSize ( int  w) [inline]

Definition at line 212 of file dominant_plane_segmentation.h.


Member Data Documentation

Definition at line 250 of file dominant_plane_segmentation.h.

Definition at line 253 of file dominant_plane_segmentation.h.

template<typename PointType >
float pcl::apps::DominantPlaneSegmentation< PointType >::downsample_leaf_ [private]

Downsampling resolution.

Definition at line 260 of file dominant_plane_segmentation.h.

template<typename PointType >
pcl::VoxelGrid<PointType> pcl::apps::DominantPlaneSegmentation< PointType >::grid_ [private]

Definition at line 246 of file dominant_plane_segmentation.h.

template<typename PointType >
pcl::ConvexHull<PointType> pcl::apps::DominantPlaneSegmentation< PointType >::hull_ [private]

Definition at line 251 of file dominant_plane_segmentation.h.

template<typename PointType >
std::vector<pcl::PointIndices> pcl::apps::DominantPlaneSegmentation< PointType >::indices_clusters_ [private]

Indices of the clusters to the main cloud found by the segmentation.

Definition at line 280 of file dominant_plane_segmentation.h.

template<typename PointType >
CloudPtr pcl::apps::DominantPlaneSegmentation< PointType >::input_ [private]

Input cloud from which to extract clusters.

Definition at line 256 of file dominant_plane_segmentation.h.

template<typename PointType >
int pcl::apps::DominantPlaneSegmentation< PointType >::k_ [private]

Number of neighbors for normal estimation.

Definition at line 262 of file dominant_plane_segmentation.h.

template<typename PointType >
double pcl::apps::DominantPlaneSegmentation< PointType >::max_z_bounds_ [private]

Keep points closer than max_z_bounds.

Definition at line 266 of file dominant_plane_segmentation.h.

template<typename PointType >
double pcl::apps::DominantPlaneSegmentation< PointType >::min_z_bounds_ [private]

Keep points farther away than min_z_bounds.

Definition at line 264 of file dominant_plane_segmentation.h.

Definition at line 247 of file dominant_plane_segmentation.h.

template<typename PointType >
int pcl::apps::DominantPlaneSegmentation< PointType >::object_cluster_min_size_ [private]

Minimum size for a cluster, clusters smaller than this won't be returned.

Definition at line 276 of file dominant_plane_segmentation.h.

template<typename PointType >
float pcl::apps::DominantPlaneSegmentation< PointType >::object_cluster_tolerance_ [private]

Tolerance between different clusters.

Definition at line 274 of file dominant_plane_segmentation.h.

template<typename PointType >
double pcl::apps::DominantPlaneSegmentation< PointType >::object_max_height_ [private]

Max height from the table plane.

Definition at line 272 of file dominant_plane_segmentation.h.

template<typename PointType >
double pcl::apps::DominantPlaneSegmentation< PointType >::object_min_height_ [private]

Min height from the table plane object points will be considered from.

Definition at line 270 of file dominant_plane_segmentation.h.

template<typename PointType >
pcl::PassThrough<PointType> pcl::apps::DominantPlaneSegmentation< PointType >::pass_ [private]

Definition at line 245 of file dominant_plane_segmentation.h.

Definition at line 252 of file dominant_plane_segmentation.h.

Definition at line 249 of file dominant_plane_segmentation.h.

template<typename PointType >
double pcl::apps::DominantPlaneSegmentation< PointType >::sac_distance_threshold_ [private]

Threshold for SAC plane segmentation.

Definition at line 268 of file dominant_plane_segmentation.h.

Definition at line 248 of file dominant_plane_segmentation.h.

template<typename PointType >
Eigen::Vector4f pcl::apps::DominantPlaneSegmentation< PointType >::table_coeffs_ [private]

Table coefficients (a,b,c,d)

Definition at line 258 of file dominant_plane_segmentation.h.

template<typename PointType >
int pcl::apps::DominantPlaneSegmentation< PointType >::wsize_ [private]

Window size in pixels for CC in compute_fast method.

Definition at line 278 of file dominant_plane_segmentation.h.


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


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:20:18