38 #ifndef PCL_ROS_CONVEX_HULL_2D_H_ 39 #define PCL_ROS_CONVEX_HULL_2D_H_ 44 #include <pcl/surface/convex_hull.h> 47 #include <dynamic_reconfigure/server.h> 79 pcl::ConvexHull<pcl::PointXYZ>
impl_;
92 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
96 #endif //#ifndef PCL_ROS_CONVEX_HULL_2D_H_ virtual void unsubscribe()
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloud, PointIndices > > > sync_input_indices_e_
Synchronized input, and indices.
ros::Subscriber sub_input_
The input PointCloud subscriber.
ros::Publisher pub_plane_
Publisher for PolygonStamped.
ConvexHull2D represents a 2D ConvexHull implementation.
void input_indices_callback(const PointCloudConstPtr &cloud, const PointIndicesConstPtr &indices)
Input point cloud callback.
PointCloud::Ptr PointCloudPtr
virtual void subscribe()
LazyNodelet connection routine.
pcl::ConvexHull< pcl::PointXYZ > impl_
The PCL implementation used.
PCLNodelet represents the base PCL Nodelet class. All PCL nodelets should inherit from this class...
virtual void onInit()
Nodelet initialization routine.
pcl::PointCloud< pcl::PointXYZ > PointCloud
PointCloud::ConstPtr PointCloudConstPtr
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloud, PointIndices > > > sync_input_indices_a_
PointIndices::ConstPtr PointIndicesConstPtr