conditional_removal.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  * $Id: conditional_removal.h 5656 2012-05-01 06:22:33Z rusu $
00035  *
00036  */
00037 
00038 #ifndef PCL_FILTER_FIELD_VAL_CONDITION_H_
00039 #define PCL_FILTER_FIELD_VAL_CONDITION_H_
00040 
00041 #include <pcl/filters/filter.h>
00042 
00043 namespace pcl
00044 {
00046   namespace ComparisonOps
00047   {
00051     typedef enum
00052     {
00053       GT, GE, LT, LE, EQ
00054     } CompareOp;
00055   }
00056 
00058 
00059   template<typename PointT>
00060   class PointDataAtOffset
00061   {
00062     public:
00064       PointDataAtOffset (uint8_t datatype, uint32_t offset) :
00065         datatype_ (datatype), offset_ (offset)
00066       {
00067       }
00068 
00073       int
00074       compare (const PointT& p, const double& val);
00075     protected:
00077       uint8_t datatype_;
00078 
00080       uint32_t offset_;
00081     private:
00082       PointDataAtOffset () : datatype_ (), offset_ () {}
00083   };
00084 
00086 
00087   template<typename PointT>
00088   class ComparisonBase
00089   {
00090     public:
00091       typedef boost::shared_ptr<ComparisonBase<PointT> > Ptr;
00092       typedef boost::shared_ptr<const ComparisonBase<PointT> > ConstPtr;
00093 
00095       ComparisonBase () : capable_ (false), field_name_ (), offset_ (), op_ () {}
00096 
00098       virtual ~ComparisonBase () {}
00099 
00101       inline bool
00102       isCapable () const
00103       {
00104         return (capable_);
00105       }
00106 
00108       virtual bool
00109       evaluate (const PointT &point) const = 0;
00110 
00111     protected:
00113       bool capable_;
00114 
00116       std::string field_name_;
00117 
00119       uint32_t offset_;
00120 
00122       ComparisonOps::CompareOp op_;
00123   };
00124 
00126 
00127   template<typename PointT>
00128   class FieldComparison : public ComparisonBase<PointT>
00129   {
00130     using ComparisonBase<PointT>::field_name_;
00131     using ComparisonBase<PointT>::op_;
00132     using ComparisonBase<PointT>::capable_;
00133 
00134     public:
00135       typedef boost::shared_ptr<FieldComparison<PointT> > Ptr;
00136       typedef boost::shared_ptr<const FieldComparison<PointT> > ConstPtr;
00137 
00143       FieldComparison (std::string field_name, ComparisonOps::CompareOp op, double compare_val);
00144 
00148       FieldComparison (const FieldComparison &src) :
00149         compare_val_ (src.compare_val_), point_data_ (src.point_data_)
00150       {
00151       }
00152 
00156       inline FieldComparison&
00157       operator = (const FieldComparison &src)
00158       {
00159         compare_val_ = src.compare_val_;
00160         point_data_  = src.point_data_;
00161         return (*this);
00162       }
00163 
00165       virtual ~FieldComparison ();
00166 
00171       virtual bool
00172       evaluate (const PointT &point) const;
00173 
00174     protected:
00176       double compare_val_;
00177 
00179       PointDataAtOffset<PointT>* point_data_;
00180 
00181     private:
00182       FieldComparison () :
00183         compare_val_ (), point_data_ ()
00184       {
00185       } // not allowed
00186   };
00187 
00189 
00190   template<typename PointT>
00191   class PackedRGBComparison : public ComparisonBase<PointT>
00192   {
00193     using ComparisonBase<PointT>::capable_;
00194     using ComparisonBase<PointT>::op_;
00195 
00196     public:
00202       PackedRGBComparison (std::string component_name, ComparisonOps::CompareOp op, double compare_val);
00203 
00205       virtual ~PackedRGBComparison () {}
00206 
00211       virtual bool
00212       evaluate (const PointT &point) const;
00213 
00214     protected:
00216       std::string component_name_;
00217 
00219       uint32_t component_offset_;
00220 
00222       double compare_val_;
00223 
00224     private:
00225       PackedRGBComparison () :
00226         component_name_ (), component_offset_ (), compare_val_ ()
00227       {
00228       } // not allowed
00229 
00230   };
00231 
00233 
00234   template<typename PointT>
00235   class PackedHSIComparison : public ComparisonBase<PointT>
00236   {
00237     using ComparisonBase<PointT>::capable_;
00238     using ComparisonBase<PointT>::op_;
00239 
00240     public:
00246       PackedHSIComparison (std::string component_name, ComparisonOps::CompareOp op, double compare_val);
00247 
00249       virtual ~PackedHSIComparison () {}
00250 
00255       virtual bool
00256       evaluate (const PointT &point) const;
00257 
00258       typedef enum
00259       {
00260         H, // -128 to 127 corresponds to -pi to pi
00261         S, // 0 to 255
00262         I  // 0 to 255
00263       } ComponentId;
00264 
00265     protected:
00267       std::string component_name_;
00268 
00270       ComponentId component_id_;
00271 
00273       double compare_val_;
00274 
00276       uint32_t rgb_offset_;
00277 
00278     private:
00279       PackedHSIComparison () :
00280         component_name_ (), component_id_ (), compare_val_ (), rgb_offset_ ()
00281       {
00282       } // not allowed
00283   };
00284   
00286 
00292   template<typename PointT>
00293   class TfQuadraticXYZComparison : public pcl::ComparisonBase<PointT>
00294   {
00295     public:
00296       EIGEN_MAKE_ALIGNED_OPERATOR_NEW     //needed whenever there is a fixed size Eigen:: vector or matrix in a class
00297 
00298       typedef boost::shared_ptr<TfQuadraticXYZComparison<PointT> > Ptr;
00299       typedef boost::shared_ptr<const TfQuadraticXYZComparison<PointT> > ConstPtr;
00300 
00303       TfQuadraticXYZComparison ();
00304 
00312       TfQuadraticXYZComparison (const pcl::ComparisonOps::CompareOp op, const Eigen::Matrix3f &comparison_matrix,
00313                                 const Eigen::Vector3f &comparison_vector, const float &comparison_scalar,
00314                                 const Eigen::Affine3f &comparison_transform = Eigen::Affine3f::Identity ());
00315 
00318       inline void
00319       setComparisonOperator (const pcl::ComparisonOps::CompareOp op)
00320       {
00321         op_ = op;
00322       }
00323 
00326       inline void
00327       setComparisonMatrix (const Eigen::Matrix3f &matrix)
00328       {
00329         //define comp_matr_ as an homogeneous matrix of the given matrix
00330         comp_matr_.block<3, 3> (0, 0) = matrix;
00331         comp_matr_.col (3) << 0, 0, 0, 1;
00332         comp_matr_.block<1, 3> (3, 0) << 0, 0, 0;
00333         tf_comp_matr_ = comp_matr_;
00334       }
00335 
00338       inline void
00339       setComparisonMatrix (const Eigen::Matrix4f &homogeneousMatrix)
00340       {
00341         comp_matr_ = homogeneousMatrix;
00342         tf_comp_matr_ = comp_matr_;
00343       }
00344 
00347       inline void
00348       setComparisonVector (const Eigen::Vector3f &vector)
00349       {
00350         comp_vect_ = vector.homogeneous ();
00351         tf_comp_vect_ = comp_vect_;
00352       }
00353 
00356       inline void
00357       setComparisonVector (const Eigen::Vector4f &homogeneousVector)
00358       {
00359         comp_vect_ = homogeneousVector;
00360         tf_comp_vect_ = comp_vect_;
00361       }
00362 
00365       inline void
00366       setComparisonScalar (const float &scalar)
00367       {
00368         comp_scalar_ = scalar;
00369       }
00370 
00380       inline void
00381       transformComparison (const Eigen::Matrix4f &transform)
00382       {
00383         tf_comp_matr_ = transform.transpose () * comp_matr_ * transform;
00384         tf_comp_vect_ = comp_vect_.transpose () * transform;
00385       }
00386 
00396       inline void
00397       transformComparison (const Eigen::Affine3f &transform)
00398       {
00399         transformComparison (transform.matrix ());
00400       }
00401 
00406       virtual bool
00407       evaluate (const PointT &point) const;
00408 
00409     protected:
00410       using pcl::ComparisonBase<PointT>::capable_;
00411       using pcl::ComparisonBase<PointT>::op_;
00412 
00413       Eigen::Matrix4f comp_matr_;
00414       Eigen::Vector4f comp_vect_;
00415 
00416       float comp_scalar_;
00417 
00418     private:
00419       Eigen::Matrix4f tf_comp_matr_;
00420       Eigen::Vector4f tf_comp_vect_;
00421   };
00422   
00424 
00425   template<typename PointT>
00426   class ConditionBase
00427   {
00428     public:
00429       typedef typename pcl::ComparisonBase<PointT> ComparisonBase;
00430       typedef typename ComparisonBase::Ptr ComparisonBasePtr;
00431       typedef typename ComparisonBase::ConstPtr ComparisonBaseConstPtr;
00432 
00433       typedef boost::shared_ptr<ConditionBase<PointT> > Ptr;
00434       typedef boost::shared_ptr<const ConditionBase<PointT> > ConstPtr;
00435 
00437       ConditionBase () : capable_ (true), comparisons_ (), conditions_ ()
00438       {
00439       }
00440 
00442       virtual ~ConditionBase ()
00443       {
00444         // comparisons are boost::shared_ptr.will take care of themselves
00445         comparisons_.clear ();
00446 
00447         // conditions are boost::shared_ptr. will take care of themselves
00448         conditions_.clear ();
00449       }
00450 
00454       void
00455       addComparison (ComparisonBaseConstPtr comparison);
00456 
00460       void
00461       addCondition (Ptr condition);
00462 
00464       inline bool
00465       isCapable () const
00466       {
00467         return (capable_);
00468       }
00469 
00473       virtual bool
00474       evaluate (const PointT &point) const = 0;
00475 
00476     protected:
00478       bool capable_;
00479 
00481       std::vector<ComparisonBaseConstPtr> comparisons_;
00482 
00484       std::vector<Ptr> conditions_;
00485   };
00486 
00488 
00489   template<typename PointT>
00490   class ConditionAnd : public ConditionBase<PointT>
00491   {
00492     using ConditionBase<PointT>::conditions_;
00493     using ConditionBase<PointT>::comparisons_;
00494 
00495     public:
00496       typedef boost::shared_ptr<ConditionAnd<PointT> > Ptr;
00497       typedef boost::shared_ptr<const ConditionAnd<PointT> > ConstPtr;
00498 
00500       ConditionAnd () :
00501         ConditionBase<PointT> ()
00502       {
00503       }
00504 
00511       virtual bool
00512       evaluate (const PointT &point) const;
00513   };
00514 
00516 
00517   template<typename PointT>
00518   class ConditionOr : public ConditionBase<PointT>
00519   {
00520     using ConditionBase<PointT>::conditions_;
00521     using ConditionBase<PointT>::comparisons_;
00522 
00523     public:
00524       typedef boost::shared_ptr<ConditionOr<PointT> > Ptr;
00525       typedef boost::shared_ptr<const ConditionOr<PointT> > ConstPtr;
00526 
00528       ConditionOr () :
00529         ConditionBase<PointT> ()
00530       {
00531       }
00532 
00539       virtual bool
00540       evaluate (const PointT &point) const;
00541   };
00542 
00544 
00574   template<typename PointT>
00575   class ConditionalRemoval : public Filter<PointT>
00576   {
00577     using Filter<PointT>::input_;
00578     using Filter<PointT>::filter_name_;
00579     using Filter<PointT>::getClassName;
00580 
00581     using Filter<PointT>::removed_indices_;
00582     using Filter<PointT>::extract_removed_indices_;
00583 
00584     typedef typename Filter<PointT>::PointCloud PointCloud;
00585     typedef typename PointCloud::Ptr PointCloudPtr;
00586     typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00587 
00588     public:
00589       typedef typename pcl::ConditionBase<PointT> ConditionBase;
00590       typedef typename ConditionBase::Ptr ConditionBasePtr;
00591       typedef typename ConditionBase::ConstPtr ConditionBaseConstPtr;
00592 
00599       ConditionalRemoval (int extract_removed_indices = false) :
00600         Filter<PointT>::Filter (extract_removed_indices), capable_ (false), keep_organized_ (false), condition_ (),
00601         user_filter_value_ (std::numeric_limits<float>::quiet_NaN ())
00602       {
00603         filter_name_ = "ConditionalRemoval";
00604       }
00605 
00611       ConditionalRemoval (ConditionBasePtr condition, bool extract_removed_indices = false) :
00612         Filter<PointT>::Filter (extract_removed_indices), capable_ (false), keep_organized_ (false), condition_ (),
00613         user_filter_value_ (std::numeric_limits<float>::quiet_NaN ())
00614       {
00615         filter_name_ = "ConditionalRemoval";
00616         setCondition (condition);
00617       }
00618 
00627       inline void
00628       setKeepOrganized (bool val)
00629       {
00630         keep_organized_ = val;
00631       }
00632 
00633       inline bool
00634       getKeepOrganized () const
00635       {
00636         return (keep_organized_);
00637       }
00638 
00644       inline void
00645       setUserFilterValue (float val)
00646       {
00647         user_filter_value_ = val;
00648       }
00649 
00656       void
00657       setCondition (ConditionBasePtr condition);
00658 
00659     protected:
00663       void
00664       applyFilter (PointCloud &output);
00665 
00666       typedef typename pcl::traits::fieldList<PointT>::type FieldList;
00667 
00669       bool capable_;
00670 
00674       bool keep_organized_;
00675 
00677       ConditionBasePtr condition_;
00678 
00682       float user_filter_value_;
00683   };
00684 }
00685 
00686 #endif 


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:14:43