| 
									
										
										
										
											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; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | #include <CppUnitLite/TestHarness.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											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
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | #include "Matrix.h"
 | 
					
						
							| 
									
										
										
										
											2009-11-02 11:50:30 +08:00
										 |  |  | #include "Ordering.h"
 | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | #include "smallExample.h"
 | 
					
						
							| 
									
										
										
										
											2010-01-18 13:51:19 +08:00
										 |  |  | #include "pose2SLAM.h"
 | 
					
						
							|  |  |  | #include "GaussianFactorGraph.h"
 | 
					
						
							| 
									
										
										
										
											2010-01-18 14:17:01 +08:00
										 |  |  | #include "NoiseModel.h"
 | 
					
						
							| 
									
										
										
										
											2009-10-31 23:24:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-09-13 12:13:03 +08:00
										 |  |  | // template definitions
 | 
					
						
							| 
									
										
										
										
											2009-10-07 02:25:04 +08:00
										 |  |  | #include "NonlinearFactorGraph-inl.h"
 | 
					
						
							| 
									
										
										
										
											2009-09-13 12:13:03 +08:00
										 |  |  | #include "NonlinearOptimizer-inl.h"
 | 
					
						
							| 
									
										
										
										
											2010-01-18 13:51:19 +08:00
										 |  |  | #include "SubgraphPreconditioner-inl.h"
 | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-10-15 04:39:59 +08:00
										 |  |  | typedef NonlinearOptimizer<ExampleNonlinearFactorGraph,VectorConfig> Optimizer; | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2009-10-07 02:25:04 +08:00
										 |  |  | TEST( NonlinearOptimizer, delta ) | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2010-01-12 04:17:28 +08:00
										 |  |  | 	shared_ptr<ExampleNonlinearFactorGraph> fg(new ExampleNonlinearFactorGraph(createNonlinearFactorGraph())); | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | 	Optimizer::shared_config initial = sharedNoisyConfig(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// Expected configuration is the difference between the noisy config
 | 
					
						
							|  |  |  | 	// and the ground-truth config. One step only because it's linear !
 | 
					
						
							| 
									
										
										
										
											2009-10-15 04:39:59 +08:00
										 |  |  | 	VectorConfig expected; | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | 	Vector dl1(2); | 
					
						
							|  |  |  | 	dl1(0) = -0.1; | 
					
						
							|  |  |  | 	dl1(1) = 0.1; | 
					
						
							|  |  |  | 	expected.insert("l1", dl1); | 
					
						
							|  |  |  | 	Vector dx1(2); | 
					
						
							|  |  |  | 	dx1(0) = -0.1; | 
					
						
							|  |  |  | 	dx1(1) = -0.1; | 
					
						
							|  |  |  | 	expected.insert("x1", dx1); | 
					
						
							|  |  |  | 	Vector dx2(2); | 
					
						
							|  |  |  | 	dx2(0) = 0.1; | 
					
						
							|  |  |  | 	dx2(1) = -0.2; | 
					
						
							|  |  |  | 	expected.insert("x2", dx2); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// Check one ordering
 | 
					
						
							| 
									
										
										
										
											2010-01-12 04:17:28 +08:00
										 |  |  | 	shared_ptr<Ordering> ord1(new Ordering()); | 
					
						
							|  |  |  | 	*ord1 += "x2","l1","x1"; | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | 	Optimizer optimizer1(fg, ord1, initial); | 
					
						
							| 
									
										
										
										
											2009-10-20 03:12:48 +08:00
										 |  |  | 	VectorConfig actual1 = optimizer1.linearizeAndOptimizeForDelta(); | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | 	CHECK(assert_equal(actual1,expected)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// Check another
 | 
					
						
							| 
									
										
										
										
											2010-01-12 04:17:28 +08:00
										 |  |  | 	shared_ptr<Ordering> ord2(new Ordering()); | 
					
						
							|  |  |  | 	*ord2 += "x1","x2","l1"; | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | 	Optimizer optimizer2(fg, ord2, initial); | 
					
						
							| 
									
										
										
										
											2009-10-20 03:12:48 +08:00
										 |  |  | 	VectorConfig actual2 = optimizer2.linearizeAndOptimizeForDelta(); | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | 	CHECK(assert_equal(actual2,expected)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// And yet another...
 | 
					
						
							| 
									
										
										
										
											2010-01-12 04:17:28 +08:00
										 |  |  | 	shared_ptr<Ordering> ord3(new Ordering()); | 
					
						
							|  |  |  | 	*ord3 += "l1","x1","x2"; | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | 	Optimizer optimizer3(fg, ord3, initial); | 
					
						
							| 
									
										
										
										
											2009-10-20 03:12:48 +08:00
										 |  |  | 	VectorConfig actual3 = optimizer3.linearizeAndOptimizeForDelta(); | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | 	CHECK(assert_equal(actual3,expected)); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2009-10-07 02:25:04 +08:00
										 |  |  | TEST( NonlinearOptimizer, iterateLM ) | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | { | 
					
						
							|  |  |  | 	// really non-linear factor graph
 | 
					
						
							| 
									
										
										
										
											2010-01-12 04:17:28 +08:00
										 |  |  |   shared_ptr<ExampleNonlinearFactorGraph> fg(new ExampleNonlinearFactorGraph(createReallyNonlinearFactorGraph())); | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// config far from minimum
 | 
					
						
							|  |  |  | 	Vector x0 = Vector_(1, 3.0); | 
					
						
							| 
									
										
										
										
											2009-10-15 04:39:59 +08:00
										 |  |  | 	boost::shared_ptr<VectorConfig> config(new VectorConfig); | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | 	config->insert("x", x0); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// ordering
 | 
					
						
							| 
									
										
										
										
											2010-01-12 04:17:28 +08:00
										 |  |  | 	shared_ptr<Ordering> ord(new Ordering()); | 
					
						
							|  |  |  | 	ord->push_back("x"); | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// create initial optimization state, with lambda=0
 | 
					
						
							| 
									
										
										
										
											2010-01-18 13:51:19 +08:00
										 |  |  | 	Optimizer::shared_solver solver(new Factorization<ExampleNonlinearFactorGraph, VectorConfig>); | 
					
						
							|  |  |  | 	Optimizer optimizer(fg, ord, config, solver, 0.); | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// normal iterate
 | 
					
						
							|  |  |  | 	Optimizer iterated1 = optimizer.iterate(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// LM iterate with lambda 0 should be the same
 | 
					
						
							|  |  |  | 	Optimizer iterated2 = optimizer.iterateLM(); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-11 08:53:43 +08:00
										 |  |  | 	// 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); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-10-07 02:25:04 +08:00
										 |  |  | 	CHECK(assert_equal(*iterated1.config(), *iterated2.config(), 1e-9)); | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2009-10-07 02:25:04 +08:00
										 |  |  | TEST( NonlinearOptimizer, optimize ) | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2010-01-12 04:17:28 +08:00
										 |  |  |   shared_ptr<ExampleNonlinearFactorGraph> fg(new ExampleNonlinearFactorGraph(createReallyNonlinearFactorGraph())); | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// test error at minimum
 | 
					
						
							|  |  |  | 	Vector xstar = Vector_(1, 0.0); | 
					
						
							| 
									
										
										
										
											2009-10-15 04:39:59 +08:00
										 |  |  | 	VectorConfig cstar; | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | 	cstar.insert("x", xstar); | 
					
						
							| 
									
										
										
										
											2010-01-12 04:17:28 +08:00
										 |  |  | 	DOUBLES_EQUAL(0.0,fg->error(cstar),0.0); | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// test error at initial = [(1-cos(3))^2 + (sin(3))^2]*50 =
 | 
					
						
							|  |  |  | 	Vector x0 = Vector_(1, 3.0); | 
					
						
							| 
									
										
										
										
											2009-10-15 04:39:59 +08:00
										 |  |  | 	boost::shared_ptr<VectorConfig> c0(new VectorConfig); | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | 	c0->insert("x", x0); | 
					
						
							| 
									
										
										
										
											2010-01-12 04:17:28 +08:00
										 |  |  | 	DOUBLES_EQUAL(199.0,fg->error(*c0),1e-3); | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// optimize parameters
 | 
					
						
							| 
									
										
										
										
											2010-01-12 04:17:28 +08:00
										 |  |  | 	shared_ptr<Ordering> ord(new Ordering()); | 
					
						
							|  |  |  | 	ord->push_back("x"); | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | 	double relativeThreshold = 1e-5; | 
					
						
							|  |  |  | 	double absoluteThreshold = 1e-5; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// initial optimization state is the same in both cases tested
 | 
					
						
							|  |  |  | 	Optimizer optimizer(fg, ord, c0); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// Gauss-Newton
 | 
					
						
							|  |  |  | 	Optimizer actual1 = optimizer.gaussNewton(relativeThreshold, | 
					
						
							|  |  |  | 			absoluteThreshold); | 
					
						
							| 
									
										
										
										
											2009-09-11 06:08:47 +08:00
										 |  |  | 	CHECK(assert_equal(*(actual1.config()),cstar)); | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// Levenberg-Marquardt
 | 
					
						
							|  |  |  | 	Optimizer actual2 = optimizer.levenbergMarquardt(relativeThreshold, | 
					
						
							|  |  |  | 			absoluteThreshold, Optimizer::SILENT); | 
					
						
							| 
									
										
										
										
											2009-09-11 06:08:47 +08:00
										 |  |  | 	CHECK(assert_equal(*(actual2.config()),cstar)); | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-18 13:51:19 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( NonlinearOptimizer, Factorization ) | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  | 	typedef NonlinearOptimizer<Pose2Graph, Pose2Config, Factorization<Pose2Graph, Pose2Config> > Optimizer; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	boost::shared_ptr<Pose2Config> config(new Pose2Config); | 
					
						
							|  |  |  | 	config->insert(1, Pose2(0.,0.,0.)); | 
					
						
							|  |  |  | 	config->insert(2, Pose2(1.5,0.,0.)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	boost::shared_ptr<Pose2Graph> graph(new Pose2Graph); | 
					
						
							| 
									
										
										
										
											2010-01-18 15:11:34 +08:00
										 |  |  | 	graph->addPrior(1, Pose2(0.,0.,0.), Isotropic::Sigma(3, 1e-10)); | 
					
						
							|  |  |  | 	graph->addConstraint(1,2, Pose2(1.,0.,0.), Isotropic::Sigma(3, 1)); | 
					
						
							| 
									
										
										
										
											2010-01-18 13:51:19 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	boost::shared_ptr<Ordering> ordering(new Ordering); | 
					
						
							|  |  |  | 	ordering->push_back(Pose2Config::Key(1)); | 
					
						
							|  |  |  | 	ordering->push_back(Pose2Config::Key(2)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	Optimizer optimizer(graph, ordering, config); | 
					
						
							|  |  |  | 	Optimizer optimized = optimizer.iterateLM(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	Pose2Config expected; | 
					
						
							|  |  |  | 	expected.insert(1, Pose2(0.,0.,0.)); | 
					
						
							|  |  |  | 	expected.insert(2, Pose2(1.,0.,0.)); | 
					
						
							|  |  |  | 	CHECK(assert_equal(expected, *optimized.config(), 1e-5)); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( NonlinearOptimizer, SubgraphPCG ) | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  | 	typedef NonlinearOptimizer<Pose2Graph, Pose2Config, SubgraphPCG<Pose2Graph, Pose2Config> > Optimizer; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	boost::shared_ptr<Pose2Config> config(new Pose2Config); | 
					
						
							|  |  |  | 	config->insert(1, Pose2(0.,0.,0.)); | 
					
						
							|  |  |  | 	config->insert(2, Pose2(1.5,0.,0.)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	boost::shared_ptr<Pose2Graph> graph(new Pose2Graph); | 
					
						
							| 
									
										
										
										
											2010-01-18 15:11:34 +08:00
										 |  |  | 	graph->addPrior(1, Pose2(0.,0.,0.), Isotropic::Sigma(3, 1e-10)); | 
					
						
							|  |  |  | 	graph->addConstraint(1,2, Pose2(1.,0.,0.), Isotropic::Sigma(3, 1)); | 
					
						
							| 
									
										
										
										
											2010-01-18 13:51:19 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	boost::shared_ptr<Ordering> ordering(new Ordering); | 
					
						
							|  |  |  | 	ordering->push_back(Pose2Config::Key(1)); | 
					
						
							|  |  |  | 	ordering->push_back(Pose2Config::Key(2)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	double relativeThreshold = 1e-5; | 
					
						
							|  |  |  | 	double absoluteThreshold = 1e-5; | 
					
						
							|  |  |  | 	Optimizer::shared_solver solver(new SubgraphPCG<Pose2Graph, Pose2Config>(*graph, *config)); | 
					
						
							|  |  |  | 	Optimizer optimizer(graph, ordering, config, solver); | 
					
						
							|  |  |  | 	Optimizer optimized = optimizer.gaussNewton(relativeThreshold, absoluteThreshold, Optimizer::SILENT); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	Pose2Config expected; | 
					
						
							|  |  |  | 	expected.insert(1, Pose2(0.,0.,0.)); | 
					
						
							|  |  |  | 	expected.insert(2, Pose2(1.,0.,0.)); | 
					
						
							|  |  |  | 	CHECK(assert_equal(expected, *optimized.config(), 1e-5)); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | int main() { | 
					
						
							|  |  |  | 	TestResult tr; | 
					
						
							|  |  |  | 	return TestRegistry::runAllTests(tr); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | /* ************************************************************************* */ |