MRPT  1.9.9
RandomGenerators.h
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2018, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 #pragma once
10 
11 #include <stdexcept>
12 #include <random>
13 #include <limits>
14 #include <vector>
15 #include <algorithm>
16 #include <cstddef>
17 #include <type_traits> // remove_reference
19 
20 // Frwd decl:
21 namespace Eigen
22 {
23 template <typename _MatrixType>
25 }
26 
27 namespace mrpt
28 {
29 /** A namespace of pseudo-random numbers generators of diferent distributions.
30  * The central class in this namespace is mrpt::random::CRandomGenerator
31  * \ingroup mrpt_random_grp
32  */
33 namespace random
34 {
35 /** A thred-safe pseudo random number generator, based on an internal MT19937
36  * randomness generator.
37  * The base algorithm for randomness is platform-independent. See
38  * http://en.wikipedia.org/wiki/Mersenne_twister
39  *
40  * For real thread-safety, each thread must create and use its own instance of
41  * this class.
42  *
43  * Single-thread programs can use the static object
44  * mrpt::random::randomGenerator
45  * \ingroup mrpt_random_grp
46  */
48 {
49  protected:
50  /** Data used internally by the MT19937 PRNG algorithm. */
51  std::mt19937_64 m_MT19937;
52 
53  std::normal_distribution<double> m_normdistribution;
54  std::uniform_int_distribution<uint32_t> m_uint32;
55  std::uniform_int_distribution<uint64_t> m_uint64;
56 
57  void MT19937_initializeGenerator(const uint32_t& seed);
58 
59  public:
60  /** @name Initialization
61  @{ */
62 
63  /** Default constructor: initialize random seed based on current time */
65  /** Constructor for providing a custom random seed to initialize the PRNG */
66  CRandomGenerator(const uint32_t seed) { randomize(seed); }
67  /** Initialize the PRNG from the given random seed */
68  void randomize(const uint32_t seed);
69  /** Randomize the generators, based on std::random_device */
70  void randomize();
71 
72  /** @} */
73 
74  /** @name Uniform pdf
75  @{ */
76 
77  /** Generate a uniformly distributed pseudo-random number using the MT19937
78  * algorithm, in the whole range of 32-bit integers.
79  * See: http://en.wikipedia.org/wiki/Mersenne_twister */
81 
82  /** Returns a uniformly distributed pseudo-random number by joining two
83  * 32bit numbers from \a drawUniform32bit() */
85 
86  /** You can call this overloaded method with either 32 or 64bit unsigned
87  * ints for the sake of general coding. */
88  void drawUniformUnsignedInt(uint32_t& ret_number)
89  {
90  ret_number = m_uint32(m_MT19937);
91  }
92  void drawUniformUnsignedInt(uint64_t& ret_number)
93  {
94  ret_number = m_uint64(m_MT19937);
95  }
96 
97  /** Return a uniform unsigned integer in the range [min_val,max_val] (both
98  * inclusive) */
99  template <typename T, typename U, typename V>
101  T& ret_number, const U min_val, const V max_val)
102  {
103  const T range = max_val - min_val + 1;
104  T rnd;
106  ret_number = min_val + (rnd % range);
107  }
108 
109  /** Generate a uniformly distributed pseudo-random number using the MT19937
110  * algorithm, scaled to the selected range. */
111  double drawUniform(const double Min, const double Max)
112  {
113  return Min +
114  (Max - Min) * drawUniform32bit() *
115  2.3283064370807973754314699618685e-10; // 0xFFFFFFFF ^ -1
116  }
117 
118  /** Fills the given matrix with independent, uniformly distributed samples.
119  * Matrix classes can be mrpt::math::CMatrixTemplateNumeric or
120  * mrpt::math::CMatrixFixedNumeric
121  * \sa drawUniform
122  */
123  template <class MAT>
125  MAT& matrix, const double unif_min = 0, const double unif_max = 1)
126  {
127  for (size_t r = 0; r < matrix.rows(); r++)
128  for (size_t c = 0; c < matrix.cols(); c++)
129  matrix.get_unsafe(r, c) = static_cast<typename MAT::Scalar>(
130  drawUniform(unif_min, unif_max));
131  }
132 
133  /** Fills the given vector with independent, uniformly distributed samples.
134  * \sa drawUniform
135  */
136  template <class VEC>
138  VEC& v, const double unif_min = 0, const double unif_max = 1)
139  {
140  const size_t N = v.size();
141  for (size_t c = 0; c < N; c++)
142  v[c] = static_cast<typename std::decay<decltype(v[c])>::type>(
143  drawUniform(unif_min, unif_max));
144  }
145 
146  /** @} */
147 
148  /** @name Normal/Gaussian pdf
149  @{ */
150 
151  /** Generate a normalized (mean=0, std=1) normally distributed sample.
152  * \param likelihood If desired, pass a pointer to a double which will
153  * receive the likelihood of the given sample to have been obtained, that
154  * is, the value of the normal pdf at the sample value.
155  */
156  double drawGaussian1D_normalized();
157 
158  /** Generate a normally distributed pseudo-random number.
159  * \param mean The mean value of desired normal distribution
160  * \param std The standard deviation value of desired normal distribution
161  */
162  double drawGaussian1D(const double mean, const double std)
163  {
164  return mean + std * drawGaussian1D_normalized();
165  }
166 
167  /** Fills the given matrix with independent, 1D-normally distributed
168  * samples.
169  * Matrix classes can be mrpt::math::CMatrixTemplateNumeric or
170  * mrpt::math::CMatrixFixedNumeric
171  * \sa drawGaussian1D
172  */
173  template <class MAT>
175  MAT& matrix, const double mean = 0, const double std = 1)
176  {
177  for (decltype(matrix.rows()) r = 0; r < matrix.rows(); r++)
178  for (decltype(matrix.cols()) c = 0; c < matrix.cols(); c++)
179  matrix.get_unsafe(r, c) = static_cast<typename MAT::Scalar>(
181  }
182 
183  /** Generates a random definite-positive matrix of the given size, using the
184  * formula C = v*v^t + epsilon*I, with "v" being a vector of gaussian random
185  * samples.
186  */
187  template <class MATRIX, class AUXVECTOR_T = MATRIX>
189  const size_t dim, const double std_scale = 1.0,
190  const double diagonal_epsilon = 1e-8)
191  {
192  AUXVECTOR_T r(dim, 1);
193  drawGaussian1DMatrix(r, 0, std_scale);
194  MATRIX cov;
195  cov.resize(dim, dim);
196  cov.multiply_AAt(r); // random semi-definite positive matrix:
197  for (size_t i = 0; i < dim; i++)
198  cov(i, i) += diagonal_epsilon; // make sure it's definite-positive
199  return cov;
200  }
201 
202  /** Fills the given vector with independent, 1D-normally distributed
203  * samples.
204  * \sa drawGaussian1D
205  */
206  template <class VEC>
208  VEC& v, const double mean = 0, const double std = 1)
209  {
210  const size_t N = v.size();
211  for (size_t c = 0; c < N; c++)
212  v[c] = static_cast<std::remove_reference_t<decltype(v[c])>>(
214  }
215 
216  /** Generate multidimensional random samples according to a given covariance
217  * matrix.
218  * Mean is assumed to be zero if mean==nullptr.
219  * \exception std::exception On invalid covariance matrix
220  * \sa drawGaussianMultivariateMany
221  */
222  template <typename T, typename MATRIX>
224  std::vector<T>& out_result, const MATRIX& cov,
225  const std::vector<T>* mean = nullptr)
226  {
227  const size_t dim = cov.cols();
228  if (cov.rows() != cov.cols())
229  throw std::runtime_error(
230  "drawGaussianMultivariate(): cov is not square.");
231  if (mean && mean->size() != dim)
232  throw std::runtime_error(
233  "drawGaussianMultivariate(): mean and cov sizes ");
234  MATRIX Z, D;
235  // Set size of output vector:
236  out_result.clear();
237  out_result.resize(dim, 0);
238  /** Computes the eigenvalues/eigenvector decomposition of this matrix,
239  * so that: M = Z � D � Z<sup>T</sup>, where columns in Z are the
240  * eigenvectors and the diagonal matrix D contains the eigenvalues
241  * as diagonal elements, sorted in <i>ascending</i> order.
242  */
243  cov.eigenVectors(Z, D);
244  // Scale eigenvectors with eigenvalues:
245  D = D.array().sqrt().matrix();
246  Z.multiply(Z, D);
247  for (size_t i = 0; i < dim; i++)
248  {
249  T rnd = this->drawGaussian1D_normalized();
250  for (size_t d = 0; d < dim; d++)
251  out_result[d] += (Z.get_unsafe(d, i) * rnd);
252  }
253  if (mean)
254  for (size_t d = 0; d < dim; d++) out_result[d] += (*mean)[d];
255  }
256 
257  /** Generate multidimensional random samples according to a given covariance
258  * matrix.
259  * Mean is assumed to be zero if mean==nullptr.
260  * \exception std::exception On invalid covariance matrix
261  * \sa drawGaussianMultivariateMany
262  */
263  template <class VECTORLIKE, class COVMATRIX>
265  VECTORLIKE& out_result, const COVMATRIX& cov,
266  const VECTORLIKE* mean = nullptr)
267  {
268  const size_t N = cov.rows();
269  if (cov.rows() != cov.cols())
270  throw std::runtime_error(
271  "drawGaussianMultivariate(): cov is not square.");
272  if (mean && size_t(mean->size()) != N)
273  throw std::runtime_error(
274  "drawGaussianMultivariate(): mean and cov sizes ");
275 
276  // Compute eigenvalues/eigenvectors of cov:
278  eigensolver(cov);
279 
280  auto eigVecs = eigensolver.eigenvectors();
281  auto eigVals = eigensolver.eigenvalues();
282 
283  // Scale eigenvectors with eigenvalues:
284  // D.Sqrt(); Z = Z * D; (for each column)
285  eigVals = eigVals.array().sqrt();
286  for (typename COVMATRIX::Index i = 0; i < eigVecs.cols(); i++)
287  eigVecs.col(i) *= eigVals[i];
288 
289  // Set size of output vector:
290  out_result.assign(N, 0);
291 
292  for (size_t i = 0; i < N; i++)
293  {
295  for (size_t d = 0; d < N; d++)
296  out_result[d] += eigVecs.coeff(d, i) * rnd;
297  }
298  if (mean)
299  for (size_t d = 0; d < N; d++) out_result[d] += (*mean)[d];
300  }
301 
302  /** Generate a given number of multidimensional random samples according to
303  * a given covariance matrix.
304  * \param cov The covariance matrix where to draw the samples from.
305  * \param desiredSamples The number of samples to generate.
306  * \param ret The output list of samples
307  * \param mean The mean, or zeros if mean==nullptr.
308  */
309  template <typename VECTOR_OF_VECTORS, typename COVMATRIX>
311  VECTOR_OF_VECTORS& ret, size_t desiredSamples, const COVMATRIX& cov,
312  const typename VECTOR_OF_VECTORS::value_type* mean = nullptr)
313  {
314  const size_t N = cov.rows();
315  if (cov.rows() != cov.cols())
316  throw std::runtime_error(
317  "drawGaussianMultivariateMany(): cov is not square.");
318  if (mean && size_t(mean->size()) != N)
319  throw std::runtime_error(
320  "drawGaussianMultivariateMany(): mean and cov sizes ");
321 
322  // Compute eigenvalues/eigenvectors of cov:
324  eigensolver(cov);
325 
327  typename COVMATRIX::PlainObject>::MatrixType eigVecs =
328  eigensolver.eigenvectors();
330  typename COVMATRIX::PlainObject>::RealVectorType eigVals =
331  eigensolver.eigenvalues();
332 
333  // Scale eigenvectors with eigenvalues:
334  // D.Sqrt(); Z = Z * D; (for each column)
335  eigVals = eigVals.array().sqrt();
336  for (typename COVMATRIX::Index i = 0; i < eigVecs.cols(); i++)
337  eigVecs.col(i) *= eigVals[i];
338 
339  // Set size of output vector:
340  ret.resize(desiredSamples);
341  for (size_t k = 0; k < desiredSamples; k++)
342  {
343  ret[k].assign(N, 0);
344  for (size_t i = 0; i < N; i++)
345  {
347  for (size_t d = 0; d < N; d++)
348  ret[k][d] += eigVecs.coeff(d, i) * rnd;
349  }
350  if (mean)
351  for (size_t d = 0; d < N; d++) ret[k][d] += (*mean)[d];
352  }
353  }
354 
355  /** @} */
356 
357  /** @name Miscellaneous
358  @{ */
359 
360  /** Returns a random permutation of a vector: all the elements of the input
361  * vector are in the output but at random positions.
362  */
363  template <class VEC>
364  void permuteVector(const VEC& in_vector, VEC& out_result)
365  {
366  out_result = in_vector;
367  const size_t N = out_result.size();
368  if (N > 1) mrpt::random::shuffle(&out_result[0], &out_result[N - 1]);
369  }
370 
371  /** @} */
372 
373 }; // end of CRandomGenerator
374 // --------------------------------------------------------------
375 
376 /** A static instance of a CRandomGenerator class, for use in single-thread
377  * applications */
378 CRandomGenerator& getRandomGenerator();
379 
380 /** A random number generator for usage in STL algorithms expecting a function
381  * like this (eg, random_shuffle):
382  */
384 {
385  return getRandomGenerator().drawUniform32bit() % i;
386 }
387 
388 /** Fills the given matrix with independent, uniformly distributed samples.
389  * Matrix classes can be mrpt::math::CMatrixTemplateNumeric or
390  * mrpt::math::CMatrixFixedNumeric
391  * \sa matrixRandomNormal
392  */
393 template <class MAT>
395  MAT& matrix, const double unif_min = 0, const double unif_max = 1)
396 {
397  for (size_t r = 0; r < matrix.rows(); r++)
398  for (size_t c = 0; c < matrix.cols(); c++)
399  matrix.get_unsafe(r, c) = static_cast<typename MAT::Scalar>(
400  getRandomGenerator().drawUniform(unif_min, unif_max));
401 }
402 
403 /** Fills the given matrix with independent, uniformly distributed samples.
404  * \sa vectorRandomNormal
405  */
406 template <class T>
408  std::vector<T>& v_out, const T& unif_min = 0, const T& unif_max = 1)
409 {
410  size_t n = v_out.size();
411  for (size_t r = 0; r < n; r++)
412  v_out[r] = getRandomGenerator().drawUniform(unif_min, unif_max);
413 }
414 
415 /** Fills the given matrix with independent, normally distributed samples.
416  * Matrix classes can be mrpt::math::CMatrixTemplateNumeric or
417  * mrpt::math::CMatrixFixedNumeric
418  * \sa matrixRandomUni
419  */
420 template <class MAT>
422  MAT& matrix, const double mean = 0, const double std = 1)
423 {
424  for (size_t r = 0; r < matrix.rows(); r++)
425  for (size_t c = 0; c < matrix.cols(); c++)
426  matrix.get_unsafe(r, c) = static_cast<typename MAT::Scalar>(
428 }
429 
430 /** Generates a random vector with independent, normally distributed samples.
431  * \sa matrixRandomUni
432  */
433 template <class T>
435  std::vector<T>& v_out, const T& mean = 0, const T& std = 1)
436 {
437  size_t n = v_out.size();
438  for (size_t r = 0; r < n; r++)
439  v_out[r] =
441 }
442 
443 /** Randomize the generators.
444  * A seed can be providen, or a current-time based seed can be used (default)
445  */
446 inline void Randomize(const uint32_t seed)
447 {
449 }
450 inline void Randomize() { getRandomGenerator().randomize(); }
451 /** Returns a random permutation of a vector: all the elements of the input
452  * vector are in the output but at random positions.
453  */
454 template <class T>
456  const std::vector<T>& in_vector, std::vector<T>& out_result)
457 {
458  getRandomGenerator().permuteVector(in_vector, out_result);
459 }
460 
461 /** Generate a given number of multidimensional random samples according to a
462 * given covariance matrix.
463 * \param cov The covariance matrix where to draw the samples from.
464 * \param desiredSamples The number of samples to generate.
465 * \param samplesLikelihoods If desired, set to a valid pointer to a vector,
466 * where it will be stored the likelihoods of having obtained each sample: the
467 * product of the gaussian-pdf for each independent variable.
468 * \param ret The output list of samples
469 *
470 * \exception std::exception On invalid covariance matrix
471 *
472 * \sa randomNormalMultiDimensional
473 */
474 template <typename T, typename MATRIX>
476  const MATRIX& cov, size_t desiredSamples, std::vector<std::vector<T>>& ret,
477  std::vector<T>* samplesLikelihoods = nullptr)
478 {
480  ret, desiredSamples, cov, static_cast<const std::vector<T>*>(nullptr),
481  samplesLikelihoods);
482 }
483 
484 /** Generate multidimensional random samples according to a given covariance
485  * matrix.
486  * \exception std::exception On invalid covariance matrix
487  * \sa randomNormalMultiDimensional
488  */
489 template <typename T, typename MATRIXLIKE>
491  const MATRIXLIKE& cov, size_t desiredSamples,
492  std::vector<std::vector<T>>& ret)
493 {
494  getRandomGenerator().drawGaussianMultivariateMany(ret, desiredSamples, cov);
495 }
496 
497 /** Generate multidimensional random samples according to a given covariance
498  * matrix.
499  * \exception std::exception On invalid covariance matrix
500  * \sa randomNormalMultiDimensionalMany
501  */
502 template <typename T, typename MATRIX>
503 void randomNormalMultiDimensional(const MATRIX& cov, std::vector<T>& out_result)
504 {
506 }
507 
508 } // End of namespace
509 } // End of namespace
uint32_t drawUniform32bit()
Generate a uniformly distributed pseudo-random number using the MT19937 algorithm, in the whole range of 32-bit integers.
double drawUniform(const double Min, const double Max)
Generate a uniformly distributed pseudo-random number using the MT19937 algorithm, scaled to the selected range.
GLsizei range
Definition: glext.h:5907
void permuteVector(const VEC &in_vector, VEC &out_result)
Returns a random permutation of a vector: all the elements of the input vector are in the output but ...
MATRIX drawDefinitePositiveMatrix(const size_t dim, const double std_scale=1.0, const double diagonal_epsilon=1e-8)
Generates a random definite-positive matrix of the given size, using the formula C = v*v^t + epsilon*...
void drawUniformUnsignedInt(uint32_t &ret_number)
You can call this overloaded method with either 32 or 64bit unsigned ints for the sake of general cod...
double Scalar
Definition: KmUtils.h:44
GLuint GLenum matrix
Definition: glext.h:6975
void shuffle(RandomIt first, RandomIt last, URBG &&g)
Uniform shuffle a sequence.
void drawGaussian1DVector(VEC &v, const double mean=0, const double std=1)
Fills the given vector with independent, 1D-normally distributed samples.
void randomize(const uint32_t seed)
Initialize the PRNG from the given random seed.
GLenum GLsizei n
Definition: glext.h:5074
void drawGaussian1DMatrix(MAT &matrix, const double mean=0, const double std=1)
Fills the given matrix with independent, 1D-normally distributed samples.
std::uniform_int_distribution< uint64_t > m_uint64
STL namespace.
std::normal_distribution< double > m_normdistribution
A thred-safe pseudo random number generator, based on an internal MT19937 randomness generator...
void randomPermutation(const std::vector< T > &in_vector, std::vector< T > &out_result)
Returns a random permutation of a vector: all the elements of the input vector are in the output but ...
void drawUniformUnsignedIntRange(T &ret_number, const U min_val, const V max_val)
Return a uniform unsigned integer in the range [min_val,max_val] (both inclusive) ...
double drawGaussian1D(const double mean, const double std)
Generate a normally distributed pseudo-random number.
void drawUniformMatrix(MAT &matrix, const double unif_min=0, const double unif_max=1)
Fills the given matrix with independent, uniformly distributed samples.
void drawGaussianMultivariate(VECTORLIKE &out_result, const COVMATRIX &cov, const VECTORLIKE *mean=nullptr)
Generate multidimensional random samples according to a given covariance matrix.
const GLubyte * c
Definition: glext.h:6313
void drawGaussianMultivariateMany(VECTOR_OF_VECTORS &ret, size_t desiredSamples, const COVMATRIX &cov, const typename VECTOR_OF_VECTORS::value_type *mean=nullptr)
Generate a given number of multidimensional random samples according to a given covariance matrix...
void Randomize(const uint32_t seed)
Randomize the generators.
std::mt19937_64 m_MT19937
Data used internally by the MT19937 PRNG algorithm.
void vectorRandomNormal(std::vector< T > &v_out, const T &mean=0, const T &std=1)
Generates a random vector with independent, normally distributed samples.
CRandomGenerator(const uint32_t seed)
Constructor for providing a custom random seed to initialize the PRNG.
ptrdiff_t random_generator_for_STL(ptrdiff_t i)
A random number generator for usage in STL algorithms expecting a function like this (eg...
_W64 int ptrdiff_t
Definition: glew.h:137
uint64_t drawUniform64bit()
Returns a uniformly distributed pseudo-random number by joining two 32bit numbers from drawUniform32b...
unsigned __int64 uint64_t
Definition: rptypes.h:50
const GLdouble * v
Definition: glext.h:3678
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
GLdouble GLdouble GLdouble r
Definition: glext.h:3705
void drawGaussianMultivariate(std::vector< T > &out_result, const MATRIX &cov, const std::vector< T > *mean=nullptr)
Generate multidimensional random samples according to a given covariance matrix.
void matrixRandomNormal(MAT &matrix, const double mean=0, const double std=1)
Fills the given matrix with independent, normally distributed samples.
void matrixRandomUni(MAT &matrix, const double unif_min=0, const double unif_max=1)
Fills the given matrix with independent, uniformly distributed samples.
void randomize()
Randomize the generators, based on std::random_device.
void MT19937_initializeGenerator(const uint32_t &seed)
std::uniform_int_distribution< uint32_t > m_uint32
CRandomGenerator()
Default constructor: initialize random seed based on current time.
void vectorRandomUni(std::vector< T > &v_out, const T &unif_min=0, const T &unif_max=1)
Fills the given matrix with independent, uniformly distributed samples.
Eigen::Matrix< typename MATRIX::Scalar, MATRIX::ColsAtCompileTime, MATRIX::ColsAtCompileTime > cov(const MATRIX &v)
Computes the covariance matrix from a list of samples in an NxM matrix, where each row is a sample...
Definition: ops_matrices.h:148
void randomNormalMultiDimensionalMany(const MATRIX &cov, size_t desiredSamples, std::vector< std::vector< T >> &ret, std::vector< T > *samplesLikelihoods=nullptr)
Generate a given number of multidimensional random samples according to a given covariance matrix...
void randomNormalMultiDimensional(const MATRIX &cov, std::vector< T > &out_result)
Generate multidimensional random samples according to a given covariance matrix.
unsigned __int32 uint32_t
Definition: rptypes.h:47
CRandomGenerator & getRandomGenerator()
A static instance of a CRandomGenerator class, for use in single-thread applications.
void drawUniformVector(VEC &v, const double unif_min=0, const double unif_max=1)
Fills the given vector with independent, uniformly distributed samples.
GLuint GLuint GLsizei GLenum type
Definition: glext.h:3528
EIGEN_STRONG_INLINE double mean() const
Computes the mean of the entire matrix.
void drawUniformUnsignedInt(uint64_t &ret_number)
double drawGaussian1D_normalized()
Generate a normalized (mean=0, std=1) normally distributed sample.



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 7d5e6d718 Fri Aug 24 01:51:28 2018 +0200 at lun nov 2 08:35:50 CET 2020