$search
#include <table_detector.h>
Public Types | |
typedef pcl::KdTree< Point >::Ptr | KdTreePtr |
typedef pcl::PointXYZ | Point |
Public Member Functions | |
bool | detectTable (const sensor_msgs::PointCloud2 &cloud, tabletop_object_detector::Table &table) |
visualization_msgs::Marker | getTableMarker (const tabletop_object_detector::Table &table) |
TableDetector () | |
~TableDetector () | |
Public Attributes | |
double | cluster_distance_ |
Min distance between two clusters. | |
double | clustering_voxel_size_ |
Size of downsampling grid before performing clustering. | |
int | inlier_threshold_ |
Min number of inliers for reliable plane detection. | |
int | min_cluster_size_ |
Min number of points for a cluster. | |
double | plane_detection_voxel_size_ |
Size of downsampling grid before performing plane detection. | |
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 Member Functions | |
bool | getPlanePoints (const pcl::PointCloud< Point > &table, const tf::Transform &table_plane_trans, sensor_msgs::PointCloud &table_points) |
tf::Transform | getPlaneTransform (pcl::ModelCoefficients coeffs, double up_direction) |
tabletop_object_detector::Table | getTable (const std_msgs::Header &header, const tf::Transform &table_plane_trans, const sensor_msgs::PointCloud &table_points) |
Private Attributes | |
int | current_marker_id_ |
The current table marker. |
Definition at line 53 of file table_detector.h.
typedef pcl::KdTree<Point>::Ptr image_segmentation_demo::TableDetector::KdTreePtr |
Definition at line 57 of file table_detector.h.
typedef pcl::PointXYZ image_segmentation_demo::TableDetector::Point |
Definition at line 56 of file table_detector.h.
image_segmentation_demo::TableDetector::TableDetector | ( | ) |
Definition at line 60 of file table_detector.cpp.
image_segmentation_demo::TableDetector::~TableDetector | ( | ) |
Definition at line 76 of file table_detector.cpp.
bool image_segmentation_demo::TableDetector::detectTable | ( | const sensor_msgs::PointCloud2 & | cloud, | |
tabletop_object_detector::Table & | table | |||
) |
Definition at line 80 of file table_detector.cpp.
bool image_segmentation_demo::TableDetector::getPlanePoints | ( | const pcl::PointCloud< Point > & | table, | |
const tf::Transform & | table_plane_trans, | |||
sensor_msgs::PointCloud & | table_points | |||
) | [private] |
Definition at line 344 of file table_detector.cpp.
tf::Transform image_segmentation_demo::TableDetector::getPlaneTransform | ( | pcl::ModelCoefficients | coeffs, | |
double | up_direction | |||
) | [private] |
Assumes plane coefficients are of the form ax+by+cz+d=0, normalized
Definition at line 310 of file table_detector.cpp.
tabletop_object_detector::Table image_segmentation_demo::TableDetector::getTable | ( | const std_msgs::Header & | header, | |
const tf::Transform & | table_plane_trans, | |||
const sensor_msgs::PointCloud & | table_points | |||
) | [private] |
Definition at line 221 of file table_detector.cpp.
visualization_msgs::Marker image_segmentation_demo::TableDetector::getTableMarker | ( | const tabletop_object_detector::Table & | table | ) |
The point cloud is a set of points belonging to the plane, in the plane coordinate system (with the origin in the plane and the z axis normal to the plane).
It is the responsibility of the caller to set the appropriate pose for the marker so that it shows up in the right reference frame.
Definition at line 255 of file table_detector.cpp.
Min distance between two clusters.
Definition at line 77 of file table_detector.h.
Size of downsampling grid before performing clustering.
Definition at line 71 of file table_detector.h.
The current table marker.
Definition at line 94 of file table_detector.h.
Min number of inliers for reliable plane detection.
Definition at line 67 of file table_detector.h.
Min number of points for a cluster.
Definition at line 79 of file table_detector.h.
Size of downsampling grid before performing plane detection.
Definition at line 69 of file table_detector.h.
Clouds are transformed into this frame before processing; leave empty if clouds are to be processed in their original frame
Definition at line 82 of file table_detector.h.
Definition at line 75 of file table_detector.h.
Filtering of point cloud in table frame after table detection.
Definition at line 75 of file table_detector.h.
Positive or negative z is closer to the "up" direction in the processing frame?
Definition at line 84 of file table_detector.h.
Definition at line 73 of file table_detector.h.
Filtering of original point cloud along the z axis.
Definition at line 73 of file table_detector.h.