test_GaussianFactorGraph.py
Go to the documentation of this file.
1 """
2 GTSAM Copyright 2010-2019, Georgia Tech Research Corporation,
3 Atlanta, Georgia 30332-0415
4 All Rights Reserved
5 
6 See LICENSE for the license information
7 
8 Unit tests for Linear Factor Graphs.
9 Author: Frank Dellaert & Gerry Chen
10 """
11 # pylint: disable=invalid-name, no-name-in-module, no-member
12 
13 from __future__ import print_function
14 
15 import unittest
16 
17 import gtsam
18 import numpy as np
19 from gtsam.symbol_shorthand import X
20 from gtsam.utils.test_case import GtsamTestCase
21 
22 
24  """Create a basic linear factor graph for testing"""
26 
27  x0 = X(0)
28  x1 = X(1)
29  x2 = X(2)
30 
31  BETWEEN_NOISE = gtsam.noiseModel.Diagonal.Sigmas(np.ones(1))
32  PRIOR_NOISE = gtsam.noiseModel.Diagonal.Sigmas(np.ones(1))
33 
34  graph.add(x1, np.eye(1), x0, -np.eye(1), np.ones(1), BETWEEN_NOISE)
35  graph.add(x2, np.eye(1), x1, -np.eye(1), 2*np.ones(1), BETWEEN_NOISE)
36  graph.add(x0, np.eye(1), np.zeros(1), PRIOR_NOISE)
37 
38  return graph, (x0, x1, x2)
39 
41  """Tests for Gaussian Factor Graphs."""
42 
43  def test_fg(self):
44  """Test solving a linear factor graph"""
45  graph, X = create_graph()
46  result = graph.optimize()
47 
48  EXPECTEDX = [0, 1, 3]
49 
50  # check solutions
51  self.assertAlmostEqual(EXPECTEDX[0], result.at(X[0]), delta=1e-8)
52  self.assertAlmostEqual(EXPECTEDX[1], result.at(X[1]), delta=1e-8)
53  self.assertAlmostEqual(EXPECTEDX[2], result.at(X[2]), delta=1e-8)
54 
56  """Test converting a linear factor graph to a nonlinear one"""
57  graph, X = create_graph()
58 
59  EXPECTEDM = [1, 2, 3]
60 
61  # create nonlinear factor graph for marginalization
64  nlresult = optimizer.optimizeSafely()
65 
66  # marginalize
67  marginals = gtsam.Marginals(nfg, nlresult)
68  m = [marginals.marginalCovariance(x) for x in X]
69 
70  # check linear marginalizations
71  self.assertAlmostEqual(EXPECTEDM[0], m[0], delta=1e-8)
72  self.assertAlmostEqual(EXPECTEDM[1], m[1], delta=1e-8)
73  self.assertAlmostEqual(EXPECTEDM[2], m[2], delta=1e-8)
74 
76  """Marginalize a linear factor graph"""
77  graph, X = create_graph()
78  result = graph.optimize()
79 
80  EXPECTEDM = [1, 2, 3]
81 
82  # linear factor graph marginalize
83  marginals = gtsam.Marginals(graph, result)
84  m = [marginals.marginalCovariance(x) for x in X]
85 
86  # check linear marginalizations
87  self.assertAlmostEqual(EXPECTEDM[0], m[0], delta=1e-8)
88  self.assertAlmostEqual(EXPECTEDM[1], m[1], delta=1e-8)
89  self.assertAlmostEqual(EXPECTEDM[2], m[2], delta=1e-8)
90 
91 if __name__ == '__main__':
92  unittest.main()
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
Definition: NoiseModel.cpp:270
static GTSAM_EXPORT NonlinearFactorGraph ConvertLinearGraph(const GaussianFactorGraph &linear_graph, const Values &linearizationPoint=Values())
#define X
Definition: icosphere.cpp:20


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:46:03