refactor python NonlinearOptimizerTest

release/4.3a0
Gerry Chen 2022-03-08 09:48:05 -05:00
parent a0d64a9448
commit bf8137b0c4
No known key found for this signature in database
GPG Key ID: E9845092D3A57286
1 changed files with 38 additions and 40 deletions

View File

@ -15,12 +15,10 @@ from __future__ import print_function
import unittest import unittest
import gtsam import gtsam
from gtsam import (DoglegOptimizer, DoglegParams, from gtsam import (DoglegOptimizer, DoglegParams, DummyPreconditionerParameters,
DummyPreconditionerParameters, GaussNewtonOptimizer, GaussNewtonOptimizer, GaussNewtonParams, GncLMParams, GncLMOptimizer,
GaussNewtonParams, GncLMParams, GncLMOptimizer, LevenbergMarquardtOptimizer, LevenbergMarquardtParams, NonlinearFactorGraph,
LevenbergMarquardtOptimizer, LevenbergMarquardtParams, Ordering, PCGSolverParameters, Point2, PriorFactorPoint2, Values)
NonlinearFactorGraph, Ordering,
PCGSolverParameters, Point2, PriorFactorPoint2, Values)
from gtsam.utils.test_case import GtsamTestCase from gtsam.utils.test_case import GtsamTestCase
KEY1 = 1 KEY1 = 1
@ -28,62 +26,62 @@ KEY2 = 2
class TestScenario(GtsamTestCase): class TestScenario(GtsamTestCase):
def test_optimize(self): """Do trivial test with three optimizer variants."""
"""Do trivial test with three optimizer variants."""
fg = NonlinearFactorGraph() def setUp(self):
"""Set up the optimization problem and ordering"""
# create graph
self.fg = NonlinearFactorGraph()
model = gtsam.noiseModel.Unit.Create(2) model = gtsam.noiseModel.Unit.Create(2)
fg.add(PriorFactorPoint2(KEY1, Point2(0, 0), model)) self.fg.add(PriorFactorPoint2(KEY1, Point2(0, 0), model))
# test error at minimum # test error at minimum
xstar = Point2(0, 0) xstar = Point2(0, 0)
optimal_values = Values() self.optimal_values = Values()
optimal_values.insert(KEY1, xstar) self.optimal_values.insert(KEY1, xstar)
self.assertEqual(0.0, fg.error(optimal_values), 0.0) self.assertEqual(0.0, self.fg.error(self.optimal_values), 0.0)
# test error at initial = [(1-cos(3))^2 + (sin(3))^2]*50 = # test error at initial = [(1-cos(3))^2 + (sin(3))^2]*50 =
x0 = Point2(3, 3) x0 = Point2(3, 3)
initial_values = Values() self.initial_values = Values()
initial_values.insert(KEY1, x0) self.initial_values.insert(KEY1, x0)
self.assertEqual(9.0, fg.error(initial_values), 1e-3) self.assertEqual(9.0, self.fg.error(self.initial_values), 1e-3)
# optimize parameters # optimize parameters
ordering = Ordering() self.ordering = Ordering()
ordering.push_back(KEY1) self.ordering.push_back(KEY1)
# Gauss-Newton def test_gauss_newton(self):
gnParams = GaussNewtonParams() gnParams = GaussNewtonParams()
gnParams.setOrdering(ordering) gnParams.setOrdering(self.ordering)
actual1 = GaussNewtonOptimizer(fg, initial_values, gnParams).optimize() actual = GaussNewtonOptimizer(self.fg, self.initial_values, gnParams).optimize()
self.assertAlmostEqual(0, fg.error(actual1)) self.assertAlmostEqual(0, self.fg.error(actual))
# Levenberg-Marquardt def test_levenberg_marquardt(self):
lmParams = LevenbergMarquardtParams.CeresDefaults() lmParams = LevenbergMarquardtParams.CeresDefaults()
lmParams.setOrdering(ordering) lmParams.setOrdering(self.ordering)
actual2 = LevenbergMarquardtOptimizer( actual = LevenbergMarquardtOptimizer(self.fg, self.initial_values, lmParams).optimize()
fg, initial_values, lmParams).optimize() self.assertAlmostEqual(0, self.fg.error(actual))
self.assertAlmostEqual(0, fg.error(actual2))
# Levenberg-Marquardt def test_levenberg_marquardt_pcg(self):
lmParams = LevenbergMarquardtParams.CeresDefaults() lmParams = LevenbergMarquardtParams.CeresDefaults()
lmParams.setLinearSolverType("ITERATIVE") lmParams.setLinearSolverType("ITERATIVE")
cgParams = PCGSolverParameters() cgParams = PCGSolverParameters()
cgParams.setPreconditionerParams(DummyPreconditionerParameters()) cgParams.setPreconditionerParams(DummyPreconditionerParameters())
lmParams.setIterativeParams(cgParams) lmParams.setIterativeParams(cgParams)
actual2 = LevenbergMarquardtOptimizer( actual = LevenbergMarquardtOptimizer(self.fg, self.initial_values, lmParams).optimize()
fg, initial_values, lmParams).optimize() self.assertAlmostEqual(0, self.fg.error(actual))
self.assertAlmostEqual(0, fg.error(actual2))
# Dogleg def test_dogleg(self):
dlParams = DoglegParams() dlParams = DoglegParams()
dlParams.setOrdering(ordering) dlParams.setOrdering(self.ordering)
actual3 = DoglegOptimizer(fg, initial_values, dlParams).optimize() actual = DoglegOptimizer(self.fg, self.initial_values, dlParams).optimize()
self.assertAlmostEqual(0, fg.error(actual3)) self.assertAlmostEqual(0, self.fg.error(actual))
# Graduated Non-Convexity (GNC) def test_graduated_non_convexity(self):
gncParams = GncLMParams() gncParams = GncLMParams()
actual4 = GncLMOptimizer(fg, initial_values, gncParams).optimize() actual = GncLMOptimizer(self.fg, self.initial_values, gncParams).optimize()
self.assertAlmostEqual(0, fg.error(actual4)) self.assertAlmostEqual(0, self.fg.error(actual))
if __name__ == "__main__": if __name__ == "__main__":