Public Types | Public Member Functions | Protected Attributes
TableObjectCluster< Point > Class Template Reference

#include <table_object_cluster.h>

List of all members.

Public Types

typedef pcl::PointCloud< Point >
::ConstPtr 
PointCloudConstPtr
typedef pcl::PointCloud< Point >
::Ptr 
PointCloudPtr

Public Member Functions

void calculateBoundingBox (const PointCloudPtr &cloud, const pcl::PointIndices &indices, const Eigen::Vector3f &plane_normal, const Eigen::Vector3f &plane_point, Eigen::Vector3f &position, Eigen::Quaternion< float > &orientation, Eigen::Vector3f &size)
void calculateBoundingBoxesOld (pcl::PointIndices::Ptr &pc_roi, std::vector< PointCloudPtr > &object_clusters, std::vector< pcl::PointCloud< pcl::PointXYZ > > &bounding_boxes)
 removes known objects by bounding box
void extractClusters (const pcl::PointIndices::Ptr &pc_roi, std::vector< PointCloudPtr > &object_clusters, std::vector< pcl::PointIndices > &object_cluster_indices)
void extractTableRoi (PointCloudPtr &hull, pcl::PointIndices &pc_roi)
 extracts objects at top of a plane
void extractTableRoi2 (const PointCloudConstPtr &pc_in, PointCloudPtr &hull, Eigen::Vector4f &plane_coeffs, pcl::PointCloud< Point > &pc_roi)
 extracts objects at top of a plane
void removeKnownObjects (const PointCloudConstPtr &pc_roi, std::vector< BoundingBox > &bounding_boxes, const PointCloudPtr &pc_roi_red)
 removes known objects by bounding box
void setClusterParams (int min_cluster_size, double cluster_tolerance)
 sets parameters for filtering
void setInputCloud (const PointCloudPtr &cloud)
void setPrismHeight (double height_min, double height_max)
 sets parameters for filtering
 TableObjectCluster ()
 ~TableObjectCluster ()

Protected Attributes

double cluster_tolerance_
 paramter for object detection
double height_max_
 paramter for object detection
double height_min_
PointCloudPtr input_
int min_cluster_size_
 paramter for object detection

Detailed Description

template<typename Point>
class TableObjectCluster< Point >

Definition at line 82 of file table_object_cluster.h.


Member Typedef Documentation

template<typename Point >
typedef pcl::PointCloud<Point>::ConstPtr TableObjectCluster< Point >::PointCloudConstPtr

Definition at line 87 of file table_object_cluster.h.

template<typename Point >
typedef pcl::PointCloud<Point>::Ptr TableObjectCluster< Point >::PointCloudPtr

Definition at line 86 of file table_object_cluster.h.


Constructor & Destructor Documentation

template<typename Point >
TableObjectCluster< Point >::TableObjectCluster ( ) [inline]

Definition at line 89 of file table_object_cluster.h.

template<typename Point >
TableObjectCluster< Point >::~TableObjectCluster ( ) [inline]

Definition at line 97 of file table_object_cluster.h.


Member Function Documentation

template<typename Point >
void TableObjectCluster< Point >::calculateBoundingBox ( const PointCloudPtr cloud,
const pcl::PointIndices &  indices,
const Eigen::Vector3f &  plane_normal,
const Eigen::Vector3f &  plane_point,
Eigen::Vector3f &  position,
Eigen::Quaternion< float > &  orientation,
Eigen::Vector3f &  size 
)

Definition at line 191 of file table_object_cluster.cpp.

template<typename Point >
void TableObjectCluster< Point >::calculateBoundingBoxesOld ( pcl::PointIndices::Ptr &  pc_roi,
std::vector< PointCloudPtr > &  object_clusters,
std::vector< pcl::PointCloud< pcl::PointXYZ > > &  bounding_boxes 
)

removes known objects by bounding box

removes known objects by bounding box

Parameters:
pc_roiinput point cloud with objects
bounding_boxesbounding boxes of known objects
pc_roi_redoutput point cloud without known objects
Returns:
nothing

Definition at line 311 of file table_object_cluster.cpp.

template<typename Point >
void TableObjectCluster< Point >::extractClusters ( const pcl::PointIndices::Ptr &  pc_roi,
std::vector< PointCloudPtr > &  object_clusters,
std::vector< pcl::PointIndices > &  object_cluster_indices 
)

Definition at line 277 of file table_object_cluster.cpp.

template<typename Point >
void TableObjectCluster< Point >::extractTableRoi ( PointCloudPtr hull,
pcl::PointIndices &  pc_roi 
)

extracts objects at top of a plane

extracts objects at top of a plane using a prism

Parameters:
pc_ininput point cloud
hullhull describing plane
pc_roioutput point cloud containing extracted objects
Returns:
nothing

Definition at line 90 of file table_object_cluster.cpp.

template<typename Point >
void TableObjectCluster< Point >::extractTableRoi2 ( const PointCloudConstPtr pc_in,
PointCloudPtr hull,
Eigen::Vector4f &  plane_coeffs,
pcl::PointCloud< Point > &  pc_roi 
)

extracts objects at top of a plane

extracts objects at top of a plane using distance

Parameters:
pc_ininput point cloud
hullhull describing plane
plane_coeffscoefficients describing plane
pc_roioutput point cloud containing extracted objects
Returns:
nothing

Definition at line 127 of file table_object_cluster.cpp.

template<typename Point >
void TableObjectCluster< Point >::removeKnownObjects ( const PointCloudConstPtr pc_roi,
std::vector< BoundingBox > &  bounding_boxes,
const PointCloudPtr pc_roi_red 
)

removes known objects by bounding box

removes known objects by bounding box

Parameters:
pc_roiinput point cloud with objects
bounding_boxesbounding boxes of known objects
pc_roi_redoutput point cloud without known objects
Returns:
nothing

Definition at line 167 of file table_object_cluster.cpp.

template<typename Point >
void TableObjectCluster< Point >::setClusterParams ( int  min_cluster_size,
double  cluster_tolerance 
) [inline]

sets parameters for filtering

sets parameters for filtering

Parameters:
min_cluster_size
cluster_tolerance
Returns:
nothing

Definition at line 211 of file table_object_cluster.h.

template<typename Point >
void TableObjectCluster< Point >::setInputCloud ( const PointCloudPtr cloud) [inline]

Definition at line 181 of file table_object_cluster.h.

template<typename Point >
void TableObjectCluster< Point >::setPrismHeight ( double  height_min,
double  height_max 
) [inline]

sets parameters for filtering

sets parameters for filtering

Parameters:
height_min
height_max
Returns:
nothing

Definition at line 194 of file table_object_cluster.h.


Member Data Documentation

template<typename Point >
double TableObjectCluster< Point >::cluster_tolerance_ [protected]

paramter for object detection

Definition at line 222 of file table_object_cluster.h.

template<typename Point >
double TableObjectCluster< Point >::height_max_ [protected]

paramter for object detection

Definition at line 220 of file table_object_cluster.h.

template<typename Point >
double TableObjectCluster< Point >::height_min_ [protected]

Definition at line 219 of file table_object_cluster.h.

template<typename Point >
PointCloudPtr TableObjectCluster< Point >::input_ [protected]

Definition at line 218 of file table_object_cluster.h.

template<typename Point >
int TableObjectCluster< Point >::min_cluster_size_ [protected]

paramter for object detection

Definition at line 221 of file table_object_cluster.h.


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


cob_table_object_cluster
Author(s): Georg Arbeiter
autogenerated on Wed Aug 26 2015 11:05:13