From afddf0084cbf216da2a51448b1d326d184cac588 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 15 Jun 2019 23:33:43 -0400 Subject: [PATCH] Inlined random direction generation --- gtsam/geometry/Unit3.cpp | 31 ++++++++++++------------------- 1 file changed, 12 insertions(+), 19 deletions(-) diff --git a/gtsam/geometry/Unit3.cpp b/gtsam/geometry/Unit3.cpp index 0e1b09958..3d46b18b8 100755 --- a/gtsam/geometry/Unit3.cpp +++ b/gtsam/geometry/Unit3.cpp @@ -23,17 +23,6 @@ #include #include // for GTSAM_USE_TBB -#ifdef __clang__ -# pragma clang diagnostic push -# pragma clang diagnostic ignored "-Wunused-variable" -#endif -#define BOOST_ALLOW_DEPRECATED_HEADERS -#include -#include -#ifdef __clang__ -# pragma clang diagnostic pop -#endif - #include #include #include @@ -56,14 +45,18 @@ Unit3 Unit3::FromPoint3(const Point3& point, OptionalJacobian<2, 3> H) { /* ************************************************************************* */ Unit3 Unit3::Random(std::mt19937& rng) { - // TODO(dellaert): allow any engine without including all of boost :-( - boost::uniform_on_sphere randomDirection(3); - // This variate_generator object is required for versions of boost somewhere - // around 1.46, instead of drawing directly using boost::uniform_on_sphere(rng). - boost::variate_generator > generator( - rng, randomDirection); - const vector d = generator(); - return Unit3(d[0], d[1], d[2]); + // http://mathworld.wolfram.com/SpherePointPicking.html + // Adapted from implementation in boost, but using std + std::uniform_real_distribution uniform(-1.0, 1.0); + double sqsum; + double x, y; + do { + x = uniform(rng); + y = uniform(rng); + sqsum = x * x + y * y; + } while (sqsum > 1); + const double mult = 2 * sqrt(1 - sqsum); + return Unit3(x * mult, y * mult, 2 * sqsum - 1); } /* ************************************************************************* */