35 using namespace gtsam;
59 SETDEBUG(
"IncrementalFixedLagSmoother update",
true);
66 typedef IncrementalFixedLagSmoother::KeyTimestampMap Timestamps;
82 Timestamps newTimestamps;
86 newTimestamps[key0] = 0.0;
89 fullinit.
insert(newValues);
92 smoother.
update(newFactors, newValues, newTimestamps);
107 Timestamps newTimestamps;
111 newTimestamps[
key2] = double(i);
114 fullinit.
insert(newValues);
117 smoother.
update(newFactors, newValues, newTimestamps);
133 Timestamps newTimestamps;
138 newTimestamps[
key2] = double(i);
141 fullinit.
insert(newValues);
144 smoother.
update(newFactors, newValues, newTimestamps);
159 Timestamps newTimestamps;
163 newTimestamps[
key2] = double(i);
166 fullinit.
insert(newValues);
169 smoother.
update(newFactors, newValues, newTimestamps);
184 Timestamps newTimestamps;
190 newTimestamps[
key2] = double(i);
193 fullinit.
insert(newValues);
196 smoother.
update(newFactors, newValues, newTimestamps);
205 Timestamps emptyNewTimestamps;
207 size_t factorIndex = 25;
209 factorToRemove.push_back(factorIndex);
214 smoother.
update(emptyNewFactors, emptyNewValues, emptyNewTimestamps,factorToRemove);
224 for(
size_t i=0; i< smootherFactorsBeforeRemove.
size(); i++){
226 if(smootherFactorsBeforeRemove[i] && i != factorIndex){
227 EXPECT(smootherFactorsBeforeRemove[i]->
equals(*actual[i]));
const gtsam::Symbol key('X', 0)
static int runAllTests(TestResult &result)
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
const ValueType at(Key j) const
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
VectorValues optimize(const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
Values calculateEstimate() const override
Values retract(const VectorValues &delta) const
std::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
FastVector< FactorIndex > FactorIndices
Define collection types:
Result update(const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const KeyTimestampMap ×tamps=KeyTimestampMap(), const FactorIndices &factorsToRemove=FactorIndices()) override
const Symbol key1('v', 1)
const NonlinearFactorGraph & getFactors() const
#define EXPECT(condition)
An iSAM2-based fixed-lag smoother.
Linear Factor Graph where all factors are Gaussians.
noiseModel::Diagonal::shared_ptr SharedDiagonal
bool check_smoother(const NonlinearFactorGraph &fullgraph, const Values &fullinit, const IncrementalFixedLagSmoother &smoother, const Key &key)
Key MakeKey(size_t index)
Chordal Bayes Net, the result of eliminating a factor graph.
void insert(Key j, const Value &val)
TEST(IncrementalFixedLagSmoother, Example)
std::uint64_t Key
Integer nonlinear key type.
const Symbol key2('v', 2)