filter.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2009, 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: filter.h 35876 2011-02-09 01:04:36Z rusu $
00035  *
00036  */
00037 
00038 #ifndef PCL_ROS_FILTER_H_
00039 #define PCL_ROS_FILTER_H_
00040 
00041 // PCL includes
00042 #include <pcl/filters/filter.h>
00043 #include "pcl_ros/pcl_nodelet.h"
00044 
00045 // Dynamic reconfigure
00046 #include <dynamic_reconfigure/server.h>
00047 #include "pcl_ros/FilterConfig.h"
00048 
00049 namespace pcl_ros
00050 {
00051   namespace sync_policies = message_filters::sync_policies;
00052 
00057   class Filter : public PCLNodelet
00058   {
00059     public:
00060       typedef sensor_msgs::PointCloud2 PointCloud2;
00061 
00062       typedef boost::shared_ptr <std::vector<int> > IndicesPtr;
00063       typedef boost::shared_ptr <const std::vector<int> > IndicesConstPtr;
00064 
00065       Filter () {}
00066 
00067     protected:
00069       ros::Subscriber sub_input_;
00070 
00071       message_filters::Subscriber<PointCloud2> sub_input_filter_;
00072 
00074       std::string filter_field_name_;
00075 
00077       double filter_limit_min_;
00078 
00080       double filter_limit_max_;
00081 
00083       bool filter_limit_negative_;
00084 
00086       std::string tf_input_frame_;
00087 
00089       std::string tf_input_orig_frame_;
00090 
00092       std::string tf_output_frame_;
00093 
00095       boost::mutex mutex_;
00096 
00101       virtual bool 
00102       child_init (ros::NodeHandle &nh, bool &has_service) 
00103       { 
00104         has_service = false; 
00105         return (true); 
00106       }
00107 
00113       virtual void 
00114       filter (const PointCloud2::ConstPtr &input, const IndicesPtr &indices, 
00115               PointCloud2 &output) = 0;
00116 
00118       virtual void 
00119       onInit ();
00120 
00125       void 
00126       computePublish (const PointCloud2::ConstPtr &input, const IndicesPtr &indices);
00127 
00128     private:
00130       boost::shared_ptr<dynamic_reconfigure::Server<pcl_ros::FilterConfig> > srv_;
00131 
00133       boost::shared_ptr<message_filters::Synchronizer<sync_policies::ExactTime<PointCloud2, PointIndices> > >       sync_input_indices_e_;
00134       boost::shared_ptr<message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud2, PointIndices> > > sync_input_indices_a_;
00135 
00137       virtual void 
00138       config_callback (pcl_ros::FilterConfig &config, uint32_t level);
00139 
00141       void 
00142       input_indices_callback (const PointCloud2::ConstPtr &cloud, 
00143                               const PointIndicesConstPtr &indices);
00144     public:
00145       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00146   };
00147 }
00148 
00149 #endif  //#ifndef PCL_ROS_FILTER_H_


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