extract_polygonal_prism_data.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  * $Id: extract_polygonal_prism_data.h 35361 2011-01-20 04:34:49Z rusu $
00035  *
00036  */
00037 
00038 #ifndef PCL_ROS_EXTRACT_POLYGONAL_PRISM_DATA_H_
00039 #define PCL_ROS_EXTRACT_POLYGONAL_PRISM_DATA_H_
00040 
00041 #include "pcl_ros/pcl_nodelet.h"
00042 #include <message_filters/sync_policies/exact_time.h>
00043 #include <message_filters/sync_policies/approximate_time.h>
00044 #include <message_filters/pass_through.h>
00045 
00046 // PCL includes
00047 #include <pcl/segmentation/extract_polygonal_prism_data.h>
00048 
00049 // Dynamic reconfigure
00050 #include <dynamic_reconfigure/server.h>
00051 #include "pcl_ros/ExtractPolygonalPrismDataConfig.h"
00052 
00053 namespace pcl_ros
00054 {
00055   namespace sync_policies = message_filters::sync_policies;
00056 
00064   class ExtractPolygonalPrismData : public PCLNodelet
00065   {
00066     typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
00067     typedef PointCloud::Ptr PointCloudPtr;
00068     typedef PointCloud::ConstPtr PointCloudConstPtr;
00069 
00070     protected:
00072       ros::Publisher pub_output_;
00073 
00075       message_filters::Subscriber<PointCloud> sub_hull_filter_;
00076 
00078       boost::shared_ptr<message_filters::Synchronizer<sync_policies::ExactTime<PointCloud, PointCloud, PointIndices> > > sync_input_hull_indices_e_;
00079       boost::shared_ptr<message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud, PointCloud, PointIndices> > > sync_input_hull_indices_a_;
00080 
00082       boost::shared_ptr<dynamic_reconfigure::Server<ExtractPolygonalPrismDataConfig> > srv_;
00083 
00086       message_filters::PassThrough<PointIndices> nf_;
00087 
00092       inline void
00093       input_callback (const PointCloudConstPtr &input)
00094       {
00095         PointIndices cloud;
00096         cloud.header.stamp = pcl_conversions::fromPCL(input->header).stamp;
00097         nf_.add (boost::make_shared<PointIndices> (cloud));
00098       }
00099 
00101       void onInit ();
00102 
00107       void config_callback (ExtractPolygonalPrismDataConfig &config, uint32_t level);
00108 
00114       void input_hull_indices_callback (const PointCloudConstPtr &cloud, 
00115                                         const PointCloudConstPtr &hull, 
00116                                         const PointIndicesConstPtr &indices);
00117 
00118     private:
00120       pcl::ExtractPolygonalPrismData<pcl::PointXYZ> impl_;
00121     public:
00122       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00123   };
00124 }
00125 
00126 #endif  //#ifndef PCL_EXTRACT_POLYGONAL_PRISM_DATA_H_


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Thu May 5 2016 04:16:43