Class ExtractPolygonalPrismData

Inheritance Relationships

Base Type

  • public PCLNodelet

Class Documentation

class ExtractPolygonalPrismData : public PCLNodelet

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

Protected Functions

inline 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 onInit()

Nodelet initialization routine.

void subscribe()

LazyNodelet connection routine.

void unsubscribe()
void config_callback(ExtractPolygonalPrismDataConfig &config, uint32_t level)

Dynamic reconfigure callback.

Parameters:
  • config – the config object

  • level – the dynamic reconfigure level

void input_hull_indices_callback(const PointCloudConstPtr &cloud, const PointCloudConstPtr &hull, const PointIndicesConstPtr &indices)

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

Protected Attributes

ros::Publisher pub_output_

The output PointIndices publisher.

message_filters::Subscriber<PointCloud> sub_hull_filter_

The message filter subscriber for PointCloud2.

boost::shared_ptr<message_filters::Synchronizer<sync_policies::ExactTime<PointCloud, PointCloud, PointIndices>>> sync_input_hull_indices_e_

Synchronized input, planar hull, and indices.

boost::shared_ptr<message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud, PointCloud, PointIndices>>> sync_input_hull_indices_a_
boost::shared_ptr<dynamic_reconfigure::Server<ExtractPolygonalPrismDataConfig>> srv_

Pointer to a dynamic reconfigure service.

message_filters::PassThrough<PointIndices> nf_

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