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