random_numbers.cpp
Go to the documentation of this file.
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 */
36 
38 
39 #include <boost/random/lagged_fibonacci.hpp>
40 #include <boost/random/uniform_int.hpp>
41 #include <boost/thread/mutex.hpp>
42 #include <boost/date_time/posix_time/posix_time.hpp>
43 #include <boost/math/constants/constants.hpp>
44 #include <boost/scoped_ptr.hpp>
45 
46 static boost::uint32_t first_seed_ = 0;
47 
49 static boost::uint32_t firstSeed(void)
50 {
51  boost::scoped_ptr<int> mem(new int());
52  first_seed_ = (boost::uint32_t)(
53  (boost::posix_time::microsec_clock::universal_time() - boost::posix_time::ptime(boost::date_time::min_date_time))
54  .total_microseconds() +
55  (unsigned long long)(mem.get()));
56  return first_seed_;
57 }
58 
62 static boost::uint32_t nextSeed(void)
63 {
64  static boost::mutex rngMutex;
65  boost::mutex::scoped_lock slock(rngMutex);
66  static boost::lagged_fibonacci607 sGen(firstSeed());
67  static boost::uniform_int<> sDist(1, 1000000000);
68  static boost::variate_generator<boost::lagged_fibonacci607&, boost::uniform_int<> > s(sGen, sDist);
69  boost::uint32_t v = s();
70  return v;
71 }
72 
74  : generator_(nextSeed())
75  , uniDist_(0, 1)
76  , normalDist_(0, 1)
77  , uni_(generator_, uniDist_)
78  , normal_(generator_, normalDist_)
79 {
80 }
81 
84 {
85  // Because we manually specified a seed, we need to save it ourselves
86  first_seed_ = seed;
87 }
88 
89 // From: "Uniform Random Rotations", Ken Shoemake, Graphics Gems III,
90 // pg. 124-132
92 {
93  double x0 = uni_();
94  double r1 = sqrt(1.0 - x0), r2 = sqrt(x0);
95  double t1 = 2.0 * boost::math::constants::pi<double>() * uni_(),
96  t2 = 2.0 * boost::math::constants::pi<double>() * uni_();
97  double c1 = cos(t1), s1 = sin(t1);
98  double c2 = cos(t2), s2 = sin(t2);
99  value[0] = s1 * r1;
100  value[1] = c1 * r1;
101  value[2] = s2 * r2;
102  value[3] = c2 * r2;
103 }
104 
106 {
107  return first_seed_;
108 }
void quaternion(double value[4])
Uniform random unit quaternion sampling. The computed value has the order (x,y,z,w) ...
boost::uint32_t getFirstSeed()
Allow the randomly generated seed to be saved so that experiments / benchmarks can be recreated in th...
static boost::uint32_t firstSeed(void)
Compute the first seed to be used; this function should be called only once.
boost::variate_generator< boost::mt19937 &, boost::normal_distribution<> > normal_
static boost::uint32_t nextSeed(void)
boost::normal_distribution normalDist_
boost::variate_generator< boost::mt19937 &, boost::uniform_real<> > uni_
RandomNumberGenerator(void)
Constructor. Always sets a "random" random seed.
static boost::uint32_t first_seed_


random_numbers
Author(s): Ioan Sucan
autogenerated on Thu Apr 1 2021 02:44:44