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 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_indices.h 6144 2012-07-04 22:06:28Z rusu $
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       typedef pcl::PointCloud<PointT> PointCloud;
00072 
00076       FilterIndices (bool extract_removed_indices = false) :
00077           negative_ (false), 
00078           keep_organized_ (false), 
00079           extract_removed_indices_ (extract_removed_indices), 
00080           user_filter_value_ (std::numeric_limits<float>::quiet_NaN ()),
00081           removed_indices_ (new std::vector<int> ())
00082       {
00083       }
00084 
00086       virtual
00087       ~FilterIndices ()
00088       {
00089       }
00090 
00091       inline void
00092       filter (PointCloud &output)
00093       {
00094         pcl::Filter<PointT>::filter (output);
00095       }
00096 
00100       inline void
00101       filter (std::vector<int> &indices)
00102       {
00103         if (!initCompute ())
00104           return;
00105 
00106         // Apply the actual filter
00107         applyFilter (indices);
00108 
00109         deinitCompute ();
00110       }
00111 
00115       inline void
00116       setNegative (bool negative)
00117       {
00118         negative_ = negative;
00119       }
00120 
00124       inline bool
00125       getNegative ()
00126       {
00127         return (negative_);
00128       }
00129 
00134       inline void
00135       setKeepOrganized (bool keep_organized)
00136       {
00137         keep_organized_ = keep_organized;
00138       }
00139 
00144       inline bool
00145       getKeepOrganized ()
00146       {
00147         return (keep_organized_);
00148       }
00149 
00154       inline void
00155       setUserFilterValue (float value)
00156       {
00157         user_filter_value_ = value;
00158       }
00159 
00163       inline IndicesConstPtr const
00164       getRemovedIndices ()
00165       {
00166         return (removed_indices_);
00167       }
00168 
00169     protected:
00170       using Filter<PointT>::initCompute;
00171       using Filter<PointT>::deinitCompute;
00172 
00174       bool negative_;
00175 
00177       bool keep_organized_;
00178 
00180       bool extract_removed_indices_;
00181 
00183       float user_filter_value_;
00184 
00186       IndicesPtr removed_indices_;
00187 
00189       virtual void
00190       applyFilter (std::vector<int> &indices) = 0;
00191   };
00192 
00194 
00203   template<>
00204   class PCL_EXPORTS FilterIndices<sensor_msgs::PointCloud2> : public Filter<sensor_msgs::PointCloud2>
00205   {
00206     public:
00207       typedef sensor_msgs::PointCloud2 PointCloud2;
00208 
00212       FilterIndices (bool extract_removed_indices = false) :
00213           negative_ (false), 
00214           keep_organized_ (false), 
00215           extract_removed_indices_ (extract_removed_indices), 
00216           user_filter_value_ (std::numeric_limits<float>::quiet_NaN ()),
00217           removed_indices_ (new std::vector<int>)
00218       {
00219       }
00220 
00222       virtual
00223       ~FilterIndices ()
00224       {
00225       }
00226 
00227       virtual void
00228       filter (PointCloud2 &output)
00229       {
00230         pcl::Filter<PointCloud2>::filter (output);
00231       }
00232 
00236       void
00237       filter (std::vector<int> &indices);
00238 
00242       inline void
00243       setNegative (bool negative)
00244       {
00245         negative_ = negative;
00246       }
00247 
00251       inline bool
00252       getNegative ()
00253       {
00254         return (negative_);
00255       }
00256 
00261       inline void
00262       setKeepOrganized (bool keep_organized)
00263       {
00264         keep_organized_ = keep_organized;
00265       }
00266 
00271       inline bool
00272       getKeepOrganized ()
00273       {
00274         return (keep_organized_);
00275       }
00276 
00281       inline void
00282       setUserFilterValue (float value)
00283       {
00284         user_filter_value_ = value;
00285       }
00286 
00290       inline IndicesConstPtr const
00291       getRemovedIndices ()
00292       {
00293         return (removed_indices_);
00294       }
00295 
00296     protected:
00298       bool negative_;
00299 
00301       bool keep_organized_;
00302 
00304       bool extract_removed_indices_;
00305 
00307       float user_filter_value_;
00308 
00310       IndicesPtr removed_indices_;
00311 
00313       virtual void
00314       applyFilter (std::vector<int> &indices) = 0;
00315   };
00316 }
00317 
00318 #endif  //#ifndef PCL_FILTERS_FILTER_INDICES_H_
00319 


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:15:11