| 
									
										
										
										
											2014-05-16 22:03:18 +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 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							| 
									
										
										
										
											2014-05-21 06:12:26 +08:00
										 |  |  |  * @file Pose2SLAMExample_g2o.cpp | 
					
						
							|  |  |  |  * @brief A 2D Pose SLAM example that reads input from g2o, converts it to a factor graph and does the | 
					
						
							|  |  |  |  * optimization. Output is written on a file, in g2o format | 
					
						
							|  |  |  |  * Syntax for the script is ./Pose2SLAMExample_g2o input.g2o output.g2o | 
					
						
							| 
									
										
										
										
											2014-05-16 22:03:18 +08:00
										 |  |  |  * @date May 15, 2014 | 
					
						
							|  |  |  |  * @author Luca Carlone | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam/slam/dataset.h>
 | 
					
						
							| 
									
										
										
										
											2014-06-01 00:51:47 +08:00
										 |  |  | #include <gtsam/slam/PriorFactor.h>
 | 
					
						
							| 
									
										
										
										
											2014-05-16 22:03:18 +08:00
										 |  |  | #include <gtsam/nonlinear/GaussNewtonOptimizer.h>
 | 
					
						
							|  |  |  | #include <fstream>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-10-17 02:39:23 +08:00
										 |  |  | // HOWTO: ./Pose2SLAMExample_g2o inputFile outputFile (maxIterations) (tukey/huber)
 | 
					
						
							| 
									
										
										
										
											2014-06-01 00:51:47 +08:00
										 |  |  | int main(const int argc, const char *argv[]) { | 
					
						
							| 
									
										
										
										
											2014-05-16 22:03:18 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-10-17 02:39:23 +08:00
										 |  |  |   string kernelType = "none"; | 
					
						
							|  |  |  |   int maxIterations = 100; // default
 | 
					
						
							|  |  |  |   string g2oFile = findExampleDataFile("noisyToyGraph.txt"); // default
 | 
					
						
							| 
									
										
										
										
											2014-05-16 22:03:18 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-10-17 02:39:23 +08:00
										 |  |  |   // Parse user's inputs
 | 
					
						
							|  |  |  |   if (argc > 1){ | 
					
						
							|  |  |  |     g2oFile = argv[1]; // input dataset filename
 | 
					
						
							|  |  |  |     // outputFile = g2oFile = argv[2]; // done later
 | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  |   if (argc > 3){ | 
					
						
							|  |  |  |     maxIterations = atoi(argv[3]); // user can specify either tukey or huber
 | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  |   if (argc > 4){ | 
					
						
							|  |  |  |     kernelType = argv[4]; // user can specify either tukey or huber
 | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // reading file and creating factor graph
 | 
					
						
							| 
									
										
										
										
											2014-06-01 23:46:23 +08:00
										 |  |  |   NonlinearFactorGraph::shared_ptr graph; | 
					
						
							|  |  |  |   Values::shared_ptr initial; | 
					
						
							| 
									
										
										
										
											2014-10-17 02:39:23 +08:00
										 |  |  |   bool is3D = false; | 
					
						
							|  |  |  |   if(kernelType.compare("none") == 0){ | 
					
						
							|  |  |  |     boost::tie(graph, initial) = readG2o(g2oFile,is3D); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  |   if(kernelType.compare("huber") == 0){ | 
					
						
							|  |  |  |     std::cout << "Using robust kernel: huber " << std::endl; | 
					
						
							|  |  |  |     boost::tie(graph, initial) = readG2o(g2oFile,is3D, KernelFunctionTypeHUBER); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  |   if(kernelType.compare("tukey") == 0){ | 
					
						
							|  |  |  |     std::cout << "Using robust kernel: tukey " << std::endl; | 
					
						
							|  |  |  |     boost::tie(graph, initial) = readG2o(g2oFile,is3D, KernelFunctionTypeTUKEY); | 
					
						
							|  |  |  |   } | 
					
						
							| 
									
										
										
										
											2014-05-19 22:53:59 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-05-21 04:53:58 +08:00
										 |  |  |   // Add prior on the pose having index (key) = 0
 | 
					
						
							| 
									
										
										
										
											2014-06-01 23:46:23 +08:00
										 |  |  |   NonlinearFactorGraph graphWithPrior = *graph; | 
					
						
							| 
									
										
										
										
											2014-06-01 00:51:47 +08:00
										 |  |  |   noiseModel::Diagonal::shared_ptr priorModel = //
 | 
					
						
							|  |  |  |       noiseModel::Diagonal::Variances((Vector(3) << 1e-6, 1e-6, 1e-8)); | 
					
						
							| 
									
										
										
										
											2014-05-17 08:50:06 +08:00
										 |  |  |   graphWithPrior.add(PriorFactor<Pose2>(0, Pose2(), priorModel)); | 
					
						
							| 
									
										
										
										
											2014-10-17 02:39:23 +08:00
										 |  |  |   std::cout << "Adding prior on pose 0 " << std::endl; | 
					
						
							| 
									
										
										
										
											2014-05-16 22:03:18 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-09-10 21:35:49 +08:00
										 |  |  |   GaussNewtonParams params; | 
					
						
							|  |  |  |   params.setVerbosity("TERMINATION"); | 
					
						
							| 
									
										
										
										
											2014-10-17 02:39:23 +08:00
										 |  |  |   if (argc > 3) { | 
					
						
							|  |  |  |     params.maxIterations = maxIterations; | 
					
						
							|  |  |  |     std::cout << "User required to perform maximum  " << params.maxIterations << " iterations "<< std::endl; | 
					
						
							| 
									
										
										
										
											2014-09-10 21:35:49 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-05-16 22:03:18 +08:00
										 |  |  |   std::cout << "Optimizing the factor graph" << std::endl; | 
					
						
							| 
									
										
										
										
											2014-09-10 21:35:49 +08:00
										 |  |  |   GaussNewtonOptimizer optimizer(graphWithPrior, *initial, params); | 
					
						
							| 
									
										
										
										
											2014-05-16 22:03:18 +08:00
										 |  |  |   Values result = optimizer.optimize(); | 
					
						
							|  |  |  |   std::cout << "Optimization complete" << std::endl; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-09-10 21:35:49 +08:00
										 |  |  |   std::cout << "initial error=" <<graph->error(*initial)<< std::endl; | 
					
						
							|  |  |  |   std::cout << "final error=" <<graph->error(result)<< std::endl; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-06-01 00:51:47 +08:00
										 |  |  |   if (argc < 3) { | 
					
						
							|  |  |  |     result.print("result"); | 
					
						
							|  |  |  |   } else { | 
					
						
							|  |  |  |     const string outputFile = argv[2]; | 
					
						
							|  |  |  |     std::cout << "Writing results to file: " << outputFile << std::endl; | 
					
						
							| 
									
										
										
										
											2014-10-17 02:39:23 +08:00
										 |  |  |     NonlinearFactorGraph::shared_ptr graphNoKernel; | 
					
						
							|  |  |  |     Values::shared_ptr initial2; | 
					
						
							|  |  |  |     boost::tie(graphNoKernel, initial2) = readG2o(g2oFile); | 
					
						
							|  |  |  |     writeG2o(*graphNoKernel, result, outputFile); | 
					
						
							| 
									
										
										
										
											2014-06-01 00:51:47 +08:00
										 |  |  |     std::cout << "done! " << std::endl; | 
					
						
							|  |  |  |   } | 
					
						
							| 
									
										
										
										
											2014-05-16 22:03:18 +08:00
										 |  |  |   return 0; | 
					
						
							|  |  |  | } |