Run yapf
parent
9dd1f8ffaf
commit
b4fdda4740
|
@ -15,11 +15,12 @@ from __future__ import print_function
|
||||||
import unittest
|
import unittest
|
||||||
|
|
||||||
import gtsam
|
import gtsam
|
||||||
from gtsam import (DoglegOptimizer, DoglegParams, DummyPreconditionerParameters,
|
from gtsam import (
|
||||||
GaussNewtonOptimizer, GaussNewtonParams, GncLMParams, GncLossType,
|
DoglegOptimizer, DoglegParams, DummyPreconditionerParameters, GaussNewtonOptimizer,
|
||||||
GncLMOptimizer, LevenbergMarquardtOptimizer, LevenbergMarquardtParams,
|
GaussNewtonParams, GncLMParams, GncLossType, GncLMOptimizer, LevenbergMarquardtOptimizer,
|
||||||
NonlinearFactorGraph, Ordering, PCGSolverParameters, Point2,
|
LevenbergMarquardtParams, NonlinearFactorGraph, Ordering, PCGSolverParameters, Point2,
|
||||||
PriorFactorPoint2, Values)
|
PriorFactorPoint2, Values
|
||||||
|
)
|
||||||
from gtsam.utils.test_case import GtsamTestCase
|
from gtsam.utils.test_case import GtsamTestCase
|
||||||
|
|
||||||
KEY1 = 1
|
KEY1 = 1
|
||||||
|
@ -28,7 +29,6 @@ KEY2 = 2
|
||||||
|
|
||||||
class TestScenario(GtsamTestCase):
|
class TestScenario(GtsamTestCase):
|
||||||
"""Do trivial test with three optimizer variants."""
|
"""Do trivial test with three optimizer variants."""
|
||||||
|
|
||||||
def setUp(self):
|
def setUp(self):
|
||||||
"""Set up the optimization problem and ordering"""
|
"""Set up the optimization problem and ordering"""
|
||||||
# create graph
|
# create graph
|
||||||
|
@ -154,11 +154,13 @@ class TestScenario(GtsamTestCase):
|
||||||
iteration_count = 0
|
iteration_count = 0
|
||||||
final_error = 0
|
final_error = 0
|
||||||
final_values = None
|
final_values = None
|
||||||
|
|
||||||
def iteration_hook(iter, error_before, error_after):
|
def iteration_hook(iter, error_before, error_after):
|
||||||
nonlocal iteration_count, final_error, final_values
|
nonlocal iteration_count, final_error, final_values
|
||||||
iteration_count = iter
|
iteration_count = iter
|
||||||
final_error = error_after
|
final_error = error_after
|
||||||
final_values = optimizer.values()
|
final_values = optimizer.values()
|
||||||
|
|
||||||
# optimize
|
# optimize
|
||||||
params = LevenbergMarquardtParams.CeresDefaults()
|
params = LevenbergMarquardtParams.CeresDefaults()
|
||||||
params.setOrdering(self.ordering)
|
params.setOrdering(self.ordering)
|
||||||
|
@ -170,5 +172,6 @@ class TestScenario(GtsamTestCase):
|
||||||
self.assertEqual(self.fg.error(actual), final_error)
|
self.assertEqual(self.fg.error(actual), final_error)
|
||||||
self.assertEqual(optimizer.iterations(), iteration_count)
|
self.assertEqual(optimizer.iterations(), iteration_count)
|
||||||
|
|
||||||
|
|
||||||
if __name__ == "__main__":
|
if __name__ == "__main__":
|
||||||
unittest.main()
|
unittest.main()
|
||||||
|
|
Loading…
Reference in New Issue