filter_indices.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2010-2012, 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 the copyright holder(s) 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_indices.h 4707 2012-02-23 10:34:17Z florentinus $
00037  *
00038  */
00039 
00040 #ifndef PCL_FILTERS_FILTER_INDICES_H_
00041 #define PCL_FILTERS_FILTER_INDICES_H_
00042 
00043 #include <pcl/filters/filter.h>
00044 
00045 namespace pcl
00046 {
00054   template<typename PointT> void
00055   removeNaNFromPointCloud (const pcl::PointCloud<PointT> &cloud_in, std::vector<int> &index);
00056 
00058 
00067   template<typename PointT>
00068   class FilterIndices : public Filter<PointT>
00069   {
00070     public:
00071       using Filter<PointT>::extract_removed_indices_;
00072       typedef pcl::PointCloud<PointT> PointCloud;
00073 
00074       typedef boost::shared_ptr< FilterIndices<PointT> > Ptr;
00075       typedef boost::shared_ptr< const FilterIndices<PointT> > ConstPtr;
00076 
00077 
00081       FilterIndices (bool extract_removed_indices = false) :
00082           negative_ (false), 
00083           keep_organized_ (false), 
00084           user_filter_value_ (std::numeric_limits<float>::quiet_NaN ())
00085       {
00086         extract_removed_indices_ = extract_removed_indices;
00087       }
00088 
00090       virtual
00091       ~FilterIndices ()
00092       {
00093       }
00094 
00095       inline void
00096       filter (PointCloud &output)
00097       {
00098         pcl::Filter<PointT>::filter (output);
00099       }
00100 
00104       inline void
00105       filter (std::vector<int> &indices)
00106       {
00107         if (!initCompute ())
00108           return;
00109 
00110         // Apply the actual filter
00111         applyFilter (indices);
00112 
00113         deinitCompute ();
00114       }
00115 
00119       inline void
00120       setNegative (bool negative)
00121       {
00122         negative_ = negative;
00123       }
00124 
00128       inline bool
00129       getNegative ()
00130       {
00131         return (negative_);
00132       }
00133 
00138       inline void
00139       setKeepOrganized (bool keep_organized)
00140       {
00141         keep_organized_ = keep_organized;
00142       }
00143 
00148       inline bool
00149       getKeepOrganized ()
00150       {
00151         return (keep_organized_);
00152       }
00153 
00158       inline void
00159       setUserFilterValue (float value)
00160       {
00161         user_filter_value_ = value;
00162       }
00163 
00164     protected:
00165       using Filter<PointT>::initCompute;
00166       using Filter<PointT>::deinitCompute;
00167 
00169       bool negative_;
00170 
00172       bool keep_organized_;
00173 
00175       float user_filter_value_;
00176 
00178       virtual void
00179       applyFilter (std::vector<int> &indices) = 0;
00180   };
00181 
00183 
00192   template<>
00193   class PCL_EXPORTS FilterIndices<pcl::PCLPointCloud2> : public Filter<pcl::PCLPointCloud2>
00194   {
00195     public:
00196       typedef pcl::PCLPointCloud2 PCLPointCloud2;
00197 
00201       FilterIndices (bool extract_removed_indices = false) :
00202           negative_ (false), 
00203           keep_organized_ (false), 
00204           user_filter_value_ (std::numeric_limits<float>::quiet_NaN ())
00205       {
00206         extract_removed_indices_ = extract_removed_indices;
00207       }
00208 
00210       virtual
00211       ~FilterIndices ()
00212       {
00213       }
00214 
00215       virtual void
00216       filter (PCLPointCloud2 &output)
00217       {
00218         pcl::Filter<PCLPointCloud2>::filter (output);
00219       }
00220 
00224       void
00225       filter (std::vector<int> &indices);
00226 
00230       inline void
00231       setNegative (bool negative)
00232       {
00233         negative_ = negative;
00234       }
00235 
00239       inline bool
00240       getNegative ()
00241       {
00242         return (negative_);
00243       }
00244 
00249       inline void
00250       setKeepOrganized (bool keep_organized)
00251       {
00252         keep_organized_ = keep_organized;
00253       }
00254 
00259       inline bool
00260       getKeepOrganized ()
00261       {
00262         return (keep_organized_);
00263       }
00264 
00269       inline void
00270       setUserFilterValue (float value)
00271       {
00272         user_filter_value_ = value;
00273       }
00274 
00275     protected:
00277       bool negative_;
00278 
00280       bool keep_organized_;
00281 
00283       float user_filter_value_;
00284 
00286       virtual void
00287       applyFilter (std::vector<int> &indices) = 0;
00288   };
00289 }
00290 
00291 #ifdef PCL_NO_PRECOMPILE
00292 #include <pcl/filters/impl/filter_indices.hpp>
00293 #endif
00294 
00295 #endif  //#ifndef PCL_FILTERS_FILTER_INDICES_H_
00296 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:24:08