pax_global_header00006660000000000000000000000064132453401720014513gustar00rootroot0000000000000052 comment=9748510bd51a5be623c1140a6a9f745ff6eda199 random_numbers-0.3.2/000077500000000000000000000000001324534017200145305ustar00rootroot00000000000000random_numbers-0.3.2/.gitignore000066400000000000000000000000031324534017200165110ustar00rootroot00000000000000*~ random_numbers-0.3.2/.travis.yml000066400000000000000000000044541324534017200166500ustar00rootroot00000000000000# Generic MoveIt Travis Continuous Integration Configuration File # Works with all MoveIt! repositories/branches # Author: Dave Coleman, Jonathan Bohren language: - cpp - python python: - "2.7" compiler: - gcc notifications: email: recipients: - dave.hershberger@sri.com on_success: change #[always|never|change] # default: change on_failure: change #[always|never|change] # default: always before_install: # Use this to prepare the system to install prerequisites or dependencies # Define some config vars - export ROS_DISTRO=hydro - export CI_SOURCE_PATH=$(pwd) - export REPOSITORY_NAME=${PWD##*/} - echo "Testing branch $TRAVIS_BRANCH of $REPOSITORY_NAME" - sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu precise main" > /etc/apt/sources.list.d/ros-latest.list' - wget http://packages.ros.org/ros.key -O - | sudo apt-key add - - sudo apt-get update -qq - sudo apt-get install -qq -y python-catkin-pkg python-rosdep python-wstool ros-$ROS_DISTRO-catkin ros-$ROS_DISTRO-ros # MongoDB hack - I don't fully understand this but its for moveit_warehouse - sudo apt-get remove -y mongodb mongodb-10gen - sudo apt-get install -y mongodb-clients mongodb-server -o Dpkg::Options::="--force-confdef" # default actions # Setup rosdep - sudo rosdep init - rosdep update install: # Use this to install any prerequisites or dependencies necessary to run your build # Create workspace - mkdir -p ~/ros/ws_moveit/src - cd ~/ros/ws_moveit/src - wstool init . # Download non-debian stuff - wstool merge https://raw.github.com/ros-planning/moveit_docs/hydro-devel/moveit.rosinstall - wstool update - git clone https://github.com/ros-planning/geometric_shapes.git # Delete the moveit.rosinstall version of this repo and use the one of the branch we are testing - rm -rf $REPOSITORY_NAME - ln -s $CI_SOURCE_PATH . # Link the repo we are testing to the new workspace - cd ../ # Install dependencies for source repos - rosdep install --from-paths src --ignore-src --rosdistro $ROS_DISTRO -y before_script: # Use this to prepare your build for testing e.g. copy database configurations, environment variables, etc. - source /opt/ros/$ROS_DISTRO/setup.bash script: # All commands must exit with code 0 on success. Anything else is considered failure. - catkin_make -j2 random_numbers-0.3.2/CHANGELOG.rst000066400000000000000000000141671324534017200165620ustar00rootroot00000000000000^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package random_numbers ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.3.2 (2018-02-27) ------------------ * Update maintainership. (`#11 `_) * Contributors: Steven! Ragnarök 0.3.1 (2016-04-04) ------------------ * Merge pull request `#10 `_ from jspricke/cmake_lib Use catkin variables for install dirs * Contributors: Dave Coleman, Jochen Sprickerhof 0.3.0 (2014-09-05) ------------------ * Update README.md with Documentation * Allow the randomly generated seed to be saved so that experiments / benc... * Initialize static int to 0 * Save the first_seed even when passed in manually. * Allow the randomly generated seed to be saved so that experiments / benchmarks can be recreated in the future * Added ability to specify random number generator seed for stochastic behavior * Added travis build status indicator in README.md * Contributors: Dave Coleman, Dave Hershberger, Ioan A Sucan 0.2.0 (2013-07-16) ------------------ * Merge pull request `#2 `_ from wjwwood/patch-1 Fix linkedit error on OS X with newer versions of Boost * Fix linkedit error on OS X with newer versions of Boost When building `random_numbers` on OS X with Boost 1.53.0 I get: ``` ==> Processing catkin package: 'random_numbers' ==> Creating build directory: 'build_isolated/random_numbers' ==> Building with env: '/Users/william/moveit_ws/install_isolated/env.sh' ==> cmake /Users/william/moveit_ws/src/random_numbers -DCATKIN_DEVEL_PREFIX=/Users/william/moveit_ws/devel_isolated/random_numbers -DCMAKE_INSTALL_PREFIX=/Users/william/moveit_ws/install_isolated -- The C compiler identification is Clang 4.2.0 -- The CXX compiler identification is Clang 4.2.0 -- Check for working C compiler: /usr/bin/cc -- Check for working C compiler: /usr/bin/cc -- works -- Detecting C compiler ABI info -- Detecting C compiler ABI info - done -- Check for working CXX compiler: /usr/bin/c++ -- Check for working CXX compiler: /usr/bin/c++ -- works -- Detecting CXX compiler ABI info -- Detecting CXX compiler ABI info - done -- Using CATKIN_DEVEL_PREFIX: /Users/william/moveit_ws/devel_isolated/random_numbers -- Using CMAKE_PREFIX_PATH: /Users/william/moveit_ws/install_isolated -- This workspace overlays: /Users/william/moveit_ws/install_isolated -- Found PythonInterp: /usr/bin/python (found version "2.7.2") -- Found PY_em: /Library/Python/2.7/site-packages/em.pyc -- Found gtest: gtests will be built -- Using CATKIN_TEST_RESULTS_DIR: /Users/william/moveit_ws/build_isolated/random_numbers/test_results -- catkin 0.5.65 WARNING: 'catkin' should be listed as a buildtool dependency in the package.xml (instead of build dependency) -- Boost version: 1.53.0 -- Found the following Boost libraries: -- date_time -- thread -- Configuring done -- Generating done -- Build files have been written to: /Users/william/moveit_ws/build_isolated/random_numbers ==> make -j4 -l4 in '/Users/william/moveit_ws/build_isolated/random_numbers' Scanning dependencies of target random_numbers [100%] Building CXX object CMakeFiles/random_numbers.dir/src/random_numbers.cpp.o Linking CXX shared library /Users/william/moveit_ws/devel_isolated/random_numbers/lib/librandom_numbers.dylib Undefined symbols for architecture x86_64: "boost::system::system_category()", referenced from: ___cxx_global_var_init3 in random_numbers.cpp.o boost::thread_exception::thread_exception(int, char const*) in random_numbers.cpp.o "boost::system::generic_category()", referenced from: ___cxx_global_var_init1 in random_numbers.cpp.o ___cxx_global_var_init2 in random_numbers.cpp.o ld: symbol(s) not found for architecture x86_64 clang: error: linker command failed with exit code 1 (use -v to see invocation) make[2]: *** [/Users/william/moveit_ws/devel_isolated/random_numbers/lib/librandom_numbers.dylib] Error 1 make[1]: *** [CMakeFiles/random_numbers.dir/all] Error 2 make: *** [all] Error 2 Traceback (most recent call last): File "./src/catkin/bin/../python/catkin/builder.py", line 658, in build_workspace_isolated number=index + 1, of=len(ordered_packages) File "./src/catkin/bin/../python/catkin/builder.py", line 443, in build_package install, jobs, force_cmake, quiet, last_env, cmake_args, make_args File "./src/catkin/bin/../python/catkin/builder.py", line 297, in build_catkin_package run_command(make_cmd, build_dir, quiet) File "./src/catkin/bin/../python/catkin/builder.py", line 186, in run_command raise subprocess.CalledProcessError(proc.returncode, ' '.join(cmd)) CalledProcessError: Command '/Users/william/moveit_ws/install_isolated/env.sh make -j4 -l4' returned non-zero exit status 2 <== Failed to process package 'random_numbers': Command '/Users/william/moveit_ws/install_isolated/env.sh make -j4 -l4' returned non-zero exit status 2 Reproduce this error by running: ==> /Users/william/moveit_ws/install_isolated/env.sh make -j4 -l4 Command failed, exiting. ``` Adding the `system` element to the `Boost` components being found fixes this. * fix typo * Create README.md * update description * Merge pull request `#1 `_ from ablasdel/patch-1 Update package.xml to buildtool_depend * Update package.xml to buildtool_depend * Added tag 0.1.3 for changeset 78f37b23c724 * Contributors: Aaron Blasdel, Tully Foote, William Woodall, isucan 0.1.3 (2012-10-12 20:13) ------------------------ * removing outdated install rule * fixing install rule * Added tag 0.1.2 for changeset 42db44939f5e * Contributors: Tully Foote 0.1.2 (2012-10-12 19:50) ------------------------ * forgot rename * Added tag 0.1.2 for changeset 79869d337273 * updating catkinization and 0.1.2 * Added tag 0.1.1 for changeset 2e564507c3d1 * Contributors: Ioan Sucan, Tully Foote 0.1.1 (2012-06-18 13:21) ------------------------ * fix manifest * Added tag 0.1.0 for changeset a1286e23910e * Contributors: Ioan Sucan 0.1.0 (2012-06-18 13:17) ------------------------ * add initial version * Contributors: Ioan Sucan random_numbers-0.3.2/CMakeLists.txt000066400000000000000000000012321324534017200172660ustar00rootroot00000000000000cmake_minimum_required(VERSION 2.8.3) project(random_numbers) find_package(catkin REQUIRED) catkin_package( LIBRARIES ${PROJECT_NAME} INCLUDE_DIRS include ) find_package(Boost REQUIRED date_time system thread) include_directories(${Boost_INCLUDE_DIR}) include_directories(include) add_library(${PROJECT_NAME} src/random_numbers.cpp) target_link_libraries(${PROJECT_NAME} ${Boost_LIBRARIES}) install(TARGETS ${PROJECT_NAME} ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}) random_numbers-0.3.2/README.md000066400000000000000000000007431324534017200160130ustar00rootroot00000000000000# random_numbers This library contains wrappers for generating floating point values, integers, quaternions using boost libraries. ## Build Status master branch: [![Build Status](https://travis-ci.org/ros-planning/random_numbers.png?branch=master)](https://travis-ci.org/ros-planning/random_numbers) ## Features New: you can pass in a custom random number generator seed to allow optional deterministic behavior during debugging, testing, etc. using the secondary constructor. random_numbers-0.3.2/include/000077500000000000000000000000001324534017200161535ustar00rootroot00000000000000random_numbers-0.3.2/include/random_numbers/000077500000000000000000000000001324534017200211665ustar00rootroot00000000000000random_numbers-0.3.2/include/random_numbers/random_numbers.h000066400000000000000000000110061324534017200243500ustar00rootroot00000000000000/********************************************************************* * 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 */ #ifndef RANDOM_NUMBERS_RANDOM_NUMBERS_ #define RANDOM_NUMBERS_RANDOM_NUMBERS_ #include #include #include #include #include namespace random_numbers { /** \brief Random number generation (wrapper for boost). 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 "random" random seed. */ class RandomNumberGenerator { public: /** \brief Constructor. Always sets a "random" random seed */ RandomNumberGenerator(void); /** \brief Constructor. Allow a seed to be specified for deterministic behaviour */ RandomNumberGenerator(boost::uint32_t seed); /** \brief Generate a random real between 0 and 1 */ double uniform01(void) { return uni_(); } /** * @brief Generate a random real within given bounds: [\e lower_bound, \e upper_bound) * @param lower_bound The lower bound * @param upper_bound The upper bound */ double uniformReal(double lower_bound, double upper_bound) { return (upper_bound - lower_bound) * uni_() + lower_bound; } /** \brief Generate a random real using a normal distribution with mean 0 and variance 1 */ double gaussian01(void) { return normal_(); } /** \brief Generate a random real using a normal distribution with given mean and variance */ double gaussian(double mean, double stddev) { return normal_() * stddev + mean; } /** \brief Uniform random unit quaternion sampling. The computed value has the order (x,y,z,w) * @param value[4] A four dimensional array in which the computed quaternion will be returned */ void quaternion(double value[4]); /** \brief Generate an integer uniformly at random within a specified range (inclusive) */ int uniformInteger(int min, int max) { boost::uniform_int<> dis(min, max); return dis(generator_); } /** * \brief Allow the randomly generated seed to be saved so that experiments / benchmarks can be recreated in the future */ boost::uint32_t getFirstSeed(); private: boost::mt19937 generator_; boost::uniform_real<> uniDist_; boost::normal_distribution<> normalDist_; boost::variate_generator > uni_; boost::variate_generator > normal_; }; } #endif random_numbers-0.3.2/package.xml000066400000000000000000000014231324534017200166450ustar00rootroot00000000000000 random_numbers 0.3.2 This library contains wrappers for generating floating point values, integers, quaternions using boost libraries. The constructor of the wrapper is guaranteed to be thread safe and initialize its random number generator to a random seed. Seeds are obtained using a separate and different random number generator. Ioan Sucan Steven! Ragnarök BSD http://ros.org/wiki/random_numbers catkin boost boost random_numbers-0.3.2/src/000077500000000000000000000000001324534017200153175ustar00rootroot00000000000000random_numbers-0.3.2/src/random_numbers.cpp000066400000000000000000000113711324534017200210410ustar00rootroot00000000000000/********************************************************************* * 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 */ #include "random_numbers/random_numbers.h" #include #include #include #include #include #include static boost::uint32_t first_seed_ = 0; /// Compute the first seed to be used; this function should be called only once static boost::uint32_t firstSeed(void) { boost::scoped_ptr mem(new int()); first_seed_ = (boost::uint32_t)((boost::posix_time::microsec_clock::universal_time() - boost::posix_time::ptime(boost::date_time::min_date_time)).total_microseconds() + (unsigned long long)(mem.get())); return first_seed_; } /// We use a different random number generator for the seeds of the /// Other random generators. The root seed is from the number of /// nano-seconds in the current time. static boost::uint32_t nextSeed(void) { static boost::mutex rngMutex; boost::mutex::scoped_lock slock(rngMutex); static boost::lagged_fibonacci607 sGen(firstSeed()); static boost::uniform_int<> sDist(1, 1000000000); static boost::variate_generator > s(sGen, sDist); boost::uint32_t v = s(); return v; } random_numbers::RandomNumberGenerator::RandomNumberGenerator(void) : generator_(nextSeed()), uniDist_(0, 1), normalDist_(0, 1), uni_(generator_, uniDist_), normal_(generator_, normalDist_) { } random_numbers::RandomNumberGenerator::RandomNumberGenerator(boost::uint32_t seed) : generator_(seed), uniDist_(0, 1), normalDist_(0, 1), uni_(generator_, uniDist_), normal_(generator_, normalDist_) { // Because we manually specified a seed, we need to save it ourselves first_seed_ = seed; } // From: "Uniform Random Rotations", Ken Shoemake, Graphics Gems III, // pg. 124-132 void random_numbers::RandomNumberGenerator::quaternion(double value[4]) { double x0 = uni_(); double r1 = sqrt(1.0 - x0), r2 = sqrt(x0); double t1 = 2.0 * boost::math::constants::pi() * uni_(), t2 = 2.0 * boost::math::constants::pi() * uni_(); double c1 = cos(t1), s1 = sin(t1); double c2 = cos(t2), s2 = sin(t2); value[0] = s1 * r1; value[1] = c1 * r1; value[2] = s2 * r2; value[3] = c2 * r2; } boost::uint32_t random_numbers::RandomNumberGenerator::getFirstSeed() { return first_seed_; }