00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #ifndef PCL_FILTER_FIELD_VAL_CONDITION_H_
00039 #define PCL_FILTER_FIELD_VAL_CONDITION_H_
00040 #include <pcl/common/eigen.h>
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
00138
00144 FieldComparison (std::string field_name, ComparisonOps::CompareOp op, double compare_val);
00145
00149 FieldComparison (const FieldComparison &src)
00150 : ComparisonBase<PointT> ()
00151 , compare_val_ (src.compare_val_), point_data_ (src.point_data_)
00152 {
00153 }
00154
00158 inline FieldComparison&
00159 operator = (const FieldComparison &src)
00160 {
00161 compare_val_ = src.compare_val_;
00162 point_data_ = src.point_data_;
00163 return (*this);
00164 }
00165
00167 virtual ~FieldComparison ();
00168
00173 virtual bool
00174 evaluate (const PointT &point) const;
00175
00176 protected:
00178 double compare_val_;
00179
00181 PointDataAtOffset<PointT>* point_data_;
00182
00183 private:
00184 FieldComparison () :
00185 compare_val_ (), point_data_ ()
00186 {
00187 }
00188 };
00189
00191
00192 template<typename PointT>
00193 class PackedRGBComparison : public ComparisonBase<PointT>
00194 {
00195 using ComparisonBase<PointT>::capable_;
00196 using ComparisonBase<PointT>::op_;
00197
00198 public:
00199 typedef boost::shared_ptr< PackedRGBComparison<PointT> > Ptr;
00200 typedef boost::shared_ptr< const PackedRGBComparison<PointT> > ConstPtr;
00201
00207 PackedRGBComparison (std::string component_name, ComparisonOps::CompareOp op, double compare_val);
00208
00210 virtual ~PackedRGBComparison () {}
00211
00216 virtual bool
00217 evaluate (const PointT &point) const;
00218
00219 protected:
00221 std::string component_name_;
00222
00224 uint32_t component_offset_;
00225
00227 double compare_val_;
00228
00229 private:
00230 PackedRGBComparison () :
00231 component_name_ (), component_offset_ (), compare_val_ ()
00232 {
00233 }
00234
00235 };
00236
00238
00239 template<typename PointT>
00240 class PackedHSIComparison : public ComparisonBase<PointT>
00241 {
00242 using ComparisonBase<PointT>::capable_;
00243 using ComparisonBase<PointT>::op_;
00244
00245 public:
00246 typedef boost::shared_ptr< PackedHSIComparison<PointT> > Ptr;
00247 typedef boost::shared_ptr< const PackedHSIComparison<PointT> > ConstPtr;
00248
00254 PackedHSIComparison (std::string component_name, ComparisonOps::CompareOp op, double compare_val);
00255
00257 virtual ~PackedHSIComparison () {}
00258
00263 virtual bool
00264 evaluate (const PointT &point) const;
00265
00266 typedef enum
00267 {
00268 H,
00269 S,
00270 I
00271 } ComponentId;
00272
00273 protected:
00275 std::string component_name_;
00276
00278 ComponentId component_id_;
00279
00281 double compare_val_;
00282
00284 uint32_t rgb_offset_;
00285
00286 private:
00287 PackedHSIComparison () :
00288 component_name_ (), component_id_ (), compare_val_ (), rgb_offset_ ()
00289 {
00290 }
00291 };
00292
00294
00308 template<typename PointT>
00309 class TfQuadraticXYZComparison : public pcl::ComparisonBase<PointT>
00310 {
00311 public:
00312 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00313
00314 typedef boost::shared_ptr<TfQuadraticXYZComparison<PointT> > Ptr;
00315 typedef boost::shared_ptr<const TfQuadraticXYZComparison<PointT> > ConstPtr;
00316
00319 TfQuadraticXYZComparison ();
00320
00322 virtual ~TfQuadraticXYZComparison () {}
00323
00331 TfQuadraticXYZComparison (const pcl::ComparisonOps::CompareOp op, const Eigen::Matrix3f &comparison_matrix,
00332 const Eigen::Vector3f &comparison_vector, const float &comparison_scalar,
00333 const Eigen::Affine3f &comparison_transform = Eigen::Affine3f::Identity ());
00334
00337 inline void
00338 setComparisonOperator (const pcl::ComparisonOps::CompareOp op)
00339 {
00340 op_ = op;
00341 }
00342
00345 inline void
00346 setComparisonMatrix (const Eigen::Matrix3f &matrix)
00347 {
00348
00349 comp_matr_.block<3, 3> (0, 0) = matrix;
00350 comp_matr_.col (3) << 0, 0, 0, 1;
00351 comp_matr_.block<1, 3> (3, 0) << 0, 0, 0;
00352 tf_comp_matr_ = comp_matr_;
00353 }
00354
00357 inline void
00358 setComparisonMatrix (const Eigen::Matrix4f &homogeneousMatrix)
00359 {
00360 comp_matr_ = homogeneousMatrix;
00361 tf_comp_matr_ = comp_matr_;
00362 }
00363
00366 inline void
00367 setComparisonVector (const Eigen::Vector3f &vector)
00368 {
00369 comp_vect_ = vector.homogeneous ();
00370 tf_comp_vect_ = comp_vect_;
00371 }
00372
00375 inline void
00376 setComparisonVector (const Eigen::Vector4f &homogeneousVector)
00377 {
00378 comp_vect_ = homogeneousVector;
00379 tf_comp_vect_ = comp_vect_;
00380 }
00381
00384 inline void
00385 setComparisonScalar (const float &scalar)
00386 {
00387 comp_scalar_ = scalar;
00388 }
00389
00399 inline void
00400 transformComparison (const Eigen::Matrix4f &transform)
00401 {
00402 tf_comp_matr_ = transform.transpose () * comp_matr_ * transform;
00403 tf_comp_vect_ = comp_vect_.transpose () * transform;
00404 }
00405
00415 inline void
00416 transformComparison (const Eigen::Affine3f &transform)
00417 {
00418 transformComparison (transform.matrix ());
00419 }
00420
00425 virtual bool
00426 evaluate (const PointT &point) const;
00427
00428 protected:
00429 using pcl::ComparisonBase<PointT>::capable_;
00430 using pcl::ComparisonBase<PointT>::op_;
00431
00432 Eigen::Matrix4f comp_matr_;
00433 Eigen::Vector4f comp_vect_;
00434
00435 float comp_scalar_;
00436
00437 private:
00438 Eigen::Matrix4f tf_comp_matr_;
00439 Eigen::Vector4f tf_comp_vect_;
00440 };
00441
00443
00444 template<typename PointT>
00445 class ConditionBase
00446 {
00447 public:
00448 typedef typename pcl::ComparisonBase<PointT> ComparisonBase;
00449 typedef typename ComparisonBase::Ptr ComparisonBasePtr;
00450 typedef typename ComparisonBase::ConstPtr ComparisonBaseConstPtr;
00451
00452 typedef boost::shared_ptr<ConditionBase<PointT> > Ptr;
00453 typedef boost::shared_ptr<const ConditionBase<PointT> > ConstPtr;
00454
00456 ConditionBase () : capable_ (true), comparisons_ (), conditions_ ()
00457 {
00458 }
00459
00461 virtual ~ConditionBase ()
00462 {
00463
00464 comparisons_.clear ();
00465
00466
00467 conditions_.clear ();
00468 }
00469
00473 void
00474 addComparison (ComparisonBaseConstPtr comparison);
00475
00479 void
00480 addCondition (Ptr condition);
00481
00483 inline bool
00484 isCapable () const
00485 {
00486 return (capable_);
00487 }
00488
00492 virtual bool
00493 evaluate (const PointT &point) const = 0;
00494
00495 protected:
00497 bool capable_;
00498
00500 std::vector<ComparisonBaseConstPtr> comparisons_;
00501
00503 std::vector<Ptr> conditions_;
00504 };
00505
00507
00508 template<typename PointT>
00509 class ConditionAnd : public ConditionBase<PointT>
00510 {
00511 using ConditionBase<PointT>::conditions_;
00512 using ConditionBase<PointT>::comparisons_;
00513
00514 public:
00515 typedef boost::shared_ptr<ConditionAnd<PointT> > Ptr;
00516 typedef boost::shared_ptr<const ConditionAnd<PointT> > ConstPtr;
00517
00519 ConditionAnd () :
00520 ConditionBase<PointT> ()
00521 {
00522 }
00523
00530 virtual bool
00531 evaluate (const PointT &point) const;
00532 };
00533
00535
00536 template<typename PointT>
00537 class ConditionOr : public ConditionBase<PointT>
00538 {
00539 using ConditionBase<PointT>::conditions_;
00540 using ConditionBase<PointT>::comparisons_;
00541
00542 public:
00543 typedef boost::shared_ptr<ConditionOr<PointT> > Ptr;
00544 typedef boost::shared_ptr<const ConditionOr<PointT> > ConstPtr;
00545
00547 ConditionOr () :
00548 ConditionBase<PointT> ()
00549 {
00550 }
00551
00558 virtual bool
00559 evaluate (const PointT &point) const;
00560 };
00561
00563
00593 template<typename PointT>
00594 class ConditionalRemoval : public Filter<PointT>
00595 {
00596 using Filter<PointT>::input_;
00597 using Filter<PointT>::filter_name_;
00598 using Filter<PointT>::getClassName;
00599
00600 using Filter<PointT>::removed_indices_;
00601 using Filter<PointT>::extract_removed_indices_;
00602
00603 typedef typename Filter<PointT>::PointCloud PointCloud;
00604 typedef typename PointCloud::Ptr PointCloudPtr;
00605 typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00606
00607 public:
00608 typedef typename pcl::ConditionBase<PointT> ConditionBase;
00609 typedef typename ConditionBase::Ptr ConditionBasePtr;
00610 typedef typename ConditionBase::ConstPtr ConditionBaseConstPtr;
00611
00618 ConditionalRemoval (int extract_removed_indices = false) :
00619 Filter<PointT>::Filter (extract_removed_indices), capable_ (false), keep_organized_ (false), condition_ (),
00620 user_filter_value_ (std::numeric_limits<float>::quiet_NaN ())
00621 {
00622 filter_name_ = "ConditionalRemoval";
00623 }
00624
00630 ConditionalRemoval (ConditionBasePtr condition, bool extract_removed_indices = false) :
00631 Filter<PointT>::Filter (extract_removed_indices), capable_ (false), keep_organized_ (false), condition_ (),
00632 user_filter_value_ (std::numeric_limits<float>::quiet_NaN ())
00633 {
00634 filter_name_ = "ConditionalRemoval";
00635 setCondition (condition);
00636 }
00637
00646 inline void
00647 setKeepOrganized (bool val)
00648 {
00649 keep_organized_ = val;
00650 }
00651
00652 inline bool
00653 getKeepOrganized () const
00654 {
00655 return (keep_organized_);
00656 }
00657
00663 inline void
00664 setUserFilterValue (float val)
00665 {
00666 user_filter_value_ = val;
00667 }
00668
00675 void
00676 setCondition (ConditionBasePtr condition);
00677
00678 protected:
00682 void
00683 applyFilter (PointCloud &output);
00684
00685 typedef typename pcl::traits::fieldList<PointT>::type FieldList;
00686
00688 bool capable_;
00689
00693 bool keep_organized_;
00694
00696 ConditionBasePtr condition_;
00697
00701 float user_filter_value_;
00702 };
00703 }
00704
00705 #ifdef PCL_NO_PRECOMPILE
00706 #include <pcl/filters/impl/conditional_removal.hpp>
00707 #endif
00708
00709 #endif