Definition at line 57 of file segment_object_in_hand.cpp.
typedef pcl::search::KdTree<Point>::Ptr tabletop_object_detector::ObjectInHandSegmenter::KdTreePtr [private] |
Definition at line 60 of file segment_object_in_hand.cpp.
typedef pcl::PointXYZRGB tabletop_object_detector::ObjectInHandSegmenter::Point [private] |
Definition at line 59 of file segment_object_in_hand.cpp.
tabletop_object_detector::ObjectInHandSegmenter::ObjectInHandSegmenter | ( | ros::NodeHandle | nh | ) | [inline] |
Definition at line 63 of file segment_object_in_hand.cpp.
void tabletop_object_detector::ObjectInHandSegmenter::combineClustersNearPoint | ( | std::vector< pcl::PointIndices > | clusters, |
pcl::PointCloud< Point > | input_cloud, | ||
std::string | wrist_frame, | ||
double | x, | ||
double | y, | ||
double | z, | ||
double | dist, | ||
pcl::PointCloud< Point > & | output_cluster | ||
) | [inline, private] |
Combine all clusters with points within dist of (x,y,z) in wrist_frame
Definition at line 258 of file segment_object_in_hand.cpp.
int tabletop_object_detector::ObjectInHandSegmenter::segmentObject | ( | std::string | wrist_frame, |
sensor_msgs::PointCloud2 & | output_cluster | ||
) | [inline, private] |
find the connected points for an object in the robot's hand based on the next point cloud received
Definition at line 141 of file segment_object_in_hand.cpp.
bool tabletop_object_detector::ObjectInHandSegmenter::serviceCallback | ( | SegmentObjectInHand::Request & | request, |
SegmentObjectInHand::Response & | response | ||
) | [inline, private] |
Service callback for segment object in hand service
Definition at line 125 of file segment_object_in_hand.cpp.
double tabletop_object_detector::ObjectInHandSegmenter::cluster_distance_ [private] |
Definition at line 111 of file segment_object_in_hand.cpp.
Definition at line 98 of file segment_object_in_hand.cpp.
Definition at line 117 of file segment_object_in_hand.cpp.
double tabletop_object_detector::ObjectInHandSegmenter::min_cluster_size_ [private] |
Definition at line 112 of file segment_object_in_hand.cpp.
Definition at line 97 of file segment_object_in_hand.cpp.
double tabletop_object_detector::ObjectInHandSegmenter::object_center_x_ [private] |
Definition at line 116 of file segment_object_in_hand.cpp.
double tabletop_object_detector::ObjectInHandSegmenter::object_center_y_ [private] |
Definition at line 116 of file segment_object_in_hand.cpp.
double tabletop_object_detector::ObjectInHandSegmenter::object_center_z_ [private] |
Definition at line 116 of file segment_object_in_hand.cpp.
Definition at line 97 of file segment_object_in_hand.cpp.
Definition at line 107 of file segment_object_in_hand.cpp.
Definition at line 120 of file segment_object_in_hand.cpp.
std::string tabletop_object_detector::ObjectInHandSegmenter::self_filtered_cloud_name_ [private] |
Definition at line 113 of file segment_object_in_hand.cpp.
Definition at line 106 of file segment_object_in_hand.cpp.
std::string tabletop_object_detector::ObjectInHandSegmenter::visualization_topic_ [private] |
Definition at line 108 of file segment_object_in_hand.cpp.
double tabletop_object_detector::ObjectInHandSegmenter::x_filter_max_ [private] |
Definition at line 101 of file segment_object_in_hand.cpp.
double tabletop_object_detector::ObjectInHandSegmenter::x_filter_min_ [private] |
Definition at line 101 of file segment_object_in_hand.cpp.
double tabletop_object_detector::ObjectInHandSegmenter::y_filter_max_ [private] |
Definition at line 102 of file segment_object_in_hand.cpp.
double tabletop_object_detector::ObjectInHandSegmenter::y_filter_min_ [private] |
Definition at line 102 of file segment_object_in_hand.cpp.
double tabletop_object_detector::ObjectInHandSegmenter::z_filter_max_ [private] |
Definition at line 103 of file segment_object_in_hand.cpp.
double tabletop_object_detector::ObjectInHandSegmenter::z_filter_min_ [private] |
Definition at line 103 of file segment_object_in_hand.cpp.