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 IMU testing scenarios. 9 Author: Frank Dellaert & Duy Nguyen Ta (Python) 13 from __future__
import print_function
19 DoglegOptimizer, DoglegParams, DummyPreconditionerParameters, GaussNewtonOptimizer,
20 GaussNewtonParams, GncLMParams, GncLossType, GncLMOptimizer, LevenbergMarquardtOptimizer,
21 LevenbergMarquardtParams, NonlinearFactorGraph, Ordering, PCGSolverParameters, Point2,
22 PriorFactorPoint2, Values
31 """Do trivial test with three optimizer variants.""" 33 """Set up the optimization problem and ordering""" 35 self.
fg = NonlinearFactorGraph()
56 gnParams = GaussNewtonParams()
59 self.assertAlmostEqual(0, self.
fg.
error(actual))
62 lmParams = LevenbergMarquardtParams.CeresDefaults()
65 self.assertAlmostEqual(0, self.
fg.
error(actual))
68 lmParams = LevenbergMarquardtParams.CeresDefaults()
69 lmParams.setLinearSolverType(
"ITERATIVE")
70 cgParams = PCGSolverParameters()
71 cgParams.setPreconditionerParams(DummyPreconditionerParameters())
72 lmParams.setIterativeParams(cgParams)
74 self.assertAlmostEqual(0, self.
fg.
error(actual))
77 dlParams = DoglegParams()
80 self.assertAlmostEqual(0, self.
fg.
error(actual))
83 gncParams = GncLMParams()
85 self.assertAlmostEqual(0, self.
fg.
error(actual))
88 base_params = LevenbergMarquardtParams()
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)
96 params_str =
str(params)
105 self.assertTrue(s
in params_str)
108 for loss_type
in (GncLossType.TLS, GncLossType.GM):
109 params.setLossType(loss_type)
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)
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 = []
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)
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()
165 params = LevenbergMarquardtParams.CeresDefaults()
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))
172 self.assertEqual(self.
fg.
error(actual), final_error)
173 self.assertEqual(optimizer.iterations(), iteration_count)
176 if __name__ ==
"__main__":
def test_gnc_params(self)
def test_iteration_hook(self)
def gtsamAssertEquals(self, actual, expected, tol=1e-9)
static shared_ptr Create(size_t dim)
def test_levenberg_marquardt(self)
def test_graduated_non_convexity(self)
int optimize(const SfmData &db, const NonlinearFactorGraph &graph, const Values &initial, bool separateCalibration=false)
graph add(PriorFactor< Pose2 >(1, priorMean, priorNoise))
def test_levenberg_marquardt_pcg(self)
def test_gauss_newton(self)