Public Member Functions | Private Member Functions | Private Attributes
ExtractClusters Class Reference

List of all members.

Public Member Functions

void add_remove_padding_hull (pcl::PointCloud< Point > &hull_in, pcl::PointCloud< Point > &hull_out, double padding)
void executeCB (const pcl_cloud_tools::GetClustersGoalConstPtr &goal)
 ExtractClusters (const ros::NodeHandle &nh)
void init (double tolerance, std::string object_name)
virtual ~ExtractClusters ()

Private Member Functions

void clustersCallback (const sensor_msgs::PointCloud2ConstPtr &cloud_in)
double compute2DPolygonalArea (PointCloud &points, const std::vector< double > &normal)
 Compute the area of a 2D planar polygon patch - using a given normal.
std::string getName () const
 Get a string representation of the name of this class.

Private Attributes

bool action_called_
std::string action_name_
actionlib::SimpleActionServer
< pcl_cloud_tools::GetClustersAction > 
as_
double base_link_head_tilt_link_angle_
pcl::ConvexHull< Pointchull_
pcl::PointCloud< pcl::Normal >
::ConstPtr 
cloud_normals_
std::vector< pcl::PointCloud
< Point > > 
cloud_object_clustered_array_
pcl::PointCloud< Pointcloud_objects_
pcl_ros::Publisher< Pointcloud_objects_pub_
pcl_ros::Publisher< Pointcloud_pub_
pcl::EuclideanClusterExtraction
< Point
cluster_
double cluster_max_height_
double cluster_min_height_
KdTreePtr clusters_tree_
bool downsample_
double eps_angle_
pcl::ExtractIndices< Pointextract_
pcl_cloud_tools::GetClustersFeedback feedback_
bool got_cluster_
int k_
int max_iter_
int min_table_inliers_
pcl::NormalEstimation< Point,
pcl::Normal > 
n3d_
ros::NodeHandle nh_
double normal_distance_weight_
double normal_search_radius_
KdTreePtr normals_tree_
int nr_cluster_
int object_cluster_max_size_
int object_cluster_min_size_
double object_cluster_tolerance_
std::string object_name_
double padding_
pcl::PCDWriter pcd_writer_
ros::Subscriber point_cloud_sub_
std::string point_cloud_topic
pcl::ExtractPolygonalPrismData
< Point
prism_
pcl::ProjectInliers< Pointproj_
bool publish_token_
pcl_cloud_tools::GetClustersResult result_
std::string rot_table_frame_
double sac_distance_
bool save_to_files_
pcl::SACSegmentationFromNormals
< Point, pcl::Normal > 
seg_
double seg_prob_
std::vector< Eigen::Vector4d * > table_coeffs_
tf::TransformListener tf_listener_
pcl_ros::Publisher< Pointtoken_pub_
tf::TransformBroadcaster transform_broadcaster_
pcl::VoxelGrid< Pointvgrid_
double voxel_size_
double z_max_limit_
double z_min_limit_

Detailed Description

Definition at line 86 of file extract_clusters_on_table.cpp.


Constructor & Destructor Documentation

Definition at line 90 of file extract_clusters_on_table.cpp.

virtual ExtractClusters::~ExtractClusters ( ) [inline, virtual]

Definition at line 153 of file extract_clusters_on_table.cpp.


Member Function Documentation

void ExtractClusters::add_remove_padding_hull ( pcl::PointCloud< Point > &  hull_in,
pcl::PointCloud< Point > &  hull_out,
double  padding 
) [inline]

Definition at line 167 of file extract_clusters_on_table.cpp.

void ExtractClusters::clustersCallback ( const sensor_msgs::PointCloud2ConstPtr &  cloud_in) [inline, private]

Definition at line 257 of file extract_clusters_on_table.cpp.

double ExtractClusters::compute2DPolygonalArea ( PointCloud points,
const std::vector< double > &  normal 
) [inline, private]

Compute the area of a 2D planar polygon patch - using a given normal.

Parameters:
pointsthe point cloud (planar)
normalthe plane normal

Definition at line 417 of file extract_clusters_on_table.cpp.

void ExtractClusters::executeCB ( const pcl_cloud_tools::GetClustersGoalConstPtr &  goal) [inline]

Definition at line 191 of file extract_clusters_on_table.cpp.

std::string ExtractClusters::getName ( void  ) const [inline, private]

Get a string representation of the name of this class.

Definition at line 491 of file extract_clusters_on_table.cpp.

void ExtractClusters::init ( double  tolerance,
std::string  object_name 
) [inline]

Definition at line 160 of file extract_clusters_on_table.cpp.


Member Data Documentation

Definition at line 449 of file extract_clusters_on_table.cpp.

Definition at line 495 of file extract_clusters_on_table.cpp.

actionlib::SimpleActionServer<pcl_cloud_tools::GetClustersAction> ExtractClusters::as_ [private]

Definition at line 494 of file extract_clusters_on_table.cpp.

Definition at line 461 of file extract_clusters_on_table.cpp.

pcl::ConvexHull<Point> ExtractClusters::chull_ [private]

Definition at line 482 of file extract_clusters_on_table.cpp.

pcl::PointCloud<pcl::Normal>::ConstPtr ExtractClusters::cloud_normals_ [private]

Definition at line 478 of file extract_clusters_on_table.cpp.

Definition at line 487 of file extract_clusters_on_table.cpp.

Definition at line 484 of file extract_clusters_on_table.cpp.

Definition at line 470 of file extract_clusters_on_table.cpp.

Definition at line 468 of file extract_clusters_on_table.cpp.

Definition at line 485 of file extract_clusters_on_table.cpp.

Definition at line 456 of file extract_clusters_on_table.cpp.

Definition at line 456 of file extract_clusters_on_table.cpp.

Definition at line 486 of file extract_clusters_on_table.cpp.

Definition at line 449 of file extract_clusters_on_table.cpp.

double ExtractClusters::eps_angle_ [private]

Definition at line 461 of file extract_clusters_on_table.cpp.

Definition at line 481 of file extract_clusters_on_table.cpp.

pcl_cloud_tools::GetClustersFeedback ExtractClusters::feedback_ [private]

Definition at line 497 of file extract_clusters_on_table.cpp.

Definition at line 449 of file extract_clusters_on_table.cpp.

Definition at line 462 of file extract_clusters_on_table.cpp.

Definition at line 462 of file extract_clusters_on_table.cpp.

Definition at line 462 of file extract_clusters_on_table.cpp.

Definition at line 476 of file extract_clusters_on_table.cpp.

Definition at line 446 of file extract_clusters_on_table.cpp.

Definition at line 460 of file extract_clusters_on_table.cpp.

Definition at line 451 of file extract_clusters_on_table.cpp.

Definition at line 486 of file extract_clusters_on_table.cpp.

Definition at line 462 of file extract_clusters_on_table.cpp.

Definition at line 457 of file extract_clusters_on_table.cpp.

Definition at line 457 of file extract_clusters_on_table.cpp.

Definition at line 456 of file extract_clusters_on_table.cpp.

Definition at line 455 of file extract_clusters_on_table.cpp.

double ExtractClusters::padding_ [private]

Definition at line 453 of file extract_clusters_on_table.cpp.

Definition at line 459 of file extract_clusters_on_table.cpp.

Definition at line 464 of file extract_clusters_on_table.cpp.

Definition at line 455 of file extract_clusters_on_table.cpp.

Definition at line 483 of file extract_clusters_on_table.cpp.

Definition at line 480 of file extract_clusters_on_table.cpp.

Definition at line 449 of file extract_clusters_on_table.cpp.

pcl_cloud_tools::GetClustersResult ExtractClusters::result_ [private]

Definition at line 498 of file extract_clusters_on_table.cpp.

Definition at line 455 of file extract_clusters_on_table.cpp.

Definition at line 460 of file extract_clusters_on_table.cpp.

Definition at line 449 of file extract_clusters_on_table.cpp.

Definition at line 479 of file extract_clusters_on_table.cpp.

double ExtractClusters::seg_prob_ [private]

Definition at line 461 of file extract_clusters_on_table.cpp.

std::vector<Eigen::Vector4d *> ExtractClusters::table_coeffs_ [private]

Definition at line 466 of file extract_clusters_on_table.cpp.

Definition at line 448 of file extract_clusters_on_table.cpp.

Definition at line 471 of file extract_clusters_on_table.cpp.

Definition at line 447 of file extract_clusters_on_table.cpp.

Definition at line 475 of file extract_clusters_on_table.cpp.

double ExtractClusters::voxel_size_ [private]

Definition at line 452 of file extract_clusters_on_table.cpp.

Definition at line 460 of file extract_clusters_on_table.cpp.

Definition at line 460 of file extract_clusters_on_table.cpp.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


pcl_cloud_tools
Author(s): Nico Blodow, Zoltan-Csaba Marton, Dejan Pangercic
autogenerated on Thu May 23 2013 17:11:36