| 
									
										
										
										
											2012-09-29 01:48:49 +08:00
										 |  |  | /* ----------------------------------------------------------------------------
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-09 06:40:47 +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) | 
					
						
							| 
									
										
										
										
											2012-09-29 01:48:49 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-09 06:40:47 +08:00
										 |  |  | * See LICENSE for the license information | 
					
						
							|  |  |  | * -------------------------------------------------------------------------- */ | 
					
						
							| 
									
										
										
										
											2012-09-29 01:48:49 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							| 
									
										
										
										
											2012-10-09 06:40:47 +08:00
										 |  |  | * @file    timeBatch.cpp | 
					
						
							|  |  |  | * @brief   Overall timing tests for batch solving | 
					
						
							|  |  |  | * @author  Richard Roberts | 
					
						
							|  |  |  | */ | 
					
						
							| 
									
										
										
										
											2012-09-29 01:48:49 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam/base/timing.h>
 | 
					
						
							|  |  |  | #include <gtsam/slam/dataset.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
 | 
					
						
							| 
									
										
										
										
											2012-10-09 06:40:47 +08:00
										 |  |  | #include <gtsam/nonlinear/Marginals.h>
 | 
					
						
							| 
									
										
										
										
											2012-09-29 01:48:49 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | int main(int argc, char *argv[]) { | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-09 06:40:47 +08:00
										 |  |  |   try { | 
					
						
							| 
									
										
										
										
											2012-09-29 01:48:49 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-09 06:40:47 +08:00
										 |  |  |     cout << "Loading data..." << endl; | 
					
						
							| 
									
										
										
										
											2012-09-29 01:48:49 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2022-02-28 04:06:56 +08:00
										 |  |  |     string datasetFile = findExampleDataFile("w10000"); | 
					
						
							| 
									
										
										
										
											2025-01-25 04:02:18 +08:00
										 |  |  |     auto [graph, initial] = load2D(datasetFile); | 
					
						
							|  |  |  |     graph->addPrior(0, initial->at<Pose2>(0), noiseModel::Unit::Create(3)); | 
					
						
							| 
									
										
										
										
											2012-09-29 01:48:49 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-09 06:40:47 +08:00
										 |  |  |     cout << "Optimizing..." << endl; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     gttic_(Create_optimizer); | 
					
						
							| 
									
										
										
										
											2025-01-25 04:02:18 +08:00
										 |  |  |     LevenbergMarquardtOptimizer optimizer(*graph, *initial); | 
					
						
							| 
									
										
										
										
											2012-10-09 06:40:47 +08:00
										 |  |  |     gttoc_(Create_optimizer); | 
					
						
							| 
									
										
										
										
											2012-09-29 01:48:49 +08:00
										 |  |  |     tictoc_print_(); | 
					
						
							| 
									
										
										
										
											2025-01-25 04:02:18 +08:00
										 |  |  |     tictoc_reset_(); | 
					
						
							| 
									
										
										
										
											2012-10-09 06:40:47 +08:00
										 |  |  |     double lastError = optimizer.error(); | 
					
						
							|  |  |  |     do { | 
					
						
							|  |  |  |       gttic_(Iterate_optimizer); | 
					
						
							|  |  |  |       optimizer.iterate(); | 
					
						
							|  |  |  |       gttoc_(Iterate_optimizer); | 
					
						
							|  |  |  |       tictoc_finishedIteration_(); | 
					
						
							|  |  |  |       tictoc_print_(); | 
					
						
							|  |  |  |       cout << "Error: " << optimizer.error() << ", lambda: " << optimizer.lambda() << endl; | 
					
						
							|  |  |  |       break; | 
					
						
							|  |  |  |     } while(!checkConvergence(optimizer.params().relativeErrorTol, | 
					
						
							|  |  |  |       optimizer.params().absoluteErrorTol, optimizer.params().errorTol, | 
					
						
							|  |  |  |       lastError, optimizer.error(), optimizer.params().verbosity)); | 
					
						
							| 
									
										
										
										
											2025-01-25 04:02:18 +08:00
										 |  |  |     tictoc_reset_(); | 
					
						
							| 
									
										
										
										
											2012-10-09 06:40:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     // Compute marginals
 | 
					
						
							| 
									
										
										
										
											2025-01-25 04:02:18 +08:00
										 |  |  |     gttic_(ConstructMarginals); | 
					
						
							|  |  |  |     Marginals marginals(*graph, optimizer.values()); | 
					
						
							|  |  |  |     gttoc_(ConstructMarginals); | 
					
						
							|  |  |  |     for(Key key: initial->keys()) { | 
					
						
							| 
									
										
										
										
											2012-10-09 06:40:47 +08:00
										 |  |  |       gttic_(marginalInformation); | 
					
						
							|  |  |  |       Matrix info = marginals.marginalInformation(key); | 
					
						
							|  |  |  |       gttoc_(marginalInformation); | 
					
						
							|  |  |  |       tictoc_finishedIteration_(); | 
					
						
							|  |  |  |     } | 
					
						
							| 
									
										
										
										
											2025-01-25 04:02:18 +08:00
										 |  |  |     tictoc_print_(); | 
					
						
							| 
									
										
										
										
											2012-10-09 06:40:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   } catch(std::exception& e) { | 
					
						
							|  |  |  |     cout << e.what() << endl; | 
					
						
							|  |  |  |     return 1; | 
					
						
							|  |  |  |   } | 
					
						
							| 
									
										
										
										
											2012-09-29 01:48:49 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   return 0; | 
					
						
							|  |  |  | } |