convex_hull.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2010, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage, Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *
34  * $Id: convex_hull.h 36116 2011-02-22 00:05:23Z rusu $
35  *
36  */
37 
38 #ifndef PCL_ROS_CONVEX_HULL_2D_H_
39 #define PCL_ROS_CONVEX_HULL_2D_H_
40 
41 #include "pcl_ros/pcl_nodelet.h"
42 
43 // PCL includes
44 #include <pcl/surface/convex_hull.h>
45 
46 namespace pcl_ros
47 {
49 
53  class ConvexHull2D : public PCLNodelet
54  {
55  typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
58 
59  private:
61  virtual void onInit ();
62 
64  virtual void subscribe ();
65  virtual void unsubscribe ();
66 
71  void input_indices_callback (const PointCloudConstPtr &cloud,
72  const PointIndicesConstPtr &indices);
73 
74  private:
76  pcl::ConvexHull<pcl::PointXYZ> impl_;
77 
80 
83 
87 
88  public:
89  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
90  };
91 }
92 
93 #endif //#ifndef PCL_ROS_CONVEX_HULL_2D_H_
ros::Publisher
pcl_ros::PCLNodelet
PCLNodelet represents the base PCL Nodelet class. All PCL nodelets should inherit from this class.
Definition: pcl_nodelet.h:73
boost::shared_ptr
pcl_ros
Definition: boundary.h:46
pcl_ros::ConvexHull2D::impl_
pcl::ConvexHull< pcl::PointXYZ > impl_
The PCL implementation used.
Definition: convex_hull.h:76
pcl_ros::ConvexHull2D::sync_input_indices_a_
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloud, PointIndices > > > sync_input_indices_a_
Definition: convex_hull.h:86
pcl_ros::ConvexHull2D::subscribe
virtual void subscribe()
LazyNodelet connection routine.
Definition: convex_hull.cpp:64
pcl_ros::ConvexHull2D::sync_input_indices_e_
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloud, PointIndices > > > sync_input_indices_e_
Synchronized input, and indices.
Definition: convex_hull.h:85
pcl_ros::PCLNodelet::PointIndicesConstPtr
PointIndices::ConstPtr PointIndicesConstPtr
Definition: pcl_nodelet.h:84
pcl_nodelet.h
pcl_ros::ConvexHull2D::onInit
virtual void onInit()
Nodelet initialization routine.
Definition: convex_hull.cpp:44
pcl_ros::ConvexHull2D::PointCloud
pcl::PointCloud< pcl::PointXYZ > PointCloud
Definition: convex_hull.h:55
pcl_ros::ConvexHull2D::input_indices_callback
void input_indices_callback(const PointCloudConstPtr &cloud, const PointIndicesConstPtr &indices)
Input point cloud callback.
Definition: convex_hull.cpp:109
pcl_ros::ConvexHull2D::PointCloudConstPtr
boost::shared_ptr< const PointCloud > PointCloudConstPtr
Definition: convex_hull.h:57
message_filters::sync_policies
pcl_ros::ConvexHull2D::sub_input_
ros::Subscriber sub_input_
The input PointCloud subscriber.
Definition: convex_hull.h:79
pcl_ros::ConvexHull2D::PointCloudPtr
boost::shared_ptr< PointCloud > PointCloudPtr
Definition: convex_hull.h:56
pcl_ros::ConvexHull2D::unsubscribe
virtual void unsubscribe()
Definition: convex_hull.cpp:96
pcl_ros::ConvexHull2D
ConvexHull2D represents a 2D ConvexHull implementation.
Definition: convex_hull.h:53
pcl_ros::ConvexHull2D::pub_plane_
ros::Publisher pub_plane_
Publisher for PolygonStamped.
Definition: convex_hull.h:82
ros::Subscriber


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Fri Jul 12 2024 02:54:40