00001 /* 00002 * Copyright (c) 2018, the mcl_3dl authors 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the copyright holder nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00030 #ifndef MCL_3DL_POINT_CLOUD_RANDOM_SAMPLER_H 00031 #define MCL_3DL_POINT_CLOUD_RANDOM_SAMPLER_H 00032 00033 #include <random> 00034 00035 #include <pcl/point_types.h> 00036 #include <pcl_ros/point_cloud.h> 00037 00038 namespace mcl_3dl 00039 { 00040 class PointCloudRandomSampler 00041 { 00042 private: 00043 std::random_device seed_gen_; 00044 std::shared_ptr<std::default_random_engine> engine_; 00045 00046 public: 00047 PointCloudRandomSampler() 00048 : engine_(new std::default_random_engine(seed_gen_())) 00049 { 00050 } 00051 template <class POINT_TYPE> 00052 typename pcl::PointCloud<POINT_TYPE>::Ptr sample( 00053 const typename pcl::PointCloud<POINT_TYPE>::ConstPtr& pc, 00054 const size_t num) const 00055 { 00056 typename pcl::PointCloud<POINT_TYPE>::Ptr output(new pcl::PointCloud<POINT_TYPE>); 00057 output->header = pc->header; 00058 00059 if (pc->points.size() == 0) 00060 return output; 00061 00062 output->points.reserve(num); 00063 std::uniform_int_distribution<size_t> ud(0, pc->points.size() - 1); 00064 for (size_t i = 0; i < num; i++) 00065 { 00066 output->push_back(pc->points[ud(*engine_)]); 00067 } 00068 00069 return output; 00070 } 00071 }; 00072 } // namespace mcl_3dl 00073 00074 #endif // MCL_3DL_POINT_CLOUD_RANDOM_SAMPLER_H