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 (
19  DoglegOptimizer, DoglegParams, DummyPreconditionerParameters, GaussNewtonOptimizer,
20  GaussNewtonParams, GncLMParams, GncLossType, GncLMOptimizer, LevenbergMarquardtOptimizer,
21  LevenbergMarquardtParams, NonlinearFactorGraph, Ordering, PCGSolverParameters, Point2,
22  PriorFactorPoint2, Values
23 )
24 from gtsam.utils.test_case import GtsamTestCase
25 
26 KEY1 = 1
27 KEY2 = 2
28 
29 
31  """Do trivial test with three optimizer variants."""
32  def setUp(self):
33  """Set up the optimization problem and ordering"""
34  # create graph
35  self.fg = NonlinearFactorGraph()
37  self.fg.add(PriorFactorPoint2(KEY1, Point2(0, 0), model))
38 
39  # test error at minimum
40  xstar = Point2(0, 0)
42  self.optimal_values.insert(KEY1, xstar)
43  self.assertEqual(0.0, self.fg.error(self.optimal_values), 0.0)
44 
45  # test error at initial = [(1-cos(3))^2 + (sin(3))^2]*50 =
46  x0 = Point2(3, 3)
48  self.initial_values.insert(KEY1, x0)
49  self.assertEqual(9.0, self.fg.error(self.initial_values), 1e-3)
50 
51  # optimize parameters
52  self.ordering = Ordering()
53  self.ordering.push_back(KEY1)
54 
55  def test_gauss_newton(self):
56  gnParams = GaussNewtonParams()
57  gnParams.setOrdering(self.ordering)
58  actual = GaussNewtonOptimizer(self.fg, self.initial_values, gnParams).optimize()
59  self.assertAlmostEqual(0, self.fg.error(actual))
60 
62  lmParams = LevenbergMarquardtParams.CeresDefaults()
63  lmParams.setOrdering(self.ordering)
64  actual = LevenbergMarquardtOptimizer(self.fg, self.initial_values, lmParams).optimize()
65  self.assertAlmostEqual(0, self.fg.error(actual))
66 
68  lmParams = LevenbergMarquardtParams.CeresDefaults()
69  lmParams.setLinearSolverType("ITERATIVE")
70  cgParams = PCGSolverParameters()
71  cgParams.setPreconditionerParams(DummyPreconditionerParameters())
72  lmParams.setIterativeParams(cgParams)
73  actual = LevenbergMarquardtOptimizer(self.fg, self.initial_values, lmParams).optimize()
74  self.assertAlmostEqual(0, self.fg.error(actual))
75 
76  def test_dogleg(self):
77  dlParams = DoglegParams()
78  dlParams.setOrdering(self.ordering)
79  actual = DoglegOptimizer(self.fg, self.initial_values, dlParams).optimize()
80  self.assertAlmostEqual(0, self.fg.error(actual))
81 
83  gncParams = GncLMParams()
84  actual = GncLMOptimizer(self.fg, self.initial_values, gncParams).optimize()
85  self.assertAlmostEqual(0, self.fg.error(actual))
86 
87  def test_gnc_params(self):
88  base_params = LevenbergMarquardtParams()
89  # Test base params
90  for base_max_iters in (50, 100):
91  base_params.setMaxIterations(base_max_iters)
92  params = GncLMParams(base_params)
93  self.assertEqual(params.baseOptimizerParams.getMaxIterations(), base_max_iters)
94 
95  # Test printing
96  params_str = str(params)
97  for s in (
98  "lossType",
99  "maxIterations",
100  "muStep",
101  "relativeCostTol",
102  "weightsTol",
103  "verbosity",
104  ):
105  self.assertTrue(s in params_str)
106 
107  # Test each parameter
108  for loss_type in (GncLossType.TLS, GncLossType.GM):
109  params.setLossType(loss_type) # Default is TLS
110  self.assertEqual(params.lossType, loss_type)
111  for max_iter in (1, 10, 100):
112  params.setMaxIterations(max_iter)
113  self.assertEqual(params.maxIterations, max_iter)
114  for mu_step in (1.1, 1.2, 1.5):
115  params.setMuStep(mu_step)
116  self.assertEqual(params.muStep, mu_step)
117  for rel_cost_tol in (1e-5, 1e-6, 1e-7):
118  params.setRelativeCostTol(rel_cost_tol)
119  self.assertEqual(params.relativeCostTol, rel_cost_tol)
120  for weights_tol in (1e-4, 1e-3, 1e-2):
121  params.setWeightsTol(weights_tol)
122  self.assertEqual(params.weightsTol, weights_tol)
123  for i in (0, 1, 2):
124  verb = GncLMParams.Verbosity(i)
125  params.setVerbosityGNC(verb)
126  self.assertEqual(params.verbosity, verb)
127  for inl in ([], [10], [0, 100]):
128  params.setKnownInliers(inl)
129  self.assertEqual(params.knownInliers, inl)
130  params.knownInliers = []
131  for out in ([], [1], [0, 10]):
132  params.setKnownInliers(out)
133  self.assertEqual(params.knownInliers, out)
134  params.knownInliers = []
135 
136  # Test optimizer params
137  optimizer = GncLMOptimizer(self.fg, self.initial_values, params)
138  for ict_factor in (0.9, 1.1):
139  new_ict = ict_factor * optimizer.getInlierCostThresholds()
140  optimizer.setInlierCostThresholds(new_ict)
141  self.assertAlmostEqual(optimizer.getInlierCostThresholds(), new_ict)
142  for w_factor in (0.8, 0.9):
143  new_weights = w_factor * optimizer.getWeights()
144  optimizer.setWeights(new_weights)
145  self.assertAlmostEqual(optimizer.getWeights(), new_weights)
146  optimizer.setInlierCostThresholdsAtProbability(0.9)
147  w1 = optimizer.getInlierCostThresholds()
148  optimizer.setInlierCostThresholdsAtProbability(0.8)
149  w2 = optimizer.getInlierCostThresholds()
150  self.assertLess(w2, w1)
151 
153  # set up iteration hook to track some testable values
154  iteration_count = 0
155  final_error = 0
156  final_values = None
157 
158  def iteration_hook(iter, error_before, error_after):
159  nonlocal iteration_count, final_error, final_values
160  iteration_count = iter
161  final_error = error_after
162  final_values = optimizer.values()
163 
164  # optimize
165  params = LevenbergMarquardtParams.CeresDefaults()
166  params.setOrdering(self.ordering)
167  params.iterationHook = iteration_hook
168  optimizer = LevenbergMarquardtOptimizer(self.fg, self.initial_values, params)
169  actual = optimizer.optimize()
170  self.assertAlmostEqual(0, self.fg.error(actual))
171  self.gtsamAssertEquals(final_values, actual)
172  self.assertEqual(self.fg.error(actual), final_error)
173  self.assertEqual(optimizer.iterations(), iteration_count)
174 
175 
176 if __name__ == "__main__":
177  unittest.main()
A insert(1, 2)=0
def gtsamAssertEquals(self, actual, expected, tol=1e-9)
Definition: test_case.py:18
Vector2 Point2
Definition: Point2.h:32
static shared_ptr Create(size_t dim)
Definition: NoiseModel.h:610
Definition: pytypes.h:1403
int optimize(const SfmData &db, const NonlinearFactorGraph &graph, const Values &initial, bool separateCalibration=false)
Definition: timeSFMBAL.h:64
graph add(PriorFactor< Pose2 >(1, priorMean, priorNoise))
static double error
Definition: testRot3.cpp:37


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:37:46