| 
									
										
										
										
											2012-06-12 06:10:23 +08:00
										 |  |  | /**
 | 
					
						
							|  |  |  |  * @file   testGradientDescentOptimizer.cpp | 
					
						
							|  |  |  |  * @brief   | 
					
						
							|  |  |  |  * @author ydjian | 
					
						
							|  |  |  |  * @date   Jun 11, 2012 | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam/slam/pose2SLAM.h>
 | 
					
						
							| 
									
										
										
										
											2012-06-12 22:19:01 +08:00
										 |  |  | #include <gtsam/nonlinear/GradientDescentOptimizer.h>
 | 
					
						
							| 
									
										
										
										
											2012-06-12 06:10:23 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | #include <CppUnitLite/TestHarness.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <boost/make_shared.hpp>
 | 
					
						
							| 
									
										
										
										
											2012-06-12 22:19:01 +08:00
										 |  |  | #include <boost/shared_ptr.hpp>
 | 
					
						
							|  |  |  | #include <boost/tuple/tuple.hpp>
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-12 06:10:23 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-12 22:19:01 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | boost::tuple<pose2SLAM::Graph, Values> generateProblem() { | 
					
						
							| 
									
										
										
										
											2012-06-12 06:10:23 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // 1. Create graph container and add factors to it
 | 
					
						
							|  |  |  |   pose2SLAM::Graph graph ; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // 2a. Add Gaussian prior
 | 
					
						
							|  |  |  |   Pose2 priorMean(0.0, 0.0, 0.0); // prior at origin
 | 
					
						
							| 
									
										
										
										
											2012-06-23 03:36:49 +08:00
										 |  |  |   SharedDiagonal priorNoise = noiseModel::Diagonal::Sigmas(Vector_(3, 0.3, 0.3, 0.1)); | 
					
						
							| 
									
										
										
										
											2012-06-24 10:48:12 +08:00
										 |  |  |   graph.addPosePrior(1, priorMean, priorNoise); | 
					
						
							| 
									
										
										
										
											2012-06-12 06:10:23 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // 2b. Add odometry factors
 | 
					
						
							| 
									
										
										
										
											2012-06-23 03:36:49 +08:00
										 |  |  |   SharedDiagonal odometryNoise = noiseModel::Diagonal::Sigmas(Vector_(3, 0.2, 0.2, 0.1)); | 
					
						
							| 
									
										
										
										
											2012-06-24 10:48:12 +08:00
										 |  |  |   graph.addRelativePose(1, 2, Pose2(2.0, 0.0, 0.0   ), odometryNoise); | 
					
						
							|  |  |  |   graph.addRelativePose(2, 3, Pose2(2.0, 0.0, M_PI_2), odometryNoise); | 
					
						
							|  |  |  |   graph.addRelativePose(3, 4, Pose2(2.0, 0.0, M_PI_2), odometryNoise); | 
					
						
							|  |  |  |   graph.addRelativePose(4, 5, Pose2(2.0, 0.0, M_PI_2), odometryNoise); | 
					
						
							| 
									
										
										
										
											2012-06-12 06:10:23 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // 2c. Add pose constraint
 | 
					
						
							| 
									
										
										
										
											2012-06-23 03:36:49 +08:00
										 |  |  |   SharedDiagonal constraintUncertainty = noiseModel::Diagonal::Sigmas(Vector_(3, 0.2, 0.2, 0.1)); | 
					
						
							| 
									
										
										
										
											2012-06-24 10:48:12 +08:00
										 |  |  |   graph.addRelativePose(5, 2, Pose2(2.0, 0.0, M_PI_2), constraintUncertainty); | 
					
						
							| 
									
										
										
										
											2012-06-12 06:10:23 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // 3. Create the data structure to hold the initialEstimate estinmate to the solution
 | 
					
						
							|  |  |  |   pose2SLAM::Values initialEstimate; | 
					
						
							|  |  |  |   Pose2 x1(0.5, 0.0, 0.2   ); initialEstimate.insertPose(1, x1); | 
					
						
							|  |  |  |   Pose2 x2(2.3, 0.1,-0.2   ); initialEstimate.insertPose(2, x2); | 
					
						
							|  |  |  |   Pose2 x3(4.1, 0.1, M_PI_2); initialEstimate.insertPose(3, x3); | 
					
						
							|  |  |  |   Pose2 x4(4.0, 2.0, M_PI  ); initialEstimate.insertPose(4, x4); | 
					
						
							|  |  |  |   Pose2 x5(2.1, 2.1,-M_PI_2); initialEstimate.insertPose(5, x5); | 
					
						
							| 
									
										
										
										
											2012-06-12 22:19:01 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   return boost::tie(graph, initialEstimate); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST(optimize, GradientDescentOptimizer) { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   pose2SLAM::Graph graph ; | 
					
						
							|  |  |  |   pose2SLAM::Values initialEstimate; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   boost::tie(graph, initialEstimate) = generateProblem(); | 
					
						
							| 
									
										
										
										
											2012-06-12 06:10:23 +08:00
										 |  |  |   // cout << "initial error = " << graph.error(initialEstimate) << endl ;
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-12 22:19:01 +08:00
										 |  |  |   // Single Step Optimization using Levenberg-Marquardt
 | 
					
						
							| 
									
										
										
										
											2012-06-13 09:21:10 +08:00
										 |  |  |   NonlinearOptimizerParams param; | 
					
						
							| 
									
										
										
										
											2012-06-12 06:10:23 +08:00
										 |  |  |   param.maxIterations = 500;    /* requires a larger number of iterations to converge */ | 
					
						
							|  |  |  |   param.verbosity = NonlinearOptimizerParams::SILENT; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   GradientDescentOptimizer optimizer(graph, initialEstimate, param); | 
					
						
							|  |  |  |   Values result = optimizer.optimize(); | 
					
						
							| 
									
										
										
										
											2012-06-13 09:21:10 +08:00
										 |  |  | //  cout << "gd1 solver final error = " << graph.error(result) << endl;
 | 
					
						
							| 
									
										
										
										
											2012-06-12 06:10:23 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /* the optimality of the solution is not comparable to the */ | 
					
						
							|  |  |  |   DOUBLES_EQUAL(0.0, graph.error(result), 1e-2); | 
					
						
							| 
									
										
										
										
											2012-06-12 22:19:01 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   CHECK(1); | 
					
						
							| 
									
										
										
										
											2012-06-12 06:10:23 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-13 09:21:10 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST(optimize, ConjugateGradientOptimizer) { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   pose2SLAM::Graph graph ; | 
					
						
							|  |  |  |   pose2SLAM::Values initialEstimate; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   boost::tie(graph, initialEstimate) = generateProblem(); | 
					
						
							|  |  |  | //  cout << "initial error = " << graph.error(initialEstimate) << endl ;
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Single Step Optimization using Levenberg-Marquardt
 | 
					
						
							|  |  |  |   NonlinearOptimizerParams param; | 
					
						
							|  |  |  |   param.maxIterations = 500;    /* requires a larger number of iterations to converge */ | 
					
						
							|  |  |  |   param.verbosity = NonlinearOptimizerParams::SILENT; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   ConjugateGradientOptimizer optimizer(graph, initialEstimate, param, true); | 
					
						
							|  |  |  |   Values result = optimizer.optimize(); | 
					
						
							|  |  |  | //  cout << "cg final error = " << graph.error(result) << endl;
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /* the optimality of the solution is not comparable to the */ | 
					
						
							|  |  |  |   DOUBLES_EQUAL(0.0, graph.error(result), 1e-2); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-12 22:19:01 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST(optimize, GradientDescentOptimizer2) { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   pose2SLAM::Graph graph ; | 
					
						
							|  |  |  |   pose2SLAM::Values initialEstimate; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   boost::tie(graph, initialEstimate) = generateProblem(); | 
					
						
							|  |  |  | //  cout << "initial error = " << graph.error(initialEstimate) << endl ;
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Single Step Optimization using Levenberg-Marquardt
 | 
					
						
							| 
									
										
										
										
											2012-06-13 09:21:10 +08:00
										 |  |  |   NonlinearOptimizerParams param; | 
					
						
							| 
									
										
										
										
											2012-06-12 22:19:01 +08:00
										 |  |  |   param.maxIterations = 500;    /* requires a larger number of iterations to converge */ | 
					
						
							| 
									
										
										
										
											2012-06-12 22:20:08 +08:00
										 |  |  |   param.verbosity = NonlinearOptimizerParams::SILENT; | 
					
						
							| 
									
										
										
										
											2012-06-12 22:19:01 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-13 09:21:10 +08:00
										 |  |  |   ConjugateGradientOptimizer optimizer(graph, initialEstimate, param, false); | 
					
						
							| 
									
										
										
										
											2012-06-12 22:19:01 +08:00
										 |  |  |   Values result = optimizer.optimize(); | 
					
						
							| 
									
										
										
										
											2012-06-13 09:21:10 +08:00
										 |  |  | //  cout << "gd2 solver final error = " << graph.error(result) << endl;
 | 
					
						
							| 
									
										
										
										
											2012-06-12 22:19:01 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /* the optimality of the solution is not comparable to the */ | 
					
						
							|  |  |  |   DOUBLES_EQUAL(0.0, graph.error(result), 1e-2); | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2012-06-12 06:10:23 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-13 09:21:10 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-12 06:10:23 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | int main() { TestResult tr; return TestRegistry::runAllTests(tr); } | 
					
						
							|  |  |  | /* ************************************************************************* */ |