|
Point Cloud Library (PCL)
1.4.0
|
00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Point Cloud Library (PCL) - www.pointclouds.org 00005 * Copyright (c) 2010-2011, 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 Willow Garage, Inc. 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: passthrough.h 3746 2011-12-31 22:19:47Z rusu $ 00037 * 00038 */ 00039 00040 #ifndef PCL_FILTERS_PASSTHROUGH_H_ 00041 #define PCL_FILTERS_PASSTHROUGH_H_ 00042 00043 #include "pcl/filters/filter.h" 00044 00045 namespace pcl 00046 { 00048 00053 template<typename PointT> 00054 class PassThrough : public Filter<PointT> 00055 { 00056 using Filter<PointT>::input_; 00057 using Filter<PointT>::filter_name_; 00058 using Filter<PointT>::getClassName; 00059 00060 using Filter<PointT>::removed_indices_; 00061 using Filter<PointT>::extract_removed_indices_; 00062 00063 typedef typename Filter<PointT>::PointCloud PointCloud; 00064 typedef typename PointCloud::Ptr PointCloudPtr; 00065 typedef typename PointCloud::ConstPtr PointCloudConstPtr; 00066 00067 public: 00069 PassThrough (bool extract_removed_indices = false) : 00070 Filter<PointT>::Filter (extract_removed_indices), keep_organized_ (false), 00071 user_filter_value_ (std::numeric_limits<float>::quiet_NaN ()), 00072 filter_field_name_ (""), 00073 filter_limit_min_ (-FLT_MAX), filter_limit_max_ (FLT_MAX), 00074 filter_limit_negative_ (false) 00075 { 00076 filter_name_ = "PassThrough"; 00077 } 00078 00087 inline void 00088 setKeepOrganized (bool val) 00089 { 00090 keep_organized_ = val; 00091 } 00092 00094 inline bool 00095 getKeepOrganized () 00096 { 00097 return (keep_organized_); 00098 } 00099 00105 inline void 00106 setUserFilterValue (float val) 00107 { 00108 user_filter_value_ = val; 00109 } 00110 00115 inline void 00116 setFilterFieldName (const std::string &field_name) 00117 { 00118 filter_field_name_ = field_name; 00119 } 00120 00122 inline std::string const 00123 getFilterFieldName () 00124 { 00125 return (filter_field_name_); 00126 } 00127 00132 inline void 00133 setFilterLimits (const double &limit_min, const double &limit_max) 00134 { 00135 filter_limit_min_ = limit_min; 00136 filter_limit_max_ = limit_max; 00137 } 00138 00143 inline void 00144 getFilterLimits (double &limit_min, double &limit_max) 00145 { 00146 limit_min = filter_limit_min_; 00147 limit_max = filter_limit_max_; 00148 } 00149 00154 inline void 00155 setFilterLimitsNegative (const bool limit_negative) 00156 { 00157 filter_limit_negative_ = limit_negative; 00158 } 00159 00163 inline void 00164 getFilterLimitsNegative (bool &limit_negative) 00165 { 00166 limit_negative = filter_limit_negative_; 00167 } 00168 00172 inline bool 00173 getFilterLimitsNegative () 00174 { 00175 return (filter_limit_negative_); 00176 } 00177 00178 protected: 00182 void 00183 applyFilter (PointCloud &output); 00184 00185 typedef typename pcl::traits::fieldList<PointT>::type FieldList; 00186 00187 private: 00191 bool keep_organized_; 00192 00196 float user_filter_value_; 00197 00199 std::string filter_field_name_; 00200 00202 double filter_limit_min_; 00203 00205 double filter_limit_max_; 00206 00208 bool filter_limit_negative_; 00209 }; 00210 00212 00217 template<> 00218 class PCL_EXPORTS PassThrough<sensor_msgs::PointCloud2> : public Filter<sensor_msgs::PointCloud2> 00219 { 00220 typedef sensor_msgs::PointCloud2 PointCloud2; 00221 typedef PointCloud2::Ptr PointCloud2Ptr; 00222 typedef PointCloud2::ConstPtr PointCloud2ConstPtr; 00223 00224 using Filter<sensor_msgs::PointCloud2>::removed_indices_; 00225 using Filter<sensor_msgs::PointCloud2>::extract_removed_indices_; 00226 00227 public: 00229 PassThrough (bool extract_removed_indices = false) : 00230 Filter<sensor_msgs::PointCloud2>::Filter (extract_removed_indices), keep_organized_ (false), 00231 user_filter_value_ (std::numeric_limits<float>::quiet_NaN ()), 00232 filter_field_name_ (""), filter_limit_min_ (-FLT_MAX), filter_limit_max_ (FLT_MAX), 00233 filter_limit_negative_ (false) 00234 { 00235 filter_name_ = "PassThrough"; 00236 } 00237 00246 inline void 00247 setKeepOrganized (bool val) 00248 { 00249 keep_organized_ = val; 00250 } 00251 00253 inline bool 00254 getKeepOrganized () 00255 { 00256 return (keep_organized_); 00257 } 00258 00264 inline void 00265 setUserFilterValue (float val) 00266 { 00267 user_filter_value_ = val; 00268 } 00269 00274 inline void 00275 setFilterFieldName (const std::string &field_name) 00276 { 00277 filter_field_name_ = field_name; 00278 } 00279 00281 inline std::string const 00282 getFilterFieldName () 00283 { 00284 return (filter_field_name_); 00285 } 00286 00291 inline void 00292 setFilterLimits (const double &limit_min, const double &limit_max) 00293 { 00294 filter_limit_min_ = limit_min; 00295 filter_limit_max_ = limit_max; 00296 } 00297 00302 inline void 00303 getFilterLimits (double &limit_min, double &limit_max) 00304 { 00305 limit_min = filter_limit_min_; 00306 limit_max = filter_limit_max_; 00307 } 00308 00313 inline void 00314 setFilterLimitsNegative (const bool limit_negative) 00315 { 00316 filter_limit_negative_ = limit_negative; 00317 } 00318 00322 inline void 00323 getFilterLimitsNegative (bool &limit_negative) 00324 { 00325 limit_negative = filter_limit_negative_; 00326 } 00327 00331 inline bool 00332 getFilterLimitsNegative () 00333 { 00334 return (filter_limit_negative_); 00335 } 00336 00337 protected: 00338 void 00339 applyFilter (PointCloud2 &output); 00340 00341 private: 00345 bool keep_organized_; 00346 00350 float user_filter_value_; 00351 00353 std::string filter_field_name_; 00354 00356 double filter_limit_min_; 00357 00359 double filter_limit_max_; 00360 00362 bool filter_limit_negative_; 00363 00364 }; 00365 } 00366 00367 #endif //#ifndef PCL_FILTERS_PASSTHROUGH_H_
1.7.6.1