Definition at line 85 of file drawer_cluster_detector.cpp.
DrawerHandlesDetector::DrawerHandlesDetector | ( | const ros::NodeHandle & | nh | ) | [inline] |
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.
DrawerHandlesDetector::DrawerHandlesDetector | ( | const ros::NodeHandle & | nh | ) | [inline] |
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.
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.
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.
pcl::PointCloud< Point > DrawerHandlesDetector::cloud_objects_ [private] |
Definition at line 453 of file drawer_cluster_detector.cpp.
pcl_ros::Publisher< Point > DrawerHandlesDetector::cloud_pub_ [private] |
Definition at line 437 of file drawer_cluster_detector.cpp.
Definition at line 454 of file drawer_cluster_detector.cpp.
double DrawerHandlesDetector::cluster_max_height_ [private] |
Definition at line 426 of file drawer_cluster_detector.cpp.
double DrawerHandlesDetector::cluster_min_height_ [private] |
Definition at line 426 of file drawer_cluster_detector.cpp.
Definition at line 455 of file drawer_cluster_detector.cpp.
double DrawerHandlesDetector::eps_angle_ [private] |
Definition at line 431 of file drawer_cluster_detector.cpp.
pcl::ExtractIndices< Point > DrawerHandlesDetector::extract_ [private] |
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.
double DrawerHandlesDetector::handle_cluster_tolerance_ [private] |
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.
int DrawerHandlesDetector::k_ [private] |
Definition at line 432 of file drawer_cluster_detector.cpp.
int DrawerHandlesDetector::max_iter_ [private] |
Definition at line 432 of file drawer_cluster_detector.cpp.
int DrawerHandlesDetector::min_table_inliers_ [private] |
Definition at line 432 of file drawer_cluster_detector.cpp.
pcl::NormalEstimation< Point, pcl::Normal > DrawerHandlesDetector::n3d_ [private] |
Definition at line 444 of file drawer_cluster_detector.cpp.
ros::NodeHandle DrawerHandlesDetector::nh_ [private] |
Definition at line 422 of file drawer_cluster_detector.cpp.
double DrawerHandlesDetector::normal_distance_weight_ [private] |
Definition at line 429 of file drawer_cluster_detector.cpp.
Definition at line 455 of file drawer_cluster_detector.cpp.
int DrawerHandlesDetector::nr_cluster_ [private] |
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.
double DrawerHandlesDetector::object_cluster_tolerance_ [private] |
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.
pcl::ProjectInliers< Point > DrawerHandlesDetector::proj_ [private] |
Definition at line 449 of file drawer_cluster_detector.cpp.
bool DrawerHandlesDetector::publish_largest_handle_pose_ [private] |
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.
double DrawerHandlesDetector::sac_distance_ [private] |
Definition at line 429 of file drawer_cluster_detector.cpp.
Definition at line 447 of file drawer_cluster_detector.cpp.
pcl::SACSegmentation< Point > DrawerHandlesDetector::seg_line_ [private] |
Definition at line 448 of file drawer_cluster_detector.cpp.
double DrawerHandlesDetector::seg_prob_ [private] |
Definition at line 431 of file drawer_cluster_detector.cpp.
pcl::VoxelGrid< Point > DrawerHandlesDetector::vgrid_ [private] |
Definition at line 443 of file drawer_cluster_detector.cpp.
double DrawerHandlesDetector::voxel_size_ [private] |
Definition at line 423 of file drawer_cluster_detector.cpp.
double DrawerHandlesDetector::x_max_limit_ [private] |
Definition at line 430 of file drawer_cluster_detector.cpp.
double DrawerHandlesDetector::x_min_limit_ [private] |
Definition at line 430 of file drawer_cluster_detector.cpp.
double DrawerHandlesDetector::y_max_limit_ [private] |
Definition at line 430 of file drawer_cluster_detector.cpp.
double DrawerHandlesDetector::y_min_limit_ [private] |
Definition at line 430 of file drawer_cluster_detector.cpp.
double DrawerHandlesDetector::z_max_limit_ [private] |
Definition at line 429 of file drawer_cluster_detector.cpp.
double DrawerHandlesDetector::z_min_limit_ [private] |
Definition at line 429 of file drawer_cluster_detector.cpp.