00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Point Cloud Library (PCL) - www.pointclouds.org 00005 * Copyright (c) 2010-2011, Willow Garage, Inc. 00006 * 00007 * All rights reserved. 00008 * 00009 * Redistribution and use in source and binary forms, with or without 00010 * modification, are permitted provided that the following conditions 00011 * are met: 00012 * 00013 * * Redistributions of source code must retain the above copyright 00014 * notice, this list of conditions and the following disclaimer. 00015 * * Redistributions in binary form must reproduce the above 00016 * copyright notice, this list of conditions and the following 00017 * disclaimer in the documentation and/or other materials provided 00018 * with the distribution. 00019 * * Neither the name of Willow Garage, Inc. nor the names of its 00020 * contributors may be used to endorse or promote products derived 00021 * from this software without specific prior written permission. 00022 * 00023 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00024 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00025 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00026 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00027 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00028 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00029 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00030 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00031 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00032 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00033 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00034 * POSSIBILITY OF SUCH DAMAGE. 00035 * 00036 * $Id: filter.h 5026 2012-03-12 02:51:44Z rusu $ 00037 * 00038 */ 00039 00040 #ifndef PCL_FILTER_H_ 00041 #define PCL_FILTER_H_ 00042 00043 #include <pcl/pcl_base.h> 00044 #include <pcl/ros/conversions.h> 00045 #include <boost/make_shared.hpp> 00046 #include <cfloat> 00047 00048 namespace pcl 00049 { 00058 template<typename PointT> void 00059 removeNaNFromPointCloud (const pcl::PointCloud<PointT> &cloud_in, 00060 pcl::PointCloud<PointT> &cloud_out, 00061 std::vector<int> &index); 00062 00064 00068 template<typename PointT> 00069 class Filter : public PCLBase<PointT> 00070 { 00071 public: 00072 using PCLBase<PointT>::indices_; 00073 using PCLBase<PointT>::input_; 00074 00075 typedef boost::shared_ptr< Filter<PointT> > Ptr; 00076 typedef boost::shared_ptr< const Filter<PointT> > ConstPtr; 00077 00078 typedef pcl::PointCloud<PointT> PointCloud; 00079 typedef typename PointCloud::Ptr PointCloudPtr; 00080 typedef typename PointCloud::ConstPtr PointCloudConstPtr; 00081 00086 Filter (bool extract_removed_indices = false) : 00087 removed_indices_ (new std::vector<int>), 00088 filter_name_ (), 00089 extract_removed_indices_ (extract_removed_indices) 00090 { 00091 } 00092 00094 inline IndicesConstPtr const 00095 getRemovedIndices () 00096 { 00097 return (removed_indices_); 00098 } 00099 00103 inline void 00104 filter (PointCloud &output) 00105 { 00106 if (!initCompute ()) 00107 return; 00108 00109 // Resize the output dataset 00110 //if (output.points.size () != indices_->size ()) 00111 // output.points.resize (indices_->size ()); 00112 00113 // Copy header at a minimum 00114 output.header = input_->header; 00115 output.sensor_origin_ = input_->sensor_origin_; 00116 output.sensor_orientation_ = input_->sensor_orientation_; 00117 00118 // Apply the actual filter 00119 applyFilter (output); 00120 00121 deinitCompute (); 00122 } 00123 00124 protected: 00125 00126 using PCLBase<PointT>::initCompute; 00127 using PCLBase<PointT>::deinitCompute; 00128 00130 IndicesPtr removed_indices_; 00131 00133 std::string filter_name_; 00134 00136 bool extract_removed_indices_; 00137 00144 virtual void 00145 applyFilter (PointCloud &output) = 0; 00146 00148 inline const std::string& 00149 getClassName () const 00150 { 00151 return (filter_name_); 00152 } 00153 }; 00154 00156 00160 template<> 00161 class PCL_EXPORTS Filter<sensor_msgs::PointCloud2> : public PCLBase<sensor_msgs::PointCloud2> 00162 { 00163 public: 00164 typedef sensor_msgs::PointCloud2 PointCloud2; 00165 typedef PointCloud2::Ptr PointCloud2Ptr; 00166 typedef PointCloud2::ConstPtr PointCloud2ConstPtr; 00167 00172 Filter (bool extract_removed_indices = false) : 00173 removed_indices_ (new std::vector<int>), 00174 extract_removed_indices_ (extract_removed_indices), 00175 filter_name_ () 00176 { 00177 } 00178 00180 inline IndicesConstPtr const 00181 getRemovedIndices () 00182 { 00183 return (removed_indices_); 00184 } 00185 00189 void 00190 filter (PointCloud2 &output); 00191 00192 protected: 00193 00195 IndicesPtr removed_indices_; 00196 00198 bool extract_removed_indices_; 00199 00201 std::string filter_name_; 00202 00209 virtual void 00210 applyFilter (PointCloud2 &output) = 0; 00211 00213 inline const std::string& 00214 getClassName () const 00215 { 00216 return (filter_name_); 00217 } 00218 }; 00219 } 00220 00221 #endif //#ifndef PCL_FILTER_H_