$search
Public Member Functions | |
| void | clearOldMarkers (std::string frame_id) |
| bool | detectTable (const sensor_msgs::PointCloud2 &cloud, TabletopSegmentation::Response &response) |
| void | filterPointCloud (const sensor_msgs::CameraInfo &info_msg, cv::Mat &mask, pcl::PointCloud< pcl::PointXYZRGB > &cloud) |
| bool | getCameraInfo (sensor_msgs::CameraInfo &camera_info_msg) |
| bool | getDepthImage (sensor_msgs::Image &image_msg, Mat &image) |
| bool | getImage (sensor_msgs::Image &image_msg, Mat &image) |
| template<typename PointT > | |
| bool | getPlanePoints (const pcl::PointCloud< PointT > &table, const tf::Transform &table_plane_trans, sensor_msgs::PointCloud &table_points) |
| tf::Transform | getPlaneTransform (pcl::ModelCoefficients coeffs, double up_direction) |
| bool | getPointCloud (sensor_msgs::PointCloud2 &cloud_msg, pcl::PointCloud< pcl::PointXYZRGB > &cloud) |
| template<class PointCloudType > | |
| Table | getTable (std_msgs::Header cloud_header, const tf::Transform &table_plane_trans, const PointCloudType &table_points) |
| GrabCutNode (const std::string &node_name, ros::NodeHandle &nh) | |
| void | imageCallback (const sensor_msgs::ImageConstPtr &msg) |
| bool | processPointCloud (const sensor_msgs::PointCloud2 &cloud_msg, const sensor_msgs::Image &image_msg, sensor_msgs::CameraInfo &camera_info_msg, cv::Mat &binary_mask, TabletopSegmentation::Response &response) |
| template<class PointCloudType > | |
| void | publishClusterMarkers (const std::vector< PointCloudType > &clusters, roslib::Header cloud_header) |
| Publishes rviz markers for the given tabletop clusters. | |
| void | publishImage (const image_transport::CameraPublisher &pub, sensor_msgs::CameraInfo &info_msg, sensor_msgs::Image &img_msg, const cv::Mat &image, const std::string &encoding) |
| void | scaleCameraInfo (sensor_msgs::CameraInfo &info, float scale) |
| bool | serviceCallback (TabletopSegmentation::Request &request, TabletopSegmentation::Response &response) |
| bool | transformPointCloud (const std::string &target_frame, const sensor_msgs::PointCloud2 &cloud_in, sensor_msgs::PointCloud2 &cloud_out) |
| bool | transformPointCloud (const std::string &target_frame, const pcl::PointCloud< pcl::PointXYZRGB > &cloud_in, pcl::PointCloud< pcl::PointXYZRGB > &cloud_out) |
| ~GrabCutNode () | |
| Empty stub. | |
Public Attributes | |
| double | cluster_distance_ |
| Min distance between two clusters. | |
| double | clustering_voxel_size_ |
| Size of downsampling grid before performing clustering. | |
| int | current_marker_id_ |
| The current marker being published. | |
| sensor_msgs::CvBridge | depth_img_bridge_ |
| image_transport::Subscriber | image_sub_ |
| Subscriber for rgbd images. | |
| sensor_msgs::CvBridge | img_bridge_ |
| int | inlier_threshold_ |
| Min number of inliers for reliable plane detection. | |
| image_transport::ImageTransport | it |
| tf::TransformListener | listener_ |
| A tf transform listener. | |
| ros::Publisher | marker_pub_ |
| Publisher for markers. | |
| sensor_msgs::Image | mask_img_msg |
| image_transport::CameraPublisher | mask_pub |
| int | min_cluster_size_ |
| Min number of points for a cluster. | |
| ros::NodeHandle | nh_ |
| The node handle. | |
| std::string | node_name_ |
| int | num_markers_published_ |
| Used to remember the number of markers we publish so we can delete them later. | |
| ros::ServiceClient | object_recognition_client |
| ros::ServiceServer | object_selection_srv_ |
| Service server for object selection. | |
| double | plane_detection_voxel_size_ |
| Size of downsampling grid before performing plane detection. | |
| ros::NodeHandle | priv_nh_ |
| Node handle in the private namespace. | |
| std::string | processing_frame_ |
| double | table_z_filter_max_ |
| double | table_z_filter_min_ |
| Filtering of point cloud in table frame after table detection. | |
| double | up_direction_ |
| Positive or negative z is closer to the "up" direction in the processing frame? | |
| double | z_filter_max_ |
| double | z_filter_min_ |
| Filtering of original point cloud along the z axis. | |
Private Types | |
| typedef pcl::KdTree< Point >::Ptr | KdTreePtr |
| typedef pcl::PointXYZ | Point |
Definition at line 82 of file augmented_object_selection.cpp.
typedef pcl::KdTree<Point>::Ptr GrabCutNode::KdTreePtr [private] |
Definition at line 85 of file augmented_object_selection.cpp.
typedef pcl::PointXYZ GrabCutNode::Point [private] |
Definition at line 84 of file augmented_object_selection.cpp.
| GrabCutNode::GrabCutNode | ( | const std::string & | node_name, | |
| ros::NodeHandle & | nh | |||
| ) | [inline] |
Definition at line 139 of file augmented_object_selection.cpp.
| GrabCutNode::~GrabCutNode | ( | ) | [inline] |
Empty stub.
Definition at line 175 of file augmented_object_selection.cpp.
| void GrabCutNode::clearOldMarkers | ( | std::string | frame_id | ) | [inline] |
Definition at line 855 of file augmented_object_selection.cpp.
| bool GrabCutNode::detectTable | ( | const sensor_msgs::PointCloud2 & | cloud, | |
| TabletopSegmentation::Response & | response | |||
| ) | [inline] |
Definition at line 649 of file augmented_object_selection.cpp.
| void GrabCutNode::filterPointCloud | ( | const sensor_msgs::CameraInfo & | info_msg, | |
| cv::Mat & | mask, | |||
| pcl::PointCloud< pcl::PointXYZRGB > & | cloud | |||
| ) | [inline] |
Definition at line 211 of file augmented_object_selection.cpp.
| bool GrabCutNode::getCameraInfo | ( | sensor_msgs::CameraInfo & | camera_info_msg | ) | [inline] |
Definition at line 275 of file augmented_object_selection.cpp.
| bool GrabCutNode::getDepthImage | ( | sensor_msgs::Image & | image_msg, | |
| Mat & | image | |||
| ) | [inline] |
Definition at line 317 of file augmented_object_selection.cpp.
| bool GrabCutNode::getImage | ( | sensor_msgs::Image & | image_msg, | |
| Mat & | image | |||
| ) | [inline] |
Definition at line 291 of file augmented_object_selection.cpp.
| bool GrabCutNode::getPlanePoints | ( | const pcl::PointCloud< PointT > & | table, | |
| const tf::Transform & | table_plane_trans, | |||
| sensor_msgs::PointCloud & | table_points | |||
| ) | [inline] |
Definition at line 569 of file augmented_object_selection.cpp.
| tf::Transform GrabCutNode::getPlaneTransform | ( | pcl::ModelCoefficients | coeffs, | |
| double | up_direction | |||
| ) | [inline] |
Assumes plane coefficients are of the form ax+by+cz+d=0, normalized
Definition at line 534 of file augmented_object_selection.cpp.
| bool GrabCutNode::getPointCloud | ( | sensor_msgs::PointCloud2 & | cloud_msg, | |
| pcl::PointCloud< pcl::PointXYZRGB > & | cloud | |||
| ) | [inline] |
Definition at line 257 of file augmented_object_selection.cpp.
| Table GrabCutNode::getTable | ( | std_msgs::Header | cloud_header, | |
| const tf::Transform & | table_plane_trans, | |||
| const PointCloudType & | table_points | |||
| ) | [inline] |
Definition at line 611 of file augmented_object_selection.cpp.
| void GrabCutNode::imageCallback | ( | const sensor_msgs::ImageConstPtr & | msg | ) | [inline] |
Definition at line 177 of file augmented_object_selection.cpp.
| bool GrabCutNode::processPointCloud | ( | const sensor_msgs::PointCloud2 & | cloud_msg, | |
| const sensor_msgs::Image & | image_msg, | |||
| sensor_msgs::CameraInfo & | camera_info_msg, | |||
| cv::Mat & | binary_mask, | |||
| TabletopSegmentation::Response & | response | |||
| ) | [inline] |
Definition at line 797 of file augmented_object_selection.cpp.
| void GrabCutNode::publishClusterMarkers | ( | const std::vector< PointCloudType > & | clusters, | |
| roslib::Header | cloud_header | |||
| ) | [inline] |
Publishes rviz markers for the given tabletop clusters.
Definition at line 836 of file augmented_object_selection.cpp.
| void GrabCutNode::publishImage | ( | const image_transport::CameraPublisher & | pub, | |
| sensor_msgs::CameraInfo & | info_msg, | |||
| sensor_msgs::Image & | img_msg, | |||
| const cv::Mat & | image, | |||
| const std::string & | encoding | |||
| ) | [inline] |
Definition at line 197 of file augmented_object_selection.cpp.
| void GrabCutNode::scaleCameraInfo | ( | sensor_msgs::CameraInfo & | info, | |
| float | scale | |||
| ) | [inline] |
Definition at line 183 of file augmented_object_selection.cpp.
| bool GrabCutNode::serviceCallback | ( | TabletopSegmentation::Request & | request, | |
| TabletopSegmentation::Response & | response | |||
| ) | [inline] |
Definition at line 343 of file augmented_object_selection.cpp.
| bool GrabCutNode::transformPointCloud | ( | const std::string & | target_frame, | |
| const sensor_msgs::PointCloud2 & | cloud_in, | |||
| sensor_msgs::PointCloud2 & | cloud_out | |||
| ) | [inline] |
Definition at line 505 of file augmented_object_selection.cpp.
| bool GrabCutNode::transformPointCloud | ( | const std::string & | target_frame, | |
| const pcl::PointCloud< pcl::PointXYZRGB > & | cloud_in, | |||
| pcl::PointCloud< pcl::PointXYZRGB > & | cloud_out | |||
| ) | [inline] |
Definition at line 488 of file augmented_object_selection.cpp.
Min distance between two clusters.
Definition at line 129 of file augmented_object_selection.cpp.
Size of downsampling grid before performing clustering.
Definition at line 123 of file augmented_object_selection.cpp.
The current marker being published.
Definition at line 112 of file augmented_object_selection.cpp.
Definition at line 102 of file augmented_object_selection.cpp.
Subscriber for rgbd images.
Definition at line 114 of file augmented_object_selection.cpp.
Definition at line 100 of file augmented_object_selection.cpp.
Min number of inliers for reliable plane detection.
Definition at line 119 of file augmented_object_selection.cpp.
Definition at line 104 of file augmented_object_selection.cpp.
A tf transform listener.
Definition at line 93 of file augmented_object_selection.cpp.
Publisher for markers.
Definition at line 108 of file augmented_object_selection.cpp.
Definition at line 106 of file augmented_object_selection.cpp.
Definition at line 96 of file augmented_object_selection.cpp.
Min number of points for a cluster.
Definition at line 131 of file augmented_object_selection.cpp.
The node handle.
Definition at line 89 of file augmented_object_selection.cpp.
| std::string GrabCutNode::node_name_ |
Definition at line 87 of file augmented_object_selection.cpp.
Used to remember the number of markers we publish so we can delete them later.
Definition at line 110 of file augmented_object_selection.cpp.
Definition at line 95 of file augmented_object_selection.cpp.
Service server for object selection.
Definition at line 98 of file augmented_object_selection.cpp.
Size of downsampling grid before performing plane detection.
Definition at line 121 of file augmented_object_selection.cpp.
Node handle in the private namespace.
Definition at line 91 of file augmented_object_selection.cpp.
| std::string GrabCutNode::processing_frame_ |
Clouds are transformed into this frame before processing; leave empty if clouds are to be processed in their original frame
Definition at line 134 of file augmented_object_selection.cpp.
Definition at line 127 of file augmented_object_selection.cpp.
Filtering of point cloud in table frame after table detection.
Definition at line 127 of file augmented_object_selection.cpp.
| double GrabCutNode::up_direction_ |
Positive or negative z is closer to the "up" direction in the processing frame?
Definition at line 136 of file augmented_object_selection.cpp.
| double GrabCutNode::z_filter_max_ |
Definition at line 125 of file augmented_object_selection.cpp.
| double GrabCutNode::z_filter_min_ |
Filtering of original point cloud along the z axis.
Definition at line 125 of file augmented_object_selection.cpp.