Fixed issues with deprecated Sampler methods
parent
45cf253cec
commit
d1d8543fc7
6
gtsam.h
6
gtsam.h
|
@ -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>
|
||||||
|
|
|
@ -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>
|
||||||
|
|
||||||
|
|
|
@ -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,
|
||||||
|
|
|
@ -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))
|
||||||
|
|
Loading…
Reference in New Issue