extract_polygonal_prism_data.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: extract_polygonal_prism_data.h 35361 2011-01-20 04:34:49Z rusu $
35  *
36  */
37 
38 #ifndef PCL_ROS_EXTRACT_POLYGONAL_PRISM_DATA_H_
39 #define PCL_ROS_EXTRACT_POLYGONAL_PRISM_DATA_H_
40 
41 #include "pcl_ros/pcl_nodelet.h"
45 
46 // PCL includes
47 #include <pcl/segmentation/extract_polygonal_prism_data.h>
48 
49 // Dynamic reconfigure
50 #include <dynamic_reconfigure/server.h>
51 #include "pcl_ros/ExtractPolygonalPrismDataConfig.h"
52 
53 namespace pcl_ros
54 {
56 
65  {
66  typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
67  typedef PointCloud::Ptr PointCloudPtr;
68  typedef PointCloud::ConstPtr PointCloudConstPtr;
69 
70  protected:
73 
76 
80 
83 
87 
92  inline void
93  input_callback (const PointCloudConstPtr &input)
94  {
95  PointIndices cloud;
96  cloud.header.stamp = pcl_conversions::fromPCL(input->header).stamp;
97  nf_.add (boost::make_shared<PointIndices> (cloud));
98  }
99 
101  void onInit ();
102 
104  void subscribe ();
105  void unsubscribe ();
106 
111  void config_callback (ExtractPolygonalPrismDataConfig &config, uint32_t level);
112 
118  void input_hull_indices_callback (const PointCloudConstPtr &cloud,
119  const PointCloudConstPtr &hull,
120  const PointIndicesConstPtr &indices);
121 
122  private:
124  pcl::ExtractPolygonalPrismData<pcl::PointXYZ> impl_;
125  public:
126  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
127  };
128 }
129 
130 #endif //#ifndef PCL_EXTRACT_POLYGONAL_PRISM_DATA_H_
void onInit()
Nodelet initialization routine.
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloud, PointCloud, PointIndices > > > sync_input_hull_indices_e_
Synchronized input, planar hull, and indices.
pcl::PointCloud< pcl::PointXYZ > PointCloud
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.
ros::Publisher pub_output_
The output PointIndices publisher.
void input_callback(const PointCloudConstPtr &input)
Input point cloud callback. Because we want to use the same synchronizer object, we push back empty e...
void fromPCL(const pcl::uint64_t &pcl_stamp, ros::Time &stamp)
void input_hull_indices_callback(const PointCloudConstPtr &cloud, const PointCloudConstPtr &hull, const PointIndicesConstPtr &indices)
Input point cloud callback. Used when use_indices is set.
PCLNodelet represents the base PCL Nodelet class. All PCL nodelets should inherit from this class...
Definition: pcl_nodelet.h:72
pcl_msgs::PointIndices PointIndices
Definition: pcl_nodelet.h:81
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloud, PointCloud, PointIndices > > > sync_input_hull_indices_a_
message_filters::Subscriber< PointCloud > sub_hull_filter_
The message filter subscriber for PointCloud2.
void add(const MConstPtr &msg)
pcl::ExtractPolygonalPrismData< pcl::PointXYZ > impl_
The PCL implementation used.
void subscribe()
LazyNodelet connection routine.
message_filters::PassThrough< PointIndices > nf_
Null passthrough filter, used for pushing empty elements in the synchronizer.
void config_callback(ExtractPolygonalPrismDataConfig &config, uint32_t level)
Dynamic reconfigure callback.
boost::shared_ptr< dynamic_reconfigure::Server< ExtractPolygonalPrismDataConfig > > srv_
Pointer to a dynamic reconfigure service.
PointIndices::ConstPtr PointIndicesConstPtr
Definition: pcl_nodelet.h:83


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Wed Jun 5 2019 19:52:52