ConvexHull2D represents a 2D ConvexHull implementation. More...
#include <convex_hull.h>

| 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. | |
ConvexHull2D represents a 2D ConvexHull implementation.
Definition at line 56 of file convex_hull.h.
| typedef pcl::PointCloud<pcl::PointXYZ> pcl_ros::ConvexHull2D::PointCloud  [private] | 
Reimplemented from pcl_ros::PCLNodelet.
Definition at line 58 of file convex_hull.h.
| typedef PointCloud::ConstPtr pcl_ros::ConvexHull2D::PointCloudConstPtr  [private] | 
Reimplemented from pcl_ros::PCLNodelet.
Definition at line 60 of file convex_hull.h.
| typedef PointCloud::Ptr pcl_ros::ConvexHull2D::PointCloudPtr  [private] | 
Reimplemented from pcl_ros::PCLNodelet.
Definition at line 59 of file convex_hull.h.
| void pcl_ros::ConvexHull2D::input_indices_callback | ( | const PointCloudConstPtr & | cloud, | 
| const PointIndicesConstPtr & | indices | ||
| ) |  [private] | 
Input point cloud callback.
| cloud | the pointer to the input point cloud | 
| indices | the pointer to the input point cloud indices | 
DEBUG
Definition at line 89 of file convex_hull.cpp.
| void pcl_ros::ConvexHull2D::onInit | ( | ) |  [private, virtual] | 
Nodelet initialization routine.
Reimplemented from pcl_ros::PCLNodelet.
Definition at line 45 of file convex_hull.cpp.
| pcl::ConvexHull<pcl::PointXYZ> pcl_ros::ConvexHull2D::impl_  [private] | 
The PCL implementation used.
Definition at line 75 of file convex_hull.h.
Publisher for PolygonStamped.
Definition at line 81 of file convex_hull.h.
The input PointCloud subscriber.
Definition at line 78 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 85 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 84 of file convex_hull.h.