Random now uses std header <random>.
parent
1f598269f5
commit
8b201f07bb
|
|
@ -21,8 +21,9 @@
|
||||||
#include <gtsam/geometry/Rot3.h>
|
#include <gtsam/geometry/Rot3.h>
|
||||||
#include <gtsam/geometry/SO3.h>
|
#include <gtsam/geometry/SO3.h>
|
||||||
#include <boost/math/constants/constants.hpp>
|
#include <boost/math/constants/constants.hpp>
|
||||||
#include <boost/random.hpp>
|
|
||||||
#include <cmath>
|
#include <cmath>
|
||||||
|
#include <random>
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
|
|
||||||
|
|
@ -34,10 +35,10 @@ void Rot3::print(const std::string& s) const {
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
Rot3 Rot3::Random(boost::mt19937& rng) {
|
Rot3 Rot3::Random(std::mt19937& rng) {
|
||||||
// TODO allow any engine without including all of boost :-(
|
// TODO allow any engine without including all of boost :-(
|
||||||
Unit3 axis = Unit3::Random(rng);
|
Unit3 axis = Unit3::Random(rng);
|
||||||
boost::uniform_real<double> randomAngle(-M_PI, M_PI);
|
uniform_real_distribution<double> randomAngle(-M_PI, M_PI);
|
||||||
double angle = randomAngle(rng);
|
double angle = randomAngle(rng);
|
||||||
return AxisAngle(axis, angle);
|
return AxisAngle(axis, angle);
|
||||||
}
|
}
|
||||||
|
|
|
||||||
|
|
@ -28,6 +28,8 @@
|
||||||
#include <gtsam/base/concepts.h>
|
#include <gtsam/base/concepts.h>
|
||||||
#include <gtsam/config.h> // Get GTSAM_USE_QUATERNIONS macro
|
#include <gtsam/config.h> // Get GTSAM_USE_QUATERNIONS macro
|
||||||
|
|
||||||
|
#include <random>
|
||||||
|
|
||||||
// You can override the default coordinate mode using this flag
|
// You can override the default coordinate mode using this flag
|
||||||
#ifndef ROT3_DEFAULT_COORDINATES_MODE
|
#ifndef ROT3_DEFAULT_COORDINATES_MODE
|
||||||
#ifdef GTSAM_USE_QUATERNIONS
|
#ifdef GTSAM_USE_QUATERNIONS
|
||||||
|
|
@ -128,8 +130,13 @@ namespace gtsam {
|
||||||
Rot3(const Quaternion& q);
|
Rot3(const Quaternion& q);
|
||||||
Rot3(double w, double x, double y, double z) : Rot3(Quaternion(w, x, y, z)) {}
|
Rot3(double w, double x, double y, double z) : Rot3(Quaternion(w, x, y, z)) {}
|
||||||
|
|
||||||
/// Random, generates a random axis, then random angle \in [-p,pi]
|
/**
|
||||||
static Rot3 Random(boost::mt19937 & rng);
|
* Random, generates a random axis, then random angle \in [-p,pi]
|
||||||
|
* Example:
|
||||||
|
* std::mt19937 engine(42);
|
||||||
|
* Unit3 unit = Unit3::Random(engine);
|
||||||
|
*/
|
||||||
|
static Rot3 Random(std::mt19937 & rng);
|
||||||
|
|
||||||
/** Virtual destructor */
|
/** Virtual destructor */
|
||||||
virtual ~Rot3() {}
|
virtual ~Rot3() {}
|
||||||
|
|
|
||||||
|
|
@ -22,11 +22,11 @@
|
||||||
#include <gtsam/geometry/Unit3.h>
|
#include <gtsam/geometry/Unit3.h>
|
||||||
|
|
||||||
#include <Eigen/Eigenvalues>
|
#include <Eigen/Eigenvalues>
|
||||||
#include <boost/random.hpp>
|
|
||||||
|
|
||||||
#include <algorithm>
|
#include <algorithm>
|
||||||
#include <cmath>
|
#include <cmath>
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
|
#include <random>
|
||||||
#include <vector>
|
#include <vector>
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
|
|
|
||||||
|
|
@ -27,8 +27,6 @@
|
||||||
#include <gtsam/base/Matrix.h>
|
#include <gtsam/base/Matrix.h>
|
||||||
#include <gtsam/dllexport.h>
|
#include <gtsam/dllexport.h>
|
||||||
|
|
||||||
#include <boost/random/mersenne_twister.hpp>
|
|
||||||
|
|
||||||
#include <string>
|
#include <string>
|
||||||
|
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
|
|
|
||||||
|
|
@ -23,8 +23,9 @@
|
||||||
#include <gtsam/dllexport.h>
|
#include <gtsam/dllexport.h>
|
||||||
|
|
||||||
#include <Eigen/Core>
|
#include <Eigen/Core>
|
||||||
#include <boost/random.hpp>
|
|
||||||
|
|
||||||
|
#include <iostream> // TODO(frank): how to avoid?
|
||||||
|
#include <random>
|
||||||
#include <string>
|
#include <string>
|
||||||
#include <type_traits>
|
#include <type_traits>
|
||||||
#include <vector>
|
#include <vector>
|
||||||
|
|
@ -112,12 +113,12 @@ class SO : public LieGroup<SO<N>, internal::DimensionSO(N)> {
|
||||||
/// currently only defined for SO3.
|
/// currently only defined for SO3.
|
||||||
static SO ChordalMean(const std::vector<SO>& rotations);
|
static SO ChordalMean(const std::vector<SO>& rotations);
|
||||||
|
|
||||||
/// Random SO(n) element (no big claims about uniformity)
|
/// Random SO(n) element (no big claims about uniformity). SO(3) is specialized in SO3.cpp
|
||||||
template <int N_ = N, typename = IsDynamic<N_>>
|
template <int N_ = N, typename = IsDynamic<N_>>
|
||||||
static SO Random(boost::mt19937& rng, size_t n = 0) {
|
static SO Random(std::mt19937& rng, size_t n = 0) {
|
||||||
if (n == 0) throw std::runtime_error("SO: Dimensionality not known.");
|
if (n == 0) throw std::runtime_error("SO: Dimensionality not known.");
|
||||||
// TODO(frank): This needs to be re-thought!
|
// TODO(frank): this might need to be re-thought
|
||||||
static boost::uniform_real<double> randomAngle(-M_PI, M_PI);
|
static std::uniform_real_distribution<double> randomAngle(-M_PI, M_PI);
|
||||||
const size_t d = SO::Dimension(n);
|
const size_t d = SO::Dimension(n);
|
||||||
Vector xi(d);
|
Vector xi(d);
|
||||||
for (size_t j = 0; j < d; j++) {
|
for (size_t j = 0; j < d; j++) {
|
||||||
|
|
@ -128,7 +129,7 @@ class SO : public LieGroup<SO<N>, internal::DimensionSO(N)> {
|
||||||
|
|
||||||
/// Random SO(N) element (no big claims about uniformity)
|
/// Random SO(N) element (no big claims about uniformity)
|
||||||
template <int N_ = N, typename = IsFixed<N_>>
|
template <int N_ = N, typename = IsFixed<N_>>
|
||||||
static SO Random(boost::mt19937& rng) {
|
static SO Random(std::mt19937& rng) {
|
||||||
// By default, use dynamic implementation above. Specialized for SO(3).
|
// By default, use dynamic implementation above. Specialized for SO(3).
|
||||||
return SO(SO<Eigen::Dynamic>::Random(rng, N).matrix());
|
return SO(SO<Eigen::Dynamic>::Random(rng, N).matrix());
|
||||||
}
|
}
|
||||||
|
|
|
||||||
|
|
@ -27,12 +27,13 @@
|
||||||
# pragma clang diagnostic push
|
# pragma clang diagnostic push
|
||||||
# pragma clang diagnostic ignored "-Wunused-variable"
|
# pragma clang diagnostic ignored "-Wunused-variable"
|
||||||
#endif
|
#endif
|
||||||
|
#define BOOST_ALLOW_DEPRECATED_HEADERS
|
||||||
#include <boost/random/uniform_on_sphere.hpp>
|
#include <boost/random/uniform_on_sphere.hpp>
|
||||||
|
#include <boost/random/variate_generator.hpp>
|
||||||
#ifdef __clang__
|
#ifdef __clang__
|
||||||
# pragma clang diagnostic pop
|
# pragma clang diagnostic pop
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#include <boost/random/variate_generator.hpp>
|
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
#include <limits>
|
#include <limits>
|
||||||
#include <cmath>
|
#include <cmath>
|
||||||
|
|
@ -54,12 +55,12 @@ Unit3 Unit3::FromPoint3(const Point3& point, OptionalJacobian<2, 3> H) {
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
Unit3 Unit3::Random(boost::mt19937 & rng) {
|
Unit3 Unit3::Random(std::mt19937& rng) {
|
||||||
// TODO(dellaert): allow any engine without including all of boost :-(
|
// TODO(dellaert): allow any engine without including all of boost :-(
|
||||||
boost::uniform_on_sphere<double> randomDirection(3);
|
boost::uniform_on_sphere<double> randomDirection(3);
|
||||||
// This variate_generator object is required for versions of boost somewhere
|
// This variate_generator object is required for versions of boost somewhere
|
||||||
// around 1.46, instead of drawing directly using boost::uniform_on_sphere(rng).
|
// around 1.46, instead of drawing directly using boost::uniform_on_sphere(rng).
|
||||||
boost::variate_generator<boost::mt19937&, boost::uniform_on_sphere<double> > generator(
|
boost::variate_generator<std::mt19937&, boost::uniform_on_sphere<double> > generator(
|
||||||
rng, randomDirection);
|
rng, randomDirection);
|
||||||
const vector<double> d = generator();
|
const vector<double> d = generator();
|
||||||
return Unit3(d[0], d[1], d[2]);
|
return Unit3(d[0], d[1], d[2]);
|
||||||
|
|
|
||||||
|
|
@ -27,9 +27,9 @@
|
||||||
#include <gtsam/dllexport.h>
|
#include <gtsam/dllexport.h>
|
||||||
|
|
||||||
#include <boost/optional.hpp>
|
#include <boost/optional.hpp>
|
||||||
#include <boost/random/mersenne_twister.hpp>
|
|
||||||
#include <boost/serialization/nvp.hpp>
|
#include <boost/serialization/nvp.hpp>
|
||||||
|
|
||||||
|
#include <random>
|
||||||
#include <string>
|
#include <string>
|
||||||
|
|
||||||
#ifdef GTSAM_USE_TBB
|
#ifdef GTSAM_USE_TBB
|
||||||
|
|
@ -97,8 +97,13 @@ public:
|
||||||
GTSAM_EXPORT static Unit3 FromPoint3(const Point3& point, //
|
GTSAM_EXPORT static Unit3 FromPoint3(const Point3& point, //
|
||||||
OptionalJacobian<2, 3> H = boost::none);
|
OptionalJacobian<2, 3> H = boost::none);
|
||||||
|
|
||||||
/// Random direction, using boost::uniform_on_sphere
|
/**
|
||||||
GTSAM_EXPORT static Unit3 Random(boost::mt19937 & rng);
|
* Random direction, using boost::uniform_on_sphere
|
||||||
|
* Example:
|
||||||
|
* std::mt19937 engine(42);
|
||||||
|
* Unit3 unit = Unit3::Random(engine);
|
||||||
|
*/
|
||||||
|
GTSAM_EXPORT static Unit3 Random(std::mt19937 & rng);
|
||||||
|
|
||||||
/// @}
|
/// @}
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -25,6 +25,7 @@
|
||||||
#include <CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
|
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
|
#include <random>
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
using namespace gtsam;
|
using namespace gtsam;
|
||||||
|
|
@ -57,7 +58,7 @@ SO4 Q3 = SO4::Expmap(v3);
|
||||||
|
|
||||||
//******************************************************************************
|
//******************************************************************************
|
||||||
TEST(SO4, Random) {
|
TEST(SO4, Random) {
|
||||||
boost::mt19937 rng(42);
|
std::mt19937 rng(42);
|
||||||
auto Q = SO4::Random(rng);
|
auto Q = SO4::Random(rng);
|
||||||
EXPECT_LONGS_EQUAL(4, Q.matrix().rows());
|
EXPECT_LONGS_EQUAL(4, Q.matrix().rows());
|
||||||
}
|
}
|
||||||
|
|
|
||||||
|
|
@ -30,9 +30,8 @@
|
||||||
|
|
||||||
#include <CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
|
|
||||||
#include <boost/random.hpp>
|
|
||||||
|
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
|
#include <random>
|
||||||
#include <stdexcept>
|
#include <stdexcept>
|
||||||
#include <type_traits>
|
#include <type_traits>
|
||||||
|
|
||||||
|
|
@ -88,7 +87,7 @@ TEST(SOn, Values) {
|
||||||
|
|
||||||
//******************************************************************************
|
//******************************************************************************
|
||||||
TEST(SOn, Random) {
|
TEST(SOn, Random) {
|
||||||
static boost::mt19937 rng(42);
|
static std::mt19937 rng(42);
|
||||||
EXPECT_LONGS_EQUAL(3, SOn::Random(rng, 3).rows());
|
EXPECT_LONGS_EQUAL(3, SOn::Random(rng, 3).rows());
|
||||||
EXPECT_LONGS_EQUAL(4, SOn::Random(rng, 4).rows());
|
EXPECT_LONGS_EQUAL(4, SOn::Random(rng, 4).rows());
|
||||||
EXPECT_LONGS_EQUAL(5, SOn::Random(rng, 5).rows());
|
EXPECT_LONGS_EQUAL(5, SOn::Random(rng, 5).rows());
|
||||||
|
|
|
||||||
|
|
@ -33,9 +33,10 @@
|
||||||
#include <CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
|
|
||||||
#include <boost/bind.hpp>
|
#include <boost/bind.hpp>
|
||||||
#include <boost/random.hpp>
|
|
||||||
#include <boost/assign/std/vector.hpp>
|
#include <boost/assign/std/vector.hpp>
|
||||||
|
|
||||||
#include <cmath>
|
#include <cmath>
|
||||||
|
#include <random>
|
||||||
|
|
||||||
using namespace boost::assign;
|
using namespace boost::assign;
|
||||||
using namespace gtsam;
|
using namespace gtsam;
|
||||||
|
|
@ -339,7 +340,7 @@ TEST(Unit3, basis) {
|
||||||
/// Check the basis derivatives of a bunch of random Unit3s.
|
/// Check the basis derivatives of a bunch of random Unit3s.
|
||||||
TEST(Unit3, basis_derivatives) {
|
TEST(Unit3, basis_derivatives) {
|
||||||
int num_tests = 100;
|
int num_tests = 100;
|
||||||
boost::mt19937 rng(42);
|
std::mt19937 rng(42);
|
||||||
for (int i = 0; i < num_tests; i++) {
|
for (int i = 0; i < num_tests; i++) {
|
||||||
Unit3 p = Unit3::Random(rng);
|
Unit3 p = Unit3::Random(rng);
|
||||||
|
|
||||||
|
|
@ -403,7 +404,7 @@ TEST(Unit3, retract_expmap) {
|
||||||
|
|
||||||
//*******************************************************************************
|
//*******************************************************************************
|
||||||
TEST(Unit3, Random) {
|
TEST(Unit3, Random) {
|
||||||
boost::mt19937 rng(42);
|
std::mt19937 rng(42);
|
||||||
// Check that means are all zero at least
|
// Check that means are all zero at least
|
||||||
Point3 expectedMean(0,0,0), actualMean(0,0,0);
|
Point3 expectedMean(0,0,0), actualMean(0,0,0);
|
||||||
for (size_t i = 0; i < 100; i++)
|
for (size_t i = 0; i < 100; i++)
|
||||||
|
|
@ -415,7 +416,7 @@ TEST(Unit3, Random) {
|
||||||
//*******************************************************************************
|
//*******************************************************************************
|
||||||
// New test that uses Unit3::Random
|
// New test that uses Unit3::Random
|
||||||
TEST(Unit3, localCoordinates_retract) {
|
TEST(Unit3, localCoordinates_retract) {
|
||||||
boost::mt19937 rng(42);
|
std::mt19937 rng(42);
|
||||||
size_t numIterations = 10000;
|
size_t numIterations = 10000;
|
||||||
|
|
||||||
for (size_t i = 0; i < numIterations; i++) {
|
for (size_t i = 0; i < numIterations; i++) {
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue