Point Cloud Library (PCL)
1.3.1
|
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: passthrough.h 1370 2011-06-19 01:06:01Z jspricke $ 00035 * 00036 */ 00037 00038 #ifndef PCL_FILTERS_PASSTHROUGH_H_ 00039 #define PCL_FILTERS_PASSTHROUGH_H_ 00040 00041 #include "pcl/filters/filter.h" 00042 00043 namespace pcl 00044 { 00046 00051 template<typename PointT> 00052 class PassThrough : public Filter<PointT> 00053 { 00054 using Filter<PointT>::input_; 00055 using Filter<PointT>::filter_name_; 00056 using Filter<PointT>::filter_field_name_; 00057 using Filter<PointT>::filter_limit_min_; 00058 using Filter<PointT>::filter_limit_max_; 00059 using Filter<PointT>::filter_limit_negative_; 00060 using Filter<PointT>::getClassName; 00061 00062 using Filter<PointT>::removed_indices_; 00063 using Filter<PointT>::extract_removed_indices_; 00064 00065 typedef typename Filter<PointT>::PointCloud PointCloud; 00066 typedef typename PointCloud::Ptr PointCloudPtr; 00067 typedef typename PointCloud::ConstPtr PointCloudConstPtr; 00068 00069 public: 00071 PassThrough (bool extract_removed_indices = false) : 00072 Filter<PointT>::Filter (extract_removed_indices), keep_organized_ (false), 00073 user_filter_value_ (std::numeric_limits<float>::quiet_NaN ()) 00074 { 00075 filter_name_ = "PassThrough"; 00076 } 00077 00086 inline void 00087 setKeepOrganized (bool val) 00088 { 00089 keep_organized_ = val; 00090 } 00091 00092 inline bool 00093 getKeepOrganized () 00094 { 00095 return (keep_organized_); 00096 } 00097 00103 inline void 00104 setUserFilterValue (float val) 00105 { 00106 user_filter_value_ = val; 00107 } 00108 protected: 00112 void 00113 applyFilter (PointCloud &output); 00114 00115 typedef typename pcl::traits::fieldList<PointT>::type FieldList; 00116 00117 private: 00121 bool keep_organized_; 00122 00126 float user_filter_value_; 00127 }; 00128 00130 00135 template<> 00136 class PCL_EXPORTS PassThrough<sensor_msgs::PointCloud2> : public Filter<sensor_msgs::PointCloud2> 00137 { 00138 typedef sensor_msgs::PointCloud2 PointCloud2; 00139 typedef PointCloud2::Ptr PointCloud2Ptr; 00140 typedef PointCloud2::ConstPtr PointCloud2ConstPtr; 00141 00142 using Filter<sensor_msgs::PointCloud2>::removed_indices_; 00143 using Filter<sensor_msgs::PointCloud2>::extract_removed_indices_; 00144 00145 public: 00147 PassThrough (bool extract_removed_indices = false) : 00148 Filter<sensor_msgs::PointCloud2>::Filter (extract_removed_indices), keep_organized_ (false), 00149 user_filter_value_ (std::numeric_limits<float>::quiet_NaN ()) 00150 { 00151 filter_name_ = "PassThrough"; 00152 } 00153 00162 inline void 00163 setKeepOrganized (bool val) 00164 { 00165 keep_organized_ = val; 00166 } 00167 00168 inline bool 00169 getKeepOrganized () 00170 { 00171 return (keep_organized_); 00172 } 00173 00179 inline void 00180 setUserFilterValue (float val) 00181 { 00182 user_filter_value_ = val; 00183 } 00184 00185 protected: 00186 void 00187 applyFilter (PointCloud2 &output); 00188 00189 private: 00193 bool keep_organized_; 00194 00198 float user_filter_value_; 00199 }; 00200 } 00201 00202 #endif //#ifndef PCL_FILTERS_PASSTHROUGH_H_