A thred-safe pseudo random number generator, based on an internal MT19937 randomness generator.
The base algorithm for randomness is platform-independent. See http://en.wikipedia.org/wiki/Mersenne_twister
For real thread-safety, each thread must create and use its own instance of this class.
Single-thread programs can use the static object mrpt::random::randomGenerator
Definition at line 47 of file RandomGenerators.h.
#include <mrpt/random/RandomGenerators.h>
Public Member Functions | |
Initialization | |
CRandomGenerator () | |
Default constructor: initialize random seed based on current time. More... | |
CRandomGenerator (const uint32_t seed) | |
Constructor for providing a custom random seed to initialize the PRNG. More... | |
void | randomize (const uint32_t seed) |
Initialize the PRNG from the given random seed. More... | |
void | randomize () |
Randomize the generators, based on std::random_device. More... | |
Uniform pdf | |
uint32_t | drawUniform32bit () |
Generate a uniformly distributed pseudo-random number using the MT19937 algorithm, in the whole range of 32-bit integers. More... | |
uint64_t | drawUniform64bit () |
Returns a uniformly distributed pseudo-random number by joining two 32bit numbers from drawUniform32bit() More... | |
void | drawUniformUnsignedInt (uint32_t &ret_number) |
You can call this overloaded method with either 32 or 64bit unsigned ints for the sake of general coding. More... | |
void | drawUniformUnsignedInt (uint64_t &ret_number) |
template<typename T , typename U , typename V > | |
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) More... | |
double | drawUniform (const double Min, const double Max) |
Generate a uniformly distributed pseudo-random number using the MT19937 algorithm, scaled to the selected range. More... | |
template<class MAT > | |
void | drawUniformMatrix (MAT &matrix, const double unif_min=0, const double unif_max=1) |
Fills the given matrix with independent, uniformly distributed samples. More... | |
template<class VEC > | |
void | drawUniformVector (VEC &v, const double unif_min=0, const double unif_max=1) |
Fills the given vector with independent, uniformly distributed samples. More... | |
Normal/Gaussian pdf | |
double | drawGaussian1D_normalized () |
Generate a normalized (mean=0, std=1) normally distributed sample. More... | |
double | drawGaussian1D (const double mean, const double std) |
Generate a normally distributed pseudo-random number. More... | |
template<class MAT > | |
void | drawGaussian1DMatrix (MAT &matrix, const double mean=0, const double std=1) |
Fills the given matrix with independent, 1D-normally distributed samples. More... | |
template<class MATRIX , class AUXVECTOR_T = MATRIX> | |
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*I, with "v" being a vector of gaussian random samples. More... | |
template<class VEC > | |
void | drawGaussian1DVector (VEC &v, const double mean=0, const double std=1) |
Fills the given vector with independent, 1D-normally distributed samples. More... | |
template<typename T , typename MATRIX > | |
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. More... | |
template<class VECTORLIKE , class COVMATRIX > | |
void | drawGaussianMultivariate (VECTORLIKE &out_result, const COVMATRIX &cov, const VECTORLIKE *mean=nullptr) |
Generate multidimensional random samples according to a given covariance matrix. More... | |
template<typename VECTOR_OF_VECTORS , typename COVMATRIX > | |
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. More... | |
Miscellaneous | |
template<class VEC > | |
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 at random positions. More... | |
Protected Member Functions | |
void | MT19937_initializeGenerator (const uint32_t &seed) |
Protected Attributes | |
std::mt19937_64 | m_MT19937 |
Data used internally by the MT19937 PRNG algorithm. More... | |
std::normal_distribution< double > | m_normdistribution |
std::uniform_int_distribution< uint32_t > | m_uint32 |
std::uniform_int_distribution< uint64_t > | m_uint64 |
|
inline |
Default constructor: initialize random seed based on current time.
Definition at line 64 of file RandomGenerators.h.
References randomize().
|
inline |
Constructor for providing a custom random seed to initialize the PRNG.
Definition at line 66 of file RandomGenerators.h.
References randomize().
|
inline |
Generates a random definite-positive matrix of the given size, using the formula C = v*v^t + epsilon*I, with "v" being a vector of gaussian random samples.
Definition at line 188 of file RandomGenerators.h.
References mrpt::math::cov(), and drawGaussian1DMatrix().
Referenced by TEST().
|
inline |
Generate a normally distributed pseudo-random number.
mean | The mean value of desired normal distribution |
std | The standard deviation value of desired normal distribution |
Definition at line 162 of file RandomGenerators.h.
References drawGaussian1D_normalized(), and mean().
Referenced by drawGaussian1DMatrix(), drawGaussian1DVector(), mrpt::maps::CBeaconMap::internal_insertObservation(), ransac_data_assoc_run(), mrpt::slam::CRejectionSamplingRangeOnlyLocalization::RS_drawFromProposal(), mrpt::maps::CBeaconMap::simulateBeaconReadings(), and mrpt::maps::CLandmarksMap::simulateRangeBearingReadings().
double CRandomGenerator::drawGaussian1D_normalized | ( | ) |
Generate a normalized (mean=0, std=1) normally distributed sample.
likelihood | If desired, pass a pointer to a double which will receive the likelihood of the given sample to have been obtained, that is, the value of the normal pdf at the sample value. |
Definition at line 42 of file RandomGenerator.cpp.
References m_MT19937, and m_normdistribution.
Referenced by mrpt::obs::CActionRobotMovement3D::computeFromOdometry_model6DOF(), mrpt::obs::CActionRobotMovement2D::computeFromOdometry_modelThrun(), mrpt::poses::CPoseRandomSampler::do_sample_2D(), mrpt::poses::CPoseRandomSampler::do_sample_3D(), drawGaussian1D(), drawGaussianMultivariate(), drawGaussianMultivariateMany(), mrpt::obs::CActionRobotMovement2D::drawSingleSample_modelThrun(), mrpt::obs::CActionRobotMovement2D::fastDrawSingleSample_modelGaussian(), mrpt::random::matrixRandomNormal(), mrpt::maps::CLandmarksMap::simulateBeaconReadings(), mrpt::kinematics::CVehicleSimulVirtualBase::simulateOneTimeStep(), mrpt::maps::CLandmarksMap::simulateRangeBearingReadings(), mrpt::maps::COccupancyGridMap2D::simulateScanRay(), and mrpt::random::vectorRandomNormal().
|
inline |
Fills the given matrix with independent, 1D-normally distributed samples.
Matrix classes can be mrpt::math::CMatrixTemplateNumeric or mrpt::math::CMatrixFixedNumeric
Definition at line 174 of file RandomGenerators.h.
References drawGaussian1D(), and mean().
Referenced by do_test_init_random(), drawDefinitePositiveMatrix(), PosePDFGaussTests::generateRandomPose2DPDF(), Pose3DPDFGaussTests::generateRandomPose3DPDF(), and Pose3DQuatPDFGaussTests::generateRandomPose3DPDF().
|
inline |
Fills the given vector with independent, 1D-normally distributed samples.
Definition at line 207 of file RandomGenerators.h.
References drawGaussian1D(), and mean().
Referenced by TEST_F().
|
inline |
Generate multidimensional random samples according to a given covariance matrix.
Mean is assumed to be zero if mean==nullptr.
std::exception | On invalid covariance matrix |
Computes the eigenvalues/eigenvector decomposition of this matrix, so that: M = Z � D � ZT, where columns in Z are the eigenvectors and the diagonal matrix D contains the eigenvalues as diagonal elements, sorted in ascending order.
Definition at line 223 of file RandomGenerators.h.
References mrpt::math::cov(), drawGaussian1D_normalized(), and mean().
Referenced by mrpt::poses::CPoint2DPDFGaussian::drawSingleSample(), mrpt::poses::CPose3DQuatPDFGaussianInf::drawSingleSample(), mrpt::poses::CPose3DQuatPDFGaussian::drawSingleSample(), mrpt::poses::CPose3DPDFGaussianInf::drawSingleSample(), mrpt::poses::CPosePDFGaussian::drawSingleSample(), mrpt::poses::CPointPDFGaussian::drawSingleSample(), mrpt::poses::CPose3DPDFGaussian::drawSingleSample(), mrpt::poses::CPosePDFGaussianInf::drawSingleSample(), mrpt::poses::CPointPDFSOG::drawSingleSample(), mrpt::maps::CMultiMetricMapPDF::prediction_and_update_pfOptimalProposal(), and mrpt::random::randomNormalMultiDimensional().
|
inline |
Generate multidimensional random samples according to a given covariance matrix.
Mean is assumed to be zero if mean==nullptr.
std::exception | On invalid covariance matrix |
Definition at line 264 of file RandomGenerators.h.
References mrpt::math::cov(), drawGaussian1D_normalized(), and mean().
|
inline |
Generate a given number of multidimensional random samples according to a given covariance matrix.
cov | The covariance matrix where to draw the samples from. |
desiredSamples | The number of samples to generate. |
ret | The output list of samples |
mean | The mean, or zeros if mean==nullptr. |
Definition at line 310 of file RandomGenerators.h.
References mrpt::math::cov(), drawGaussian1D_normalized(), and mean().
Referenced by mrpt::poses::CPosePDFParticles::copyFrom(), mrpt::poses::CPose3DQuatPDFGaussianInf::drawManySamples(), mrpt::poses::CPose3DQuatPDFGaussian::drawManySamples(), mrpt::poses::CPose3DPDFGaussianInf::drawManySamples(), mrpt::poses::CPosePDFGaussian::drawManySamples(), mrpt::poses::CPose3DPDFGaussian::drawManySamples(), mrpt::poses::CPosePDFGaussianInf::drawManySamples(), mrpt::random::randomNormalMultiDimensionalMany(), and mrpt::math::transform_gaussian_montecarlo().
|
inline |
Generate a uniformly distributed pseudo-random number using the MT19937 algorithm, scaled to the selected range.
Definition at line 111 of file RandomGenerators.h.
References drawUniform32bit().
Referenced by atan2_lut_test(), mrpt::bayes::CParticleFilterCapable::computeResampling(), mrpt::poses::CPosePDFParticles::drawSingleSample(), drawUniformMatrix(), drawUniformVector(), mrpt::bayes::CParticleFilterCapable::fastDrawSample(), mrpt::maps::CBeaconMap::internal_insertObservation(), mrpt::random::matrixRandomUni(), mrpt::hmtslam::CLSLAM_RBPF_2DLASER::prediction_and_update_pfAuxiliaryPFOptimal(), mrpt::poses::CPosePDFParticles::resetAroundSetOfPoses(), mrpt::poses::CPosePDFParticles::resetUniform(), mrpt::slam::CMonteCarloLocalization2D::resetUniformFreeSpace(), mrpt::slam::CRejectionSamplingRangeOnlyLocalization::RS_drawFromProposal(), mrpt::maps::CLandmarksMap::simulateRangeBearingReadings(), mrpt::nav::PlannerRRT_SE2_TPS::solve(), and mrpt::random::vectorRandomUni().
uint32_t CRandomGenerator::drawUniform32bit | ( | ) |
Generate a uniformly distributed pseudo-random number using the MT19937 algorithm, in the whole range of 32-bit integers.
See: http://en.wikipedia.org/wiki/Mersenne_twister
Definition at line 31 of file RandomGenerator.cpp.
References m_MT19937, and m_uint32.
Referenced by mrpt::slam::CGridMapAligner::AlignPDF_robustMatch(), drawUniform(), mrpt::slam::PF_implementation< mrpt::math::TPose3D, CMonteCarloLocalization3D, mrpt::bayes::particle_storage_mode::VALUE >::PF_SLAM_aux_perform_one_rejection_sampling_step(), mrpt::slam::PF_implementation< mrpt::math::TPose3D, CMonteCarloLocalization3D, mrpt::bayes::particle_storage_mode::VALUE >::PF_SLAM_implementation_pfAuxiliaryPFStandardAndOptimal(), mrpt::random::random_generator_for_STL(), and TEST().
uint64_t CRandomGenerator::drawUniform64bit | ( | ) |
Returns a uniformly distributed pseudo-random number by joining two 32bit numbers from drawUniform32bit()
Definition at line 28 of file RandomGenerator.cpp.
|
inline |
Fills the given matrix with independent, uniformly distributed samples.
Matrix classes can be mrpt::math::CMatrixTemplateNumeric or mrpt::math::CMatrixFixedNumeric
Definition at line 124 of file RandomGenerators.h.
References drawUniform().
You can call this overloaded method with either 32 or 64bit unsigned ints for the sake of general coding.
Definition at line 88 of file RandomGenerators.h.
References m_MT19937, and m_uint32.
Referenced by drawUniformUnsignedIntRange().
Definition at line 92 of file RandomGenerators.h.
|
inline |
Return a uniform unsigned integer in the range [min_val,max_val] (both inclusive)
Definition at line 100 of file RandomGenerators.h.
References drawUniformUnsignedInt().
|
inline |
Fills the given vector with independent, uniformly distributed samples.
Definition at line 137 of file RandomGenerators.h.
References drawUniform().
Referenced by mrpt::bayes::CParticleFilterCapable::computeResampling(), and mrpt::math::RANSAC_Template< NUMTYPE >::execute().
|
inline |
Returns a random permutation of a vector: all the elements of the input vector are in the output but at random positions.
Definition at line 364 of file RandomGenerators.h.
References mrpt::random::shuffle().
Referenced by mrpt::random::randomPermutation(), mrpt::tfest::se2_l2_robust(), and mrpt::tfest::se3_l2_robust().
void CRandomGenerator::randomize | ( | ) |
Randomize the generators, based on std::random_device.
Definition at line 37 of file RandomGenerator.cpp.
References MT19937_initializeGenerator().
Referenced by CRandomGenerator().
Initialize the PRNG from the given random seed.
Definition at line 32 of file RandomGenerator.cpp.
References MT19937_initializeGenerator().
Referenced by mrpt::random::Randomize(), ransac_data_assoc_run(), run_test_pf_localization(), TEST(), TEST_F(), mrpt::hmtslam::CHMTSLAM::thread_LSLAM(), and mrpt::hmtslam::CHMTSLAM::thread_TBI().
|
protected |
Data used internally by the MT19937 PRNG algorithm.
Definition at line 51 of file RandomGenerators.h.
Referenced by drawGaussian1D_normalized(), drawUniform32bit(), drawUniform64bit(), drawUniformUnsignedInt(), and MT19937_initializeGenerator().
|
protected |
Definition at line 53 of file RandomGenerators.h.
Referenced by drawGaussian1D_normalized().
|
protected |
Definition at line 54 of file RandomGenerators.h.
Referenced by drawUniform32bit(), and drawUniformUnsignedInt().
|
protected |
Definition at line 55 of file RandomGenerators.h.
Referenced by drawUniform64bit(), and drawUniformUnsignedInt().
Page generated by Doxygen 1.8.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at mié 12 jul 2023 10:03:34 CEST |