point_cloud_uniform_sampler.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2020, the mcl_3dl authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #ifndef MCL_3DL_POINT_CLOUD_RANDOM_SAMPLERS_POINT_CLOUD_UNIFORM_SAMPLER_H
31 #define MCL_3DL_POINT_CLOUD_RANDOM_SAMPLERS_POINT_CLOUD_UNIFORM_SAMPLER_H
32 
33 #include <memory>
34 #include <random>
35 
36 #include <pcl/point_cloud.h>
37 
39 
40 namespace mcl_3dl
41 {
42 template <class POINT_TYPE>
44 {
45 private:
46  std::random_device seed_gen_;
47  std::shared_ptr<std::default_random_engine> engine_;
48 
49 public:
51  : engine_(new std::default_random_engine(seed_gen_()))
52  {
53  }
54  typename pcl::PointCloud<POINT_TYPE>::Ptr sample(
55  const typename pcl::PointCloud<POINT_TYPE>::ConstPtr& pc,
56  const size_t num) const final
57  {
58  typename pcl::PointCloud<POINT_TYPE>::Ptr output(new pcl::PointCloud<POINT_TYPE>);
59  output->header = pc->header;
60 
61  if (pc->points.size() == 0)
62  return output;
63 
64  output->points.reserve(num);
65  std::uniform_int_distribution<size_t> ud(0, pc->points.size() - 1);
66  for (size_t i = 0; i < num; i++)
67  {
68  output->push_back(pc->points[ud(*engine_)]);
69  }
70 
71  return output;
72  }
73 };
74 
75 } // namespace mcl_3dl
76 
77 #endif // MCL_3DL_POINT_CLOUD_RANDOM_SAMPLERS_POINT_CLOUD_UNIFORM_SAMPLER_H
pcl::PointCloud< POINT_TYPE >::Ptr sample(const typename pcl::PointCloud< POINT_TYPE >::ConstPtr &pc, const size_t num) const final
std::shared_ptr< std::default_random_engine > engine_


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Wed May 12 2021 02:16:29