Loading...
Searching...
No Matches
RandomNumbers.h
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Ioan Sucan, Jonathan Gammell */
36
37#ifndef OMPL_UTIL_RANDOM_NUMBERS_
38#define OMPL_UTIL_RANDOM_NUMBERS_
39
40#include <memory>
41#include <random>
42#include <cassert>
43#include <cstdint>
44#include <algorithm>
45
46#include "ompl/config.h"
47#include "ompl/util/ProlateHyperspheroid.h"
48
49namespace ompl
50{
57 class RNG
58 {
59 public:
61 RNG();
62
64 RNG(std::uint_fast32_t localSeed);
65
67 double uniform01()
68 {
69 return uniDist_(generator_);
70 }
71
73 double uniformReal(double lower_bound, double upper_bound)
74 {
75 assert(lower_bound <= upper_bound);
76 return (upper_bound - lower_bound) * uniDist_(generator_) + lower_bound;
77 }
78
80 int uniformInt(int lower_bound, int upper_bound)
81 {
82 auto r = (int)floor(uniformReal((double)lower_bound, (double)(upper_bound) + 1.0));
83 return (r > upper_bound) ? upper_bound : r;
84 }
85
88 {
89 return uniDist_(generator_) <= 0.5;
90 }
91
93 double gaussian01()
94 {
95 return normalDist_(generator_);
96 }
97
99 double gaussian(double mean, double stddev)
100 {
101 return normalDist_(generator_) * stddev + mean;
102 }
103
110 double halfNormalReal(double r_min, double r_max, double focus = 3.0);
111
115 int halfNormalInt(int r_min, int r_max, double focus = 3.0);
116
119 void quaternion(double value[4]);
120
123 void eulerRPY(double value[3]);
124
127 static void setSeed(std::uint_fast32_t seed);
128
132 static std::uint_fast32_t getSeed();
133
136 void setLocalSeed(std::uint_fast32_t localSeed);
137
142 std::uint_fast32_t getLocalSeed() const
143 {
144 return localSeed_;
145 }
146
149 void uniformNormalVector(std::vector<double> &v);
150
154 void uniformInBall(double r, std::vector<double> &v);
155
164 void uniformProlateHyperspheroidSurface(const std::shared_ptr<const ProlateHyperspheroid> &phsPtr,
165 double value[]);
166
175 void uniformProlateHyperspheroid(const std::shared_ptr<const ProlateHyperspheroid> &phsPtr, double value[]);
176
178 template <class RandomAccessIterator>
179 void shuffle(RandomAccessIterator first, RandomAccessIterator last)
180 {
181 std::shuffle(first, last, generator_);
182 }
183
184 private:
187 class SphericalData;
188
190 std::uint_fast32_t localSeed_;
191 std::mt19937 generator_;
192 std::uniform_real_distribution<> uniDist_{0, 1};
193 std::normal_distribution<> normalDist_{0, 1};
194 // A structure holding boost::uniform_on_sphere distributions and the associated boost::variate_generators for
195 // various dimension
196 std::shared_ptr<SphericalData> sphericalDataPtr_;
197 };
198} // namespace ompl
199
200#endif
Random number generation. An instance of this class cannot be used by multiple threads at once (membe...
void quaternion(double value[4])
Uniform random unit quaternion sampling. The computed value has the order (x,y,z,w)....
double gaussian(double mean, double stddev)
Generate a random real using a normal distribution with given mean and variance.
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_...
void eulerRPY(double value[3])
Uniform random sampling of Euler roll-pitch-yaw angles, each in the range (-pi, pi]....
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...
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...
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 ...
double uniformReal(double lower_bound, double upper_bound)
Generate a random real within given bounds: [lower_bound, upper_bound)
void shuffle(RandomAccessIterator first, RandomAccessIterator last)
randomly rearrange elements in the range [first, last)
void uniformInBall(double r, std::vector< double > &v)
Uniform random sampling of the content of an n-ball, with a radius appropriately distributed between ...
double gaussian01()
Generate a random real using a normal distribution with mean 0 and variance 1.
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...
RNG()
Constructor. Always sets a different random seed.
static std::uint_fast32_t getSeed()
Get the seed used to generate the seeds of each RNG instance. Passing the returned value to setSeed()...
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,...
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...
bool uniformBool()
Generate a random boolean.
int uniformInt(int lower_bound, int upper_bound)
Generate a random integer within given bounds: [lower_bound, upper_bound].
double uniform01()
Generate a random real between 0 and 1.
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...
Main namespace. Contains everything in this library.