eradicated last vestiges of boost/random in gtsam_unstable
parent
afddf0084c
commit
8e81890f9b
|
@ -4,10 +4,7 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
#include <boost/random/linear_congruential.hpp>
|
#include <random>
|
||||||
#include <boost/random/uniform_real.hpp>
|
|
||||||
#include <boost/random/normal_distribution.hpp>
|
|
||||||
#include <boost/random/variate_generator.hpp>
|
|
||||||
|
|
||||||
#include <gtsam_unstable/geometry/SimPolygon2D.h>
|
#include <gtsam_unstable/geometry/SimPolygon2D.h>
|
||||||
|
|
||||||
|
@ -16,11 +13,11 @@ namespace gtsam {
|
||||||
using namespace std;
|
using namespace std;
|
||||||
|
|
||||||
const size_t max_it = 100000;
|
const size_t max_it = 100000;
|
||||||
boost::minstd_rand SimPolygon2D::rng(42u);
|
std::minstd_rand SimPolygon2D::rng(42u);
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
void SimPolygon2D::seedGenerator(unsigned long seed) {
|
void SimPolygon2D::seedGenerator(unsigned long seed) {
|
||||||
rng = boost::minstd_rand(seed);
|
rng = std::minstd_rand(seed);
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
@ -225,23 +222,23 @@ SimPolygon2D SimPolygon2D::randomRectangle(
|
||||||
|
|
||||||
/* ***************************************************************** */
|
/* ***************************************************************** */
|
||||||
Point2 SimPolygon2D::randomPoint2(double s) {
|
Point2 SimPolygon2D::randomPoint2(double s) {
|
||||||
boost::uniform_real<> gen_t(-s/2.0, s/2.0);
|
std::uniform_real_distribution<> gen_t(-s/2.0, s/2.0);
|
||||||
return Point2(gen_t(rng), gen_t(rng));
|
return Point2(gen_t(rng), gen_t(rng));
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ***************************************************************** */
|
/* ***************************************************************** */
|
||||||
Rot2 SimPolygon2D::randomAngle() {
|
Rot2 SimPolygon2D::randomAngle() {
|
||||||
boost::uniform_real<> gen_r(-M_PI, M_PI); // modified range to avoid degenerate cases in triangles
|
// modified range to avoid degenerate cases in triangles:
|
||||||
|
std::uniform_real_distribution<> gen_r(-M_PI, M_PI);
|
||||||
return Rot2::fromAngle(gen_r(rng));
|
return Rot2::fromAngle(gen_r(rng));
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ***************************************************************** */
|
/* ***************************************************************** */
|
||||||
double SimPolygon2D::randomDistance(double mu, double sigma, double min_dist) {
|
double SimPolygon2D::randomDistance(double mu, double sigma, double min_dist) {
|
||||||
boost::normal_distribution<double> norm_dist(mu, sigma);
|
std::normal_distribution<> norm_dist(mu, sigma);
|
||||||
boost::variate_generator<boost::minstd_rand&, boost::normal_distribution<double> > gen_d(rng, norm_dist);
|
|
||||||
double d = -10.0;
|
double d = -10.0;
|
||||||
for (size_t i=0; i<max_it; ++i) {
|
for (size_t i=0; i<max_it; ++i) {
|
||||||
d = std::abs(gen_d());
|
d = std::abs(norm_dist(rng));
|
||||||
if (d > min_dist)
|
if (d > min_dist)
|
||||||
return d;
|
return d;
|
||||||
}
|
}
|
||||||
|
@ -294,8 +291,8 @@ Point2 SimPolygon2D::randomBoundedPoint2(
|
||||||
const Point2Vector& landmarks,
|
const Point2Vector& landmarks,
|
||||||
const std::vector<SimPolygon2D>& obstacles, double min_landmark_dist) {
|
const std::vector<SimPolygon2D>& obstacles, double min_landmark_dist) {
|
||||||
|
|
||||||
boost::uniform_real<> gen_x(0.0, UR_corner.x() - LL_corner.x());
|
std::uniform_real_distribution<> gen_x(0.0, UR_corner.x() - LL_corner.x());
|
||||||
boost::uniform_real<> gen_y(0.0, UR_corner.y() - LL_corner.y());
|
std::uniform_real_distribution<> gen_y(0.0, UR_corner.y() - LL_corner.y());
|
||||||
|
|
||||||
for (size_t i=0; i<max_it; ++i) {
|
for (size_t i=0; i<max_it; ++i) {
|
||||||
Point2 p = Point2(gen_x(rng), gen_y(rng)) + LL_corner;
|
Point2 p = Point2(gen_x(rng), gen_y(rng)) + LL_corner;
|
||||||
|
|
|
@ -6,10 +6,11 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <map>
|
|
||||||
#include <gtsam/geometry/Pose2.h>
|
#include <gtsam/geometry/Pose2.h>
|
||||||
#include <gtsam_unstable/geometry/SimWall2D.h>
|
#include <gtsam_unstable/geometry/SimWall2D.h>
|
||||||
#include <boost/random/linear_congruential.hpp>
|
|
||||||
|
#include <map>
|
||||||
|
#include <random>
|
||||||
|
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
|
|
||||||
|
@ -19,7 +20,7 @@ namespace gtsam {
|
||||||
class GTSAM_UNSTABLE_EXPORT SimPolygon2D {
|
class GTSAM_UNSTABLE_EXPORT SimPolygon2D {
|
||||||
protected:
|
protected:
|
||||||
Point2Vector landmarks_;
|
Point2Vector landmarks_;
|
||||||
static boost::minstd_rand rng;
|
static std::minstd_rand rng;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
|
||||||
|
|
|
@ -1,12 +1,13 @@
|
||||||
/**
|
/**
|
||||||
* @file testSimPolygon
|
* @file testSimPolygon2D.cpp
|
||||||
* @author Alex Cunningham
|
* @author Alex Cunningham
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <CppUnitLite/TestHarness.h>
|
|
||||||
#include <gtsam/base/TestableAssertions.h>
|
#include <gtsam/base/TestableAssertions.h>
|
||||||
#include <gtsam_unstable/geometry/SimPolygon2D.h>
|
#include <gtsam_unstable/geometry/SimPolygon2D.h>
|
||||||
|
|
||||||
|
#include <CppUnitLite/TestHarness.h>
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
using namespace gtsam;
|
using namespace gtsam;
|
||||||
|
|
||||||
|
|
|
@ -11,13 +11,12 @@
|
||||||
|
|
||||||
#include <gtsam/discrete/DiscreteFactorGraph.h>
|
#include <gtsam/discrete/DiscreteFactorGraph.h>
|
||||||
#include <gtsam/geometry/Pose2.h>
|
#include <gtsam/geometry/Pose2.h>
|
||||||
#include <boost/random/mersenne_twister.hpp>
|
|
||||||
//#include <boost/random/uniform_int_distribution.hpp> // FIXME: does not exist in boost 1.46
|
|
||||||
#include <boost/random/uniform_int.hpp> // Old header - should still exist
|
|
||||||
|
|
||||||
#include <vector>
|
#include <vector>
|
||||||
|
#include <cmath.>
|
||||||
|
#include <random>
|
||||||
|
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
#include <math.h>
|
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
using namespace gtsam;
|
using namespace gtsam;
|
||||||
|
@ -229,8 +228,8 @@ public:
|
||||||
Marginals marginals(size);
|
Marginals marginals(size);
|
||||||
|
|
||||||
// NOTE: using older interface for boost.random due to interface changes after boost 1.46
|
// NOTE: using older interface for boost.random due to interface changes after boost 1.46
|
||||||
boost::mt19937 rng;
|
std::mt19937 rng;
|
||||||
boost::uniform_int<Index> random_cell(0,size-1);
|
std::uniform_int_distribution<> random_cell(0, size - 1);
|
||||||
|
|
||||||
// run Metropolis for the requested number of operations
|
// run Metropolis for the requested number of operations
|
||||||
// compute initial probability of occupancy grid, P(x_t)
|
// compute initial probability of occupancy grid, P(x_t)
|
||||||
|
|
|
@ -20,13 +20,13 @@
|
||||||
#include <gtsam_unstable/base/DSF.h>
|
#include <gtsam_unstable/base/DSF.h>
|
||||||
#include <gtsam/base/DSFMap.h>
|
#include <gtsam/base/DSFMap.h>
|
||||||
|
|
||||||
#include <boost/random.hpp>
|
|
||||||
#include <boost/timer.hpp>
|
#include <boost/timer.hpp>
|
||||||
#include <boost/format.hpp>
|
#include <boost/format.hpp>
|
||||||
#include <boost/assign/std/vector.hpp>
|
#include <boost/assign/std/vector.hpp>
|
||||||
|
|
||||||
#include <iostream>
|
|
||||||
#include <fstream>
|
#include <fstream>
|
||||||
|
#include <iostream>
|
||||||
|
#include <random>
|
||||||
#include <vector>
|
#include <vector>
|
||||||
#include <utility>
|
#include <utility>
|
||||||
|
|
||||||
|
@ -59,13 +59,14 @@ int main(int argc, char* argv[]) {
|
||||||
cout << format("\nTesting with %1% images, %2% points, %3% matches\n")
|
cout << format("\nTesting with %1% images, %2% points, %3% matches\n")
|
||||||
% (int)m % (int)N % (int)nm;
|
% (int)m % (int)N % (int)nm;
|
||||||
cout << "Generating " << nm << " matches" << endl;
|
cout << "Generating " << nm << " matches" << endl;
|
||||||
boost::variate_generator<boost::mt19937, boost::uniform_int<size_t> > rn(
|
std::mt19937 rng;
|
||||||
boost::mt19937(), boost::uniform_int<size_t>(0, N - 1));
|
std::uniform_int_distribution<> rn(0, N - 1);
|
||||||
|
|
||||||
typedef pair<size_t, size_t> Match;
|
typedef pair<size_t, size_t> Match;
|
||||||
vector<Match> matches;
|
vector<Match> matches;
|
||||||
matches.reserve(nm);
|
matches.reserve(nm);
|
||||||
for (size_t k = 0; k < nm; k++)
|
for (size_t k = 0; k < nm; k++)
|
||||||
matches.push_back(Match(rn(), rn()));
|
matches.push_back(Match(rn(rng), rn(rng)));
|
||||||
|
|
||||||
os << format("%1%,%2%,%3%,") % (int)m % (int)N % (int)nm;
|
os << format("%1%,%2%,%3%,") % (int)m % (int)N % (int)nm;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue