pcl_ros::ExtractPolygonalPrismData Class Reference

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>

Inheritance diagram for pcl_ros::ExtractPolygonalPrismData:
Inheritance graph
[legend]

List of all members.

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.

Detailed Description

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).

Author:
Radu Bogdan Rusu

Definition at line 62 of file extract_polygonal_prism_data.h.


Member Typedef Documentation

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 53 of file extract_polygonal_prism_data.h.

typedef PointCloud::ConstPtr pcl_ros::ExtractPolygonalPrismData::PointCloudConstPtr [private]

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 55 of file extract_polygonal_prism_data.h.

typedef PointCloud::Ptr pcl_ros::ExtractPolygonalPrismData::PointCloudPtr [private]

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 54 of file extract_polygonal_prism_data.h.


Member Function Documentation

void pcl_ros::ExtractPolygonalPrismData::config_callback ( ExtractPolygonalPrismDataConfig config,
uint32_t  level 
) [protected]

Dynamic reconfigure callback.

Parameters:
config the config object
level the dynamic reconfigure level

Definition at line 92 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 80 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.

Parameters:
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 112 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 44 of file extract_polygonal_prism_data.cpp.


Member Data Documentation

The PCL implementation used.

Definition at line 107 of file extract_polygonal_prism_data.h.

Null passthrough filter, used for pushing empty elements in the synchronizer.

Definition at line 73 of file extract_polygonal_prism_data.h.

The output PointIndices publisher.

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 59 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 69 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 62 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 66 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 65 of file extract_polygonal_prism_data.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Friends


pcl_ros
Author(s): Maintained by Radu Bogdan Rusu
autogenerated on Fri Jan 11 09:15:53 2013