Add unit test

release/4.3a0
Fan Jiang 2020-07-11 14:37:54 -04:00
parent 72ce0c088a
commit 25513379e3
1 changed files with 12 additions and 1 deletions

View File

@ -17,7 +17,8 @@ import unittest
import gtsam import gtsam
from gtsam import (DoglegOptimizer, DoglegParams, GaussNewtonOptimizer, from gtsam import (DoglegOptimizer, DoglegParams, GaussNewtonOptimizer,
GaussNewtonParams, LevenbergMarquardtOptimizer, GaussNewtonParams, LevenbergMarquardtOptimizer,
LevenbergMarquardtParams, NonlinearFactorGraph, Ordering, LevenbergMarquardtParams, PCGSolverParameters,
DummyPreconditionerParameters, NonlinearFactorGraph, Ordering,
Point2, PriorFactorPoint2, Values) Point2, PriorFactorPoint2, Values)
from gtsam.utils.test_case import GtsamTestCase from gtsam.utils.test_case import GtsamTestCase
@ -61,6 +62,16 @@ class TestScenario(GtsamTestCase):
fg, initial_values, lmParams).optimize() fg, initial_values, lmParams).optimize()
self.assertAlmostEqual(0, fg.error(actual2)) self.assertAlmostEqual(0, fg.error(actual2))
# Levenberg-Marquardt
lmParams = LevenbergMarquardtParams.CeresDefaults()
lmParams.setLinearSolverType("ITERATIVE")
cgParams = PCGSolverParameters()
cgParams.setPreconditionerParams(DummyPreconditionerParameters())
lmParams.setIterativeParams(cgParams)
actual2 = LevenbergMarquardtOptimizer(
fg, initial_values, lmParams).optimize()
self.assertAlmostEqual(0, fg.error(actual2))
# Dogleg # Dogleg
dlParams = DoglegParams() dlParams = DoglegParams()
dlParams.setOrdering(ordering) dlParams.setOrdering(ordering)