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

List of all members.

Public Member Functions

 DrawerHandlesDetector (const ros::NodeHandle &nh)
 DrawerHandlesDetector (const ros::NodeHandle &nh)
void init ()
virtual ~DrawerHandlesDetector ()
virtual ~DrawerHandlesDetector ()

Private Member Functions

void executeCB (const handle_detection::HandleDetectionGoalConstPtr &goal)
void getHandlePose (pcl::PointCloud< Point >::Ptr line_projected, pcl::ModelCoefficients::Ptr table_coeff, std::string &frame, geometry_msgs::PoseStamped &pose)
void getHandlePose (pcl::PointCloud< Point >::Ptr line_projected, pcl::ModelCoefficients::Ptr table_coeff, std::string &frame, geometry_msgs::PoseStamped &pose)
std::string getName () const
 Get a string representation of the name of this class.
std::string getName () const
 Get a string representation of the name of this class.
void ptuFinderCallback (const sensor_msgs::PointCloud2ConstPtr &cloud_in)

Private Attributes

actionlib::SimpleActionServer
< handle_detection::HandleDetectionAction > 
as_
pcl::ConvexHull< Pointchull_
pcl_ros::Publisher< Pointcloud_handle_pub_
pcl::PointCloud< pcl::Normal >
::ConstPtr 
cloud_normals_
pcl::PointCloud< Pointcloud_objects_
pcl_ros::Publisher< Pointcloud_pub_
pcl::EuclideanClusterExtraction
< Point
cluster_
double cluster_max_height_
double cluster_min_height_
KdTreePtr clusters_tree_
double eps_angle_
pcl::ExtractIndices< Pointextract_
pcl::EuclideanClusterExtraction
< Point
handle_cluster_
int handle_cluster_max_size_
int handle_cluster_min_size_
double handle_cluster_tolerance_
ros::Publisher handle_pose_pub_
std::string handle_pose_topic_
int k_
int max_iter_
int min_table_inliers_
pcl::NormalEstimation< Point,
pcl::Normal > 
n3d_
ros::NodeHandle nh_
double normal_distance_weight_
KdTreePtr normals_tree_
int nr_cluster_
int object_cluster_max_size_
int object_cluster_min_size_
double object_cluster_tolerance_
std::string output_handle_topic_
ros::Subscriber point_cloud_sub_
std::string point_cloud_topic_
pcl::ExtractPolygonalPrismData
< Point
prism_
pcl::ProjectInliers< Pointproj_
bool publish_largest_handle_pose_
handle_detection::HandleDetectionResult result_
double sac_distance_
pcl::SACSegmentationFromNormals
< Point, pcl::Normal > 
seg_
pcl::SACSegmentation< Pointseg_line_
double seg_prob_
pcl::VoxelGrid< Pointvgrid_
double voxel_size_
double x_max_limit_
double x_min_limit_
double y_max_limit_
double y_min_limit_
double z_max_limit_
double z_min_limit_

Detailed Description

Definition at line 85 of file drawer_cluster_detector.cpp.


Constructor & Destructor Documentation

Definition at line 89 of file drawer_cluster_detector.cpp.

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

Definition at line 165 of file drawer_cluster_detector.cpp.

Definition at line 91 of file drawer_handles_detector.cpp.

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

Definition at line 178 of file drawer_handles_detector.cpp.


Member Function Documentation

void DrawerHandlesDetector::executeCB ( const handle_detection::HandleDetectionGoalConstPtr &  goal) [inline, private]

Definition at line 183 of file drawer_handles_detector.cpp.

void DrawerHandlesDetector::getHandlePose ( pcl::PointCloud< Point >::Ptr  line_projected,
pcl::ModelCoefficients::Ptr  table_coeff,
std::string &  frame,
geometry_msgs::PoseStamped &  pose 
) [inline, private]

Definition at line 373 of file drawer_cluster_detector.cpp.

void DrawerHandlesDetector::getHandlePose ( pcl::PointCloud< Point >::Ptr  line_projected,
pcl::ModelCoefficients::Ptr  table_coeff,
std::string &  frame,
geometry_msgs::PoseStamped &  pose 
) [inline, private]

Definition at line 380 of file drawer_handles_detector.cpp.

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

Get a string representation of the name of this class.

Definition at line 459 of file drawer_cluster_detector.cpp.

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

Get a string representation of the name of this class.

Definition at line 474 of file drawer_handles_detector.cpp.

void DrawerHandlesDetector::init ( ) [inline]

Definition at line 171 of file drawer_cluster_detector.cpp.

void DrawerHandlesDetector::ptuFinderCallback ( const sensor_msgs::PointCloud2ConstPtr &  cloud_in) [inline, private]

Definition at line 181 of file drawer_cluster_detector.cpp.


Member Data Documentation

actionlib::SimpleActionServer<handle_detection::HandleDetectionAction> DrawerHandlesDetector::as_ [private]

Definition at line 469 of file drawer_handles_detector.cpp.

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

Definition at line 451 of file drawer_cluster_detector.cpp.

Definition at line 438 of file drawer_cluster_detector.cpp.

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

Definition at line 446 of file drawer_cluster_detector.cpp.

Definition at line 453 of file drawer_cluster_detector.cpp.

Definition at line 437 of file drawer_cluster_detector.cpp.

Definition at line 454 of file drawer_cluster_detector.cpp.

Definition at line 426 of file drawer_cluster_detector.cpp.

Definition at line 426 of file drawer_cluster_detector.cpp.

Definition at line 455 of file drawer_cluster_detector.cpp.

Definition at line 431 of file drawer_cluster_detector.cpp.

Definition at line 450 of file drawer_cluster_detector.cpp.

Definition at line 454 of file drawer_cluster_detector.cpp.

Definition at line 427 of file drawer_cluster_detector.cpp.

Definition at line 427 of file drawer_cluster_detector.cpp.

Definition at line 426 of file drawer_cluster_detector.cpp.

Definition at line 439 of file drawer_cluster_detector.cpp.

Definition at line 425 of file drawer_cluster_detector.cpp.

Definition at line 432 of file drawer_cluster_detector.cpp.

Definition at line 432 of file drawer_cluster_detector.cpp.

Definition at line 432 of file drawer_cluster_detector.cpp.

Definition at line 444 of file drawer_cluster_detector.cpp.

Definition at line 422 of file drawer_cluster_detector.cpp.

Definition at line 429 of file drawer_cluster_detector.cpp.

Definition at line 455 of file drawer_cluster_detector.cpp.

Definition at line 432 of file drawer_cluster_detector.cpp.

Definition at line 427 of file drawer_cluster_detector.cpp.

Definition at line 427 of file drawer_cluster_detector.cpp.

Definition at line 426 of file drawer_cluster_detector.cpp.

Definition at line 425 of file drawer_cluster_detector.cpp.

Definition at line 436 of file drawer_cluster_detector.cpp.

Definition at line 425 of file drawer_cluster_detector.cpp.

Definition at line 452 of file drawer_cluster_detector.cpp.

Definition at line 449 of file drawer_cluster_detector.cpp.

Definition at line 434 of file drawer_cluster_detector.cpp.

handle_detection::HandleDetectionResult DrawerHandlesDetector::result_ [private]

Definition at line 470 of file drawer_handles_detector.cpp.

Definition at line 429 of file drawer_cluster_detector.cpp.

Definition at line 447 of file drawer_cluster_detector.cpp.

Definition at line 448 of file drawer_cluster_detector.cpp.

Definition at line 431 of file drawer_cluster_detector.cpp.

Definition at line 443 of file drawer_cluster_detector.cpp.

Definition at line 423 of file drawer_cluster_detector.cpp.

Definition at line 430 of file drawer_cluster_detector.cpp.

Definition at line 430 of file drawer_cluster_detector.cpp.

Definition at line 430 of file drawer_cluster_detector.cpp.

Definition at line 430 of file drawer_cluster_detector.cpp.

Definition at line 429 of file drawer_cluster_detector.cpp.

Definition at line 429 of file drawer_cluster_detector.cpp.


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


handle_detection
Author(s): Nico Blodow
autogenerated on Thu May 23 2013 06:56:42