#include <table_object_cluster.h>
Public Types | |
| typedef pcl::PointCloud< Point > ::ConstPtr | PointCloudConstPtr |
| typedef pcl::PointCloud< Point > ::Ptr | PointCloudPtr |
Public Member Functions | |
| void | calculateBoundingBox (const PointCloudPtr &cloud, const pcl::PointIndices &indices, const Eigen::Vector3f &plane_normal, const Eigen::Vector3f &plane_point, Eigen::Vector3f &position, Eigen::Quaternion< float > &orientation, Eigen::Vector3f &size) |
| void | calculateBoundingBoxesOld (pcl::PointIndices::Ptr &pc_roi, std::vector< PointCloudPtr > &object_clusters, std::vector< pcl::PointCloud< pcl::PointXYZ > > &bounding_boxes) |
| removes known objects by bounding box | |
| void | extractClusters (const pcl::PointIndices::Ptr &pc_roi, std::vector< PointCloudPtr > &object_clusters, std::vector< pcl::PointIndices > &object_cluster_indices) |
| void | extractTableRoi (PointCloudPtr &hull, pcl::PointIndices &pc_roi) |
| extracts objects at top of a plane | |
| void | extractTableRoi2 (const PointCloudConstPtr &pc_in, PointCloudPtr &hull, Eigen::Vector4f &plane_coeffs, pcl::PointCloud< Point > &pc_roi) |
| extracts objects at top of a plane | |
| void | removeKnownObjects (const PointCloudConstPtr &pc_roi, std::vector< BoundingBox > &bounding_boxes, const PointCloudPtr &pc_roi_red) |
| removes known objects by bounding box | |
| void | setClusterParams (int min_cluster_size, double cluster_tolerance) |
| sets parameters for filtering | |
| void | setInputCloud (const PointCloudPtr &cloud) |
| void | setPrismHeight (double height_min, double height_max) |
| sets parameters for filtering | |
| TableObjectCluster () | |
| ~TableObjectCluster () | |
Protected Attributes | |
| double | cluster_tolerance_ |
| paramter for object detection | |
| double | height_max_ |
| paramter for object detection | |
| double | height_min_ |
| PointCloudPtr | input_ |
| int | min_cluster_size_ |
| paramter for object detection | |
Definition at line 82 of file table_object_cluster.h.
| typedef pcl::PointCloud<Point>::ConstPtr TableObjectCluster< Point >::PointCloudConstPtr |
Definition at line 87 of file table_object_cluster.h.
| typedef pcl::PointCloud<Point>::Ptr TableObjectCluster< Point >::PointCloudPtr |
Definition at line 86 of file table_object_cluster.h.
| TableObjectCluster< Point >::TableObjectCluster | ( | ) | [inline] |
Definition at line 89 of file table_object_cluster.h.
| TableObjectCluster< Point >::~TableObjectCluster | ( | ) | [inline] |
Definition at line 97 of file table_object_cluster.h.
| void TableObjectCluster< Point >::calculateBoundingBox | ( | const PointCloudPtr & | cloud, |
| const pcl::PointIndices & | indices, | ||
| const Eigen::Vector3f & | plane_normal, | ||
| const Eigen::Vector3f & | plane_point, | ||
| Eigen::Vector3f & | position, | ||
| Eigen::Quaternion< float > & | orientation, | ||
| Eigen::Vector3f & | size | ||
| ) |
Definition at line 191 of file table_object_cluster.cpp.
| void TableObjectCluster< Point >::calculateBoundingBoxesOld | ( | pcl::PointIndices::Ptr & | pc_roi, |
| std::vector< PointCloudPtr > & | object_clusters, | ||
| std::vector< pcl::PointCloud< pcl::PointXYZ > > & | bounding_boxes | ||
| ) |
removes known objects by bounding box
removes known objects by bounding box
| pc_roi | input point cloud with objects |
| bounding_boxes | bounding boxes of known objects |
| pc_roi_red | output point cloud without known objects |
Definition at line 311 of file table_object_cluster.cpp.
| void TableObjectCluster< Point >::extractClusters | ( | const pcl::PointIndices::Ptr & | pc_roi, |
| std::vector< PointCloudPtr > & | object_clusters, | ||
| std::vector< pcl::PointIndices > & | object_cluster_indices | ||
| ) |
Definition at line 277 of file table_object_cluster.cpp.
| void TableObjectCluster< Point >::extractTableRoi | ( | PointCloudPtr & | hull, |
| pcl::PointIndices & | pc_roi | ||
| ) |
extracts objects at top of a plane
extracts objects at top of a plane using a prism
| pc_in | input point cloud |
| hull | hull describing plane |
| pc_roi | output point cloud containing extracted objects |
Definition at line 90 of file table_object_cluster.cpp.
| void TableObjectCluster< Point >::extractTableRoi2 | ( | const PointCloudConstPtr & | pc_in, |
| PointCloudPtr & | hull, | ||
| Eigen::Vector4f & | plane_coeffs, | ||
| pcl::PointCloud< Point > & | pc_roi | ||
| ) |
extracts objects at top of a plane
extracts objects at top of a plane using distance
| pc_in | input point cloud |
| hull | hull describing plane |
| plane_coeffs | coefficients describing plane |
| pc_roi | output point cloud containing extracted objects |
Definition at line 127 of file table_object_cluster.cpp.
| void TableObjectCluster< Point >::removeKnownObjects | ( | const PointCloudConstPtr & | pc_roi, |
| std::vector< BoundingBox > & | bounding_boxes, | ||
| const PointCloudPtr & | pc_roi_red | ||
| ) |
removes known objects by bounding box
removes known objects by bounding box
| pc_roi | input point cloud with objects |
| bounding_boxes | bounding boxes of known objects |
| pc_roi_red | output point cloud without known objects |
Definition at line 167 of file table_object_cluster.cpp.
| void TableObjectCluster< Point >::setClusterParams | ( | int | min_cluster_size, |
| double | cluster_tolerance | ||
| ) | [inline] |
sets parameters for filtering
sets parameters for filtering
| min_cluster_size | |
| cluster_tolerance |
Definition at line 211 of file table_object_cluster.h.
| void TableObjectCluster< Point >::setInputCloud | ( | const PointCloudPtr & | cloud | ) | [inline] |
Definition at line 181 of file table_object_cluster.h.
| void TableObjectCluster< Point >::setPrismHeight | ( | double | height_min, |
| double | height_max | ||
| ) | [inline] |
sets parameters for filtering
sets parameters for filtering
| height_min | |
| height_max |
Definition at line 194 of file table_object_cluster.h.
double TableObjectCluster< Point >::cluster_tolerance_ [protected] |
paramter for object detection
Definition at line 222 of file table_object_cluster.h.
double TableObjectCluster< Point >::height_max_ [protected] |
paramter for object detection
Definition at line 220 of file table_object_cluster.h.
double TableObjectCluster< Point >::height_min_ [protected] |
Definition at line 219 of file table_object_cluster.h.
PointCloudPtr TableObjectCluster< Point >::input_ [protected] |
Definition at line 218 of file table_object_cluster.h.
int TableObjectCluster< Point >::min_cluster_size_ [protected] |
paramter for object detection
Definition at line 221 of file table_object_cluster.h.