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 3, 2019
1 parent d009887 commit 3e5eab2
Show file tree
Hide file tree
Showing 34 changed files with 189 additions and 322 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
7 changes: 0 additions & 7 deletions outofcore/include/pcl/outofcore/boost.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,11 +44,4 @@

#include <boost/filesystem.hpp>
#include <boost/thread.hpp>
#include <boost/random/uniform_int.hpp>
#include <boost/uuid/uuid.hpp>
#include <boost/uuid/uuid_generators.hpp>
#include <boost/uuid/uuid_io.hpp>
#include <boost/random/mersenne_twister.hpp>
#include <boost/random/uniform_int.hpp>
#include <boost/random/bernoulli_distribution.hpp>
#include <boost/foreach.hpp>
16 changes: 7 additions & 9 deletions outofcore/include/pcl/outofcore/impl/octree_base_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ namespace pcl
boost::mutex OutofcoreOctreeBaseNode<ContainerT, PointT>::rng_mutex_;

template<typename ContainerT, typename PointT>
boost::mt19937 OutofcoreOctreeBaseNode<ContainerT, PointT>::rand_gen_;
std::mt19937 OutofcoreOctreeBaseNode<ContainerT, PointT>::rng_;

template<typename ContainerT, typename PointT>
const double OutofcoreOctreeBaseNode<ContainerT, PointT>::sample_percent_ = .125;
Expand Down Expand Up @@ -597,25 +597,23 @@ namespace pcl

// Create random number generator
boost::mutex::scoped_lock lock(rng_mutex_);
boost::uniform_int<boost::uint64_t> buffdist(0, inputsize-1);
boost::variate_generator<boost::mt19937&, boost::uniform_int<boost::uint64_t> > buffdie(rand_gen_, buffdist);
std::uniform_int_distribution<uint64_t> buffdist(0, inputsize-1);

// Randomly pick sampled points
for(boost::uint64_t i = 0; i < samplesize; ++i)
for(uint64_t i = 0; i < samplesize; ++i)
{
boost::uint64_t buffstart = buffdie();
uint64_t buffstart = buffdist(rng_);
insertBuff[i] = ( sampleBuff[buffstart] );
}
}
// Have to do it the slow way
else
{
boost::mutex::scoped_lock lock(rng_mutex_);
boost::bernoulli_distribution<double> buffdist(percent);
boost::variate_generator<boost::mt19937&, boost::bernoulli_distribution<double> > buffcoin(rand_gen_, buffdist);
std::bernoulli_distribution buffdist(percent);

for(boost::uint64_t i = 0; i < inputsize; ++i)
if(buffcoin())
for(uint64_t i = 0; i < inputsize; ++i)
if(buffdist(rng_))
insertBuff.push_back( p[i] );
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,9 @@

// Boost
#include <pcl/outofcore/boost.h>
#include <boost/random/bernoulli_distribution.hpp>
#include <boost/random/uniform_int.hpp>
#include <boost/uuid/uuid_io.hpp>

// PCL
#include <pcl/io/pcd_io.h>
Expand Down
12 changes: 5 additions & 7 deletions outofcore/include/pcl/outofcore/impl/octree_ram_container.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,12 +50,11 @@ namespace pcl
{
namespace outofcore
{

template<typename PointT>
boost::mutex OutofcoreOctreeRamContainer<PointT>::rng_mutex_;

template<typename PointT>
boost::mt19937 OutofcoreOctreeRamContainer<PointT>::rand_gen_ (static_cast<unsigned int>(std::time( NULL)));
std::mt19937 OutofcoreOctreeRamContainer<PointT>::rng_ ([] {std::random_device rd; return rd(); } ());

template<typename PointT> void
OutofcoreOctreeRamContainer<PointT>::convertToXYZ (const boost::filesystem::path& path)
Expand Down Expand Up @@ -121,16 +120,15 @@ namespace pcl
const double percent,
AlignedPointTVector& v)
{
boost::uint64_t samplesize = static_cast<boost::uint64_t> (percent * static_cast<double> (count));
uint64_t samplesize = static_cast<uint64_t> (percent * static_cast<double> (count));

boost::mutex::scoped_lock lock (rng_mutex_);

boost::uniform_int < boost::uint64_t > buffdist (start, start + count);
boost::variate_generator<boost::mt19937&, boost::uniform_int<boost::uint64_t> > buffdie (rand_gen_, buffdist);
std::uniform_int_distribution < uint64_t > buffdist (start, start + count);

for (boost::uint64_t i = 0; i < samplesize; i++)
for (uint64_t i = 0; i < samplesize; i++)
{
boost::uint64_t buffstart = buffdie ();
uint64_t buffstart = buffdist (rng_);
v.push_back (container_[buffstart]);
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,8 @@

#pragma once

#include <vector>
#include <string>
#include <vector>

#include <pcl/outofcore/boost.h>

Expand Down Expand Up @@ -96,7 +96,6 @@ namespace pcl
AlignedPointTVector container_;

static boost::mutex rng_mutex_;
static boost::mt19937 rand_gen_;
};
}//namespace outofcore
}//namespace pcl
6 changes: 3 additions & 3 deletions outofcore/include/pcl/outofcore/octree_base_node.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,8 @@

#pragma once

#include <random>

#include <pcl/common/io.h>
#include <pcl/PCLPointCloud2.h>

Expand Down Expand Up @@ -561,10 +563,8 @@ namespace pcl

/** \brief Mersenne Twister: A 623-dimensionally equidistributed uniform
* pseudo-random number generator */
static boost::mt19937 rand_gen_;
static std::mt19937 rng_;

/** \brief Random number generator seed */
const static boost::uint32_t rngseed = 0xAABBCCDD;
/** \brief Extension for this class to find the pcd files on disk */
const static std::string pcd_extension;

Expand Down
3 changes: 3 additions & 0 deletions outofcore/include/pcl/outofcore/octree_disk_container.h
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,9 @@
#include <vector>
#include <string>

// Boost
#include <boost/uuid/random_generator.hpp>

#include <pcl/outofcore/boost.h>
#include <pcl/outofcore/octree_abstract_node_container.h>
#include <pcl/io/pcd_io.h>
Expand Down
3 changes: 2 additions & 1 deletion outofcore/include/pcl/outofcore/octree_ram_container.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@
#pragma once

// C++
#include <random>
#include <vector>

#include <pcl/outofcore/boost.h>
Expand Down Expand Up @@ -165,7 +166,7 @@ namespace pcl
AlignedPointTVector container_;

static boost::mutex rng_mutex_;
static boost::mt19937 rand_gen_;
static std::mt19937 rng_;
};
}
}
Loading

0 comments on commit 3e5eab2

Please sign in to comment.