Go to the documentation of this file.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
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:
00092 PassThrough (bool extract_removed_indices = false) :
00093 FilterIndices<PointT>::FilterIndices (extract_removed_indices),
00094 filter_field_name_ (""),
00095 filter_limit_min_ (FLT_MIN),
00096 filter_limit_max_ (FLT_MAX)
00097 {
00098 filter_name_ = "PassThrough";
00099 }
00100
00105 inline void
00106 setFilterFieldName (const std::string &field_name)
00107 {
00108 filter_field_name_ = field_name;
00109 }
00110
00114 inline std::string const
00115 getFilterFieldName ()
00116 {
00117 return (filter_field_name_);
00118 }
00119
00125 inline void
00126 setFilterLimits (const float &limit_min, const float &limit_max)
00127 {
00128 filter_limit_min_ = limit_min;
00129 filter_limit_max_ = limit_max;
00130 }
00131
00136 inline void
00137 getFilterLimits (float &limit_min, float &limit_max)
00138 {
00139 limit_min = filter_limit_min_;
00140 limit_max = filter_limit_max_;
00141 }
00142
00148 inline void
00149 setFilterLimitsNegative (const bool limit_negative)
00150 {
00151 negative_ = limit_negative;
00152 }
00153
00158 inline void
00159 getFilterLimitsNegative (bool &limit_negative)
00160 {
00161 limit_negative = negative_;
00162 }
00163
00168 inline bool
00169 getFilterLimitsNegative ()
00170 {
00171 return (negative_);
00172 }
00173
00174 protected:
00175 using PCLBase<PointT>::input_;
00176 using PCLBase<PointT>::indices_;
00177 using Filter<PointT>::filter_name_;
00178 using Filter<PointT>::getClassName;
00179 using FilterIndices<PointT>::negative_;
00180 using FilterIndices<PointT>::keep_organized_;
00181 using FilterIndices<PointT>::user_filter_value_;
00182 using FilterIndices<PointT>::extract_removed_indices_;
00183 using FilterIndices<PointT>::removed_indices_;
00184
00188 void
00189 applyFilter (PointCloud &output);
00190
00194 void
00195 applyFilter (std::vector<int> &indices)
00196 {
00197 applyFilterIndices (indices);
00198 }
00199
00203 void
00204 applyFilterIndices (std::vector<int> &indices);
00205
00206 private:
00208 std::string filter_field_name_;
00209
00211 float filter_limit_min_;
00212
00214 float filter_limit_max_;
00215 };
00216
00218
00223 template<>
00224 class PCL_EXPORTS PassThrough<sensor_msgs::PointCloud2> : public Filter<sensor_msgs::PointCloud2>
00225 {
00226 typedef sensor_msgs::PointCloud2 PointCloud2;
00227 typedef PointCloud2::Ptr PointCloud2Ptr;
00228 typedef PointCloud2::ConstPtr PointCloud2ConstPtr;
00229
00230 using Filter<sensor_msgs::PointCloud2>::removed_indices_;
00231 using Filter<sensor_msgs::PointCloud2>::extract_removed_indices_;
00232
00233 public:
00235 PassThrough (bool extract_removed_indices = false) :
00236 Filter<sensor_msgs::PointCloud2>::Filter (extract_removed_indices), keep_organized_ (false),
00237 user_filter_value_ (std::numeric_limits<float>::quiet_NaN ()),
00238 filter_field_name_ (""), filter_limit_min_ (-FLT_MAX), filter_limit_max_ (FLT_MAX),
00239 filter_limit_negative_ (false)
00240 {
00241 filter_name_ = "PassThrough";
00242 }
00243
00252 inline void
00253 setKeepOrganized (bool val)
00254 {
00255 keep_organized_ = val;
00256 }
00257
00259 inline bool
00260 getKeepOrganized ()
00261 {
00262 return (keep_organized_);
00263 }
00264
00270 inline void
00271 setUserFilterValue (float val)
00272 {
00273 user_filter_value_ = val;
00274 }
00275
00280 inline void
00281 setFilterFieldName (const std::string &field_name)
00282 {
00283 filter_field_name_ = field_name;
00284 }
00285
00287 inline std::string const
00288 getFilterFieldName ()
00289 {
00290 return (filter_field_name_);
00291 }
00292
00297 inline void
00298 setFilterLimits (const double &limit_min, const double &limit_max)
00299 {
00300 filter_limit_min_ = limit_min;
00301 filter_limit_max_ = limit_max;
00302 }
00303
00308 inline void
00309 getFilterLimits (double &limit_min, double &limit_max)
00310 {
00311 limit_min = filter_limit_min_;
00312 limit_max = filter_limit_max_;
00313 }
00314
00319 inline void
00320 setFilterLimitsNegative (const bool limit_negative)
00321 {
00322 filter_limit_negative_ = limit_negative;
00323 }
00324
00328 inline void
00329 getFilterLimitsNegative (bool &limit_negative)
00330 {
00331 limit_negative = filter_limit_negative_;
00332 }
00333
00337 inline bool
00338 getFilterLimitsNegative ()
00339 {
00340 return (filter_limit_negative_);
00341 }
00342
00343 protected:
00344 void
00345 applyFilter (PointCloud2 &output);
00346
00347 private:
00351 bool keep_organized_;
00352
00356 float user_filter_value_;
00357
00359 std::string filter_field_name_;
00360
00362 double filter_limit_min_;
00363
00365 double filter_limit_max_;
00366
00368 bool filter_limit_negative_;
00369
00370 };
00371 }
00372
00373 #endif // PCL_FILTERS_PASSTHROUGH_H_
00374