Point Cloud Library (PCL)
1.3.1
|
00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2009, 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: random_sample.h 3029 2011-11-01 04:12:25Z svn $ 00035 * 00036 */ 00037 00038 #ifndef PCL_FILTERS_RANDOM_SUBSAMPLE_H_ 00039 #define PCL_FILTERS_RANDOM_SUBSAMPLE_H_ 00040 00041 #include "pcl/filters/filter_indices.h" 00042 #include <time.h> 00043 #include <limits.h> 00044 00045 namespace pcl 00046 { 00053 template<typename PointT> 00054 class RandomSample : public FilterIndices<PointT> 00055 { 00056 using FilterIndices<PointT>::filter_name_; 00057 using FilterIndices<PointT>::getClassName; 00058 using FilterIndices<PointT>::indices_; 00059 using FilterIndices<PointT>::input_; 00060 00061 typedef typename FilterIndices<PointT>::PointCloud PointCloud; 00062 typedef typename PointCloud::Ptr PointCloudPtr; 00063 typedef typename PointCloud::ConstPtr PointCloudConstPtr; 00064 00065 public: 00067 RandomSample () : sample_ (UINT_MAX), seed_(time(NULL)) 00068 { 00069 filter_name_ = "RandomSample"; 00070 } 00071 00075 inline void 00076 setSample (unsigned int sample) 00077 { 00078 sample_ = sample; 00079 } 00080 00083 inline unsigned int 00084 getSample () 00085 { 00086 return (sample_); 00087 } 00088 00092 inline void 00093 setSeed (unsigned int seed) 00094 { 00095 seed_ = seed; 00096 } 00097 00100 inline unsigned int 00101 getSeed () 00102 { 00103 return (seed_); 00104 } 00105 00107 unsigned int sample_; 00109 unsigned int seed_; 00110 00111 protected: 00115 void 00116 applyFilter (PointCloud &output); 00117 00121 void 00122 applyFilter (std::vector<int> &indices); 00123 00124 00125 }; 00126 00128 00132 template<> 00133 class PCL_EXPORTS RandomSample<sensor_msgs::PointCloud2> : public FilterIndices<sensor_msgs::PointCloud2> 00134 { 00135 using FilterIndices<sensor_msgs::PointCloud2>::filter_name_; 00136 using FilterIndices<sensor_msgs::PointCloud2>::getClassName; 00137 00138 typedef sensor_msgs::PointCloud2 PointCloud2; 00139 typedef PointCloud2::Ptr PointCloud2Ptr; 00140 typedef PointCloud2::ConstPtr PointCloud2ConstPtr; 00141 00142 public: 00144 RandomSample () : sample_ (UINT_MAX), seed_(time(NULL)) 00145 { 00146 filter_name_ = "RandomSample"; 00147 } 00148 00152 inline void 00153 setSample (unsigned int sample) 00154 { 00155 sample_ = sample; 00156 } 00157 00160 inline unsigned int 00161 getSample () 00162 { 00163 return (sample_); 00164 } 00165 00169 inline void 00170 setSeed (unsigned int seed) 00171 { 00172 seed_ = seed; 00173 } 00174 00177 inline unsigned int 00178 getSeed () 00179 { 00180 return (seed_); 00181 } 00182 00183 protected: 00187 void 00188 applyFilter (PointCloud2 &output); 00189 00193 void 00194 applyFilter (std::vector<int> &indices); 00195 00197 unsigned int sample_; 00199 unsigned int seed_; 00200 }; 00201 } 00202 00203 #endif //#ifndef PCL_FILTERS_RANDOM_SUBSAMPLE_H_