RandomNumbers.h
164 void uniformProlateHyperspheroidSurface(const std::shared_ptr<const ProlateHyperspheroid> &phsPtr,
175 void uniformProlateHyperspheroid(const std::shared_ptr<const ProlateHyperspheroid> &phsPtr, double value[]);
double gaussian01()
Generate a random real using a normal distribution with mean 0 and variance 1.
Definition: RandomNumbers.h:157
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 ...
Definition: RandomNumbers.cpp:287
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-dime...
Definition: RandomNumbers.cpp:307
void shuffle(RandomAccessIterator first, RandomAccessIterator last)
randomly rearrange elements in the range [first, last)
Definition: RandomNumbers.h:243
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,...
Definition: RandomNumbers.cpp:244
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 se...
Definition: RandomNumbers.cpp:213
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_...
Definition: RandomNumbers.cpp:257
void quaternion(double value[4])
Uniform random unit quaternion sampling. The computed value has the order (x,y,z,w)....
Definition: RandomNumbers.cpp:265
int uniformInt(int lower_bound, int upper_bound)
Generate a random integer within given bounds: [lower_bound, upper_bound].
Definition: RandomNumbers.h:144
double gaussian(double mean, double stddev)
Generate a random real using a normal distribution with given mean and variance.
Definition: RandomNumbers.h:163
std::uint_fast32_t getLocalSeed() const
Get the seed used for the instance of a RNG. Passing the returned value to the setInstanceSeed() of a...
Definition: RandomNumbers.h:206
void uniformInBall(double r, std::vector< double > &v)
Uniform random sampling of the content of an n-ball, with a radius appropriately distributed between ...
Definition: RandomNumbers.cpp:295
static std::uint_fast32_t getSeed()
Get the seed used to generate the seeds of each RNG instance. Passing the returned value to setSeed()...
Definition: RandomNumbers.cpp:208
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...
Definition: RandomNumbers.cpp:321
double uniformReal(double lower_bound, double upper_bound)
Generate a random real within given bounds: [lower_bound, upper_bound)
Definition: RandomNumbers.h:137
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 g...
Definition: RandomNumbers.cpp:230
void eulerRPY(double value[3])
Uniform random sampling of Euler roll-pitch-yaw angles, each in the range (-pi, pi]....
Definition: RandomNumbers.cpp:280
Main namespace. Contains everything in this library.
Definition: MultiLevelPlanarManipulatorDemo.cpp:65