test_NonlinearOptimizer.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 IMU testing scenarios.
9 Author: Frank Dellaert & Duy Nguyen Ta (Python)
10 """
11 # pylint: disable=invalid-name, no-name-in-module
12 
13 from __future__ import print_function
14 
15 import unittest
16 
17 import gtsam
18 from gtsam import (DoglegOptimizer, DoglegParams,
19  DummyPreconditionerParameters, GaussNewtonOptimizer,
20  GaussNewtonParams, LevenbergMarquardtOptimizer,
21  LevenbergMarquardtParams, NonlinearFactorGraph, Ordering,
22  PCGSolverParameters, Point2, PriorFactorPoint2, Values)
23 from gtsam.utils.test_case import GtsamTestCase
24 
25 KEY1 = 1
26 KEY2 = 2
27 
28 
30  def test_optimize(self):
31  """Do trivial test with three optimizer variants."""
32  fg = NonlinearFactorGraph()
34  fg.add(PriorFactorPoint2(KEY1, Point2(0, 0), model))
35 
36  # test error at minimum
37  xstar = Point2(0, 0)
38  optimal_values = Values()
39  optimal_values.insert(KEY1, xstar)
40  self.assertEqual(0.0, fg.error(optimal_values), 0.0)
41 
42  # test error at initial = [(1-cos(3))^2 + (sin(3))^2]*50 =
43  x0 = Point2(3, 3)
44  initial_values = Values()
45  initial_values.insert(KEY1, x0)
46  self.assertEqual(9.0, fg.error(initial_values), 1e-3)
47 
48  # optimize parameters
49  ordering = Ordering()
50  ordering.push_back(KEY1)
51 
52  # Gauss-Newton
53  gnParams = GaussNewtonParams()
54  gnParams.setOrdering(ordering)
55  actual1 = GaussNewtonOptimizer(fg, initial_values, gnParams).optimize()
56  self.assertAlmostEqual(0, fg.error(actual1))
57 
58  # Levenberg-Marquardt
59  lmParams = LevenbergMarquardtParams.CeresDefaults()
60  lmParams.setOrdering(ordering)
61  actual2 = LevenbergMarquardtOptimizer(
62  fg, initial_values, lmParams).optimize()
63  self.assertAlmostEqual(0, fg.error(actual2))
64 
65  # Levenberg-Marquardt
66  lmParams = LevenbergMarquardtParams.CeresDefaults()
67  lmParams.setLinearSolverType("ITERATIVE")
68  cgParams = PCGSolverParameters()
69  cgParams.setPreconditionerParams(DummyPreconditionerParameters())
70  lmParams.setIterativeParams(cgParams)
71  actual2 = LevenbergMarquardtOptimizer(
72  fg, initial_values, lmParams).optimize()
73  self.assertAlmostEqual(0, fg.error(actual2))
74 
75  # Dogleg
76  dlParams = DoglegParams()
77  dlParams.setOrdering(ordering)
78  actual3 = DoglegOptimizer(fg, initial_values, dlParams).optimize()
79  self.assertAlmostEqual(0, fg.error(actual3))
80 
81 
82 if __name__ == "__main__":
83  unittest.main()
Vector2 Point2
Definition: Point2.h:27
static shared_ptr Create(size_t dim)
Definition: NoiseModel.h:608
int optimize(const SfmData &db, const NonlinearFactorGraph &graph, const Values &initial, bool separateCalibration=false)
Definition: timeSFMBAL.h:63


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