diff --git a/gtsam/slam/tests/testGeneralSFMFactor.cpp b/gtsam/slam/tests/testGeneralSFMFactor.cpp index 4b02fe6bb..82ca97dd2 100644 --- a/gtsam/slam/tests/testGeneralSFMFactor.cpp +++ b/gtsam/slam/tests/testGeneralSFMFactor.cpp @@ -395,7 +395,7 @@ TEST( GeneralSFMFactor, optimize_varK_BA ) { shared_ptr ordering = getOrdering(X,L); NonlinearOptimizationParameters::sharedThis params ( - new NonlinearOptimizationParameters(1e-5, 1e-5, 0.0, 100, 1e-5, 10, NonlinearOptimizationParameters::SILENT)); + new NonlinearOptimizationParameters(1e-2, 1e-2, 0.0, 100, 1e-5, 10, NonlinearOptimizationParameters::SILENT)); Optimizer optimizer(graph, values, ordering, params); //cout << "optimize_varK_BA::" << endl ;