Using variate_generator in Sphere2 random for compatibility with old boost
parent
3fc41d5da3
commit
6df79b8dac
|
@ -22,6 +22,7 @@
|
||||||
#include <gtsam/geometry/Point2.h>
|
#include <gtsam/geometry/Point2.h>
|
||||||
#include <boost/random/mersenne_twister.hpp>
|
#include <boost/random/mersenne_twister.hpp>
|
||||||
#include <boost/random/uniform_on_sphere.hpp>
|
#include <boost/random/uniform_on_sphere.hpp>
|
||||||
|
#include <boost/random/variate_generator.hpp>
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
|
@ -47,7 +48,11 @@ Sphere2 Sphere2::FromPoint3(const Point3& point,
|
||||||
Sphere2 Sphere2::Random(boost::mt19937 & rng) {
|
Sphere2 Sphere2::Random(boost::mt19937 & rng) {
|
||||||
// TODO allow any engine without including all of boost :-(
|
// TODO allow any engine without including all of boost :-(
|
||||||
boost::uniform_on_sphere<double> randomDirection(3);
|
boost::uniform_on_sphere<double> randomDirection(3);
|
||||||
vector<double> d = randomDirection(rng);
|
// 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<boost::mt19937&, boost::uniform_on_sphere<double> >
|
||||||
|
generator(rng, randomDirection);
|
||||||
|
vector<double> d = generator();
|
||||||
Sphere2 result;
|
Sphere2 result;
|
||||||
result.p_ = Point3(d[0], d[1], d[2]);
|
result.p_ = Point3(d[0], d[1], d[2]);
|
||||||
return result;
|
return result;
|
||||||
|
|
|
@ -312,7 +312,7 @@ TEST(Sphere2, localCoordinates_retract_expmap) {
|
||||||
|
|
||||||
//*******************************************************************************
|
//*******************************************************************************
|
||||||
TEST(Sphere2, Random) {
|
TEST(Sphere2, Random) {
|
||||||
boost::random::mt19937 rng(42);
|
boost::mt19937 rng(42);
|
||||||
// Check that is deterministic given same random seed
|
// Check that is deterministic given same random seed
|
||||||
Point3 expected(-0.667578, 0.671447, 0.321713);
|
Point3 expected(-0.667578, 0.671447, 0.321713);
|
||||||
Point3 actual = Sphere2::Random(rng).point3();
|
Point3 actual = Sphere2::Random(rng).point3();
|
||||||
|
|
Loading…
Reference in New Issue