Public Member Functions | Private Types | Private Member Functions | Private Attributes
tabletop_object_detector::TabletopSegmentor Class Reference

List of all members.

Public Member Functions

 TabletopSegmentor (ros::NodeHandle nh)
 Subscribes to and advertises topics; initializes fitter and marker publication flags.
 ~TabletopSegmentor ()
 Empty stub.

Private Types

typedef pcl::search::KdTree
< Point >::Ptr 
KdTreePtr
typedef pcl::PointXYZRGB Point

Private Member Functions

template<class PointCloudType >
void addConvexHullTable (Table &table, const PointCloudType &convex_hull, bool flatten_table)
 Converts table convex hull into a triangle mesh to add to a Table message.
void clearOldMarkers (std::string frame_id)
 Clears old published markers and remembers the current number of published markers.
template<class PointCloudType >
Table getTable (std_msgs::Header cloud_header, const tf::Transform &table_plane_trans, const PointCloudType &table_points)
 Converts raw table detection results into a Table message type.
void processCloud (const sensor_msgs::PointCloud2 &cloud, TabletopSegmentation::Response &response, Table table)
 Complete processing for new style point cloud.
template<class PointCloudType >
void publishClusterMarkers (const std::vector< PointCloudType > &clusters, std_msgs::Header cloud_header)
 Publishes rviz markers for the given tabletop clusters.
bool serviceCallback (TabletopSegmentation::Request &request, TabletopSegmentation::Response &response)
 Callback for service calls.
template<class PointCloudType >
bool tableMsgToPointCloud (Table &table, std::string frame_id, PointCloudType &table_hull)
 Pull out and transform the convex hull points from a Table message.

Private 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.
bool flatten_table_
int inlier_threshold_
 Min number of inliers for reliable plane detection.
tf::TransformListener listener_
 A tf transform listener.
ros::Publisher marker_pub_
 Publisher for markers.
int min_cluster_size_
 Min number of points for a cluster.
ros::NodeHandle nh_
 The node handle.
int num_markers_published_
 Used to remember the number of markers we publish so we can delete them later.
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_
ros::ServiceServer segmentation_srv_
 Service server for object detection.
double table_padding_
 How much the table gets padded in the horizontal direction.
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 x_filter_max_
double x_filter_min_
double y_filter_max_
double y_filter_min_
double z_filter_max_
double z_filter_min_
 Filtering of original point cloud along the z, y, and x axes.

Detailed Description

Definition at line 72 of file tabletop_segmentation.cpp.


Member Typedef Documentation

typedef pcl::search::KdTree<Point>::Ptr tabletop_object_detector::TabletopSegmentor::KdTreePtr [private]

Definition at line 75 of file tabletop_segmentation.cpp.

typedef pcl::PointXYZRGB tabletop_object_detector::TabletopSegmentor::Point [private]

Definition at line 74 of file tabletop_segmentation.cpp.


Constructor & Destructor Documentation

Subscribes to and advertises topics; initializes fitter and marker publication flags.

Also attempts to connect to database

Definition at line 157 of file tabletop_segmentation.cpp.

Empty stub.

Definition at line 191 of file tabletop_segmentation.cpp.


Member Function Documentation

template<class PointCloudType >
void tabletop_object_detector::TabletopSegmentor::addConvexHullTable ( Table table,
const PointCloudType &  convex_hull,
bool  flatten_table 
) [private]

Converts table convex hull into a triangle mesh to add to a Table message.

Definition at line 269 of file tabletop_segmentation.cpp.

void tabletop_object_detector::TabletopSegmentor::clearOldMarkers ( std::string  frame_id) [private]

Clears old published markers and remembers the current number of published markers.

Definition at line 384 of file tabletop_segmentation.cpp.

template<class PointCloudType >
Table tabletop_object_detector::TabletopSegmentor::getTable ( std_msgs::Header  cloud_header,
const tf::Transform table_plane_trans,
const PointCloudType &  table_points 
) [private]

Converts raw table detection results into a Table message type.

Definition at line 331 of file tabletop_segmentation.cpp.

void tabletop_object_detector::TabletopSegmentor::processCloud ( const sensor_msgs::PointCloud2 &  cloud,
TabletopSegmentation::Response response,
Table  table 
) [private]

Complete processing for new style point cloud.

Definition at line 618 of file tabletop_segmentation.cpp.

template<class PointCloudType >
void tabletop_object_detector::TabletopSegmentor::publishClusterMarkers ( const std::vector< PointCloudType > &  clusters,
std_msgs::Header  cloud_header 
) [private]

Publishes rviz markers for the given tabletop clusters.

Definition at line 371 of file tabletop_segmentation.cpp.

Callback for service calls.

Processes the latest point cloud and gives back the resulting array of models.

Definition at line 196 of file tabletop_segmentation.cpp.

template<class PointCloudType >
bool tabletop_object_detector::TabletopSegmentor::tableMsgToPointCloud ( Table table,
std::string  frame_id,
PointCloudType &  table_hull 
) [private]

Pull out and transform the convex hull points from a Table message.

Definition at line 448 of file tabletop_segmentation.cpp.


Member Data Documentation

Min distance between two clusters.

Definition at line 105 of file tabletop_segmentation.cpp.

Size of downsampling grid before performing clustering.

Definition at line 97 of file tabletop_segmentation.cpp.

The current marker being published.

Definition at line 90 of file tabletop_segmentation.cpp.

Definition at line 113 of file tabletop_segmentation.cpp.

Min number of inliers for reliable plane detection.

Definition at line 93 of file tabletop_segmentation.cpp.

A tf transform listener.

Definition at line 118 of file tabletop_segmentation.cpp.

Publisher for markers.

Definition at line 83 of file tabletop_segmentation.cpp.

Min number of points for a cluster.

Definition at line 107 of file tabletop_segmentation.cpp.

The node handle.

Definition at line 79 of file tabletop_segmentation.cpp.

Used to remember the number of markers we publish so we can delete them later.

Definition at line 88 of file tabletop_segmentation.cpp.

Size of downsampling grid before performing plane detection.

Definition at line 95 of file tabletop_segmentation.cpp.

Node handle in the private namespace.

Definition at line 81 of file tabletop_segmentation.cpp.

Clouds are transformed into this frame before processing; leave empty if clouds are to be processed in their original frame

Definition at line 110 of file tabletop_segmentation.cpp.

Service server for object detection.

Definition at line 85 of file tabletop_segmentation.cpp.

How much the table gets padded in the horizontal direction.

Definition at line 115 of file tabletop_segmentation.cpp.

Definition at line 103 of file tabletop_segmentation.cpp.

Filtering of point cloud in table frame after table detection.

Definition at line 103 of file tabletop_segmentation.cpp.

Positive or negative z is closer to the "up" direction in the processing frame?

Definition at line 112 of file tabletop_segmentation.cpp.

Definition at line 101 of file tabletop_segmentation.cpp.

Definition at line 101 of file tabletop_segmentation.cpp.

Definition at line 100 of file tabletop_segmentation.cpp.

Definition at line 100 of file tabletop_segmentation.cpp.

Definition at line 99 of file tabletop_segmentation.cpp.

Filtering of original point cloud along the z, y, and x axes.

Definition at line 99 of file tabletop_segmentation.cpp.


The documentation for this class was generated from the following file:


tabletop_object_detector
Author(s): Marius Muja and Matei Ciocarlie
autogenerated on Fri Jan 3 2014 11:48:48