| 
									
										
										
										
											2010-10-14 12:54:38 +08:00
										 |  |  | /* ----------------------------------------------------------------------------
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * GTSAM Copyright 2010, Georgia Tech Research Corporation,  | 
					
						
							|  |  |  |  * Atlanta, Georgia 30332-0415 | 
					
						
							|  |  |  |  * All Rights Reserved | 
					
						
							|  |  |  |  * Authors: Frank Dellaert, et al. (see THANKS for the full author list) | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * See LICENSE for the license information | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | /** 
 | 
					
						
							|  |  |  |  * @file    testNonlinearOptimizer.cpp | 
					
						
							|  |  |  |  * @brief   Unit tests for NonlinearOptimizer class | 
					
						
							|  |  |  |  * @author  Frank Dellaert | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <iostream>
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-10-31 23:24:22 +08:00
										 |  |  | #include <boost/assign/std/list.hpp> // for operator +=
 | 
					
						
							|  |  |  | using namespace boost::assign; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-26 04:10:33 +08:00
										 |  |  | #include <CppUnitLite/TestHarness.h>
 | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-12 04:17:28 +08:00
										 |  |  | #include <boost/shared_ptr.hpp>
 | 
					
						
							|  |  |  | using namespace boost; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-18 03:34:57 +08:00
										 |  |  | #define GTSAM_MAGIC_KEY
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-20 01:23:19 +08:00
										 |  |  | #include <gtsam/base/Matrix.h>
 | 
					
						
							|  |  |  | #include <gtsam/slam/smallExample.h>
 | 
					
						
							|  |  |  | #include <gtsam/slam/pose2SLAM.h>
 | 
					
						
							|  |  |  | #include <gtsam/linear/GaussianFactorGraph.h>
 | 
					
						
							|  |  |  | #include <gtsam/linear/NoiseModel.h>
 | 
					
						
							| 
									
										
										
										
											2009-10-31 23:24:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-09-13 12:13:03 +08:00
										 |  |  | // template definitions
 | 
					
						
							| 
									
										
										
										
											2010-08-20 01:23:19 +08:00
										 |  |  | #include <gtsam/nonlinear/NonlinearFactorGraph-inl.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/NonlinearOptimizer-inl.h>
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //#include <gtsam/linear/SubgraphSolver-inl.h>
 | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-03-05 06:46:27 +08:00
										 |  |  | const double tol = 1e-5; | 
					
						
							| 
									
										
										
										
											2010-01-27 12:39:35 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | typedef NonlinearOptimizer<example::Graph,example::Values> Optimizer; | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-07-08 05:41:50 +08:00
										 |  |  | TEST( NonlinearOptimizer, linearizeAndOptimizeForDelta ) | 
					
						
							| 
									
										
										
										
											2010-01-20 10:28:23 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2010-03-13 02:52:04 +08:00
										 |  |  | 	shared_ptr<example::Graph> fg(new example::Graph( | 
					
						
							|  |  |  | 			example::createNonlinearFactorGraph())); | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	Optimizer::shared_values initial = example::sharedNoisyValues(); | 
					
						
							| 
									
										
										
										
											2010-01-20 10:28:23 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	// Expected values structure is the difference between the noisy config
 | 
					
						
							| 
									
										
										
										
											2010-01-20 10:28:23 +08:00
										 |  |  | 	// and the ground-truth config. One step only because it's linear !
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   Ordering ord1; ord1 += "x2","l1","x1"; | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	VectorValues expected(initial->dims(ord1)); | 
					
						
							| 
									
										
										
										
											2010-01-20 10:28:23 +08:00
										 |  |  | 	Vector dl1(2); | 
					
						
							|  |  |  | 	dl1(0) = -0.1; | 
					
						
							|  |  |  | 	dl1(1) = 0.1; | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 	expected[ord1["l1"]] = dl1; | 
					
						
							| 
									
										
										
										
											2010-01-20 10:28:23 +08:00
										 |  |  | 	Vector dx1(2); | 
					
						
							|  |  |  | 	dx1(0) = -0.1; | 
					
						
							|  |  |  | 	dx1(1) = -0.1; | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 	expected[ord1["x1"]] = dx1; | 
					
						
							| 
									
										
										
										
											2010-01-20 10:28:23 +08:00
										 |  |  | 	Vector dx2(2); | 
					
						
							|  |  |  | 	dx2(0) = 0.1; | 
					
						
							|  |  |  | 	dx2(1) = -0.2; | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 	expected[ord1["x2"]] = dx2; | 
					
						
							| 
									
										
										
										
											2010-01-20 10:28:23 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// Check one ordering
 | 
					
						
							| 
									
										
										
										
											2010-10-22 11:51:10 +08:00
										 |  |  | 	Optimizer optimizer1(fg, initial, Optimizer::shared_ordering(new Ordering(ord1))); | 
					
						
							| 
									
										
										
										
											2010-01-27 12:39:35 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	VectorValues actual1 = optimizer1.linearizeAndOptimizeForDelta(); | 
					
						
							| 
									
										
										
										
											2010-01-20 10:28:23 +08:00
										 |  |  | 	CHECK(assert_equal(actual1,expected)); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | // SL-FIX	// Check another
 | 
					
						
							|  |  |  | //	shared_ptr<Ordering> ord2(new Ordering());
 | 
					
						
							|  |  |  | //	*ord2 += "x1","x2","l1";
 | 
					
						
							|  |  |  | //	solver = Optimizer::shared_solver(new Optimizer::solver(ord2));
 | 
					
						
							|  |  |  | //	Optimizer optimizer2(fg, initial, solver);
 | 
					
						
							|  |  |  | //
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | //	VectorValues actual2 = optimizer2.linearizeAndOptimizeForDelta();
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //	CHECK(assert_equal(actual2,expected));
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	// And yet another...
 | 
					
						
							|  |  |  | //	shared_ptr<Ordering> ord3(new Ordering());
 | 
					
						
							|  |  |  | //	*ord3 += "l1","x1","x2";
 | 
					
						
							|  |  |  | //	solver = Optimizer::shared_solver(new Optimizer::solver(ord3));
 | 
					
						
							|  |  |  | //	Optimizer optimizer3(fg, initial, solver);
 | 
					
						
							|  |  |  | //
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | //	VectorValues actual3 = optimizer3.linearizeAndOptimizeForDelta();
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //	CHECK(assert_equal(actual3,expected));
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	// More...
 | 
					
						
							|  |  |  | //	shared_ptr<Ordering> ord4(new Ordering());
 | 
					
						
							|  |  |  | //	*ord4 += "x1","x2", "l1";
 | 
					
						
							|  |  |  | //	solver = Optimizer::shared_solver(new Optimizer::solver(ord4));
 | 
					
						
							|  |  |  | //	Optimizer optimizer4(fg, initial, solver);
 | 
					
						
							|  |  |  | //
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | //	VectorValues actual4 = optimizer4.linearizeAndOptimizeForDelta();
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //	CHECK(assert_equal(actual4,expected));
 | 
					
						
							| 
									
										
										
										
											2010-01-20 10:28:23 +08:00
										 |  |  | } | 
					
						
							| 
									
										
										
										
											2010-01-18 13:51:19 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-01-20 10:28:23 +08:00
										 |  |  | TEST( NonlinearOptimizer, iterateLM ) | 
					
						
							| 
									
										
										
										
											2010-01-18 13:51:19 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2010-01-20 10:28:23 +08:00
										 |  |  | 	// really non-linear factor graph
 | 
					
						
							| 
									
										
										
										
											2010-03-13 02:52:04 +08:00
										 |  |  |   shared_ptr<example::Graph> fg(new example::Graph( | 
					
						
							|  |  |  |   		example::createReallyNonlinearFactorGraph())); | 
					
						
							| 
									
										
										
										
											2010-01-20 10:28:23 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// config far from minimum
 | 
					
						
							|  |  |  | 	Point2 x0(3,0); | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	boost::shared_ptr<example::Values> config(new example::Values); | 
					
						
							| 
									
										
										
										
											2010-01-20 10:28:23 +08:00
										 |  |  | 	config->insert(simulated2D::PoseKey(1), x0); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// ordering
 | 
					
						
							|  |  |  | 	shared_ptr<Ordering> ord(new Ordering()); | 
					
						
							|  |  |  | 	ord->push_back("x1"); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// create initial optimization state, with lambda=0
 | 
					
						
							| 
									
										
										
										
											2010-10-22 11:51:10 +08:00
										 |  |  | 	Optimizer optimizer(fg, config, ord, 0.); | 
					
						
							| 
									
										
										
										
											2010-01-20 10:28:23 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// normal iterate
 | 
					
						
							|  |  |  | 	Optimizer iterated1 = optimizer.iterate(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// LM iterate with lambda 0 should be the same
 | 
					
						
							|  |  |  | 	Optimizer iterated2 = optimizer.iterateLM(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// Try successive iterates. TODO: ugly pointers, better way ?
 | 
					
						
							|  |  |  | 	Optimizer *pointer = new Optimizer(iterated2); | 
					
						
							|  |  |  | 	for (int i=0;i<10;i++) { | 
					
						
							|  |  |  | 		Optimizer* newOptimizer = new Optimizer(pointer->iterateLM()); | 
					
						
							|  |  |  | 		delete pointer; | 
					
						
							|  |  |  | 		pointer = newOptimizer; | 
					
						
							|  |  |  | 	} | 
					
						
							|  |  |  | 	delete(pointer); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-23 03:29:15 +08:00
										 |  |  | 	CHECK(assert_equal(*iterated1.values(), *iterated2.values(), 1e-9)); | 
					
						
							| 
									
										
										
										
											2010-01-20 10:28:23 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( NonlinearOptimizer, optimize ) | 
					
						
							|  |  |  | { | 
					
						
							| 
									
										
										
										
											2010-03-13 02:52:04 +08:00
										 |  |  |   shared_ptr<example::Graph> fg(new example::Graph( | 
					
						
							|  |  |  |   		example::createReallyNonlinearFactorGraph())); | 
					
						
							| 
									
										
										
										
											2010-01-20 10:28:23 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// test error at minimum
 | 
					
						
							|  |  |  | 	Point2 xstar(0,0); | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	example::Values cstar; | 
					
						
							| 
									
										
										
										
											2010-01-20 10:28:23 +08:00
										 |  |  | 	cstar.insert(simulated2D::PoseKey(1), xstar); | 
					
						
							|  |  |  | 	DOUBLES_EQUAL(0.0,fg->error(cstar),0.0); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// test error at initial = [(1-cos(3))^2 + (sin(3))^2]*50 =
 | 
					
						
							|  |  |  | 	Point2 x0(3,3); | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	boost::shared_ptr<example::Values> c0(new example::Values); | 
					
						
							| 
									
										
										
										
											2010-01-20 10:28:23 +08:00
										 |  |  | 	c0->insert(simulated2D::PoseKey(1), x0); | 
					
						
							|  |  |  | 	DOUBLES_EQUAL(199.0,fg->error(*c0),1e-3); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// optimize parameters
 | 
					
						
							|  |  |  | 	shared_ptr<Ordering> ord(new Ordering()); | 
					
						
							|  |  |  | 	ord->push_back("x1"); | 
					
						
							|  |  |  | 	double relativeThreshold = 1e-5; | 
					
						
							|  |  |  | 	double absoluteThreshold = 1e-5; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// initial optimization state is the same in both cases tested
 | 
					
						
							| 
									
										
										
										
											2010-10-22 11:51:10 +08:00
										 |  |  | 	Optimizer optimizer(fg, c0, ord); | 
					
						
							| 
									
										
										
										
											2010-01-20 10:28:23 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// Gauss-Newton
 | 
					
						
							|  |  |  | 	Optimizer actual1 = optimizer.gaussNewton(relativeThreshold, | 
					
						
							|  |  |  | 			absoluteThreshold); | 
					
						
							| 
									
										
										
										
											2010-10-23 03:29:15 +08:00
										 |  |  | 	DOUBLES_EQUAL(0,fg->error(*(actual1.values())),tol); | 
					
						
							| 
									
										
										
										
											2010-01-20 10:28:23 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// Levenberg-Marquardt
 | 
					
						
							|  |  |  | 	Optimizer actual2 = optimizer.levenbergMarquardt(relativeThreshold, | 
					
						
							| 
									
										
										
										
											2010-10-16 09:55:47 +08:00
										 |  |  | 			absoluteThreshold, Optimizer::Parameters::SILENT); | 
					
						
							| 
									
										
										
										
											2010-10-23 03:29:15 +08:00
										 |  |  | 	DOUBLES_EQUAL(0,fg->error(*(actual2.values())),tol); | 
					
						
							| 
									
										
										
										
											2010-01-20 10:28:23 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-07-23 05:17:02 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-08-06 23:10:19 +08:00
										 |  |  | TEST( NonlinearOptimizer, SimpleLMOptimizer ) | 
					
						
							| 
									
										
										
										
											2010-07-23 05:17:02 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2010-08-10 01:20:03 +08:00
										 |  |  | 	shared_ptr<example::Graph> fg(new example::Graph( | 
					
						
							|  |  |  | 			example::createReallyNonlinearFactorGraph())); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	Point2 x0(3,3); | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	boost::shared_ptr<example::Values> c0(new example::Values); | 
					
						
							| 
									
										
										
										
											2010-08-10 01:20:03 +08:00
										 |  |  | 	c0->insert(simulated2D::PoseKey(1), x0); | 
					
						
							| 
									
										
										
										
											2010-07-23 05:17:02 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	Optimizer::shared_values actual = Optimizer::optimizeLM(fg, c0); | 
					
						
							| 
									
										
										
										
											2010-08-10 01:20:03 +08:00
										 |  |  | 	DOUBLES_EQUAL(0,fg->error(*actual),tol); | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2010-07-23 05:17:02 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-10 01:20:03 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( NonlinearOptimizer, SimpleLMOptimizer_noshared ) | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  | 	example::Graph fg = example::createReallyNonlinearFactorGraph(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	Point2 x0(3,3); | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	example::Values c0; | 
					
						
							| 
									
										
										
										
											2010-08-10 01:20:03 +08:00
										 |  |  | 	c0.insert(simulated2D::PoseKey(1), x0); | 
					
						
							| 
									
										
										
										
											2010-07-23 05:17:02 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	Optimizer::shared_values actual = Optimizer::optimizeLM(fg, c0); | 
					
						
							| 
									
										
										
										
											2010-08-10 01:20:03 +08:00
										 |  |  | 	DOUBLES_EQUAL(0,fg.error(*actual),tol); | 
					
						
							| 
									
										
										
										
											2010-07-23 05:17:02 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-06 23:10:19 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( NonlinearOptimizer, SimpleGNOptimizer ) | 
					
						
							|  |  |  | { | 
					
						
							| 
									
										
										
										
											2010-08-10 01:20:03 +08:00
										 |  |  | 	shared_ptr<example::Graph> fg(new example::Graph( | 
					
						
							|  |  |  | 			example::createReallyNonlinearFactorGraph())); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	Point2 x0(3,3); | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	boost::shared_ptr<example::Values> c0(new example::Values); | 
					
						
							| 
									
										
										
										
											2010-08-10 01:20:03 +08:00
										 |  |  | 	c0->insert(simulated2D::PoseKey(1), x0); | 
					
						
							| 
									
										
										
										
											2010-08-06 23:10:19 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	Optimizer::shared_values actual = Optimizer::optimizeGN(fg, c0); | 
					
						
							| 
									
										
										
										
											2010-08-10 01:20:03 +08:00
										 |  |  | 	DOUBLES_EQUAL(0,fg->error(*actual),tol); | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2010-08-06 23:10:19 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-10 01:20:03 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( NonlinearOptimizer, SimpleGNOptimizer_noshared ) | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  | 	example::Graph fg = example::createReallyNonlinearFactorGraph(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	Point2 x0(3,3); | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	example::Values c0; | 
					
						
							| 
									
										
										
										
											2010-08-10 01:20:03 +08:00
										 |  |  | 	c0.insert(simulated2D::PoseKey(1), x0); | 
					
						
							| 
									
										
										
										
											2010-08-06 23:10:19 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	Optimizer::shared_values actual = Optimizer::optimizeGN(fg, c0); | 
					
						
							| 
									
										
										
										
											2010-08-10 01:20:03 +08:00
										 |  |  | 	DOUBLES_EQUAL(0,fg.error(*actual),tol); | 
					
						
							| 
									
										
										
										
											2010-08-06 23:10:19 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-20 10:28:23 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( NonlinearOptimizer, Factorization ) | 
					
						
							|  |  |  | { | 
					
						
							| 
									
										
										
										
											2010-10-22 11:51:10 +08:00
										 |  |  | 	typedef NonlinearOptimizer<Pose2Graph, Pose2Values, GaussianFactorGraph, GaussianSequentialSolver > Optimizer; | 
					
						
							| 
									
										
										
										
											2010-01-18 13:51:19 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	boost::shared_ptr<Pose2Values> config(new Pose2Values); | 
					
						
							| 
									
										
										
										
											2010-01-18 13:51:19 +08:00
										 |  |  | 	config->insert(1, Pose2(0.,0.,0.)); | 
					
						
							|  |  |  | 	config->insert(2, Pose2(1.5,0.,0.)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	boost::shared_ptr<Pose2Graph> graph(new Pose2Graph); | 
					
						
							| 
									
										
										
										
											2010-08-08 11:10:29 +08:00
										 |  |  | 	graph->addPrior(1, Pose2(0.,0.,0.), noiseModel::Isotropic::Sigma(3, 1e-10)); | 
					
						
							|  |  |  | 	graph->addConstraint(1,2, Pose2(1.,0.,0.), noiseModel::Isotropic::Sigma(3, 1)); | 
					
						
							| 
									
										
										
										
											2010-01-18 13:51:19 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	boost::shared_ptr<Ordering> ordering(new Ordering); | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	ordering->push_back(Pose2Values::Key(1)); | 
					
						
							|  |  |  | 	ordering->push_back(Pose2Values::Key(2)); | 
					
						
							| 
									
										
										
										
											2010-01-20 10:28:23 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-22 11:51:10 +08:00
										 |  |  | 	Optimizer optimizer(graph, config, ordering); | 
					
						
							| 
									
										
										
										
											2010-01-20 10:28:23 +08:00
										 |  |  | 	Optimizer optimized = optimizer.iterateLM(); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	Pose2Values expected; | 
					
						
							| 
									
										
										
										
											2010-01-20 10:28:23 +08:00
										 |  |  | 	expected.insert(1, Pose2(0.,0.,0.)); | 
					
						
							|  |  |  | 	expected.insert(2, Pose2(1.,0.,0.)); | 
					
						
							| 
									
										
										
										
											2010-10-23 03:29:15 +08:00
										 |  |  | 	CHECK(assert_equal(expected, *optimized.values(), 1e-5)); | 
					
						
							| 
									
										
										
										
											2010-01-20 10:28:23 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | ///* ************************************************************************* */
 | 
					
						
							|  |  |  | // SL-FIX TEST( NonlinearOptimizer, SubgraphSolver )
 | 
					
						
							|  |  |  | //{
 | 
					
						
							|  |  |  | //	using namespace pose2SLAM;
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | //	typedef SubgraphSolver<Graph, Values> Solver;
 | 
					
						
							|  |  |  | //	typedef NonlinearOptimizer<Graph, Values, SubgraphPreconditioner, Solver> Optimizer;
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //
 | 
					
						
							|  |  |  | //	// Create a graph
 | 
					
						
							|  |  |  | //	boost::shared_ptr<Graph> graph(new Graph);
 | 
					
						
							|  |  |  | //	graph->addPrior(1, Pose2(0., 0., 0.), noiseModel::Isotropic::Sigma(3, 1e-10));
 | 
					
						
							|  |  |  | //	graph->addConstraint(1, 2, Pose2(1., 0., 0.), noiseModel::Isotropic::Sigma(3, 1));
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	// Create an initial config
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | //	boost::shared_ptr<Values> config(new Values);
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //	config->insert(1, Pose2(0., 0., 0.));
 | 
					
						
							|  |  |  | //	config->insert(2, Pose2(1.5, 0., 0.));
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	// Create solver and optimizer
 | 
					
						
							|  |  |  | //	Optimizer::shared_solver solver
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | //		(new SubgraphSolver<Graph, Values> (*graph, *config));
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //	Optimizer optimizer(graph, config, solver);
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	// Optimize !!!!
 | 
					
						
							|  |  |  | //	double relativeThreshold = 1e-5;
 | 
					
						
							|  |  |  | //	double absoluteThreshold = 1e-5;
 | 
					
						
							|  |  |  | //	Optimizer optimized = optimizer.gaussNewton(relativeThreshold,
 | 
					
						
							|  |  |  | //			absoluteThreshold, Optimizer::SILENT);
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	// Check solution
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | //	Values expected;
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //	expected.insert(1, Pose2(0., 0., 0.));
 | 
					
						
							|  |  |  | //	expected.insert(2, Pose2(1., 0., 0.));
 | 
					
						
							| 
									
										
										
										
											2010-10-23 03:29:15 +08:00
										 |  |  | //	CHECK(assert_equal(expected, *optimized.values(), 1e-5));
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //}
 | 
					
						
							| 
									
										
										
										
											2010-01-18 13:51:19 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-07-08 05:41:50 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | // SL-FIX TEST( NonlinearOptimizer, MultiFrontalSolver )
 | 
					
						
							| 
									
										
										
										
											2010-07-08 05:41:50 +08:00
										 |  |  | //{
 | 
					
						
							|  |  |  | //	shared_ptr<example::Graph> fg(new example::Graph(
 | 
					
						
							|  |  |  | //			example::createNonlinearFactorGraph()));
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | //	Optimizer::shared_values initial = example::sharedNoisyValues();
 | 
					
						
							| 
									
										
										
										
											2010-07-08 05:41:50 +08:00
										 |  |  | //
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | //	Values expected;
 | 
					
						
							| 
									
										
										
										
											2010-07-08 05:41:50 +08:00
										 |  |  | //	expected.insert(simulated2D::PoseKey(1), Point2(0.0, 0.0));
 | 
					
						
							|  |  |  | //	expected.insert(simulated2D::PoseKey(2), Point2(1.5, 0.0));
 | 
					
						
							|  |  |  | //	expected.insert(simulated2D::PointKey(1), Point2(0.0, -1.0));
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	Optimizer::shared_solver solver;
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	// Check one ordering
 | 
					
						
							|  |  |  | //	shared_ptr<Ordering> ord1(new Ordering());
 | 
					
						
							|  |  |  | //	*ord1 += "x2","l1","x1";
 | 
					
						
							|  |  |  | //	solver = Optimizer::shared_solver(new Optimizer::solver(ord1));
 | 
					
						
							|  |  |  | //	Optimizer optimizer1(fg, initial, solver);
 | 
					
						
							|  |  |  | //
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | //	Values actual = optimizer1.levenbergMarquardt();
 | 
					
						
							| 
									
										
										
										
											2010-07-08 05:41:50 +08:00
										 |  |  | //	CHECK(assert_equal(actual,expected));
 | 
					
						
							|  |  |  | //}
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | int main() { | 
					
						
							|  |  |  | 	TestResult tr; | 
					
						
							|  |  |  | 	return TestRegistry::runAllTests(tr); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | /* ************************************************************************* */ |