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 36 #include <pcl/point_cloud.h> 42 template <
class POINT_TYPE>
47 std::shared_ptr<std::default_random_engine>
engine_;
51 : engine_(new
std::default_random_engine(seed_gen_()))
54 typename pcl::PointCloud<POINT_TYPE>::Ptr
sample(
55 const typename pcl::PointCloud<POINT_TYPE>::ConstPtr& pc,
56 const size_t num)
const final 58 typename pcl::PointCloud<POINT_TYPE>::Ptr output(
new pcl::PointCloud<POINT_TYPE>);
59 output->header = pc->header;
61 if (pc->points.size() == 0)
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++)
68 output->push_back(pc->points[ud(*engine_)]);
77 #endif // MCL_3DL_POINT_CLOUD_RANDOM_SAMPLERS_POINT_CLOUD_UNIFORM_SAMPLER_H