pcl_ros::ConvexHull2D Class Reference

ConvexHull2D represents a 2D ConvexHull implementation. More...

#include <convex_hull.h>

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

List of all members.

Private Types

typedef pcl::PointCloud
< pcl::PointXYZ > 
PointCloud
typedef PointCloud::ConstPtr PointCloudConstPtr
typedef PointCloud::Ptr PointCloudPtr

Private Member Functions

void input_indices_callback (const PointCloudConstPtr &cloud, const PointIndicesConstPtr &indices)
 Input point cloud callback.
virtual void onInit ()
 Nodelet initialization routine.

Private Attributes

pcl::ConvexHull< pcl::PointXYZ > impl_
 The PCL implementation used.
ros::Publisher pub_plane_
 Publisher for PolygonStamped.
ros::Subscriber sub_input_
 The input PointCloud subscriber.
boost::shared_ptr
< message_filters::Synchronizer
< sync_policies::ApproximateTime
< PointCloud, PointIndices > > > 
sync_input_indices_a_
boost::shared_ptr
< message_filters::Synchronizer
< sync_policies::ExactTime
< PointCloud, PointIndices > > > 
sync_input_indices_e_
 Synchronized input, and indices.

Detailed Description

ConvexHull2D represents a 2D ConvexHull implementation.

Author:
Radu Bogdan Rusu

Definition at line 51 of file convex_hull.h.


Member Typedef Documentation

typedef pcl::PointCloud<pcl::PointXYZ> pcl_ros::ConvexHull2D::PointCloud [private]

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 46 of file convex_hull.h.

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

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 48 of file convex_hull.h.

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

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 47 of file convex_hull.h.


Member Function Documentation

void pcl_ros::ConvexHull2D::input_indices_callback ( const PointCloudConstPtr cloud,
const PointIndicesConstPtr indices 
) [private]

Input point cloud callback.

Parameters:
cloud the pointer to the input point cloud
indices the pointer to the input point cloud indices

DEBUG

Definition at line 88 of file convex_hull.cpp.

void pcl_ros::ConvexHull2D::onInit (  )  [private, virtual]

Nodelet initialization routine.

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 44 of file convex_hull.cpp.


Member Data Documentation

pcl::ConvexHull<pcl::PointXYZ> pcl_ros::ConvexHull2D::impl_ [private]

The PCL implementation used.

Definition at line 63 of file convex_hull.h.

ros::Publisher pcl_ros::ConvexHull2D::pub_plane_ [private]

Publisher for PolygonStamped.

Definition at line 69 of file convex_hull.h.

ros::Subscriber pcl_ros::ConvexHull2D::sub_input_ [private]

The input PointCloud subscriber.

Definition at line 66 of file convex_hull.h.

boost::shared_ptr<message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud, PointIndices> > > pcl_ros::ConvexHull2D::sync_input_indices_a_ [private]

Definition at line 73 of file convex_hull.h.

boost::shared_ptr<message_filters::Synchronizer<sync_policies::ExactTime<PointCloud, PointIndices> > > pcl_ros::ConvexHull2D::sync_input_indices_e_ [private]

Synchronized input, and indices.

Definition at line 72 of file convex_hull.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