Merge pull request #1085 from yunzc/feature/gnc_base_params
correctly parse optimizer params for base optimizer in gncrelease/4.3a0
						commit
						686e16aaae
					
				|  | @ -184,7 +184,8 @@ class GTSAM_EXPORT GncOptimizer { | |||
|   /// Compute optimal solution using graduated non-convexity.
 | ||||
|   Values optimize() { | ||||
|     NonlinearFactorGraph graph_initial = this->makeWeightedGraph(weights_); | ||||
|     BaseOptimizer baseOptimizer(graph_initial, state_); | ||||
|     BaseOptimizer baseOptimizer( | ||||
|         graph_initial, state_, params_.baseOptimizerParams); | ||||
|     Values result = baseOptimizer.optimize(); | ||||
|     double mu = initializeMu(); | ||||
|     double prev_cost = graph_initial.error(result); | ||||
|  | @ -228,7 +229,8 @@ class GTSAM_EXPORT GncOptimizer { | |||
| 
 | ||||
|       // variable/values update
 | ||||
|       NonlinearFactorGraph graph_iter = this->makeWeightedGraph(weights_); | ||||
|       BaseOptimizer baseOptimizer_iter(graph_iter, state_); | ||||
|       BaseOptimizer baseOptimizer_iter( | ||||
|           graph_iter, state_, params_.baseOptimizerParams); | ||||
|       result = baseOptimizer_iter.optimize(); | ||||
| 
 | ||||
|       // stopping condition
 | ||||
|  |  | |||
|  | @ -98,6 +98,30 @@ TEST(GncOptimizer, gncConstructor) { | |||
|   CHECK(gnc.equals(gnc2)); | ||||
| } | ||||
| 
 | ||||
| /* ************************************************************************* */ | ||||
| TEST(GncOptimizer, solverParameterParsing) { | ||||
|   // has to have Gaussian noise models !
 | ||||
|   auto fg = example::createReallyNonlinearFactorGraph();  // just a unary factor
 | ||||
|                                                           // on a 2D point
 | ||||
| 
 | ||||
|   Point2 p0(3, 3); | ||||
|   Values initial; | ||||
|   initial.insert(X(1), p0); | ||||
| 
 | ||||
|   LevenbergMarquardtParams lmParams; | ||||
|   lmParams.setMaxIterations(0); // forces not to perform optimization
 | ||||
|   GncParams<LevenbergMarquardtParams> gncParams(lmParams); | ||||
|   auto gnc = GncOptimizer<GncParams<LevenbergMarquardtParams>>(fg, initial, | ||||
|                                                                gncParams); | ||||
|   Values result = gnc.optimize(); | ||||
| 
 | ||||
|   // check that LM did not perform optimization and result is the same as the initial guess
 | ||||
|   DOUBLES_EQUAL(fg.error(initial), fg.error(result), tol); | ||||
| 
 | ||||
|   // also check the params:
 | ||||
|   DOUBLES_EQUAL(0.0, gncParams.baseOptimizerParams.maxIterations, tol); | ||||
| } | ||||
| 
 | ||||
| /* ************************************************************************* */ | ||||
| TEST(GncOptimizer, gncConstructorWithRobustGraphAsInput) { | ||||
|   auto fg = example::sharedNonRobustFactorGraphWithOutliers(); | ||||
|  |  | |||
		Loading…
	
		Reference in New Issue