Skip to content

Commit

Permalink
Use random generator from C++11 instead of from Boost
Browse files Browse the repository at this point in the history
  • Loading branch information
Heiko Thiel committed Apr 1, 2019
1 parent d009887 commit 77f65ba
Show file tree
Hide file tree
Showing 44 changed files with 242 additions and 483 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -5,11 +5,11 @@
* Author: aitor
*/

#include <random>

#include <pcl/apps/3d_rec_framework/pipeline/global_nn_recognizer_crh.h>
#include <pcl/recognition/crh_alignment.h>
#include <pcl/registration/icp.h>
#include <boost/random.hpp>
#include <boost/random/normal_distribution.hpp>
#include <pcl/common/time.h>

template<template<class > class Distance, typename PointInT, typename FeatureT>
Expand Down Expand Up @@ -428,17 +428,12 @@ template<template<class > class Distance, typename PointInT, typename FeatureT>

if (noisify_)
{
double noise_std = noise_;
boost::posix_time::ptime time = boost::posix_time::microsec_clock::local_time();
boost::posix_time::time_duration duration( time.time_of_day() );
boost::mt19937 rng;
rng.seed (static_cast<unsigned int> (duration.total_milliseconds()));
boost::normal_distribution<> nd (0.0, noise_std);
boost::variate_generator<boost::mt19937&, boost::normal_distribution<> > var_nor (rng, nd);
std::random_device rd;
std::mt19937 rng(rd());
std::normal_distribution<float> nd (0.0f, noise_);
// Noisify each point in the dataset
for (size_t cp = 0; cp < view->points.size (); ++cp)
view->points[cp].z += static_cast<float> (var_nor ());

view->points[cp].z += static_cast<float> (nd (rng));
}

//pro view, compute signatures and CRH
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,6 @@

#include <pcl/apps/3d_rec_framework/pipeline/global_nn_recognizer_cvfh.h>
#include <pcl/registration/icp.h>
#include <boost/random.hpp>
#include <boost/random/normal_distribution.hpp>
#include <pcl/common/time.h>
#include <pcl/visualization/pcl_visualizer.h>

Expand Down Expand Up @@ -653,17 +651,12 @@ template<template<class > class Distance, typename PointInT, typename FeatureT>

if (noisify_)
{
double noise_std = noise_;
boost::posix_time::ptime time = boost::posix_time::microsec_clock::local_time();
boost::posix_time::time_duration duration( time.time_of_day() );
boost::mt19937 rng;
rng.seed (static_cast<unsigned int> (duration.total_milliseconds()));
boost::normal_distribution<> nd (0.0, noise_std);
boost::variate_generator<boost::mt19937&, boost::normal_distribution<> > var_nor (rng, nd);
std::random_device rd;
std::mt19937 rng(rd());
std::normal_distribution<float> nd (0.0f, noise_);
// Noisify each point in the dataset
for (size_t cp = 0; cp < view->points.size (); ++cp)
view->points[cp].z += static_cast<float> (var_nor ());

view->points[cp].z += nd (rng);
}

//pro view, compute signatures
Expand Down
11 changes: 0 additions & 11 deletions common/include/pcl/common/impl/random.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,14 +40,10 @@
#ifndef PCL_COMMON_RANDOM_HPP_
#define PCL_COMMON_RANDOM_HPP_

#include <boost/version.hpp>
#include <pcl/pcl_macros.h>

/////////////////////////////////////////////////////////////////////////////////////////////////////////
template <typename T>
pcl::common::UniformGenerator<T>::UniformGenerator(T min, T max, pcl::uint32_t seed)
: distribution_ (min, max)
, generator_ (rng_, distribution_)
{
parameters_ = Parameters (min, max, seed);
if(parameters_.seed != -1)
Expand All @@ -60,7 +56,6 @@ template <typename T>
pcl::common::UniformGenerator<T>::UniformGenerator(const Parameters& parameters)
: parameters_ (parameters)
, distribution_ (parameters_.min, parameters_.max)
, generator_ (rng_, distribution_)
{
if(parameters_.seed != -1)
rng_.seed (parameters_.seed);
Expand All @@ -87,7 +82,6 @@ pcl::common::UniformGenerator<T>::setParameters (T min, T max, pcl::uint32_t see
typename DistributionType::param_type params (parameters_.min, parameters_.max);
distribution_.param (params);
distribution_.reset ();
generator_.distribution () = distribution_;
if (seed != -1)
{
parameters_.seed = seed;
Expand All @@ -103,7 +97,6 @@ pcl::common::UniformGenerator<T>::setParameters (const Parameters& parameters)
typename DistributionType::param_type params (parameters_.min, parameters_.max);
distribution_.param (params);
distribution_.reset ();
generator_.distribution () = distribution_;
if (parameters_.seed != -1)
rng_.seed (parameters_.seed);
}
Expand All @@ -112,7 +105,6 @@ pcl::common::UniformGenerator<T>::setParameters (const Parameters& parameters)
template <typename T>
pcl::common::NormalGenerator<T>::NormalGenerator(T mean, T sigma, pcl::uint32_t seed)
: distribution_ (mean, sigma)
, generator_ (rng_, distribution_)
{
parameters_ = Parameters (mean, sigma, seed);
if(parameters_.seed != -1)
Expand All @@ -125,7 +117,6 @@ template <typename T>
pcl::common::NormalGenerator<T>::NormalGenerator(const Parameters& parameters)
: parameters_ (parameters)
, distribution_ (parameters_.mean, parameters_.sigma)
, generator_ (rng_, distribution_)
{
if(parameters_.seed != -1)
rng_.seed (parameters_.seed);
Expand All @@ -152,7 +143,6 @@ pcl::common::NormalGenerator<T>::setParameters (T mean, T sigma, pcl::uint32_t s
typename DistributionType::param_type params (parameters_.mean, parameters_.sigma);
distribution_.param (params);
distribution_.reset ();
generator_.distribution () = distribution_;
if (seed != -1)
rng_.seed (parameters_.seed);
}
Expand All @@ -165,7 +155,6 @@ pcl::common::NormalGenerator<T>::setParameters (const Parameters& parameters)
typename DistributionType::param_type params (parameters_.mean, parameters_.sigma);
distribution_.param (params);
distribution_.reset ();
generator_.distribution () = distribution_;
if (parameters_.seed != -1)
rng_.seed (parameters_.seed);
}
Expand Down
45 changes: 16 additions & 29 deletions common/include/pcl/common/random.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,40 +39,33 @@

#pragma once

#ifdef __GNUC__
#pragma GCC system_header
#endif

#include <boost/random/uniform_real.hpp>
#include <boost/random/uniform_int.hpp>
#include <boost/random/variate_generator.hpp>
#include <boost/random/normal_distribution.hpp>
#include <boost/random/mersenne_twister.hpp>
#include <random>

#include <pcl/pcl_macros.h>

namespace pcl
{
namespace common
{
/// uniform distribution dummy struct
template <typename T> struct uniform_distribution;
template <typename T, typename T2=void> struct uniform_distribution;
/// uniform distribution int specialized
template<>
struct uniform_distribution<int>
template <typename T>
struct uniform_distribution<T, std::enable_if_t<std::is_integral<T>::value>>
{
typedef boost::uniform_int<int> type;
typedef std::uniform_int_distribution<T> type;
};
/// uniform distribution float specialized
template<>
struct uniform_distribution<float>
template <typename T>
struct uniform_distribution<T, std::enable_if_t<std::is_floating_point<T>::value>>
{
typedef boost::uniform_real<float> type;
typedef std::uniform_real_distribution<T> type;
};
/// normal distribution
template<typename T>
struct normal_distribution
{
typedef boost::normal_distribution<T> type;
typedef std::normal_distribution<T> type;
};

/** \brief UniformGenerator class generates a random number from range [min, max] at each run picked
Expand Down Expand Up @@ -136,19 +129,16 @@ namespace pcl

/// \return a randomly generated number in the interval [min, max]
inline T
run () { return (generator_ ()); }
run () { return (distribution_ (rng_)); }

private:
typedef boost::mt19937 EngineType;
typedef typename uniform_distribution<T>::type DistributionType;
/// parameters
Parameters parameters_;
/// random number generator
std::mt19937 rng_;
/// uniform distribution
DistributionType distribution_;
/// random number generator
EngineType rng_;
/// generator of random number from a uniform distribution
boost::variate_generator<EngineType&, DistributionType> generator_;
};

/** \brief NormalGenerator class generates a random number from a normal distribution specified
Expand Down Expand Up @@ -211,18 +201,15 @@ namespace pcl

/// \return a randomly generated number in the normal distribution (mean, sigma)
inline T
run () { return (generator_ ()); }
run () { return (distribution_ (rng_)); }

typedef boost::mt19937 EngineType;
typedef typename normal_distribution<T>::type DistributionType;
/// parameters
Parameters parameters_;
/// random number generator
std::mt19937 rng_;
/// normal distribution
DistributionType distribution_;
/// random number generator
EngineType rng_;
/// generator of random number from a normal distribution
boost::variate_generator<EngineType&, DistributionType > generator_;
};
}
}
Expand Down
21 changes: 13 additions & 8 deletions features/include/pcl/features/3dsc.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,8 @@

#pragma once

#include <random>

#include <pcl/point_types.h>
#include <pcl/features/boost.h>
#include <pcl/features/feature.h>
Expand Down Expand Up @@ -103,16 +105,19 @@ namespace pcl
point_density_radius_(0.2),
descriptor_length_ (),
rng_alg_ (),
rng_ (new boost::uniform_01<boost::mt19937> (rng_alg_))
rng_ (0.0f, 1.0f)
{
feature_name_ = "ShapeContext3DEstimation";
search_radius_ = 2.5;

// Create a random number generator object
if (random)
rng_->base ().seed (static_cast<unsigned> (std::time(0)));
{
std::random_device rd;
rng_alg_.seed (rd());
}
else
rng_->base ().seed (12345u);
rng_alg_.seed (12345u);
}

~ShapeContext3DEstimation() {}
Expand Down Expand Up @@ -211,11 +216,11 @@ namespace pcl
/** \brief Descriptor length */
size_t descriptor_length_;

/** \brief Boost-based random number generator algorithm. */
boost::mt19937 rng_alg_;
/** \brief Random number generator algorithm. */
std::mt19937 rng_alg_;

/** \brief Boost-based random number generator distribution. */
boost::shared_ptr<boost::uniform_01<boost::mt19937> > rng_;
/** \brief Random number generator distribution. */
std::uniform_real_distribution<> rng_;

/* \brief Shift computed descriptor "L" times along the azimuthal direction
* \param[in] block_size the size of each azimuthal block
Expand All @@ -229,7 +234,7 @@ namespace pcl
inline double
rnd ()
{
return ((*rng_) ());
return (rng_ (rng_alg_));
}
};
}
Expand Down
1 change: 0 additions & 1 deletion features/include/pcl/features/boost.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,6 @@
#include <boost/unordered_map.hpp>
#include <boost/function.hpp>
#include <boost/bind.hpp>
#include <boost/random.hpp>
#include <boost/property_map/property_map.hpp>
//#include <boost/graph/adjacency_list.hpp>
//#include <boost/graph/johnson_all_pairs_shortest.hpp>
2 changes: 0 additions & 2 deletions filters/include/pcl/filters/boost.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,8 +45,6 @@
#endif

// Marking all Boost headers as system headers to remove warnings
#include <boost/random.hpp>
#include <boost/random/normal_distribution.hpp>
#include <boost/shared_ptr.hpp>
#include <boost/make_shared.hpp>
#include <boost/dynamic_bitset.hpp>
Expand Down
15 changes: 7 additions & 8 deletions filters/include/pcl/filters/impl/normal_space.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,8 +41,9 @@
#include <pcl/filters/normal_space.h>
#include <pcl/common/io.h>

#include <vector>
#include <list>
#include <random>
#include <vector>

///////////////////////////////////////////////////////////////////////////////
template<typename PointT, typename NormalT> bool
Expand All @@ -59,12 +60,6 @@ pcl::NormalSpaceSampling<PointT, NormalT>::initCompute ()
return false;
}

boost::mt19937 rng (static_cast<unsigned int> (seed_));
boost::uniform_int<unsigned int> uniform_distrib (0, unsigned (input_->size ()));
if (rng_uniform_distribution_ != NULL)
delete rng_uniform_distribution_;
rng_uniform_distribution_ = new boost::variate_generator<boost::mt19937, boost::uniform_int<unsigned int> > (rng, uniform_distrib);

return (true);
}

Expand Down Expand Up @@ -228,6 +223,10 @@ pcl::NormalSpaceSampling<PointT, NormalT>::applyFilter (std::vector<int> &indice
boost::dynamic_bitset<> is_sampled_flag (input_normals_->points.size ());
// Maintaining flags to check if all points in the bin are sampled
boost::dynamic_bitset<> bin_empty_flag (normals_hg.size ());

std::mt19937 rng (static_cast<unsigned int> (seed_));
std::uniform_int_distribution<unsigned int> uniform_distrib (0, unsigned (input_->size ()));

unsigned int i = 0;
while (i < sample_)
{
Expand All @@ -244,7 +243,7 @@ pcl::NormalSpaceSampling<PointT, NormalT>::applyFilter (std::vector<int> &indice
// Picking up a sample at random from jth bin
do
{
random_index = static_cast<unsigned int> ((*rng_uniform_distribution_) () % M);
random_index = static_cast<unsigned int> (uniform_distrib (rng) % M);
pos = start_index[j] + random_index;
} while (is_sampled_flag.test (pos));

Expand Down
9 changes: 5 additions & 4 deletions filters/include/pcl/filters/impl/voxel_grid_covariance.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,8 @@
#ifndef PCL_VOXEL_GRID_COVARIANCE_IMPL_H_
#define PCL_VOXEL_GRID_COVARIANCE_IMPL_H_

#include <random>

#include <pcl/common/common.h>
#include <pcl/filters/boost.h>
#include <pcl/filters/voxel_grid_covariance.h>
Expand Down Expand Up @@ -411,9 +413,8 @@ pcl::VoxelGridCovariance<PointT>::getDisplayCloud (pcl::PointCloud<PointXYZ>& ce
cell_cloud.clear ();

int pnt_per_cell = 1000;
boost::mt19937 rng;
boost::normal_distribution<> nd (0.0, leaf_size_.head (3).norm ());
boost::variate_generator<boost::mt19937&, boost::normal_distribution<> > var_nor (rng, nd);
std::mt19937 rng;
std::normal_distribution<> nd (0.0, leaf_size_.head (3).norm ());

Eigen::LLT<Eigen::Matrix3d> llt_of_cov;
Eigen::Matrix3d cholesky_decomp;
Expand All @@ -435,7 +436,7 @@ pcl::VoxelGridCovariance<PointT>::getDisplayCloud (pcl::PointCloud<PointXYZ>& ce
// Random points generated by sampling the normal distribution given by voxel mean and covariance matrix
for (int i = 0; i < pnt_per_cell; i++)
{
rand_point = Eigen::Vector3d (var_nor (), var_nor (), var_nor ());
rand_point = Eigen::Vector3d (nd (rng), nd (rng), nd (rng));
dist_point = cell_mean + cholesky_decomp * rand_point;
cell_cloud.push_back (PointXYZ (static_cast<float> (dist_point (0)), static_cast<float> (dist_point (1)), static_cast<float> (dist_point (2))));
}
Expand Down
Loading

0 comments on commit 77f65ba

Please sign in to comment.