segbot_velodyne_outlier_removal.h
Go to the documentation of this file.
00001 /*
00002  * Because of https://github.com/ros-perception/perception_pcl/issues/9, filter.cpp from pcl_ros is copied into this
00003  * code.
00004  *
00005  * filter.h software license:
00006  *
00007  * Software License Agreement (BSD License)
00008  *
00009  *  Copyright (c) 2009, Willow Garage, Inc.
00010  *  All rights reserved.
00011  *
00012  *  Redistribution and use in source and binary forms, with or without
00013  *  modification, are permitted provided that the following conditions
00014  *  are met:
00015  *
00016  *   * Redistributions of source code must retain the above copyright
00017  *     notice, this list of conditions and the following disclaimer.
00018  *   * Redistributions in binary form must reproduce the above
00019  *     copyright notice, this list of conditions and the following
00020  *     disclaimer in the documentation and/or other materials provided
00021  *     with the distribution.
00022  *   * Neither the name of Willow Garage, Inc. nor the names of its
00023  *     contributors may be used to endorse or promote products derived
00024  *     from this software without specific prior written permission.
00025  *
00026  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00027  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00028  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00029  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00030  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00031  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00032  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00033  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00034  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00035  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00036  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00037  *  POSSIBILITY OF SUCH DAMAGE.
00038  *
00039  * $Id: filter.h 35876 2011-02-09 01:04:36Z rusu $
00040  *
00041  */
00042 
00043 #ifndef SEGBOT_SENSORS_VELODYNE_FILTER_H_
00044 #define SEGBOT_SENSORS_VELODYNE_FILTER_H_
00045 
00046 // PCL includes
00047 #include <pcl/filters/filter.h>
00048 #include "pcl_ros/pcl_nodelet.h"
00049 
00050 // Dynamic reconfigure
00051 #include <dynamic_reconfigure/server.h>
00052 #include "pcl_ros/FilterConfig.h"
00053 
00054 #include <geometry_msgs/Point.h>
00055 
00056 // PCL includes
00057 #include <pcl_ros/filters/filter.h>
00058 
00059 // Dynamic reconfigure
00060 #include <segbot_sensors/SegbotVelodyneOutlierRemovalConfig.h>
00061 
00062 namespace segbot_sensors
00063 {
00064   namespace sync_policies = message_filters::sync_policies;
00065 
00066   using namespace pcl_ros;
00067 
00072   class Filter : public PCLNodelet
00073   {
00074     public:
00075       typedef sensor_msgs::PointCloud2 PointCloud2;
00076 
00077       typedef boost::shared_ptr <std::vector<int> > IndicesPtr;
00078       typedef boost::shared_ptr <const std::vector<int> > IndicesConstPtr;
00079 
00080       Filter () {}
00081 
00082     protected:
00084       ros::Subscriber sub_input_;
00085 
00086       message_filters::Subscriber<PointCloud2> sub_input_filter_;
00087 
00089       std::string filter_field_name_;
00090 
00092       double filter_limit_min_;
00093 
00095       double filter_limit_max_;
00096 
00098       bool filter_limit_negative_;
00099 
00101       std::string tf_input_frame_;
00102 
00104       std::string tf_input_orig_frame_;
00105 
00107       std::string tf_output_frame_;
00108 
00110       boost::mutex mutex_;
00111 
00116       virtual bool
00117       child_init (ros::NodeHandle &nh, bool &has_service)
00118       {
00119         has_service = false;
00120         return (true);
00121       }
00122 
00128       virtual void
00129       filter (const PointCloud2::ConstPtr &input, const IndicesPtr &indices,
00130               PointCloud2 &output) = 0;
00131 
00133       virtual void
00134       onInit ();
00135 
00140       void
00141       computePublish (const PointCloud2::ConstPtr &input, const IndicesPtr &indices);
00142 
00143     private:
00145       boost::shared_ptr<dynamic_reconfigure::Server<pcl_ros::FilterConfig> > srv_;
00146 
00148       boost::shared_ptr<message_filters::Synchronizer<sync_policies::ExactTime<PointCloud2, PointIndices> > >       sync_input_indices_e_;
00149       boost::shared_ptr<message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud2, PointIndices> > > sync_input_indices_a_;
00150 
00152       virtual void
00153       config_callback (pcl_ros::FilterConfig &config, uint32_t level);
00154 
00156       void
00157       input_indices_callback (const PointCloud2::ConstPtr &cloud,
00158                               const PointIndicesConstPtr &indices);
00159     public:
00160       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00161   };
00162 
00163   class SegbotVelodyneOutlierRemoval : public Filter
00164   {
00165     protected:
00167       boost::shared_ptr <dynamic_reconfigure::Server<SegbotVelodyneOutlierRemovalConfig> > srv_;
00168 
00174       inline void
00175       filter (const PointCloud2::ConstPtr &input, const IndicesPtr &indices,
00176               PointCloud2 &output)
00177       {
00178         boost::mutex::scoped_lock lock (mutex_);
00179         pcl::PCLPointCloud2::Ptr pcl_cloud(new pcl::PCLPointCloud2);
00180         pcl_conversions::toPCL(*input, *pcl_cloud);
00181         pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
00182         pcl::fromPCLPointCloud2(*pcl_cloud, *cloud);
00183 
00184         for (pcl::PointCloud<pcl::PointXYZ>::iterator it = cloud->begin(); it != cloud->end();) {
00185           // http://www.ecse.rpi.edu/Homepages/wrf/Research/Short_Notes/pnpoly.html
00186           float &x = it->x;
00187           float &y = it->y;
00188           bool point_not_in_polygon = false;
00189           for (int i = 0, j = footprint_.size() - 1; i < footprint_.size(); j = i++) {
00190             if (((footprint_[i].y > y) != (footprint_[j].y > y)) &&
00191                 (x < (footprint_[j].x - footprint_[i].x) * (y - footprint_[i].y) / (footprint_[j].y - footprint_[i].y) + footprint_[i].x)) {
00192               point_not_in_polygon = !point_not_in_polygon;
00193             }
00194           }
00195           if (point_not_in_polygon) {
00196             it = cloud->erase(it);
00197           } else {
00198             // Keep the point.
00199             ++it;
00200           }
00201         }
00202 
00203         pcl::toPCLPointCloud2(*cloud, *pcl_cloud);
00204         pcl_conversions::moveFromPCL(*pcl_cloud, output);
00205       }
00206 
00211       bool child_init (ros::NodeHandle &nh, bool &has_service);
00212 
00217       void config_callback (segbot_sensors::SegbotVelodyneOutlierRemovalConfig &config, uint32_t level);
00218 
00219     public:
00220       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00221 
00222     private:
00223       std::vector<geometry_msgs::Point> footprint_;
00224       boost::shared_ptr<ros::Publisher> footprint_publisher_;
00225       std::string frame_;
00226   };
00227 }
00228 
00229 #endif


segbot_sensors
Author(s): Piyush Khandelwal
autogenerated on Thu Jun 6 2019 21:37:13