import GncLMParams, GncLMOptimizer to prevent pybind's automatic long names from name concat

release/4.3a0
John Lambert 2021-08-12 18:31:24 -04:00 committed by GitHub
parent 30d028ef74
commit db9b98030b
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
1 changed files with 3 additions and 3 deletions

View File

@ -17,7 +17,7 @@ import unittest
import gtsam import gtsam
from gtsam import (DoglegOptimizer, DoglegParams, from gtsam import (DoglegOptimizer, DoglegParams,
DummyPreconditionerParameters, GaussNewtonOptimizer, DummyPreconditionerParameters, GaussNewtonOptimizer,
GaussNewtonParams, GncParams, GncOptimizer, GaussNewtonParams, GncLMParams, GncLMOptimizer,
LevenbergMarquardtOptimizer, LevenbergMarquardtParams, LevenbergMarquardtOptimizer, LevenbergMarquardtParams,
NonlinearFactorGraph, Ordering, NonlinearFactorGraph, Ordering,
PCGSolverParameters, Point2, PriorFactorPoint2, Values) PCGSolverParameters, Point2, PriorFactorPoint2, Values)
@ -80,8 +80,8 @@ class TestScenario(GtsamTestCase):
self.assertAlmostEqual(0, fg.error(actual3)) self.assertAlmostEqual(0, fg.error(actual3))
# Graduated Non-Convexity (GNC) # Graduated Non-Convexity (GNC)
gncParams = GncParams() gncParams = GncLMParams()
actual4 = GncOptimizer(fg, initial_values, gncParams).optimize() actual4 = GncLMOptimizer(fg, initial_values, gncParams).optimize()
self.assertAlmostEqual(0, fg.error(actual4)) self.assertAlmostEqual(0, fg.error(actual4))