Deprecated several methods and madrng mutable, so methods are const

release/4.3a0
Frank Dellaert 2020-04-04 12:28:46 -04:00
parent 84a33e959f
commit 8383e9e285
3 changed files with 66 additions and 56 deletions

View File

@ -11,6 +11,8 @@
/**
* @file Sampler.cpp
* @brief sampling from a NoiseModel to generate
* @author Frank Dellaert
* @author Alex Cunningham
*/
@ -19,24 +21,18 @@ namespace gtsam {
/* ************************************************************************* */
Sampler::Sampler(const noiseModel::Diagonal::shared_ptr& model, int32_t seed)
: model_(model), generator_(static_cast<unsigned>(seed))
{
}
: model_(model), generator_(static_cast<unsigned>(seed)) {}
/* ************************************************************************* */
Sampler::Sampler(const Vector& sigmas, int32_t seed)
: model_(noiseModel::Diagonal::Sigmas(sigmas, true)), generator_(static_cast<unsigned>(seed))
{
}
: model_(noiseModel::Diagonal::Sigmas(sigmas, true)),
generator_(static_cast<unsigned>(seed)) {}
/* ************************************************************************* */
Sampler::Sampler(int32_t seed)
: generator_(static_cast<unsigned>(seed))
{
}
Sampler::Sampler(int32_t seed) : generator_(static_cast<unsigned>(seed)) {}
/* ************************************************************************* */
Vector Sampler::sampleDiagonal(const Vector& sigmas) {
Vector Sampler::sampleDiagonal(const Vector& sigmas) const {
size_t d = sigmas.size();
Vector result(d);
for (size_t i = 0; i < d; i++) {
@ -55,18 +51,19 @@ Vector Sampler::sampleDiagonal(const Vector& sigmas) {
}
/* ************************************************************************* */
Vector Sampler::sample() {
Vector Sampler::sample() const {
assert(model_.get());
const Vector& sigmas = model_->sigmas();
return sampleDiagonal(sigmas);
}
/* ************************************************************************* */
Vector Sampler::sampleNewModel(const noiseModel::Diagonal::shared_ptr& model) {
Vector Sampler::sampleNewModel(
const noiseModel::Diagonal::shared_ptr& model) const {
assert(model.get());
const Vector& sigmas = model->sigmas();
return sampleDiagonal(sigmas);
}
/* ************************************************************************* */
} // \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
* the given distribution
* @brief sampling from a NoiseModel to generate
* @author Frank Dellaert
* @author Alex Cunningham
*/
@ -27,67 +27,74 @@ namespace gtsam {
/**
* Sampling structure that keeps internal random number generators for
* 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 {
protected:
protected:
/** noiseModel created at generation */
noiseModel::Diagonal::shared_ptr model_;
/** generator */
std::mt19937_64 generator_;
mutable std::mt19937_64 generator_;
public:
public:
typedef boost::shared_ptr<Sampler> shared_ptr;
/// @name constructors
/// @{
/**
* Create a sampler for the distribution specified by a diagonal NoiseModel
* with a manually specified seed
*
* 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,
int32_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
*/
Sampler(const Vector& sigmas, int32_t seed = 42u);
explicit Sampler(const Vector& sigmas, int32_t seed = 42u);
/**
* Create a sampler without a given noisemodel - pass in to sample
*
* NOTE: do not use zero as a seed, it will break the generator
*/
Sampler(int32_t seed = 42u);
/// @}
/// @name access functions
/// @{
size_t dim() const {
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_; }
/**
* sample from distribution
* NOTE: not const due to need to update the underlying generator
*/
Vector sample();
/// @}
/// @name basic functionality
/// @{
/**
* Sample from noisemodel passed in as an argument,
* 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);
/// sample from distribution
Vector sample() const;
protected:
/// @}
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4
/// @name Deprecated
/// @{
explicit Sampler(int32_t seed = 42u);
Vector sampleNewModel(const noiseModel::Diagonal::shared_ptr& model) const;
/// @}
#endif
protected:
/** 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 Frank Dellaert
*/
#include <CppUnitLite/TestHarness.h>
@ -22,14 +24,15 @@ using namespace gtsam;
const double tol = 1e-5;
static const Vector3 kSigmas(1.0, 0.1, 0.0);
/* ************************************************************************* */
TEST(testSampler, basic) {
Vector sigmas = Vector3(1.0, 0.1, 0.0);
noiseModel::Diagonal::shared_ptr model = noiseModel::Diagonal::Sigmas(sigmas);
auto model = noiseModel::Diagonal::Sigmas(kSigmas);
char seed = 'A';
Sampler sampler1(model, seed), sampler2(model, 1), sampler3(model, 1);
EXPECT(assert_equal(sigmas, sampler1.sigmas()));
EXPECT(assert_equal(sigmas, sampler2.sigmas()));
EXPECT(assert_equal(kSigmas, sampler1.sigmas()));
EXPECT(assert_equal(kSigmas, sampler2.sigmas()));
EXPECT_LONGS_EQUAL(3, sampler1.dim());
EXPECT_LONGS_EQUAL(3, sampler2.dim());
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);
}
/* ************************************************************************* */