Merge pull request #270 from borglab/fix/sampler

Fix/sampler
release/4.3a0
Frank Dellaert 2020-04-05 17:12:38 -04:00 committed by GitHub
commit 5d8c99935c
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
7 changed files with 77 additions and 69 deletions

View File

@ -1563,17 +1563,15 @@ virtual class Robust : gtsam::noiseModel::Base {
#include <gtsam/linear/Sampler.h> #include <gtsam/linear/Sampler.h>
class Sampler { class Sampler {
//Constructors // Constructors
Sampler(gtsam::noiseModel::Diagonal* model, int seed); Sampler(gtsam::noiseModel::Diagonal* model, int seed);
Sampler(Vector sigmas, int seed); Sampler(Vector sigmas, int seed);
Sampler(int seed);
//Standard Interface // Standard Interface
size_t dim() const; size_t dim() const;
Vector sigmas() const; Vector sigmas() const;
gtsam::noiseModel::Diagonal* model() const; gtsam::noiseModel::Diagonal* model() const;
Vector sample(); Vector sample();
Vector sampleNewModel(gtsam::noiseModel::Diagonal* model);
}; };
#include <gtsam/linear/VectorValues.h> #include <gtsam/linear/VectorValues.h>

View File

@ -25,7 +25,6 @@
#include <cmath> #include <cmath>
#include <iostream> #include <iostream>
#include <limits> #include <limits>
#include <random>
#include <stdexcept> #include <stdexcept>
#include <typeinfo> #include <typeinfo>

View File

@ -11,6 +11,8 @@
/** /**
* @file Sampler.cpp * @file Sampler.cpp
* @brief sampling from a diagonal NoiseModel
* @author Frank Dellaert
* @author Alex Cunningham * @author Alex Cunningham
*/ */
@ -18,25 +20,16 @@
namespace gtsam { namespace gtsam {
/* ************************************************************************* */ /* ************************************************************************* */
Sampler::Sampler(const noiseModel::Diagonal::shared_ptr& model, int32_t seed) Sampler::Sampler(const noiseModel::Diagonal::shared_ptr& model,
: model_(model), generator_(static_cast<unsigned>(seed)) uint_fast64_t seed)
{ : model_(model), generator_(seed) {}
}
/* ************************************************************************* */ /* ************************************************************************* */
Sampler::Sampler(const Vector& sigmas, int32_t seed) Sampler::Sampler(const Vector& sigmas, uint_fast64_t seed)
: model_(noiseModel::Diagonal::Sigmas(sigmas, true)), generator_(static_cast<unsigned>(seed)) : model_(noiseModel::Diagonal::Sigmas(sigmas, true)), generator_(seed) {}
{
}
/* ************************************************************************* */ /* ************************************************************************* */
Sampler::Sampler(int32_t seed) Vector Sampler::sampleDiagonal(const Vector& sigmas) const {
: generator_(static_cast<unsigned>(seed))
{
}
/* ************************************************************************* */
Vector Sampler::sampleDiagonal(const Vector& sigmas) {
size_t d = sigmas.size(); size_t d = sigmas.size();
Vector result(d); Vector result(d);
for (size_t i = 0; i < d; i++) { for (size_t i = 0; i < d; i++) {
@ -55,18 +48,23 @@ Vector Sampler::sampleDiagonal(const Vector& sigmas) {
} }
/* ************************************************************************* */ /* ************************************************************************* */
Vector Sampler::sample() { Vector Sampler::sample() const {
assert(model_.get()); assert(model_.get());
const Vector& sigmas = model_->sigmas(); const Vector& sigmas = model_->sigmas();
return sampleDiagonal(sigmas); return sampleDiagonal(sigmas);
} }
/* ************************************************************************* */ /* ************************************************************************* */
Vector Sampler::sampleNewModel(const noiseModel::Diagonal::shared_ptr& model) { #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4
Sampler::Sampler(uint_fast64_t seed) : generator_(seed) {}
Vector Sampler::sampleNewModel(
const noiseModel::Diagonal::shared_ptr& model) const {
assert(model.get()); assert(model.get());
const Vector& sigmas = model->sigmas(); const Vector& sigmas = model->sigmas();
return sampleDiagonal(sigmas); return sampleDiagonal(sigmas);
} }
#endif
/* ************************************************************************* */ /* ************************************************************************* */
} // \namespace gtsam } // namespace gtsam

View File

@ -10,9 +10,9 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/** /**
* @brief sampling that can be parameterized using a NoiseModel to generate samples from
* @file Sampler.h * @file Sampler.h
* the given distribution * @brief sampling from a NoiseModel
* @author Frank Dellaert
* @author Alex Cunningham * @author Alex Cunningham
*/ */
@ -27,67 +27,74 @@ namespace gtsam {
/** /**
* Sampling structure that keeps internal random number generators for * Sampling structure that keeps internal random number generators for
* diagonal distributions specified by NoiseModel * diagonal distributions specified by NoiseModel
*
* This is primarily to allow for variable seeds, and does roughly the same
* thing as sample() in NoiseModel.
*/ */
class GTSAM_EXPORT Sampler { class GTSAM_EXPORT Sampler {
protected: protected:
/** noiseModel created at generation */ /** noiseModel created at generation */
noiseModel::Diagonal::shared_ptr model_; noiseModel::Diagonal::shared_ptr model_;
/** generator */ /** generator */
std::mt19937_64 generator_; mutable std::mt19937_64 generator_;
public: public:
typedef boost::shared_ptr<Sampler> shared_ptr; typedef boost::shared_ptr<Sampler> shared_ptr;
/// @name constructors
/// @{
/** /**
* Create a sampler for the distribution specified by a diagonal NoiseModel * Create a sampler for the distribution specified by a diagonal NoiseModel
* with a manually specified seed * with a manually specified seed
* *
* NOTE: do not use zero as a seed, it will break the generator * NOTE: do not use zero as a seed, it will break the generator
*/ */
Sampler(const noiseModel::Diagonal::shared_ptr& model, int32_t seed = 42u); explicit Sampler(const noiseModel::Diagonal::shared_ptr& model,
uint_fast64_t seed = 42u);
/** /**
* Create a sampler for a distribution specified by a vector of sigmas directly * Create a sampler for a distribution specified by a vector of sigmas
* directly
* *
* NOTE: do not use zero as a seed, it will break the generator * NOTE: do not use zero as a seed, it will break the generator
*/ */
Sampler(const Vector& sigmas, int32_t seed = 42u); explicit Sampler(const Vector& sigmas, uint_fast64_t seed = 42u);
/** /// @}
* Create a sampler without a given noisemodel - pass in to sample /// @name access functions
* /// @{
* NOTE: do not use zero as a seed, it will break the generator
*/ size_t dim() const {
Sampler(int32_t seed = 42u); assert(model_.get());
return model_->dim();
}
Vector sigmas() const {
assert(model_.get());
return model_->sigmas();
}
/** access functions */
size_t dim() const { assert(model_.get()); return model_->dim(); }
Vector sigmas() const { assert(model_.get()); return model_->sigmas(); }
const noiseModel::Diagonal::shared_ptr& model() const { return model_; } const noiseModel::Diagonal::shared_ptr& model() const { return model_; }
/** /// @}
* sample from distribution /// @name basic functionality
* NOTE: not const due to need to update the underlying generator /// @{
*/
Vector sample();
/** /// sample from distribution
* Sample from noisemodel passed in as an argument, Vector sample() const;
* can be used without having initialized a model for the system.
*
* NOTE: not const due to need to update the underlying generator
*/
Vector sampleNewModel(const noiseModel::Diagonal::shared_ptr& model);
protected: /// @}
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4
/// @name Deprecated
/// @{
explicit Sampler(uint_fast64_t seed = 42u);
Vector sampleNewModel(const noiseModel::Diagonal::shared_ptr& model) const;
/// @}
#endif
protected:
/** given sigmas for a diagonal model, returns a sample */ /** given sigmas for a diagonal model, returns a sample */
Vector sampleDiagonal(const Vector& sigmas); Vector sampleDiagonal(const Vector& sigmas) const;
}; };
} // \namespace gtsam } // namespace gtsam

View File

@ -10,8 +10,10 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/** /**
* @file testSampler * @file testSampler.cpp
* @brief unit tests for Sampler class
* @author Alex Cunningham * @author Alex Cunningham
* @author Frank Dellaert
*/ */
#include <CppUnitLite/TestHarness.h> #include <CppUnitLite/TestHarness.h>
@ -22,14 +24,15 @@ using namespace gtsam;
const double tol = 1e-5; const double tol = 1e-5;
static const Vector3 kSigmas(1.0, 0.1, 0.0);
/* ************************************************************************* */ /* ************************************************************************* */
TEST(testSampler, basic) { TEST(testSampler, basic) {
Vector sigmas = Vector3(1.0, 0.1, 0.0); auto model = noiseModel::Diagonal::Sigmas(kSigmas);
noiseModel::Diagonal::shared_ptr model = noiseModel::Diagonal::Sigmas(sigmas);
char seed = 'A'; char seed = 'A';
Sampler sampler1(model, seed), sampler2(model, 1), sampler3(model, 1); Sampler sampler1(model, seed), sampler2(model, 1), sampler3(model, 1);
EXPECT(assert_equal(sigmas, sampler1.sigmas())); EXPECT(assert_equal(kSigmas, sampler1.sigmas()));
EXPECT(assert_equal(sigmas, sampler2.sigmas())); EXPECT(assert_equal(kSigmas, sampler2.sigmas()));
EXPECT_LONGS_EQUAL(3, sampler1.dim()); EXPECT_LONGS_EQUAL(3, sampler1.dim());
EXPECT_LONGS_EQUAL(3, sampler2.dim()); EXPECT_LONGS_EQUAL(3, sampler2.dim());
Vector actual1 = sampler1.sample(); Vector actual1 = sampler1.sample();
@ -38,5 +41,8 @@ TEST(testSampler, basic) {
} }
/* ************************************************************************* */ /* ************************************************************************* */
int main() { TestResult tr; return TestRegistry::runAllTests(tr); } int main() {
TestResult tr;
return TestRegistry::runAllTests(tr);
}
/* ************************************************************************* */ /* ************************************************************************* */

View File

@ -48,7 +48,7 @@ class GTSAM_EXPORT ScenarioRunner {
const Bias estimatedBias_; const Bias estimatedBias_;
// Create two samplers for acceleration and omega noise // Create two samplers for acceleration and omega noise
mutable Sampler gyroSampler_, accSampler_; Sampler gyroSampler_, accSampler_;
public: public:
ScenarioRunner(const Scenario& scenario, const SharedParams& p, ScenarioRunner(const Scenario& scenario, const SharedParams& p,

View File

@ -252,7 +252,7 @@ GraphAndValues load2D(const string& filename, SharedNoiseModel model, Key maxID,
is.seekg(0, ios::beg); is.seekg(0, ios::beg);
// If asked, create a sampler with random number generator // If asked, create a sampler with random number generator
Sampler sampler; std::unique_ptr<Sampler> sampler;
if (addNoise) { if (addNoise) {
noiseModel::Diagonal::shared_ptr noise; noiseModel::Diagonal::shared_ptr noise;
if (model) if (model)
@ -261,7 +261,7 @@ GraphAndValues load2D(const string& filename, SharedNoiseModel model, Key maxID,
throw invalid_argument( throw invalid_argument(
"gtsam::load2D: invalid noise model for adding noise" "gtsam::load2D: invalid noise model for adding noise"
"(current version assumes diagonal noise model)!"); "(current version assumes diagonal noise model)!");
sampler = Sampler(noise); sampler.reset(new Sampler(noise));
} }
// Parse the pose constraints // Parse the pose constraints
@ -289,7 +289,7 @@ GraphAndValues load2D(const string& filename, SharedNoiseModel model, Key maxID,
model = modelInFile; model = modelInFile;
if (addNoise) if (addNoise)
l1Xl2 = l1Xl2.retract(sampler.sample()); l1Xl2 = l1Xl2.retract(sampler->sample());
// Insert vertices if pure odometry file // Insert vertices if pure odometry file
if (!initial->exists(id1)) if (!initial->exists(id1))