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_IMPL_FIELD_VAL_CONDITION_H_
00039 #define PCL_FILTER_IMPL_FIELD_VAL_CONDITION_H_
00040 
00041 #include <pcl/common/io.h>
00042 #include <boost/shared_ptr.hpp>
00043 #include <vector>
00044 #include <Eigen/Geometry>
00045 
00049 template <typename PointT>
00050 pcl::FieldComparison<PointT>::FieldComparison (
00051     std::string field_name, ComparisonOps::CompareOp op, double compare_val) :
00052       compare_val_ (compare_val), point_data_ (NULL)
00053 {
00054   field_name_ = field_name;
00055   op_ = op;
00056 
00057   
00058   std::vector<sensor_msgs::PointField> point_fields; 
00059   
00060   PointCloud<PointT> dummyCloud;
00061   pcl::getFields (dummyCloud, point_fields);
00062 
00063   
00064   if (point_fields.empty ())
00065   {
00066     PCL_WARN ("[pcl::FieldComparison::FieldComparison] no fields found!\n");
00067     capable_ = false;
00068     return;
00069   }
00070 
00071   
00072   size_t d;
00073   for (d = 0; d < point_fields.size (); ++d)
00074   {
00075     if (point_fields[d].name == field_name) 
00076       break;
00077   }
00078   
00079   if (d == point_fields.size ())
00080   {
00081     PCL_WARN ("[pcl::FieldComparison::FieldComparison] field not found!\n");
00082     capable_ = false;
00083     return;
00084   }
00085   uint8_t datatype = point_fields[d].datatype;
00086   uint32_t offset = point_fields[d].offset;
00087 
00088   point_data_ = new PointDataAtOffset<PointT>(datatype, offset);
00089   capable_ = true;
00090 }
00091 
00093 template <typename PointT>
00094 pcl::FieldComparison<PointT>::~FieldComparison () 
00095 {
00096   if (point_data_ != NULL)
00097   {
00098     delete point_data_;
00099     point_data_ = NULL;
00100   }
00101 }
00102 
00104 template <typename PointT> bool
00105 pcl::FieldComparison<PointT>::evaluate (const PointT &point) const
00106 {
00107   if (!this->capable_)
00108   {
00109     PCL_WARN ("[pcl::FieldComparison::evaluate] invalid compariosn!\n");
00110     return (false);
00111   }
00112 
00113   
00114   
00115   
00116   int compare_result = point_data_->compare (point, compare_val_);
00117   
00118   switch (this->op_)
00119   {
00120     case pcl::ComparisonOps::GT :
00121       return (compare_result > 0);
00122     case pcl::ComparisonOps::GE :
00123       return (compare_result >= 0);
00124     case pcl::ComparisonOps::LT :
00125       return (compare_result < 0);
00126     case pcl::ComparisonOps::LE :
00127       return (compare_result <= 0);
00128     case pcl::ComparisonOps::EQ :
00129       return (compare_result == 0);
00130     default:
00131       PCL_WARN ("[pcl::FieldComparison::evaluate] unrecognized op_!\n");
00132       return (false);
00133   }
00134 }
00135 
00139 template <typename PointT>
00140 pcl::PackedRGBComparison<PointT>::PackedRGBComparison (
00141     std::string component_name, ComparisonOps::CompareOp op, double compare_val) :
00142   component_name_ (component_name), component_offset_ (), compare_val_ (compare_val)
00143 {
00144   
00145   std::vector<sensor_msgs::PointField> point_fields;
00146   
00147   PointCloud<PointT> dummyCloud;
00148   pcl::getFields (dummyCloud, point_fields);
00149 
00150   
00151   size_t d;
00152   for (d = 0; d < point_fields.size (); ++d)
00153   {
00154     if (point_fields[d].name == "rgb" || point_fields[d].name == "rgba")
00155       break;
00156   }
00157   if (d == point_fields.size ())
00158   {
00159     PCL_WARN ("[pcl::PackedRGBComparison::PackedRGBComparison] rgb field not found!\n");
00160     capable_ = false;
00161     return;
00162   }
00163 
00164   
00165   uint8_t datatype = point_fields[d].datatype;
00166   if (datatype != sensor_msgs::PointField::FLOAT32 &&
00167       datatype != sensor_msgs::PointField::UINT32 &&
00168       datatype != sensor_msgs::PointField::INT32)
00169   {
00170     PCL_WARN ("[pcl::PackedRGBComparison::PackedRGBComparison] has unusable type!\n");
00171     capable_ = false;
00172     return;
00173   }
00174 
00175   
00176   if (component_name == "r")
00177   {
00178     component_offset_ = point_fields[d].offset + 2;
00179   }
00180   else if (component_name == "g")
00181   {
00182     component_offset_ = point_fields[d].offset + 1;
00183   }
00184   else if (component_name == "b")
00185   {
00186     component_offset_ = point_fields[d].offset;
00187   }
00188   else
00189   {
00190     PCL_WARN ("[pcl::PackedRGBComparison::PackedRGBComparison] unrecognized component name!\n");
00191     capable_ = false;
00192     return;
00193   }
00194 
00195   
00196   capable_ = true;
00197   op_ = op;
00198 }
00199 
00200 
00202 template <typename PointT> bool
00203 pcl::PackedRGBComparison<PointT>::evaluate (const PointT &point) const
00204 {
00205   
00206   const uint8_t* pt_data = reinterpret_cast<const uint8_t*> (&point);
00207   uint8_t my_val = *(pt_data + component_offset_);
00208 
00209   
00210   switch (this->op_) 
00211   {
00212     case pcl::ComparisonOps::GT :
00213       return (my_val > this->compare_val_);
00214     case pcl::ComparisonOps::GE :
00215       return (my_val >= this->compare_val_);
00216     case pcl::ComparisonOps::LT :
00217       return (my_val < this->compare_val_);
00218     case pcl::ComparisonOps::LE :
00219       return (my_val <= this->compare_val_);
00220     case pcl::ComparisonOps::EQ :
00221       return (my_val == this->compare_val_);
00222     default:
00223       PCL_WARN ("[pcl::PackedRGBComparison::evaluate] unrecognized op_!\n");
00224       return (false);
00225   }
00226 }
00227 
00231 template <typename PointT>
00232 pcl::PackedHSIComparison<PointT>::PackedHSIComparison (
00233     std::string component_name, ComparisonOps::CompareOp op, double compare_val) : 
00234   component_name_ (component_name), component_id_ (), compare_val_ (compare_val), rgb_offset_ ()
00235 {
00236   
00237   std::vector<sensor_msgs::PointField> point_fields; 
00238   
00239   PointCloud<PointT> dummyCloud;
00240   pcl::getFields (dummyCloud, point_fields);
00241 
00242   
00243   size_t d;
00244   for (d = 0; d < point_fields.size (); ++d)
00245     if (point_fields[d].name == "rgb" || point_fields[d].name == "rgba") 
00246       break;
00247   if (d == point_fields.size ())
00248   {
00249     PCL_WARN ("[pcl::PackedHSIComparison::PackedHSIComparison] rgb field not found!\n");
00250     capable_ = false;
00251     return;
00252   }
00253 
00254   
00255   uint8_t datatype = point_fields[d].datatype;
00256   if (datatype != sensor_msgs::PointField::FLOAT32 && 
00257       datatype != sensor_msgs::PointField::UINT32 && 
00258       datatype != sensor_msgs::PointField::INT32) 
00259   {
00260     PCL_WARN ("[pcl::PackedHSIComparison::PackedHSIComparison] has unusable type!\n");
00261     capable_ = false;
00262     return;
00263   }
00264 
00265   
00266   uint32_t offset = point_fields[d].offset;
00267   if (offset % 4 != 0)
00268   {
00269     PCL_WARN ("[pcl::PackedHSIComparison::PackedHSIComparison] rgb field is not 32 bit aligned!\n");
00270     capable_ = false;
00271     return;
00272   }
00273   rgb_offset_ = point_fields[d].offset;
00274 
00275   
00276   if (component_name == "h" ) 
00277   {
00278     component_id_ = H;
00279   } 
00280   else if (component_name == "s") 
00281   {
00282     component_id_ = S;
00283   } 
00284   else if (component_name == "i") 
00285   { 
00286     component_id_ = I;
00287   } 
00288   else 
00289   {
00290     PCL_WARN ("[pcl::PackedRGBComparison::PackedRGBComparison] unrecognized component name!\n");
00291     capable_ = false;
00292     return;
00293   }
00294 
00295   
00296   capable_ = true;
00297   op_ = op;
00298 }
00299 
00301 template <typename PointT> bool
00302 pcl::PackedHSIComparison<PointT>::evaluate (const PointT &point) const
00303 {
00304   
00305   static uint32_t rgb_val_ = 0;
00306   static uint8_t r_ = 0;
00307   static uint8_t g_ = 0;
00308   static uint8_t b_ = 0;
00309   static int8_t h_ = 0;
00310   static uint8_t s_ = 0;
00311   static uint8_t i_ = 0;
00312 
00313   
00314   const uint8_t* pt_data = reinterpret_cast<const uint8_t*> (&point);
00315   const uint32_t* rgb_data = reinterpret_cast<const uint32_t*> (pt_data + rgb_offset_);
00316   uint32_t new_rgb_val = *rgb_data;
00317 
00318   if (rgb_val_ != new_rgb_val) 
00319   { 
00320     rgb_val_ = new_rgb_val;
00321     
00322     r_ = static_cast <uint8_t> (rgb_val_ >> 16); 
00323     g_ = static_cast <uint8_t> (rgb_val_ >> 8);
00324     b_ = static_cast <uint8_t> (rgb_val_);
00325 
00326     
00327     float hx = (2.0f * r_ - g_ - b_) / 4.0f;  
00328     float hy = static_cast<float> (g_ - b_) * 111.0f / 255.0f; 
00329     h_ = static_cast<int8_t> (atan2(hy, hx) * 128.0f / M_PI);
00330 
00331     int32_t i = (r_+g_+b_)/3; 
00332     i_ = static_cast<uint8_t> (i);
00333 
00334     int32_t m;  
00335     m = (r_ < g_) ? r_ : g_;
00336     m = (m < b_) ? m : b_;
00337 
00338     s_ = static_cast<uint8_t> ((i == 0) ? 0 : 255 - (m * 255) / i); 
00339   }
00340 
00341   float my_val = 0;
00342 
00343   switch (component_id_) 
00344   {
00345     case H:
00346       my_val = static_cast <float> (h_);
00347       break;
00348     case S:
00349       my_val = static_cast <float> (s_);
00350       break;
00351     case I:
00352       my_val = static_cast <float> (i_);
00353       break;
00354     default:
00355       assert (false);
00356   }
00357 
00358   
00359   switch (this->op_) 
00360   {
00361     case pcl::ComparisonOps::GT :
00362       return (my_val > this->compare_val_);
00363     case pcl::ComparisonOps::GE :
00364       return (my_val >= this->compare_val_);
00365     case pcl::ComparisonOps::LT :
00366       return (my_val < this->compare_val_);
00367     case pcl::ComparisonOps::LE :
00368       return (my_val <= this->compare_val_);
00369     case pcl::ComparisonOps::EQ :
00370       return (my_val == this->compare_val_);
00371     default:
00372       PCL_WARN ("[pcl::PackedHSIComparison::evaluate] unrecognized op_!\n");
00373       return (false);
00374   }
00375 }
00376 
00377 
00381 template<typename PointT>
00382 pcl::TfQuadraticXYZComparison<PointT>::TfQuadraticXYZComparison () :
00383   comp_matr_ (), comp_vect_ (), comp_scalar_ (0.0)
00384 {
00385   
00386   std::vector<sensor_msgs::PointField> point_fields;
00387   
00388   PointCloud<PointT> dummyCloud;
00389   pcl::getFields (dummyCloud, point_fields);
00390 
00391   
00392   size_t dX;
00393   for (dX = 0; dX < point_fields.size (); ++dX)
00394   {
00395     if (point_fields[dX].name == "x")
00396       break;
00397   }
00398   if (dX == point_fields.size ())
00399   {
00400     PCL_WARN ("[pcl::TfQuadraticXYZComparison::TfQuadraticXYZComparison] x field not found!\n");
00401     capable_ = false;
00402     return;
00403   }
00404 
00405   
00406   size_t dY;
00407   for (dY = 0; dY < point_fields.size (); ++dY)
00408   {
00409     if (point_fields[dY].name == "y")
00410       break;
00411   }
00412   if (dY == point_fields.size ())
00413   {
00414     PCL_WARN ("[pcl::TfQuadraticXYZComparison::TfQuadraticXYZComparison] y field not found!\n");
00415     capable_ = false;
00416     return;
00417   }
00418 
00419   
00420   size_t dZ;
00421   for (dZ = 0; dZ < point_fields.size (); ++dZ)
00422   {
00423     if (point_fields[dZ].name == "z")
00424       break;
00425   }
00426   if (dZ == point_fields.size ())
00427   {
00428     PCL_WARN ("[pcl::TfQuadraticXYZComparison::TfQuadraticXYZComparison] z field not found!\n");
00429     capable_ = false;
00430     return;
00431   }
00432 
00433   comp_matr_ << 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0;
00434   comp_vect_ << 0.0, 0.0, 0.0, 1.0;
00435   tf_comp_matr_ = comp_matr_;
00436   tf_comp_vect_ = comp_vect_;
00437   op_ = pcl::ComparisonOps::EQ;
00438   capable_ = true;
00439 }
00440 
00442 template<typename PointT>
00443 pcl::TfQuadraticXYZComparison<PointT>::TfQuadraticXYZComparison (const pcl::ComparisonOps::CompareOp op,
00444                                                                  const Eigen::Matrix3f &comparison_matrix,
00445                                                                  const Eigen::Vector3f &comparison_vector,
00446                                                                  const float &comparison_scalar,
00447                                                                  const Eigen::Affine3f &comparison_transform) :
00448   comp_matr_ (), comp_vect_ (), comp_scalar_ (comparison_scalar)
00449 {
00450   
00451   std::vector<sensor_msgs::PointField> point_fields;
00452   
00453   PointCloud<PointT> dummyCloud;
00454   pcl::getFields (dummyCloud, point_fields);
00455 
00456   
00457   size_t dX;
00458   for (dX = 0; dX < point_fields.size (); ++dX)
00459   {
00460     if (point_fields[dX].name == "x")
00461       break;
00462   }
00463   if (dX == point_fields.size ())
00464   {
00465     PCL_WARN ("[pcl::TfQuadraticXYZComparison::TfQuadraticXYZComparison] x field not found!\n");
00466     capable_ = false;
00467     return;
00468   }
00469 
00470   
00471   size_t dY;
00472   for (dY = 0; dY < point_fields.size (); ++dY)
00473   {
00474     if (point_fields[dY].name == "y")
00475       break;
00476   }
00477   if (dY == point_fields.size ())
00478   {
00479     PCL_WARN ("[pcl::TfQuadraticXYZComparison::TfQuadraticXYZComparison] y field not found!\n");
00480     capable_ = false;
00481     return;
00482   }
00483 
00484   
00485   size_t dZ;
00486   for (dZ = 0; dZ < point_fields.size (); ++dZ)
00487   {
00488     if (point_fields[dZ].name == "z")
00489       break;
00490   }
00491   if (dZ == point_fields.size ())
00492   {
00493     PCL_WARN ("[pcl::TfQuadraticXYZComparison::TfQuadraticXYZComparison] z field not found!\n");
00494     capable_ = false;
00495     return;
00496   }
00497 
00498   capable_ = true;
00499   op_ = op;
00500   setComparisonMatrix (comparison_matrix);
00501   setComparisonVector (comparison_vector);
00502   if (!comparison_transform.matrix ().isIdentity ())
00503     transformComparison (comparison_transform);
00504 }
00505 
00507 template<typename PointT>
00508 bool
00509 pcl::TfQuadraticXYZComparison<PointT>::evaluate (const PointT &point) const
00510 {
00511   Eigen::Vector4f pointAffine;
00512   pointAffine << point.x, point.y, point.z, 1; 
00513   
00514   float myVal = static_cast<float>(2.0f * tf_comp_vect_.transpose () * pointAffine) + static_cast<float>(pointAffine.transpose () * tf_comp_matr_ * pointAffine) + comp_scalar_ - 3.0f;
00515   
00516   
00517   switch (this->op_)
00518   {
00519     case pcl::ComparisonOps::GT:
00520       return (myVal > 0);
00521     case pcl::ComparisonOps::GE:
00522       return (myVal >= 0);
00523     case pcl::ComparisonOps::LT:
00524       return (myVal < 0);
00525     case pcl::ComparisonOps::LE:
00526       return (myVal <= 0);
00527     case pcl::ComparisonOps::EQ:
00528       return (myVal == 0);
00529     default:
00530       PCL_WARN ("[pcl::transformableQuadricXYZComparison::evaluate] unrecognized op_!\n");
00531       return (false);
00532   }
00533 }
00534 
00538 template <typename PointT> int
00539 pcl::PointDataAtOffset<PointT>::compare (const PointT& p, const double& val) 
00540 {
00541   
00542   
00543   
00544   
00545   const uint8_t* pt_data = reinterpret_cast<const uint8_t*> (&p);
00546 
00547   switch (datatype_) 
00548   {
00549     case sensor_msgs::PointField::INT8 : 
00550     {
00551       int8_t pt_val;
00552       memcpy (&pt_val, pt_data + this->offset_, sizeof (int8_t));
00553       return (pt_val > static_cast<int8_t>(val)) - (pt_val < static_cast<int8_t> (val));
00554     }
00555     case sensor_msgs::PointField::UINT8 : 
00556     {
00557       uint8_t pt_val;
00558       memcpy (&pt_val, pt_data + this->offset_, sizeof (uint8_t));
00559       return (pt_val > static_cast<uint8_t>(val)) - (pt_val < static_cast<uint8_t> (val));
00560     }
00561     case sensor_msgs::PointField::INT16 :
00562     {
00563       int16_t pt_val;
00564       memcpy (&pt_val, pt_data + this->offset_, sizeof (int16_t));
00565       return (pt_val > static_cast<int16_t>(val)) - (pt_val < static_cast<int16_t> (val));
00566     }
00567     case sensor_msgs::PointField::UINT16 : 
00568     {
00569       uint16_t pt_val;
00570       memcpy (&pt_val, pt_data + this->offset_, sizeof (uint16_t));
00571       return (pt_val > static_cast<uint16_t> (val)) - (pt_val < static_cast<uint16_t> (val));
00572     }
00573     case sensor_msgs::PointField::INT32 : 
00574     {
00575       int32_t pt_val;
00576       memcpy (&pt_val, pt_data + this->offset_, sizeof (int32_t));
00577       return (pt_val > static_cast<int32_t> (val)) - (pt_val < static_cast<int32_t> (val));
00578     }
00579     case sensor_msgs::PointField::UINT32 : 
00580     {
00581       uint32_t pt_val;
00582       memcpy (&pt_val, pt_data + this->offset_, sizeof (uint32_t));
00583       return (pt_val > static_cast<uint32_t> (val)) - (pt_val < static_cast<uint32_t> (val));
00584     }
00585     case sensor_msgs::PointField::FLOAT32 : 
00586     {
00587       float pt_val;
00588       memcpy (&pt_val, pt_data + this->offset_, sizeof (float));
00589       return (pt_val > static_cast<float> (val)) - (pt_val < static_cast<float> (val));
00590     }
00591     case sensor_msgs::PointField::FLOAT64 : 
00592     {
00593       double pt_val;
00594       memcpy (&pt_val, pt_data + this->offset_, sizeof (double));
00595       return (pt_val > val) - (pt_val < val);
00596     }
00597     default : 
00598       PCL_WARN ("[pcl::pcl::PointDataAtOffset::compare] unknown data_type!\n");
00599       return (0);
00600   }
00601 }
00602 
00606 template <typename PointT> void 
00607 pcl::ConditionBase<PointT>::addComparison (ComparisonBaseConstPtr comparison)
00608 {
00609   if (!comparison->isCapable ())
00610     capable_ = false;
00611   comparisons_.push_back (comparison);
00612 }
00613 
00615 template <typename PointT> void 
00616 pcl::ConditionBase<PointT>::addCondition (Ptr condition)
00617 {
00618   if (!condition->isCapable ())
00619     capable_ = false;
00620   conditions_.push_back (condition);
00621 }
00622 
00626 template <typename PointT> bool
00627 pcl::ConditionAnd<PointT>::evaluate (const PointT &point) const
00628 {
00629   for (size_t i = 0; i < comparisons_.size (); ++i)
00630     if (!comparisons_[i]->evaluate (point))
00631       return (false);
00632 
00633   for (size_t i = 0; i < conditions_.size (); ++i)
00634     if (!conditions_[i]->evaluate (point))
00635       return (false);
00636 
00637   return (true);
00638 }
00639 
00643 template <typename PointT> bool 
00644 pcl::ConditionOr<PointT>::evaluate (const PointT &point) const
00645 {
00646   if (comparisons_.empty () && conditions_.empty ()) 
00647     return (true);
00648   for (size_t i = 0; i < comparisons_.size (); ++i)
00649     if (comparisons_[i]->evaluate(point))
00650       return (true);
00651 
00652   for (size_t i = 0; i < conditions_.size (); ++i)
00653     if (conditions_[i]->evaluate (point))
00654       return (true);
00655 
00656   return (false);
00657 }
00658 
00662 template <typename PointT> void 
00663 pcl::ConditionalRemoval<PointT>::setCondition (ConditionBasePtr condition)
00664 {
00665   condition_ = condition;
00666   capable_ = condition_->isCapable ();
00667 }
00668 
00670 template <typename PointT> void
00671 pcl::ConditionalRemoval<PointT>::applyFilter (PointCloud &output)
00672 {
00673   if (capable_ == false)
00674   {
00675     PCL_WARN ("[pcl::%s::applyFilter] not capable!\n", getClassName ().c_str ());
00676     return;
00677   }
00678   
00679   if (!input_)
00680   {
00681     PCL_WARN ("[pcl::%s::applyFilter] No input dataset given!\n", getClassName ().c_str ());
00682     return;
00683   }
00684 
00685   if (condition_.get () == NULL) 
00686   {
00687     PCL_WARN ("[pcl::%s::applyFilter] No filtering condition given!\n", getClassName ().c_str ());
00688     return;
00689   }
00690 
00691   
00692   output.header       = input_->header;
00693   if (!keep_organized_)
00694   {
00695     output.height    = 1;   
00696     output.is_dense  = true;
00697   } 
00698   else 
00699   {
00700     output.height   = this->input_->height;
00701     output.width    = this->input_->width;
00702     output.is_dense = this->input_->is_dense;
00703   }
00704   output.points.resize (input_->points.size ());
00705   removed_indices_->resize (input_->points.size ());
00706 
00707   int nr_p = 0;
00708   int nr_removed_p = 0;
00709 
00710   if (!keep_organized_)
00711   {
00712     for (size_t cp = 0; cp < Filter<PointT>::indices_->size (); ++cp)
00713     {
00714       
00715       if (!pcl_isfinite (input_->points[(*Filter < PointT > ::indices_)[cp]].x)
00716           || !pcl_isfinite (input_->points[(*Filter < PointT > ::indices_)[cp]].y)
00717           || !pcl_isfinite (input_->points[(*Filter < PointT > ::indices_)[cp]].z))
00718       {
00719         if (extract_removed_indices_)
00720         {
00721           (*removed_indices_)[nr_removed_p] = (*Filter<PointT>::indices_)[cp];
00722           nr_removed_p++;
00723         }
00724         continue;
00725       }
00726 
00727       if (condition_->evaluate (input_->points[(*Filter < PointT > ::indices_)[cp]]))
00728       {
00729         pcl::for_each_type<FieldList> (
00730                                        pcl::NdConcatenateFunctor<PointT, PointT> (
00731                                                                                   input_->points[(*Filter < PointT > ::indices_)[cp]],
00732                                                                                   output.points[nr_p]));
00733         nr_p++;
00734       }
00735       else
00736       {
00737         if (extract_removed_indices_)
00738         {
00739           (*removed_indices_)[nr_removed_p] = (*Filter<PointT>::indices_)[cp];
00740           nr_removed_p++;
00741         }
00742       }
00743     }
00744 
00745     output.width = nr_p;
00746     output.points.resize (nr_p);
00747   }
00748   else
00749   {
00750     std::vector<int> indices = *Filter<PointT>::indices_;
00751     std::sort (indices.begin (), indices.end ());   
00752     size_t ci = 0;
00753     for (size_t cp = 0; cp < input_->points.size (); ++cp)
00754     {
00755       if (cp == static_cast<size_t> (indices[ci]))
00756       {
00757         if (ci < indices.size ())
00758         {
00759           ci++;
00760           if (cp == static_cast<size_t> (indices[ci]))   
00761             continue;
00762         }
00763 
00764         
00765         pcl::for_each_type<FieldList> (pcl::NdConcatenateFunctor<PointT, PointT> (input_->points[cp],
00766                                                                                   output.points[cp]));
00767         if (!condition_->evaluate (input_->points[cp]))
00768         {
00769           output.points[cp].getVector4fMap ().setConstant (user_filter_value_);
00770 
00771           if (extract_removed_indices_)
00772           {
00773             (*removed_indices_)[nr_removed_p] = static_cast<int> (cp);
00774             nr_removed_p++;
00775           }
00776         }
00777       }
00778       else
00779       {
00780         output.points[cp].getVector4fMap ().setConstant (user_filter_value_);
00781         
00782       }
00783     }
00784   }
00785   removed_indices_->resize (nr_removed_p);
00786 }
00787 
00788 #define PCL_INSTANTIATE_PointDataAtOffset(T) template class PCL_EXPORTS pcl::PointDataAtOffset<T>;
00789 #define PCL_INSTANTIATE_ComparisonBase(T) template class PCL_EXPORTS pcl::ComparisonBase<T>;
00790 #define PCL_INSTANTIATE_FieldComparison(T) template class PCL_EXPORTS pcl::FieldComparison<T>;
00791 #define PCL_INSTANTIATE_PackedRGBComparison(T) template class PCL_EXPORTS pcl::PackedRGBComparison<T>;
00792 #define PCL_INSTANTIATE_PackedHSIComparison(T) template class PCL_EXPORTS pcl::PackedHSIComparison<T>;
00793 #define PCL_INSTANTIATE_TfQuadraticXYZComparison(T) template class PCL_EXPORTS pcl::TfQuadraticXYZComparison<T>;
00794 #define PCL_INSTANTIATE_ConditionBase(T) template class PCL_EXPORTS pcl::ConditionBase<T>;
00795 #define PCL_INSTANTIATE_ConditionAnd(T) template class PCL_EXPORTS pcl::ConditionAnd<T>;
00796 #define PCL_INSTANTIATE_ConditionOr(T) template class PCL_EXPORTS pcl::ConditionOr<T>;
00797 #define PCL_INSTANTIATE_ConditionalRemoval(T) template class PCL_EXPORTS pcl::ConditionalRemoval<T>;
00798 
00799 #endif