passthrough.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$
00037  *
00038  */
00039 
00040 #ifndef PCL_FILTERS_PASSTHROUGH_H_
00041 #define PCL_FILTERS_PASSTHROUGH_H_
00042 
00043 #include <pcl/filters/filter_indices.h>
00044 
00045 namespace pcl
00046 {
00079   template <typename PointT>
00080   class PassThrough : public FilterIndices<PointT>
00081   {
00082     protected:
00083       typedef typename FilterIndices<PointT>::PointCloud PointCloud;
00084       typedef typename PointCloud::Ptr PointCloudPtr;
00085       typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00086       typedef typename pcl::traits::fieldList<PointT>::type FieldList;
00087 
00088     public:
00089 
00090       typedef boost::shared_ptr< PassThrough<PointT> > Ptr;
00091       typedef boost::shared_ptr< const PassThrough<PointT> > ConstPtr;
00092 
00093 
00097       PassThrough (bool extract_removed_indices = false) :
00098         FilterIndices<PointT>::FilterIndices (extract_removed_indices),
00099         filter_field_name_ (""),
00100         filter_limit_min_ (FLT_MIN),
00101         filter_limit_max_ (FLT_MAX)
00102       {
00103         filter_name_ = "PassThrough";
00104       }
00105 
00110       inline void
00111       setFilterFieldName (const std::string &field_name)
00112       {
00113         filter_field_name_ = field_name;
00114       }
00115 
00119       inline std::string const
00120       getFilterFieldName ()
00121       {
00122         return (filter_field_name_);
00123       }
00124 
00130       inline void
00131       setFilterLimits (const float &limit_min, const float &limit_max)
00132       {
00133         filter_limit_min_ = limit_min;
00134         filter_limit_max_ = limit_max;
00135       }
00136 
00141       inline void
00142       getFilterLimits (float &limit_min, float &limit_max)
00143       {
00144         limit_min = filter_limit_min_;
00145         limit_max = filter_limit_max_;
00146       }
00147 
00153       inline void
00154       setFilterLimitsNegative (const bool limit_negative)
00155       {
00156         negative_ = limit_negative;
00157       }
00158 
00163       inline void
00164       getFilterLimitsNegative (bool &limit_negative)
00165       {
00166         limit_negative = negative_;
00167       }
00168 
00173       inline bool
00174       getFilterLimitsNegative ()
00175       {
00176         return (negative_);
00177       }
00178 
00179     protected:
00180       using PCLBase<PointT>::input_;
00181       using PCLBase<PointT>::indices_;
00182       using Filter<PointT>::filter_name_;
00183       using Filter<PointT>::getClassName;
00184       using FilterIndices<PointT>::negative_;
00185       using FilterIndices<PointT>::keep_organized_;
00186       using FilterIndices<PointT>::user_filter_value_;
00187       using FilterIndices<PointT>::extract_removed_indices_;
00188       using FilterIndices<PointT>::removed_indices_;
00189 
00193       void
00194       applyFilter (PointCloud &output);
00195 
00199       void
00200       applyFilter (std::vector<int> &indices)
00201       {
00202         applyFilterIndices (indices);
00203       }
00204 
00208       void
00209       applyFilterIndices (std::vector<int> &indices);
00210 
00211     private:
00213       std::string filter_field_name_;
00214 
00216       float filter_limit_min_;
00217 
00219       float filter_limit_max_;
00220   };
00221 
00223 
00228   template<>
00229   class PCL_EXPORTS PassThrough<pcl::PCLPointCloud2> : public Filter<pcl::PCLPointCloud2>
00230   {
00231     typedef pcl::PCLPointCloud2 PCLPointCloud2;
00232     typedef PCLPointCloud2::Ptr PCLPointCloud2Ptr;
00233     typedef PCLPointCloud2::ConstPtr PCLPointCloud2ConstPtr;
00234 
00235     using Filter<pcl::PCLPointCloud2>::removed_indices_;
00236     using Filter<pcl::PCLPointCloud2>::extract_removed_indices_;
00237 
00238     public:
00240       PassThrough (bool extract_removed_indices = false) :
00241         Filter<pcl::PCLPointCloud2>::Filter (extract_removed_indices), keep_organized_ (false),
00242         user_filter_value_ (std::numeric_limits<float>::quiet_NaN ()),
00243         filter_field_name_ (""), filter_limit_min_ (-FLT_MAX), filter_limit_max_ (FLT_MAX),
00244         filter_limit_negative_ (false)
00245       {
00246         filter_name_ = "PassThrough";
00247       }
00248 
00257       inline void
00258       setKeepOrganized (bool val)
00259       {
00260         keep_organized_ = val;
00261       }
00262 
00264       inline bool
00265       getKeepOrganized ()
00266       {
00267         return (keep_organized_);
00268       }
00269 
00275       inline void
00276       setUserFilterValue (float val)
00277       {
00278         user_filter_value_ = val;
00279       }
00280 
00285       inline void
00286       setFilterFieldName (const std::string &field_name)
00287       {
00288         filter_field_name_ = field_name;
00289       }
00290 
00292       inline std::string const
00293       getFilterFieldName ()
00294       {
00295         return (filter_field_name_);
00296       }
00297 
00302       inline void
00303       setFilterLimits (const double &limit_min, const double &limit_max)
00304       {
00305         filter_limit_min_ = limit_min;
00306         filter_limit_max_ = limit_max;
00307       }
00308 
00313       inline void
00314       getFilterLimits (double &limit_min, double &limit_max)
00315       {
00316         limit_min = filter_limit_min_;
00317         limit_max = filter_limit_max_;
00318       }
00319 
00324       inline void
00325       setFilterLimitsNegative (const bool limit_negative)
00326       {
00327         filter_limit_negative_ = limit_negative;
00328       }
00329 
00333       inline void
00334       getFilterLimitsNegative (bool &limit_negative)
00335       {
00336         limit_negative = filter_limit_negative_;
00337       }
00338 
00342       inline bool
00343       getFilterLimitsNegative ()
00344       {
00345         return (filter_limit_negative_);
00346       }
00347 
00348     protected:
00349       void
00350       applyFilter (PCLPointCloud2 &output);
00351 
00352     private:
00356       bool keep_organized_;
00357 
00361       float user_filter_value_;
00362 
00364       std::string filter_field_name_;
00365 
00367       double filter_limit_min_;
00368 
00370       double filter_limit_max_;
00371 
00373       bool filter_limit_negative_;
00374 
00375   };
00376 }
00377 
00378 #ifdef PCL_NO_PRECOMPILE
00379 #include <pcl/filters/impl/passthrough.hpp>
00380 #endif
00381 
00382 #endif  // PCL_FILTERS_PASSTHROUGH_H_
00383 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:27:52