testIncrementalFixedLagSmoother.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
19 #include <gtsam/base/debug.h>
20 #include <gtsam/geometry/Point2.h>
21 #include <gtsam/geometry/Pose3.h>
22 #include <gtsam/inference/Key.h>
24 #include <gtsam/inference/Symbol.h>
27 #include <gtsam/nonlinear/ISAM2.h>
29 #include <gtsam/nonlinear/Values.h>
31 #include <gtsam/slam/PriorFactor.h>
32 #include <gtsam/slam/dataset.h> // For writeG2o
34 
36 
37 #include <iostream>
38 #include <string>
39 
40 using namespace std;
41 using namespace gtsam;
44 
45 /* ************************************************************************* */
46 bool check_smoother(const NonlinearFactorGraph& fullgraph,
47  const Values& fullinit,
48  const IncrementalFixedLagSmoother& smoother,
49  const Key& key) {
50  GaussianFactorGraph linearized = *fullgraph.linearize(fullinit);
51  VectorValues delta = linearized.optimize();
52  Values fullfinal = fullinit.retract(delta);
53 
54  Point2 expected = fullfinal.at<Point2>(key);
55  Point2 actual = smoother.calculateEstimate<Point2>(key);
56 
57  return assert_equal(expected, actual);
58 }
59 
60 /* ************************************************************************* */
62  const std::string indent = "") {
63  // Print the current clique
64  std::cout << indent << "P( ";
65  for (Key key : clique->conditional()->frontals()) {
66  std::cout << DefaultKeyFormatter(key) << " ";
67  }
68  if (clique->conditional()->nrParents() > 0) std::cout << "| ";
69  for (Key key : clique->conditional()->parents()) {
70  std::cout << DefaultKeyFormatter(key) << " ";
71  }
72  std::cout << ")" << std::endl;
73 
74  // Recursively print all of the children
75  for (const ISAM2Clique::shared_ptr& child : clique->children) {
76  PrintSymbolicTreeHelper(child, indent + " ");
77  }
78 }
79 
80 /* ************************************************************************* */
81 void PrintSymbolicTree(const ISAM2& isam, const std::string& label) {
82  std::cout << label << std::endl;
83  if (!isam.roots().empty()) {
84  for (const ISAM2::sharedClique& root : isam.roots()) {
86  }
87  } else
88  std::cout << "{Empty Tree}" << std::endl;
89 }
90 
91 /* ************************************************************************* */
93  // Test the IncrementalFixedLagSmoother in a pure linear environment. Thus,
94  // full optimization and the IncrementalFixedLagSmoother should be identical
95  // (even with the linearized approximations at the end of the smoothing lag)
96 
97  SETDEBUG("IncrementalFixedLagSmoother update", true);
98 
99  // Set up parameters
100  SharedDiagonal odoNoise = noiseModel::Diagonal::Sigmas(Vector2(0.1, 0.1));
101  SharedDiagonal loopNoise = noiseModel::Diagonal::Sigmas(Vector2(0.1, 0.1));
102 
103  // Create a Fixed-Lag Smoother
104  typedef IncrementalFixedLagSmoother::KeyTimestampMap Timestamps;
105  IncrementalFixedLagSmoother smoother(12.0, ISAM2Params());
106 
107  // Create containers to keep the full graph
108  Values fullinit;
109  NonlinearFactorGraph fullgraph;
110 
111  // i keeps track of the time step
112  size_t i = 0;
113 
114  // Add a prior at time 0 and update the HMF
115  {
116  Key key0 = X(0);
117 
118  NonlinearFactorGraph newFactors;
119  Values newValues;
120  Timestamps newTimestamps;
121 
122  newFactors.addPrior(key0, Point2(0.0, 0.0), odoNoise);
123  newValues.insert(key0, Point2(0.01, 0.01));
124  newTimestamps[key0] = 0.0;
125 
126  fullgraph.push_back(newFactors);
127  fullinit.insert(newValues);
128 
129  // Update the smoother
130  smoother.update(newFactors, newValues, newTimestamps);
131 
132  // Check
133  CHECK(check_smoother(fullgraph, fullinit, smoother, key0));
134 
135  ++i;
136  }
137 
138  // Add odometry from time 0 to time 5
139  while (i <= 5) {
140  Key key1 = X(i - 1);
141  Key key2 = X(i);
142 
143  NonlinearFactorGraph newFactors;
144  Values newValues;
145  Timestamps newTimestamps;
146 
147  newFactors.emplace_shared<BetweenPoint2>(key1, key2, Point2(1.0, 0.0),
148  odoNoise);
149  newValues.insert(key2, Point2(double(i) + 0.1, -0.1));
150  newTimestamps[key2] = double(i);
151 
152  fullgraph.push_back(newFactors);
153  fullinit.insert(newValues);
154 
155  // Update the smoother
156  smoother.update(newFactors, newValues, newTimestamps);
157 
158  // Check
159  CHECK(check_smoother(fullgraph, fullinit, smoother, key2));
160 
161  ++i;
162  }
163 
164  // Add odometry from time 5 to 6 to the HMF and a loop closure at time 5 to
165  // the TSM
166  {
167  // Add the odometry factor to the HMF
168  Key key1 = X(i - 1);
169  Key key2 = X(i);
170 
171  NonlinearFactorGraph newFactors;
172  Values newValues;
173  Timestamps newTimestamps;
174 
175  newFactors.emplace_shared<BetweenPoint2>(key1, key2, Point2(1.0, 0.0),
176  odoNoise);
177  newFactors.emplace_shared<BetweenPoint2>(X(2), X(5), Point2(3.5, 0.0),
178  loopNoise);
179  newValues.insert(key2, Point2(double(i) + 0.1, -0.1));
180  newTimestamps[key2] = double(i);
181 
182  fullgraph.push_back(newFactors);
183  fullinit.insert(newValues);
184 
185  // Update the smoother
186  smoother.update(newFactors, newValues, newTimestamps);
187 
188  // Check
189  CHECK(check_smoother(fullgraph, fullinit, smoother, key2));
190 
191  ++i;
192  }
193 
194  // Add odometry from time 6 to time 15
195  while (i <= 15) {
196  Key key1 = X(i - 1);
197  Key key2 = X(i);
198 
199  NonlinearFactorGraph newFactors;
200  Values newValues;
201  Timestamps newTimestamps;
202 
203  // Add the odometry factor twice to ensure the removeFactor test below
204  // works, where we need to keep the connectivity of the graph.
205  newFactors.emplace_shared<BetweenPoint2>(key1, key2, Point2(1.0, 0.0),
206  odoNoise);
207  newFactors.emplace_shared<BetweenPoint2>(key1, key2, Point2(1.0, 0.0),
208  odoNoise);
209  newValues.insert(key2, Point2(double(i) + 0.1, -0.1));
210  newTimestamps[key2] = double(i);
211 
212  fullgraph.push_back(newFactors);
213  fullinit.insert(newValues);
214 
215  // Update the smoother
216  smoother.update(newFactors, newValues, newTimestamps);
217 
218  // Check
219  CHECK(check_smoother(fullgraph, fullinit, smoother, key2));
220 
221  ++i;
222  }
223 
224  // add/remove an extra factor
225  {
226  Key key1 = X(i - 1);
227  Key key2 = X(i);
228 
229  NonlinearFactorGraph newFactors;
230  Values newValues;
231  Timestamps newTimestamps;
232 
233  // add 2 odometry factors
234  newFactors.emplace_shared<BetweenPoint2>(key1, key2, Point2(1.0, 0.0),
235  odoNoise);
236  newFactors.emplace_shared<BetweenPoint2>(key1, key2, Point2(1.0, 0.0),
237  odoNoise);
238  newValues.insert(key2, Point2(double(i) + 0.1, -0.1));
239  newTimestamps[key2] = double(i);
240  ++i;
241 
242  fullgraph.push_back(newFactors);
243  fullinit.insert(newValues);
244 
245  // Update the smoother
246  smoother.update(newFactors, newValues, newTimestamps);
247 
248  // Check
249  CHECK(check_smoother(fullgraph, fullinit, smoother, key2));
250 
251  // now remove one of the two and try again
252  // empty values and new factors for fake update in which we only remove
253  // factors
254  NonlinearFactorGraph emptyNewFactors;
255  Values emptyNewValues;
256  Timestamps emptyNewTimestamps;
257 
258  size_t factorIndex =
259  25; // any index that does not break connectivity of the graph
260  FactorIndices factorToRemove;
261  factorToRemove.push_back(factorIndex);
262 
263  const NonlinearFactorGraph smootherFactorsBeforeRemove =
264  smoother.getFactors();
265 
266  std::cout << "fullgraph.size() = " << fullgraph.size() << std::endl;
267  std::cout << "smootherFactorsBeforeRemove.size() = "
268  << smootherFactorsBeforeRemove.size() << std::endl;
269 
270  // remove factor
271  smoother.update(emptyNewFactors, emptyNewValues, emptyNewTimestamps,
272  factorToRemove);
273 
274  // Note: the following test (checking that the number of factor is reduced
275  // by 1) fails since we are not reusing slots, hence also when removing a
276  // factor we do not change the size of the factor graph size_t
277  // nrFactorsAfterRemoval = smoother.getFactors().size();
278  // DOUBLES_EQUAL(nrFactorsBeforeRemoval-1, nrFactorsAfterRemoval, 1e-5);
279 
280  // check that the factors in the smoother are right
281  NonlinearFactorGraph actual = smoother.getFactors();
282  for (size_t i = 0; i < smootherFactorsBeforeRemove.size(); i++) {
283  // check that the factors that were not removed are there
284  if (smootherFactorsBeforeRemove[i] && i != factorIndex) {
285  EXPECT(smootherFactorsBeforeRemove[i]->equals(*actual[i]));
286  } else { // while the factors that were not there or were removed are no
287  // longer there
288  EXPECT(!actual[i]);
289  }
290  }
291  }
292 
293  {
294  SETDEBUG("BayesTreeMarginalizationHelper", true);
295  PrintSymbolicTree(smoother.getISAM2(),
296  "Bayes Tree Before marginalization test:");
297 
298  // Do pressure test on marginalization. Enlarge max_i to enhance the test.
299  const int max_i = 500;
300  while (i <= max_i) {
301  Key key_0 = X(i);
302  Key key_1 = X(i - 1);
303  Key key_2 = X(i - 2);
304  Key key_3 = X(i - 3);
305  Key key_4 = X(i - 4);
306  Key key_5 = X(i - 5);
307  Key key_6 = X(i - 6);
308  Key key_7 = X(i - 7);
309  Key key_8 = X(i - 8);
310  Key key_9 = X(i - 9);
311  Key key_10 = X(i - 10);
312 
313  NonlinearFactorGraph newFactors;
314  Values newValues;
315  Timestamps newTimestamps;
316 
317  // To make a complex graph
318  const Point2 z(1.0, 0.0);
319  newFactors.emplace_shared<BetweenPoint2>(key_1, key_0, z, odoNoise);
320  if (i % 2 == 0)
321  newFactors.emplace_shared<BetweenPoint2>(key_2, key_1, z, odoNoise);
322  if (i % 3 == 0)
323  newFactors.emplace_shared<BetweenPoint2>(key_3, key_2, z, odoNoise);
324  if (i % 4 == 0)
325  newFactors.emplace_shared<BetweenPoint2>(key_4, key_3, z, odoNoise);
326  if (i % 5 == 0)
327  newFactors.emplace_shared<BetweenPoint2>(key_5, key_4, z, odoNoise);
328  if (i % 6 == 0)
329  newFactors.emplace_shared<BetweenPoint2>(key_6, key_5, z, odoNoise);
330  if (i % 7 == 0)
331  newFactors.emplace_shared<BetweenPoint2>(key_7, key_6, z, odoNoise);
332  if (i % 8 == 0)
333  newFactors.emplace_shared<BetweenPoint2>(key_8, key_7, z, odoNoise);
334  if (i % 9 == 0)
335  newFactors.emplace_shared<BetweenPoint2>(key_9, key_8, z, odoNoise);
336  if (i % 10 == 0)
337  newFactors.emplace_shared<BetweenPoint2>(key_10, key_9, z, odoNoise);
338 
339  newValues.insert(key_0, Point2(double(i) + 0.1, -0.1));
340  newTimestamps[key_0] = double(i);
341 
342  fullgraph.push_back(newFactors);
343  fullinit.insert(newValues);
344 
345  // Update the smoother
346  smoother.update(newFactors, newValues, newTimestamps);
347 
348  // Check
349  CHECK(check_smoother(fullgraph, fullinit, smoother, key_0));
351  smoother.getISAM2(),
352  "Bayes Tree marginalization test: i = " + std::to_string(i));
353 
354  ++i;
355  }
356  }
357 }
358 
359 int main() {
360  TestResult tr;
361  return TestRegistry::runAllTests(tr);
362 }
363 /* ************************************************************************* */
key1
const Symbol key1('v', 1)
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
gtsam::ISAM2Params
Definition: ISAM2Params.h:136
check_smoother
bool check_smoother(const NonlinearFactorGraph &fullgraph, const Values &fullinit, const IncrementalFixedLagSmoother &smoother, const Key &key)
Definition: testIncrementalFixedLagSmoother.cpp:46
main
int main()
Definition: testIncrementalFixedLagSmoother.cpp:359
GaussianFactorGraph.h
Linear Factor Graph where all factors are Gaussians.
gtsam::ISAM2
Definition: ISAM2.h:45
SETDEBUG
#define SETDEBUG(S, V)
Definition: debug.h:61
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
gtsam::Vector2
Eigen::Vector2d Vector2
Definition: Vector.h:43
TestHarness.h
gtsam::NonlinearFactorGraph::linearize
std::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
Definition: NonlinearFactorGraph.cpp:239
Ordering.h
Variable ordering for the elimination algorithm.
X
#define X
Definition: icosphere.cpp:20
GaussianBayesNet.h
Chordal Bayes Net, the result of eliminating a factor graph.
odoNoise
SharedDiagonal odoNoise
Definition: testGaussianISAM2.cpp:41
gtsam::ISAM2::sharedClique
Base::sharedClique sharedClique
Shared pointer to a clique.
Definition: ISAM2.h:103
Point2.h
2D Point
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
Key.h
gtsam::GaussianFactorGraph
Definition: GaussianFactorGraph.h:73
gtsam::Values::at
const ValueType at(Key j) const
Definition: Values-inl.h:261
gtsam::Values::retract
Values retract(const VectorValues &delta) const
Definition: Values.cpp:99
gtsam::IncrementalFixedLagSmoother::update
Result update(const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const KeyTimestampMap &timestamps=KeyTimestampMap(), const FactorIndices &factorsToRemove=FactorIndices()) override
Definition: IncrementalFixedLagSmoother.cpp:45
gtsam::IncrementalFixedLagSmoother
Definition: IncrementalFixedLagSmoother.h:34
gtsam.examples.PlanarManipulatorExample.delta
def delta(g0, g1)
Definition: PlanarManipulatorExample.py:45
key2
const Symbol key2('v', 2)
dataset.h
utility functions for loading datasets
gtsam::VectorValues
Definition: VectorValues.h:74
BetweenFactor.h
PrintSymbolicTree
void PrintSymbolicTree(const ISAM2 &isam, const std::string &label)
Definition: testIncrementalFixedLagSmoother.cpp:81
PrintSymbolicTreeHelper
void PrintSymbolicTreeHelper(const ISAM2Clique::shared_ptr &clique, const std::string indent="")
Definition: testIncrementalFixedLagSmoother.cpp:61
isam
NonlinearISAM isam(relinearizeInterval)
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
gtsam::IncrementalFixedLagSmoother::getISAM2
const ISAM2 & getISAM2() const
Get the iSAM2 object which is used for the inference internally.
Definition: IncrementalFixedLagSmoother.h:118
gtsam::SharedDiagonal
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:764
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:916
gtsam::NonlinearFactorGraph::addPrior
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
Definition: NonlinearFactorGraph.h:199
Symbol.h
pybind_wrapper_test_script.z
z
Definition: pybind_wrapper_test_script.py:61
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
gtsam::equals
Definition: Testable.h:112
TestResult
Definition: TestResult.h:26
key
const gtsam::Symbol key('X', 0)
IncrementalFixedLagSmoother.h
An iSAM2-based fixed-lag smoother.
gtsam::FactorGraph::size
size_t size() const
Definition: FactorGraph.h:297
ISAM2.h
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
gtsam::ISAM2Clique::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: ISAM2Clique.h:41
gtsam::IncrementalFixedLagSmoother::getFactors
const NonlinearFactorGraph & getFactors() const
Definition: IncrementalFixedLagSmoother.h:95
gtsam
traits
Definition: SFMdata.h:40
TEST
TEST(IncrementalFixedLagSmoother, Example)
Definition: testIncrementalFixedLagSmoother.cpp:92
PriorFactor.h
NonlinearFactorGraph.h
Factor Graph consisting of non-linear factors.
gtsam::FactorGraph::push_back
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:147
gtsam::Values
Definition: Values.h:65
CHECK
#define CHECK(condition)
Definition: Test.h:108
std
Definition: BFloat16.h:88
gtsam::Values::insert
void insert(Key j, const Value &val)
Definition: Values.cpp:156
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:41
gtsam::IncrementalFixedLagSmoother::calculateEstimate
Values calculateEstimate() const override
Definition: IncrementalFixedLagSmoother.h:74
gtsam::GaussianFactorGraph::optimize
VectorValues optimize(const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
Definition: GaussianFactorGraph.cpp:309
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
Values.h
A non-templated config holding any types of Manifold-group elements.
Pose3.h
3D Pose manifold SO(3) x R^3 and group SE(3)
gtsam::FactorGraph::emplace_shared
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:153
debug.h
Global debugging flags.
gtsam::FactorIndices
FastVector< FactorIndex > FactorIndices
Define collection types:
Definition: Factor.h:37
gtsam::BetweenFactor
Definition: BetweenFactor.h:40


gtsam
Author(s):
autogenerated on Wed Mar 19 2025 03:06:52