2 GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, 3 Atlanta, Georgia 30332-0415 6 See LICENSE for the license information 8 Unit tests for Linear Factor Graphs. 9 Author: Frank Dellaert & Gerry Chen 13 from __future__
import print_function
24 """Create a basic linear factor graph for testing""" 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)
38 return graph, (x0, x1, x2)
41 """Tests for Gaussian Factor Graphs.""" 44 """Test solving a linear factor graph""" 46 result = graph.optimize()
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)
56 """Test converting a linear factor graph to a nonlinear one""" 64 nlresult = optimizer.optimizeSafely()
68 m = [marginals.marginalCovariance(x)
for x
in X]
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)
76 """Marginalize a linear factor graph""" 78 result = graph.optimize()
84 m = [marginals.marginalCovariance(x)
for x
in X]
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)
91 if __name__ ==
'__main__':
def test_convertNonlinear(self)
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
static GTSAM_EXPORT NonlinearFactorGraph ConvertLinearGraph(const GaussianFactorGraph &linear_graph, const Values &linearizationPoint=Values())
def test_linearMarginalization(self)