Program Listing for File RandomNumbers.h

Return to documentation for file (src/ompl/util/RandomNumbers.h)

/*********************************************************************
 * Software License Agreement (BSD License)
 *
 *  Copyright (c) 2008, Willow Garage, Inc.
 *  All rights reserved.
 *
 *  Redistribution and use in source and binary forms, with or without
 *  modification, are permitted provided that the following conditions
 *  are met:
 *
 *   * Redistributions of source code must retain the above copyright
 *     notice, this list of conditions and the following disclaimer.
 *   * Redistributions in binary form must reproduce the above
 *     copyright notice, this list of conditions and the following
 *     disclaimer in the documentation and/or other materials provided
 *     with the distribution.
 *   * Neither the name of the Willow Garage nor the names of its
 *     contributors may be used to endorse or promote products derived
 *     from this software without specific prior written permission.
 *
 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
 *  POSSIBILITY OF SUCH DAMAGE.
 *********************************************************************/

/* Author: Ioan Sucan, Jonathan Gammell */

#ifndef OMPL_UTIL_RANDOM_NUMBERS_
#define OMPL_UTIL_RANDOM_NUMBERS_

#include <memory>
#include <random>
#include <cassert>
#include <cstdint>
#include <algorithm>

#include "ompl/util/ProlateHyperspheroid.h"

namespace ompl
{
    class RNG
    {
    public:
        RNG();

        RNG(std::uint_fast32_t localSeed);

        double uniform01()
        {
            return uniDist_(generator_);
        }

        double uniformReal(double lower_bound, double upper_bound)
        {
            assert(lower_bound <= upper_bound);
            return (upper_bound - lower_bound) * uniDist_(generator_) + lower_bound;
        }

        int uniformInt(int lower_bound, int upper_bound)
        {
            auto r = (int)floor(uniformReal((double)lower_bound, (double)(upper_bound) + 1.0));
            return (r > upper_bound) ? upper_bound : r;
        }

        bool uniformBool()
        {
            return uniDist_(generator_) <= 0.5;
        }

        double gaussian01()
        {
            return normalDist_(generator_);
        }

        double gaussian(double mean, double stddev)
        {
            return normalDist_(generator_) * stddev + mean;
        }

        double halfNormalReal(double r_min, double r_max, double focus = 3.0);

        int halfNormalInt(int r_min, int r_max, double focus = 3.0);

        void quaternion(double value[4]);

        void eulerRPY(double value[3]);

        static void setSeed(std::uint_fast32_t seed);

        static std::uint_fast32_t getSeed();

        void setLocalSeed(std::uint_fast32_t localSeed);

        std::uint_fast32_t getLocalSeed() const
        {
            return localSeed_;
        }

        void uniformNormalVector(std::vector<double> &v);

        void uniformInBall(double r, std::vector<double> &v);

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

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

        template <class RandomAccessIterator>
        void shuffle(RandomAccessIterator first, RandomAccessIterator last)
        {
            std::shuffle(first, last, generator_);
        }

    private:
        class SphericalData;

        std::uint_fast32_t localSeed_;
        std::mt19937 generator_;
        std::uniform_real_distribution<> uniDist_{0, 1};
        std::normal_distribution<> normalDist_{0, 1};
        // A structure holding boost::uniform_on_sphere distributions and the associated boost::variate_generators for
        // various dimension
        std::shared_ptr<SphericalData> sphericalDataPtr_;
    };
}  // namespace ompl

#endif