TableObjectDetector Class Reference

List of all members.

Public Member Functions

void input_callback (const sensor_msgs::PointCloud2ConstPtr &cloud2_in)
 TableObjectDetector ()

Public Attributes

pcl::PointCloud< Point >::ConstPtr cloud_
pcl::PointCloud< Point >::ConstPtr cloud_downsampled_
pcl::PointCloud< Point >::ConstPtr cloud_filtered_
pcl::PointCloud< pcl::Normal >
::ConstPtr 
cloud_normals_
pcl::PointCloud< Point >::ConstPtr cloud_objects_
pcl::PointCloud< Point >::ConstPtr cloud_objects_downsampled_
ros::Publisher cloud_pub_
ros::Subscriber cloud_sub_
pcl::EuclideanClusterExtraction
< Point
cluster_
KdTreePtr clusters_tree_
double downsample_leaf_
double downsample_leaf_objects_
pcl::VoxelGrid< Pointgrid_
pcl::VoxelGrid< Pointgrid_objects_
pcl::ConvexHull< Pointhull_
int k_
double max_z_bounds_
double min_z_bounds_
pcl::NormalEstimation< Point,
pcl::Normal > 
n3d_
ros::NodeHandle nh_
double normal_distance_weight_
KdTreePtr normals_tree_
double object_cluster_min_size_
double object_cluster_tolerance_
double object_max_height_
double object_min_height_
pcl::PassThrough< Pointpass_
pcl::ExtractPolygonalPrismData
< Point
prism_
pcl::ProjectInliers< Pointproj_
double sac_distance_threshold_
pcl::SACSegmentationFromNormals
< Point, pcl::Normal > 
seg_
pcl::ModelCoefficients::ConstPtr table_coefficients_
pcl::PointCloud< Point >::ConstPtr table_hull_
pcl::PointIndices::ConstPtr table_inliers_
pcl::PointCloud< Point >::ConstPtr table_projected_

Private Types

typedef pcl::KdTree< Point >::Ptr KdTreePtr
typedef pcl::PointXYZRGB Point

Detailed Description

Author:
Radu Bogdan Rusu

table_object_detector detects tables and objects.

Definition at line 80 of file table_object_detector.cpp.


Member Typedef Documentation

typedef pcl::KdTree<Point>::Ptr TableObjectDetector::KdTreePtr [private]

Definition at line 69 of file table_object_detector.cpp.

typedef pcl::PointXYZRGB TableObjectDetector::Point [private]

Definition at line 68 of file table_object_detector.cpp.


Constructor & Destructor Documentation

TableObjectDetector::TableObjectDetector (  )  [inline]

Definition at line 120 of file table_object_detector.cpp.


Member Function Documentation

void TableObjectDetector::input_callback ( const sensor_msgs::PointCloud2ConstPtr &  cloud2_in  )  [inline]

Definition at line 205 of file table_object_detector.cpp.


Member Data Documentation

Definition at line 103 of file table_object_detector.cpp.

Definition at line 105 of file table_object_detector.cpp.

Definition at line 105 of file table_object_detector.cpp.

Definition at line 107 of file table_object_detector.cpp.

Definition at line 117 of file table_object_detector.cpp.

Definition at line 117 of file table_object_detector.cpp.

Definition at line 75 of file table_object_detector.cpp.

Definition at line 74 of file table_object_detector.cpp.

pcl::EuclideanClusterExtraction<Point> TableObjectDetector::cluster_

Definition at line 86 of file table_object_detector.cpp.

Definition at line 78 of file table_object_detector.cpp.

Definition at line 90 of file table_object_detector.cpp.

Definition at line 90 of file table_object_detector.cpp.

Definition at line 80 of file table_object_detector.cpp.

Definition at line 80 of file table_object_detector.cpp.

Definition at line 84 of file table_object_detector.cpp.

Definition at line 91 of file table_object_detector.cpp.

Definition at line 92 of file table_object_detector.cpp.

Definition at line 92 of file table_object_detector.cpp.

pcl::NormalEstimation<Point, pcl::Normal> TableObjectDetector::n3d_

Definition at line 81 of file table_object_detector.cpp.

ros::NodeHandle TableObjectDetector::nh_

Definition at line 72 of file table_object_detector.cpp.

Definition at line 94 of file table_object_detector.cpp.

Definition at line 78 of file table_object_detector.cpp.

Definition at line 100 of file table_object_detector.cpp.

Definition at line 100 of file table_object_detector.cpp.

Definition at line 97 of file table_object_detector.cpp.

Definition at line 97 of file table_object_detector.cpp.

pcl::PassThrough<Point> TableObjectDetector::pass_

Definition at line 79 of file table_object_detector.cpp.

pcl::ExtractPolygonalPrismData<Point> TableObjectDetector::prism_

Definition at line 85 of file table_object_detector.cpp.

pcl::ProjectInliers<Point> TableObjectDetector::proj_

Definition at line 83 of file table_object_detector.cpp.

Definition at line 93 of file table_object_detector.cpp.

pcl::SACSegmentationFromNormals<Point, pcl::Normal> TableObjectDetector::seg_

Definition at line 82 of file table_object_detector.cpp.

pcl::ModelCoefficients::ConstPtr TableObjectDetector::table_coefficients_

Definition at line 111 of file table_object_detector.cpp.

Definition at line 115 of file table_object_detector.cpp.

pcl::PointIndices::ConstPtr TableObjectDetector::table_inliers_

Definition at line 109 of file table_object_detector.cpp.

Definition at line 113 of file table_object_detector.cpp.


The documentation for this class was generated from the following file:
 All Classes Files Functions Variables Typedefs


pcl_tutorials
Author(s): Radu Bogdan Rusu, Bastian Steder
autogenerated on Fri Jan 11 09:13:01 2013