Inlined random direction generation

release/4.3a0
Frank Dellaert 2019-06-15 23:33:43 -04:00 committed by Frank Dellaert
parent 50e484a3c6
commit afddf0084c
1 changed files with 12 additions and 19 deletions

View File

@ -23,17 +23,6 @@
#include <gtsam/geometry/Point2.h>
#include <gtsam/config.h> // for GTSAM_USE_TBB
#ifdef __clang__
# pragma clang diagnostic push
# pragma clang diagnostic ignored "-Wunused-variable"
#endif
#define BOOST_ALLOW_DEPRECATED_HEADERS
#include <boost/random/uniform_on_sphere.hpp>
#include <boost/random/variate_generator.hpp>
#ifdef __clang__
# pragma clang diagnostic pop
#endif
#include <iostream>
#include <limits>
#include <cmath>
@ -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<double> 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<std::mt19937&, boost::uniform_on_sphere<double> > generator(
rng, randomDirection);
const vector<double> d = generator();
return Unit3(d[0], d[1], d[2]);
// http://mathworld.wolfram.com/SpherePointPicking.html
// Adapted from implementation in boost, but using std <random>
std::uniform_real_distribution<double> 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);
}
/* ************************************************************************* */