ExtractPolygonalPrismData uses a set of point indices that represent a planar model, and together with a given height, generates a 3D polygonal prism. The polygonal prism is then used to segment all points lying inside it. More...
#include <extract_polygonal_prism_data.h>

| Protected Member Functions | |
| void | config_callback (ExtractPolygonalPrismDataConfig &config, uint32_t level) | 
| Dynamic reconfigure callback. | |
| void | input_callback (const PointCloudConstPtr &input) | 
| Input point cloud callback. Because we want to use the same synchronizer object, we push back empty elements with the same timestamp. | |
| void | input_hull_indices_callback (const PointCloudConstPtr &cloud, const PointCloudConstPtr &hull, const PointIndicesConstPtr &indices) | 
| Input point cloud callback. Used when use_indices is set. | |
| void | onInit () | 
| Nodelet initialization routine. | |
| Protected Attributes | |
| message_filters::PassThrough < PointIndices > | nf_ | 
| Null passthrough filter, used for pushing empty elements in the synchronizer. | |
| ros::Publisher | pub_output_ | 
| The output PointIndices publisher. | |
| boost::shared_ptr < dynamic_reconfigure::Server < ExtractPolygonalPrismDataConfig > > | srv_ | 
| Pointer to a dynamic reconfigure service. | |
| message_filters::Subscriber < PointCloud > | sub_hull_filter_ | 
| The message filter subscriber for PointCloud2. | |
| boost::shared_ptr < message_filters::Synchronizer < sync_policies::ApproximateTime < PointCloud, PointCloud, PointIndices > > > | sync_input_hull_indices_a_ | 
| boost::shared_ptr < message_filters::Synchronizer < sync_policies::ExactTime < PointCloud, PointCloud, PointIndices > > > | sync_input_hull_indices_e_ | 
| Synchronized input, planar hull, and indices. | |
| Private Types | |
| typedef pcl::PointCloud < pcl::PointXYZ > | PointCloud | 
| typedef PointCloud::ConstPtr | PointCloudConstPtr | 
| typedef PointCloud::Ptr | PointCloudPtr | 
| Private Attributes | |
| pcl::ExtractPolygonalPrismData < pcl::PointXYZ > | impl_ | 
| The PCL implementation used. | |
ExtractPolygonalPrismData uses a set of point indices that represent a planar model, and together with a given height, generates a 3D polygonal prism. The polygonal prism is then used to segment all points lying inside it.
An example of its usage is to extract the data lying within a set of 3D boundaries (e.g., objects supported by a plane).
Definition at line 64 of file extract_polygonal_prism_data.h.
| typedef pcl::PointCloud<pcl::PointXYZ> pcl_ros::ExtractPolygonalPrismData::PointCloud  [private] | 
Reimplemented from pcl_ros::PCLNodelet.
Definition at line 66 of file extract_polygonal_prism_data.h.
| typedef PointCloud::ConstPtr pcl_ros::ExtractPolygonalPrismData::PointCloudConstPtr  [private] | 
Reimplemented from pcl_ros::PCLNodelet.
Definition at line 68 of file extract_polygonal_prism_data.h.
| typedef PointCloud::Ptr pcl_ros::ExtractPolygonalPrismData::PointCloudPtr  [private] | 
Reimplemented from pcl_ros::PCLNodelet.
Definition at line 67 of file extract_polygonal_prism_data.h.
| void pcl_ros::ExtractPolygonalPrismData::config_callback | ( | ExtractPolygonalPrismDataConfig & | config, | 
| uint32_t | level | ||
| ) |  [protected] | 
Dynamic reconfigure callback.
| config | the config object | 
| level | the dynamic reconfigure level | 
Definition at line 93 of file extract_polygonal_prism_data.cpp.
| void pcl_ros::ExtractPolygonalPrismData::input_callback | ( | const PointCloudConstPtr & | input | ) |  [inline, protected] | 
Input point cloud callback. Because we want to use the same synchronizer object, we push back empty elements with the same timestamp.
Definition at line 93 of file extract_polygonal_prism_data.h.
| void pcl_ros::ExtractPolygonalPrismData::input_hull_indices_callback | ( | const PointCloudConstPtr & | cloud, | 
| const PointCloudConstPtr & | hull, | ||
| const PointIndicesConstPtr & | indices | ||
| ) |  [protected] | 
Input point cloud callback. Used when use_indices is set.
| cloud | the pointer to the input point cloud | 
| hull | the pointer to the planar hull point cloud | 
| indices | the pointer to the input point cloud indices | 
DEBUG
Definition at line 113 of file extract_polygonal_prism_data.cpp.
| void pcl_ros::ExtractPolygonalPrismData::onInit | ( | ) |  [protected, virtual] | 
Nodelet initialization routine.
Reimplemented from pcl_ros::PCLNodelet.
Definition at line 45 of file extract_polygonal_prism_data.cpp.
The PCL implementation used.
Definition at line 120 of file extract_polygonal_prism_data.h.
Null passthrough filter, used for pushing empty elements in the synchronizer.
Definition at line 86 of file extract_polygonal_prism_data.h.
The output PointIndices publisher.
Reimplemented from pcl_ros::PCLNodelet.
Definition at line 72 of file extract_polygonal_prism_data.h.
| boost::shared_ptr<dynamic_reconfigure::Server<ExtractPolygonalPrismDataConfig> > pcl_ros::ExtractPolygonalPrismData::srv_  [protected] | 
Pointer to a dynamic reconfigure service.
Definition at line 82 of file extract_polygonal_prism_data.h.
| message_filters::Subscriber<PointCloud> pcl_ros::ExtractPolygonalPrismData::sub_hull_filter_  [protected] | 
The message filter subscriber for PointCloud2.
Definition at line 75 of file extract_polygonal_prism_data.h.
| boost::shared_ptr<message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud, PointCloud, PointIndices> > > pcl_ros::ExtractPolygonalPrismData::sync_input_hull_indices_a_  [protected] | 
Definition at line 79 of file extract_polygonal_prism_data.h.
| boost::shared_ptr<message_filters::Synchronizer<sync_policies::ExactTime<PointCloud, PointCloud, PointIndices> > > pcl_ros::ExtractPolygonalPrismData::sync_input_hull_indices_e_  [protected] | 
Synchronized input, planar hull, and indices.
Definition at line 78 of file extract_polygonal_prism_data.h.