Random number generation. An instance of this class cannot be used by multiple threads at once (member functions are not const). However, the constructor is thread safe and different instances can be used safely in any number of threads. It is also guaranteed that all created instances will have a different random seed. More...

#include <ompl/util/RandomNumbers.h>

Public Member Functions

 RNG ()
 Constructor. Always sets a different random seed.
 
 RNG (std::uint_fast32_t localSeed)
 Constructor. Set to the specified instance seed.
 
double uniform01 ()
 Generate a random real between 0 and 1.
 
double uniformReal (double lower_bound, double upper_bound)
 Generate a random real within given bounds: [lower_bound, upper_bound)
 
int uniformInt (int lower_bound, int upper_bound)
 Generate a random integer within given bounds: [lower_bound, upper_bound].
 
bool uniformBool ()
 Generate a random boolean.
 
double gaussian01 ()
 Generate a random real using a normal distribution with mean 0 and variance 1.
 
double gaussian (double mean, double stddev)
 Generate a random real using a normal distribution with given mean and variance.
 
double halfNormalReal (double r_min, double r_max, double focus=3.0)
 Generate a random real using a half-normal distribution. The value is within specified bounds [r_min, r_max], but with a bias towards r_max. The function is implemended using a Gaussian distribution with mean at r_max - r_min. The distribution is 'folded' around r_max axis towards r_min. The variance of the distribution is (r_max - r_min) / focus. The higher the focus, the more probable it is that generated numbers are close to r_max.
 
int halfNormalInt (int r_min, int r_max, double focus=3.0)
 Generate a random integer using a half-normal distribution. The value is within specified bounds ([r_min, r_max]), but with a bias towards r_max. The function is implemented on top of halfNormalReal()
 
void quaternion (double value[4])
 Uniform random unit quaternion sampling. The computed value has the order (x,y,z,w). The return variable value is expected to already exist.
 
void eulerRPY (double value[3])
 Uniform random sampling of Euler roll-pitch-yaw angles, each in the range (-pi, pi]. The computed value has the order (roll, pitch, yaw). The return variable value is expected to already exist.
 
void setLocalSeed (std::uint_fast32_t localSeed)
 Set the seed used for the instance of a RNG. Use this function to ensure that an instance of an RNG generates the same deterministic sequence of numbers. This function resets the member generators.
 
std::uint_fast32_t getLocalSeed () const
 Get the seed used for the instance of a RNG. Passing the returned value to the setInstanceSeed() of another RNG will assure that the two objects generate the same sequence of numbers. Useful for comparing different settings of a planner while maintaining the same stochastic behaviour, assuming that every "random" decision made by the planner is made from the same RNG.
 
void uniformNormalVector (std::vector< double > &v)
 Uniform random sampling of a unit-length vector. I.e., the surface of an n-ball. The return variable value is expected to already exist.
 
void uniformInBall (double r, std::vector< double > &v)
 Uniform random sampling of the content of an n-ball, with a radius appropriately distributed between [0,r) so that the distribution is uniform in a Cartesian coordinate system. The return variable value is expected to already exist.
 
void uniformProlateHyperspheroidSurface (const std::shared_ptr< const ProlateHyperspheroid > &phsPtr, double value[])
 Uniform random sampling of the surface of a prolate hyperspheroid, a special symmetric type of n-dimensional ellipse. The return variable value is expected to already exist. More...
 
void uniformProlateHyperspheroid (const std::shared_ptr< const ProlateHyperspheroid > &phsPtr, double value[])
 Uniform random sampling of a prolate hyperspheroid, a special symmetric type of n-dimensional ellipse. The return variable value is expected to already exist. More...
 
template<class RandomAccessIterator >
void shuffle (RandomAccessIterator first, RandomAccessIterator last)
 randomly rearrange elements in the range [first, last)
 

Static Public Member Functions

static void setSeed (std::uint_fast32_t seed)
 Set the seed used to generate the seeds of each RNG instance. Use this function to ensure the same sequence of random numbers is generated across multiple instances of RNG.
 
static std::uint_fast32_t getSeed ()
 Get the seed used to generate the seeds of each RNG instance. Passing the returned value to setSeed() at a subsequent execution of the code will ensure deterministic (repeatable) behaviour across multiple instances of RNG. Useful for debugging.
 

Detailed Description

Random number generation. An instance of this class cannot be used by multiple threads at once (member functions are not const). However, the constructor is thread safe and different instances can be used safely in any number of threads. It is also guaranteed that all created instances will have a different random seed.

Definition at line 89 of file RandomNumbers.h.

Member Function Documentation

◆ uniformProlateHyperspheroid()

void ompl::RNG::uniformProlateHyperspheroid ( const std::shared_ptr< const ProlateHyperspheroid > &  phsPtr,
double  value[] 
)

Uniform random sampling of a prolate hyperspheroid, a special symmetric type of n-dimensional ellipse. The return variable value is expected to already exist.

J. D. Gammell, T. D. Barfoot, S. S. Srinivasa, "Informed sampling for asymptotically optimal path planning."
IEEE Transactions on Robotics (T-RO), 34(4): 966-984, Aug. 2018. DOI: TRO.2018.2830331. arXiv: 1706.06454 [cs.RO]. Illustration video. Short description video.

Definition at line 321 of file RandomNumbers.cpp.

◆ uniformProlateHyperspheroidSurface()

void ompl::RNG::uniformProlateHyperspheroidSurface ( const std::shared_ptr< const ProlateHyperspheroid > &  phsPtr,
double  value[] 
)

Uniform random sampling of the surface of a prolate hyperspheroid, a special symmetric type of n-dimensional ellipse. The return variable value is expected to already exist.

J. D. Gammell, T. D. Barfoot, S. S. Srinivasa, "Informed sampling for asymptotically optimal path planning."
IEEE Transactions on Robotics (T-RO), 34(4): 966-984, Aug. 2018. DOI: TRO.2018.2830331. arXiv: 1706.06454 [cs.RO] Illustration video. Short description video.

Definition at line 307 of file RandomNumbers.cpp.


The documentation for this class was generated from the following files: