Removed sample() functions and global random number generator

release/4.3a0
Alex Cunningham 2012-06-22 16:38:01 +00:00
parent ae9088efdc
commit 18ba9bcb3d
12 changed files with 238 additions and 331 deletions

18
gtsam.h
View File

@ -690,7 +690,6 @@ class Diagonal {
static gtsam::noiseModel::Diagonal* Sigmas(Vector sigmas);
static gtsam::noiseModel::Diagonal* Variances(Vector variances);
static gtsam::noiseModel::Diagonal* Precisions(Vector precisions);
Vector sample() const;
// Matrix R() const; // FIXME: cannot parse!!!
void print(string s) const;
};
@ -699,7 +698,6 @@ class Isotropic {
static gtsam::noiseModel::Isotropic* Sigma(size_t dim, double sigma);
static gtsam::noiseModel::Isotropic* Variance(size_t dim, double varianace);
static gtsam::noiseModel::Isotropic* Precision(size_t dim, double precision);
Vector sample() const;
void print(string s) const;
};
@ -731,7 +729,19 @@ class SharedGaussian {
class SharedDiagonal {
SharedDiagonal(Vector sigmas);
void print(string s) const;
Vector sample() const;
};
class Sampler {
Sampler(gtsam::noiseModel::Diagonal* model, int seed);
Sampler(Vector sigmas, int seed);
Sampler(int seed);
size_t dim() const;
Vector sigmas() const;
gtsam::noiseModel::Diagonal* model() const;
Vector sample();
Vector sampleNewModel(gtsam::noiseModel::Diagonal* model);
};
class VectorValues {
@ -926,7 +936,7 @@ class NonlinearFactor {
void equals(const gtsam::NonlinearFactor& other, double tol) const;
gtsam::KeyVector keys() const;
size_t size() const;
size_t dim() const;
// size_t dim() const; // FIXME: Doesn't link
};
class Values {

View File

@ -23,13 +23,11 @@
#include <sstream>
#include <iomanip>
#include <cmath>
#include <stdexcept>
#include <boost/foreach.hpp>
#include <boost/optional.hpp>
#include <cstdio>
#include <boost/random/normal_distribution.hpp>
#include <boost/random/variate_generator.hpp>
#include <gtsam/base/Vector.h>
#include <gtsam/base/types.h>
@ -39,8 +37,6 @@
using namespace std;
boost::minstd_rand generator(42u);
namespace gtsam {
/* ************************************************************************* */
@ -432,19 +428,6 @@ Vector concatVectors(size_t nrVectors, ...)
return concatVectors(vs);
}
/* ************************************************************************* */
Vector rand_vector_norm(size_t dim, double mean, double sigma)
{
boost::normal_distribution<double> norm_dist(mean, sigma);
boost::variate_generator<boost::minstd_rand&, boost::normal_distribution<double> > norm(generator, norm_dist);
Vector v(dim);
for(int i = 0; i<v.size(); ++i)
v(i) = norm();
return v;
}
/* ************************************************************************* */
} // namespace gtsam

View File

@ -22,19 +22,9 @@
#include <list>
#include <vector>
#include <iostream>
#include <gtsam/base/types.h>
#include <gtsam/3rdparty/Eigen/Eigen/Dense>
#include <boost/random/linear_congruential.hpp>
/**
* Static random number generator - needs to maintain a state
* over time, hence the static generator. Be careful in
* cases where multiple processes (as is frequently the case with
* multi-robot scenarios) are using the sample() facilities
* in NoiseModel, as they will each have the same seed.
*/
// FIXME: make this go away - use the Sampler class instead
extern boost::minstd_rand generator;
namespace gtsam {
@ -358,20 +348,6 @@ Vector concatVectors(const std::list<Vector>& vs);
*/
Vector concatVectors(size_t nrVectors, ...);
/**
* random vector
*/
Vector rand_vector_norm(size_t dim, double mean = 0, double sigma = 1);
/**
* Sets the generator to use a different seed value.
* Default argument resets the RNG
* @param seed is the new seed
*/
inline void seedRNG(unsigned int seed = 42u) {
generator.seed(seed);
}
} // namespace gtsam
#include <boost/serialization/nvp.hpp>

View File

@ -297,27 +297,6 @@ TEST( TestVector, linear_dependent3 )
EXPECT(!linear_dependent(v1, v2));
}
/* ************************************************************************* */
TEST( TestVector, random )
{
// Assumes seed not previously reset during this test
seedRNG();
Vector v1_42 = rand_vector_norm(5);
// verify that resetting the RNG produces the same value
seedRNG();
Vector v2_42 = rand_vector_norm(5);
EXPECT(assert_equal(v1_42, v2_42, 1e-6));
// verify that different seed produces a different value
seedRNG(41u);
Vector v3_41 = rand_vector_norm(5);
EXPECT(assert_inequal(v1_42, v3_41, 1e-6));
}
/* ************************************************************************* */
int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
/* ************************************************************************* */

View File

@ -255,18 +255,6 @@ void Diagonal::WhitenInPlace(Matrix& H) const {
vector_scale_inplace(invsigmas(), H);
}
/* ************************************************************************* */
Vector Diagonal::sample() const {
Vector result(dim_);
for (size_t i = 0; i < dim_; i++) {
typedef boost::normal_distribution<double> Normal;
Normal dist(0.0, this->sigmas_(i));
boost::variate_generator<boost::minstd_rand&, Normal> norm(generator, dist);
result(i) = norm();
}
return result;
}
/* ************************************************************************* */
// Constrained
/* ************************************************************************* */
@ -464,18 +452,6 @@ void Isotropic::WhitenInPlace(Matrix& H) const {
H *= invsigma_;
}
/* ************************************************************************* */
// faster version
Vector Isotropic::sample() const {
typedef boost::normal_distribution<double> Normal;
Normal dist(0.0, this->sigma_);
boost::variate_generator<boost::minstd_rand&, Normal> norm(generator, dist);
Vector result(dim_);
for (size_t i = 0; i < dim_; i++)
result(i) = norm();
return result;
}
/* ************************************************************************* */
// Unit
/* ************************************************************************* */

View File

@ -298,11 +298,6 @@ namespace gtsam {
Vector invsigmas() const;
double invsigma(size_t i) const;
/**
* generate random variate
*/
virtual Vector sample() const;
/**
* Return R itself, but note that Whiten(H) is cheaper than R*H
*/
@ -525,11 +520,6 @@ namespace gtsam {
*/
inline double sigma() const { return sigma_; }
/**
* generate random variate
*/
virtual Vector sample() const;
private:
/** Serialization function */
friend class boost::serialization::access;

View File

@ -66,7 +66,7 @@ Vector Sampler::sample() {
}
/* ************************************************************************* */
Vector Sampler::sample(const noiseModel::Diagonal::shared_ptr& model) {
Vector Sampler::sampleNewModel(const noiseModel::Diagonal::shared_ptr& model) {
assert(model.get());
const Vector& sigmas = model->sigmas();
return sampleDiagonal(sigmas);

View File

@ -20,6 +20,8 @@
#include <gtsam/linear/NoiseModel.h>
#include <boost/random/linear_congruential.hpp>
namespace gtsam {
/**
@ -79,7 +81,7 @@ public:
*
* NOTE: not const due to need to update the underlying generator
*/
Vector sample(const noiseModel::Diagonal::shared_ptr& model);
Vector sampleNewModel(const noiseModel::Diagonal::shared_ptr& model);
protected:

View File

@ -58,9 +58,6 @@ namespace gtsam { // note, deliberately not in noiseModel namespace
/// Print
inline void print(const std::string &s) const { (*this)->print(s); }
/// Generate a sample
inline Vector sample() const { return (*this)->sample(); }
/** Serialization function */
friend class boost::serialization::access;
template<class ARCHIVE>

View File

@ -24,6 +24,7 @@
#include <boost/foreach.hpp>
#include <boost/shared_ptr.hpp>
#include <numeric>
#include <stdexcept>
namespace gtsam {

View File

@ -131,15 +131,6 @@ TEST(NoiseModel, equals)
EXPECT(assert_inequal(*i1,*i2));
}
/* ************************************************************************* */
TEST(NoiseModel, sample)
{
Vector s = Vector_(3,1.0,2.0,3.0);
SharedDiagonal model = sharedSigmas(s);
Vector v = model->sample();
// no check as no way yet to set random seed
}
// TODO enable test once a mechanism for smart constraints exists
///* ************************************************************************* */
//TEST(NoiseModel, ConstrainedSmart )
@ -346,8 +337,5 @@ TEST(NoiseModel, robustNoise)
}
/* ************************************************************************* */
int main() {
TestResult tr;
return TestRegistry::runAllTests(tr);
}
int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
/* ************************************************************************* */

View File

@ -20,10 +20,10 @@
#include <sstream>
#include <cstdlib>
#include <gtsam/linear/Sampler.h>
#include <gtsam/slam/dataset.h>
using namespace std;
using namespace gtsam;
#define LINESIZE 81920
@ -78,13 +78,13 @@ namespace gtsam {
}
/* ************************************************************************* */
pair<pose2SLAM::Graph::shared_ptr, pose2SLAM::Values::shared_ptr> load2D(
pair<string, boost::optional<SharedDiagonal> > dataset,
int maxID, bool addNoise, bool smart) {
return load2D(dataset.first, dataset.second, maxID, addNoise, smart);
}
/* ************************************************************************* */
pair<pose2SLAM::Graph::shared_ptr, pose2SLAM::Values::shared_ptr> load2D(
const string& filename, boost::optional<SharedDiagonal> model, int maxID,
bool addNoise, bool smart) {
@ -118,6 +118,9 @@ namespace gtsam {
is.clear(); /* clears the end-of-file and error flags */
is.seekg(0, ios::beg);
// Create a sampler with random number generator
Sampler sampler(42u);
// load the factors
while (is) {
is >> tag;
@ -146,7 +149,7 @@ namespace gtsam {
}
if (addNoise)
l1Xl2 = l1Xl2.retract((*model)->sample());
l1Xl2 = l1Xl2.retract(sampler.sampleNewModel(*model));
// Insert vertices if pure odometry file
if (!poses->exists(id1))
@ -242,4 +245,6 @@ namespace gtsam {
}
return true;
}
}
/* ************************************************************************* */
} // \namespace gtsam