diff --git a/gtsam_unstable/geometry/SimPolygon2D.cpp b/gtsam_unstable/geometry/SimPolygon2D.cpp index eb732f2c5..2d4bd7a2d 100644 --- a/gtsam_unstable/geometry/SimPolygon2D.cpp +++ b/gtsam_unstable/geometry/SimPolygon2D.cpp @@ -4,10 +4,7 @@ */ #include -#include -#include -#include -#include +#include #include @@ -16,11 +13,11 @@ namespace gtsam { using namespace std; const size_t max_it = 100000; -boost::minstd_rand SimPolygon2D::rng(42u); +std::minstd_rand SimPolygon2D::rng(42u); /* ************************************************************************* */ 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) { - 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)); } /* ***************************************************************** */ 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)); } /* ***************************************************************** */ double SimPolygon2D::randomDistance(double mu, double sigma, double min_dist) { - boost::normal_distribution norm_dist(mu, sigma); - boost::variate_generator > gen_d(rng, norm_dist); + std::normal_distribution<> norm_dist(mu, sigma); double d = -10.0; for (size_t i=0; i min_dist) return d; } @@ -294,8 +291,8 @@ Point2 SimPolygon2D::randomBoundedPoint2( const Point2Vector& landmarks, const std::vector& obstacles, double min_landmark_dist) { - boost::uniform_real<> 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_x(0.0, UR_corner.x() - LL_corner.x()); + std::uniform_real_distribution<> gen_y(0.0, UR_corner.y() - LL_corner.y()); for (size_t i=0; i #include #include -#include + +#include +#include namespace gtsam { @@ -19,7 +20,7 @@ namespace gtsam { class GTSAM_UNSTABLE_EXPORT SimPolygon2D { protected: Point2Vector landmarks_; - static boost::minstd_rand rng; + static std::minstd_rand rng; public: diff --git a/gtsam_unstable/geometry/tests/testSimPolygon2D.cpp b/gtsam_unstable/geometry/tests/testSimPolygon2D.cpp index 6528f3f91..5cdd6c100 100644 --- a/gtsam_unstable/geometry/tests/testSimPolygon2D.cpp +++ b/gtsam_unstable/geometry/tests/testSimPolygon2D.cpp @@ -1,12 +1,13 @@ /** - * @file testSimPolygon + * @file testSimPolygon2D.cpp * @author Alex Cunningham */ -#include #include #include +#include + using namespace std; using namespace gtsam; diff --git a/gtsam_unstable/slam/tests/testOccupancyGrid.cpp b/gtsam_unstable/slam/tests/testOccupancyGrid.cpp index d92e5442e..1d28a7523 100644 --- a/gtsam_unstable/slam/tests/testOccupancyGrid.cpp +++ b/gtsam_unstable/slam/tests/testOccupancyGrid.cpp @@ -11,13 +11,12 @@ #include #include -#include -//#include // FIXME: does not exist in boost 1.46 -#include // Old header - should still exist #include +#include +#include + #include -#include using namespace std; using namespace gtsam; @@ -229,8 +228,8 @@ public: Marginals marginals(size); // NOTE: using older interface for boost.random due to interface changes after boost 1.46 - boost::mt19937 rng; - boost::uniform_int random_cell(0,size-1); + std::mt19937 rng; + std::uniform_int_distribution<> random_cell(0, size - 1); // run Metropolis for the requested number of operations // compute initial probability of occupancy grid, P(x_t) diff --git a/gtsam_unstable/timing/timeDSFvariants.cpp b/gtsam_unstable/timing/timeDSFvariants.cpp index 26ed76d02..d8182ae19 100644 --- a/gtsam_unstable/timing/timeDSFvariants.cpp +++ b/gtsam_unstable/timing/timeDSFvariants.cpp @@ -20,13 +20,13 @@ #include #include -#include #include #include #include -#include #include +#include +#include #include #include @@ -59,13 +59,14 @@ int main(int argc, char* argv[]) { cout << format("\nTesting with %1% images, %2% points, %3% matches\n") % (int)m % (int)N % (int)nm; cout << "Generating " << nm << " matches" << endl; - boost::variate_generator > rn( - boost::mt19937(), boost::uniform_int(0, N - 1)); + std::mt19937 rng; + std::uniform_int_distribution<> rn(0, N - 1); + typedef pair Match; vector matches; matches.reserve(nm); 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;