Fixed issues with deprecated Sampler methods
parent
45cf253cec
commit
d1d8543fc7
2
gtsam.h
2
gtsam.h
|
@ -1566,14 +1566,12 @@ class Sampler {
|
|||
// Constructors
|
||||
Sampler(gtsam::noiseModel::Diagonal* model, int seed);
|
||||
Sampler(Vector sigmas, int seed);
|
||||
Sampler(int seed);
|
||||
|
||||
// Standard Interface
|
||||
size_t dim() const;
|
||||
Vector sigmas() const;
|
||||
gtsam::noiseModel::Diagonal* model() const;
|
||||
Vector sample();
|
||||
Vector sampleNewModel(gtsam::noiseModel::Diagonal* model);
|
||||
};
|
||||
|
||||
#include <gtsam/linear/VectorValues.h>
|
||||
|
|
|
@ -25,7 +25,6 @@
|
|||
#include <cmath>
|
||||
#include <iostream>
|
||||
#include <limits>
|
||||
#include <random>
|
||||
#include <stdexcept>
|
||||
#include <typeinfo>
|
||||
|
||||
|
|
|
@ -48,7 +48,7 @@ class GTSAM_EXPORT ScenarioRunner {
|
|||
const Bias estimatedBias_;
|
||||
|
||||
// Create two samplers for acceleration and omega noise
|
||||
mutable Sampler gyroSampler_, accSampler_;
|
||||
Sampler gyroSampler_, accSampler_;
|
||||
|
||||
public:
|
||||
ScenarioRunner(const Scenario& scenario, const SharedParams& p,
|
||||
|
|
|
@ -252,7 +252,7 @@ GraphAndValues load2D(const string& filename, SharedNoiseModel model, Key maxID,
|
|||
is.seekg(0, ios::beg);
|
||||
|
||||
// If asked, create a sampler with random number generator
|
||||
Sampler sampler;
|
||||
std::unique_ptr<Sampler> sampler;
|
||||
if (addNoise) {
|
||||
noiseModel::Diagonal::shared_ptr noise;
|
||||
if (model)
|
||||
|
@ -261,7 +261,7 @@ GraphAndValues load2D(const string& filename, SharedNoiseModel model, Key maxID,
|
|||
throw invalid_argument(
|
||||
"gtsam::load2D: invalid noise model for adding noise"
|
||||
"(current version assumes diagonal noise model)!");
|
||||
sampler = Sampler(noise);
|
||||
sampler.reset(new Sampler(noise));
|
||||
}
|
||||
|
||||
// Parse the pose constraints
|
||||
|
@ -289,7 +289,7 @@ GraphAndValues load2D(const string& filename, SharedNoiseModel model, Key maxID,
|
|||
model = modelInFile;
|
||||
|
||||
if (addNoise)
|
||||
l1Xl2 = l1Xl2.retract(sampler.sample());
|
||||
l1Xl2 = l1Xl2.retract(sampler->sample());
|
||||
|
||||
// Insert vertices if pure odometry file
|
||||
if (!initial->exists(id1))
|
||||
|
|
Loading…
Reference in New Issue