| 
									
										
										
										
											2013-08-01 02:53:26 +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 | 
					
						
							|  |  |  | * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							| 
									
										
										
										
											2013-11-08 05:41:23 +08:00
										 |  |  | * @file    SolverComparer.cpp | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  | * @brief   Incremental and batch solving, timing, and accuracy comparisons | 
					
						
							|  |  |  | * @author  Richard Roberts | 
					
						
							| 
									
										
										
										
											2013-11-08 05:41:23 +08:00
										 |  |  | * @date    August, 2013 | 
					
						
							| 
									
										
										
										
											2014-09-30 17:31:17 +08:00
										 |  |  | * | 
					
						
							|  |  |  | * Here is an example. Below, to run in batch mode, we first generate an initialization in incremental mode. | 
					
						
							|  |  |  | * | 
					
						
							|  |  |  | * Solve in incremental and write to file w_inc: | 
					
						
							|  |  |  | * ./SolverComparer --incremental -d w10000 -o w_inc | 
					
						
							|  |  |  | * | 
					
						
							|  |  |  | * You can then perturb that initialization to get batch something to optimize. | 
					
						
							|  |  |  | * Read in w_inc, perturb it with noise of stddev 0.6, and write to w_pert: | 
					
						
							|  |  |  | * ./SolverComparer --perturb 0.6 -i w_inc -o w_pert | 
					
						
							|  |  |  | * | 
					
						
							|  |  |  | * Then optimize with batch, read in w_pert, solve in batch, and write to w_batch: | 
					
						
							|  |  |  | * ./SolverComparer --batch -d w10000 -i w_pert -o w_batch | 
					
						
							|  |  |  | * | 
					
						
							|  |  |  | * And finally compare solutions in w_inc and w_batch to check that batch converged to the global minimum | 
					
						
							|  |  |  | * ./SolverComparer --compare w_inc w_batch | 
					
						
							|  |  |  | * | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  | */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam/slam/BetweenFactor.h>
 | 
					
						
							| 
									
										
										
										
											2015-07-13 09:57:26 +08:00
										 |  |  | #include <gtsam/sam/BearingRangeFactor.h>
 | 
					
						
							| 
									
										
										
										
											2015-05-13 06:05:34 +08:00
										 |  |  | #include <gtsam/slam/dataset.h>
 | 
					
						
							|  |  |  | #include <gtsam/slam/PriorFactor.h>
 | 
					
						
							|  |  |  | #include <gtsam/geometry/Pose2.h>
 | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  | #include <gtsam/nonlinear/ISAM2.h>
 | 
					
						
							| 
									
										
										
										
											2013-08-01 23:38:15 +08:00
										 |  |  | #include <gtsam/nonlinear/GaussNewtonOptimizer.h>
 | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  | #include <gtsam/nonlinear/Marginals.h>
 | 
					
						
							| 
									
										
										
										
											2015-05-13 06:05:34 +08:00
										 |  |  | #include <gtsam/linear/GaussianJunctionTree.h>
 | 
					
						
							|  |  |  | #include <gtsam/linear/GaussianEliminationTree.h>
 | 
					
						
							|  |  |  | #include <gtsam/inference/Symbol.h>
 | 
					
						
							|  |  |  | #include <gtsam/base/timing.h>
 | 
					
						
							|  |  |  | #include <gtsam/base/treeTraversal-inst.h>
 | 
					
						
							| 
									
										
										
										
											2015-06-22 09:14:20 +08:00
										 |  |  | #include <gtsam/config.h> // for GTSAM_USE_TBB
 | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | #include <boost/archive/binary_iarchive.hpp>
 | 
					
						
							| 
									
										
										
										
											2015-05-13 06:05:34 +08:00
										 |  |  | #include <boost/archive/binary_oarchive.hpp>
 | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  | #include <boost/program_options.hpp>
 | 
					
						
							|  |  |  | #include <boost/range/algorithm/set_algorithm.hpp>
 | 
					
						
							| 
									
										
										
										
											2016-05-23 05:11:42 +08:00
										 |  |  | #include <boost/range/adaptor/reversed.hpp>
 | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  | #include <boost/random.hpp>
 | 
					
						
							| 
									
										
										
										
											2015-05-13 06:05:34 +08:00
										 |  |  | #include <boost/serialization/export.hpp>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <fstream>
 | 
					
						
							|  |  |  | #include <iostream>
 | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-19 23:51:06 +08:00
										 |  |  | #ifdef GTSAM_USE_TBB
 | 
					
						
							| 
									
										
										
										
											2013-08-15 03:47:30 +08:00
										 |  |  | #include <tbb/tbb.h>
 | 
					
						
							|  |  |  | #undef max // TBB seems to include windows.h and we don't want these macros
 | 
					
						
							|  |  |  | #undef min
 | 
					
						
							| 
									
										
										
										
											2013-08-19 23:51:06 +08:00
										 |  |  | #endif
 | 
					
						
							| 
									
										
										
										
											2013-08-15 03:47:30 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | using namespace gtsam::symbol_shorthand; | 
					
						
							|  |  |  | namespace po = boost::program_options; | 
					
						
							|  |  |  | namespace br = boost::range; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | typedef Pose2 Pose; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | typedef NoiseModelFactor1<Pose> NM1; | 
					
						
							|  |  |  | typedef NoiseModelFactor2<Pose,Pose> NM2; | 
					
						
							|  |  |  | typedef BearingRangeFactor<Pose,Point2> BR; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | double chi2_red(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& config) { | 
					
						
							|  |  |  |   // Compute degrees of freedom (observations - variables)
 | 
					
						
							|  |  |  |   // In ocaml, +1 was added to the observations to account for the prior, but
 | 
					
						
							|  |  |  |   // the factor graph already includes a factor for the prior/equality constraint.
 | 
					
						
							|  |  |  |   //  double dof = graph.size() - config.size();
 | 
					
						
							|  |  |  |   int graph_dim = 0; | 
					
						
							| 
									
										
										
										
											2016-05-20 21:20:03 +08:00
										 |  |  |   for(const boost::shared_ptr<gtsam::NonlinearFactor>& nlf: graph) { | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |     graph_dim += (int)nlf->dim(); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  |   double dof = double(graph_dim) - double(config.dim()); // kaess: changed to dim
 | 
					
						
							|  |  |  |   return 2. * graph.error(config) / dof; // kaess: added factor 2, graph.error returns half of actual error
 | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // Global variables (these are only set once at program startup and never modified after)
 | 
					
						
							|  |  |  | string outputFile; | 
					
						
							|  |  |  | string inputFile; | 
					
						
							|  |  |  | string datasetName; | 
					
						
							|  |  |  | int firstStep; | 
					
						
							|  |  |  | int lastStep; | 
					
						
							| 
									
										
										
										
											2013-08-15 03:47:30 +08:00
										 |  |  | int nThreads; | 
					
						
							| 
									
										
										
										
											2013-08-16 04:16:59 +08:00
										 |  |  | int relinSkip; | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  | bool incremental; | 
					
						
							| 
									
										
										
										
											2014-02-23 06:13:32 +08:00
										 |  |  | bool dogleg; | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  | bool batch; | 
					
						
							|  |  |  | bool compare; | 
					
						
							|  |  |  | bool perturb; | 
					
						
							| 
									
										
										
										
											2013-11-08 05:41:23 +08:00
										 |  |  | bool stats; | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  | double perturbationNoise; | 
					
						
							|  |  |  | string compareFile1, compareFile2; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | Values initial; | 
					
						
							| 
									
										
										
										
											2013-08-01 23:38:15 +08:00
										 |  |  | NonlinearFactorGraph datasetMeasurements; | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | // Run functions for each mode
 | 
					
						
							|  |  |  | void runIncremental(); | 
					
						
							|  |  |  | void runBatch(); | 
					
						
							|  |  |  | void runCompare(); | 
					
						
							|  |  |  | void runPerturb(); | 
					
						
							| 
									
										
										
										
											2013-11-08 05:41:23 +08:00
										 |  |  | void runStats(); | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | int main(int argc, char *argv[]) { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   po::options_description desc("Available options"); | 
					
						
							|  |  |  |   desc.add_options() | 
					
						
							|  |  |  |     ("help", "Print help message") | 
					
						
							|  |  |  |     ("write-solution,o", po::value<string>(&outputFile)->default_value(""), "Write graph and solution to the specified file") | 
					
						
							|  |  |  |     ("read-solution,i", po::value<string>(&inputFile)->default_value(""), "Read graph and solution from the specified file") | 
					
						
							|  |  |  |     ("dataset,d", po::value<string>(&datasetName)->default_value(""), "Read a dataset file (if and only if --incremental is used)") | 
					
						
							|  |  |  |     ("first-step,f", po::value<int>(&firstStep)->default_value(0), "First step to process from the dataset file") | 
					
						
							|  |  |  |     ("last-step,l", po::value<int>(&lastStep)->default_value(-1), "Last step to process, or -1 to process until the end of the dataset") | 
					
						
							| 
									
										
										
										
											2013-08-15 03:47:30 +08:00
										 |  |  |     ("threads", po::value<int>(&nThreads)->default_value(-1), "Number of threads, or -1 to use all processors") | 
					
						
							| 
									
										
										
										
											2013-08-16 04:16:59 +08:00
										 |  |  |     ("relinSkip", po::value<int>(&relinSkip)->default_value(10), "Fluid relinearization check every arg steps") | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |     ("incremental", "Run in incremental mode using ISAM2 (default)") | 
					
						
							| 
									
										
										
										
											2014-02-23 06:13:32 +08:00
										 |  |  |     ("dogleg", "When in incremental mode, solve with Dogleg instead of Gauss-Newton in iSAM2") | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |     ("batch", "Run in batch mode, requires an initialization from --read-solution") | 
					
						
							|  |  |  |     ("compare", po::value<vector<string> >()->multitoken(), "Compare two solution files") | 
					
						
							|  |  |  |     ("perturb", po::value<double>(&perturbationNoise), "Perturb a solution file with the specified noise") | 
					
						
							| 
									
										
										
										
											2013-11-08 05:41:23 +08:00
										 |  |  |     ("stats", "Gather factorization statistics about the dataset, writes text-file histograms") | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |     ; | 
					
						
							|  |  |  |   po::variables_map vm; | 
					
						
							|  |  |  |   po::store(po::command_line_parser(argc, argv).options(desc).run(), vm); | 
					
						
							|  |  |  |   po::notify(vm); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   batch = (vm.count("batch") > 0); | 
					
						
							|  |  |  |   compare = (vm.count("compare") > 0); | 
					
						
							|  |  |  |   perturb = (vm.count("perturb") > 0); | 
					
						
							| 
									
										
										
										
											2013-11-08 05:41:23 +08:00
										 |  |  |   stats = (vm.count("stats") > 0); | 
					
						
							|  |  |  |   const int modesSpecified = int(batch) + int(compare) + int(perturb) + int(stats); | 
					
						
							|  |  |  |   incremental = (vm.count("incremental") > 0 || modesSpecified == 0); | 
					
						
							| 
									
										
										
										
											2014-02-23 06:13:32 +08:00
										 |  |  |   dogleg = (vm.count("dogleg") > 0); | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |   if(compare) { | 
					
						
							|  |  |  |     const vector<string>& compareFiles = vm["compare"].as<vector<string> >(); | 
					
						
							|  |  |  |     if(compareFiles.size() != 2) { | 
					
						
							|  |  |  |       cout << "Must specify two files with --compare"; | 
					
						
							|  |  |  |       exit(1); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |     compareFile1 = compareFiles[0]; | 
					
						
							|  |  |  |     compareFile2 = compareFiles[1]; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-11-08 05:41:23 +08:00
										 |  |  |   if(modesSpecified > 1) { | 
					
						
							|  |  |  |     cout << "Only one of --incremental, --batch, --compare, --perturb, and --stats may be specified\n" << desc << endl; | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |     exit(1); | 
					
						
							|  |  |  |   } | 
					
						
							| 
									
										
										
										
											2013-08-01 23:38:15 +08:00
										 |  |  |   if((incremental || batch) && datasetName.empty()) { | 
					
						
							|  |  |  |     cout << "In incremental and batch modes, a dataset must be specified\n" << desc << endl; | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |     exit(1); | 
					
						
							|  |  |  |   } | 
					
						
							| 
									
										
										
										
											2013-11-08 05:41:23 +08:00
										 |  |  |   if(!(incremental || batch || stats) && !datasetName.empty()) { | 
					
						
							| 
									
										
										
										
											2013-08-01 23:38:15 +08:00
										 |  |  |     cout << "A dataset may only be specified in incremental or batch modes\n" << desc << endl; | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |     exit(1); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  |   if(batch && inputFile.empty()) { | 
					
						
							|  |  |  |     cout << "In batch model, an input file must be specified\n" << desc << endl; | 
					
						
							|  |  |  |     exit(1); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  |   if(perturb && (inputFile.empty() || outputFile.empty())) { | 
					
						
							|  |  |  |     cout << "In perturb mode, specify input and output files\n" << desc << endl; | 
					
						
							|  |  |  |     exit(1); | 
					
						
							|  |  |  |   } | 
					
						
							| 
									
										
										
										
											2013-11-08 05:41:23 +08:00
										 |  |  |   if(stats && (datasetName.empty() || inputFile.empty())) { | 
					
						
							|  |  |  |     cout << "In stats mode, specify dataset and input file\n" << desc << endl; | 
					
						
							|  |  |  |     exit(1); | 
					
						
							|  |  |  |   } | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Read input file
 | 
					
						
							|  |  |  |   if(!inputFile.empty()) | 
					
						
							|  |  |  |   { | 
					
						
							|  |  |  |     cout << "Reading input file " << inputFile << endl; | 
					
						
							| 
									
										
										
										
											2013-08-02 21:33:23 +08:00
										 |  |  |     std::ifstream readerStream(inputFile.c_str(), ios::binary); | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |     boost::archive::binary_iarchive reader(readerStream); | 
					
						
							| 
									
										
										
										
											2013-08-01 23:38:15 +08:00
										 |  |  |     reader >> initial; | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-01 23:38:15 +08:00
										 |  |  |   // Read dataset
 | 
					
						
							|  |  |  |   if(!datasetName.empty()) | 
					
						
							|  |  |  |   { | 
					
						
							|  |  |  |     cout << "Loading dataset " << datasetName << endl; | 
					
						
							| 
									
										
										
										
											2013-08-12 03:26:29 +08:00
										 |  |  |     try { | 
					
						
							|  |  |  |       string datasetFile = findExampleDataFile(datasetName); | 
					
						
							|  |  |  |       std::pair<NonlinearFactorGraph::shared_ptr, Values::shared_ptr> data = | 
					
						
							|  |  |  |         load2D(datasetFile); | 
					
						
							|  |  |  |       datasetMeasurements = *data.first; | 
					
						
							|  |  |  |     } catch(std::exception& e) { | 
					
						
							|  |  |  |       cout << e.what() << endl; | 
					
						
							|  |  |  |       exit(1); | 
					
						
							|  |  |  |     } | 
					
						
							| 
									
										
										
										
											2013-08-01 23:38:15 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-19 23:51:06 +08:00
										 |  |  | #ifdef GTSAM_USE_TBB
 | 
					
						
							| 
									
										
										
										
											2018-10-09 09:38:50 +08:00
										 |  |  |   std::unique_ptr<tbb::task_scheduler_init> init; | 
					
						
							| 
									
										
										
										
											2013-08-15 06:53:57 +08:00
										 |  |  |   if(nThreads > 0) { | 
					
						
							|  |  |  |     cout << "Using " << nThreads << " threads" << endl; | 
					
						
							| 
									
										
										
										
											2013-08-15 03:47:30 +08:00
										 |  |  |     init.reset(new tbb::task_scheduler_init(nThreads)); | 
					
						
							| 
									
										
										
										
											2013-08-15 06:53:57 +08:00
										 |  |  |   } else | 
					
						
							|  |  |  |     cout << "Using threads for all processors" << endl; | 
					
						
							| 
									
										
										
										
											2013-08-19 23:51:06 +08:00
										 |  |  | #else
 | 
					
						
							|  |  |  |   if(nThreads > 0) { | 
					
						
							|  |  |  |     std::cout << "GTSAM is not compiled with TBB, so threading is disabled and the --threads option cannot be used." << endl; | 
					
						
							|  |  |  |     exit(1); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | #endif
 | 
					
						
							| 
									
										
										
										
											2013-08-01 23:38:15 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |   // Run mode
 | 
					
						
							|  |  |  |   if(incremental) | 
					
						
							|  |  |  |     runIncremental(); | 
					
						
							|  |  |  |   else if(batch) | 
					
						
							|  |  |  |     runBatch(); | 
					
						
							|  |  |  |   else if(compare) | 
					
						
							|  |  |  |     runCompare(); | 
					
						
							|  |  |  |   else if(perturb) | 
					
						
							|  |  |  |     runPerturb(); | 
					
						
							| 
									
										
										
										
											2013-11-08 05:41:23 +08:00
										 |  |  |   else if(stats) | 
					
						
							|  |  |  |     runStats(); | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   return 0; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | void runIncremental() | 
					
						
							|  |  |  | { | 
					
						
							| 
									
										
										
										
											2013-08-16 04:16:59 +08:00
										 |  |  |   ISAM2Params params; | 
					
						
							| 
									
										
										
										
											2014-02-23 06:13:32 +08:00
										 |  |  |   if(dogleg) | 
					
						
							|  |  |  |     params.optimizationParams = ISAM2DoglegParams(); | 
					
						
							| 
									
										
										
										
											2013-08-16 04:16:59 +08:00
										 |  |  |   params.relinearizeSkip = relinSkip; | 
					
						
							|  |  |  |   params.enablePartialRelinearizationCheck = true; | 
					
						
							|  |  |  |   ISAM2 isam2(params); | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Look for the first measurement to use
 | 
					
						
							|  |  |  |   cout << "Looking for first measurement from step " << firstStep << endl; | 
					
						
							|  |  |  |   size_t nextMeasurement = 0; | 
					
						
							|  |  |  |   bool havePreviousPose = false; | 
					
						
							|  |  |  |   Key firstPose; | 
					
						
							|  |  |  |   while(nextMeasurement < datasetMeasurements.size()) | 
					
						
							|  |  |  |   { | 
					
						
							| 
									
										
										
										
											2018-11-07 02:28:47 +08:00
										 |  |  |     if(BetweenFactor<Pose>::shared_ptr factor = | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |       boost::dynamic_pointer_cast<BetweenFactor<Pose> >(datasetMeasurements[nextMeasurement])) | 
					
						
							|  |  |  |     { | 
					
						
							| 
									
										
										
										
											2018-11-07 02:28:47 +08:00
										 |  |  |       Key key1 = factor->key1(), key2 = factor->key2(); | 
					
						
							| 
									
										
										
										
											2015-05-13 06:07:49 +08:00
										 |  |  |       if(((int)key1 >= firstStep && key1 < key2) || ((int)key2 >= firstStep && key2 < key1)) { | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |         // We found an odometry starting at firstStep
 | 
					
						
							|  |  |  |         firstPose = std::min(key1, key2); | 
					
						
							|  |  |  |         break; | 
					
						
							|  |  |  |       } | 
					
						
							| 
									
										
										
										
											2015-05-13 06:07:49 +08:00
										 |  |  |       if(((int)key2 >= firstStep && key1 < key2) || ((int)key1 >= firstStep && key2 < key1)) { | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |         // We found an odometry joining firstStep with a previous pose
 | 
					
						
							|  |  |  |         havePreviousPose = true; | 
					
						
							|  |  |  |         firstPose = std::max(key1, key2); | 
					
						
							|  |  |  |         break; | 
					
						
							|  |  |  |       } | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |     ++ nextMeasurement; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   if(nextMeasurement == datasetMeasurements.size()) { | 
					
						
							|  |  |  |     cout << "The supplied first step is past the end of the dataset" << endl; | 
					
						
							|  |  |  |     exit(1); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // If we didn't find an odometry linking to a previous pose, create a first pose and a prior
 | 
					
						
							|  |  |  |   if(!havePreviousPose) { | 
					
						
							|  |  |  |     cout << "Looks like " << firstPose << " is the first time step, so adding a prior on it" << endl; | 
					
						
							|  |  |  |     NonlinearFactorGraph newFactors; | 
					
						
							|  |  |  |     Values newVariables; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-12-29 00:13:11 +08:00
										 |  |  |     newFactors.push_back(boost::make_shared<PriorFactor<Pose> >(firstPose, Pose(), noiseModel::Unit::Create(3))); | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |     newVariables.insert(firstPose, Pose()); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     isam2.update(newFactors, newVariables); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   cout << "Playing forward time steps..." << endl; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-05-13 06:05:34 +08:00
										 |  |  |   for (size_t step = firstPose; | 
					
						
							|  |  |  |       nextMeasurement < datasetMeasurements.size() && (lastStep == -1 || (int)step <= lastStep); | 
					
						
							|  |  |  |       ++step) | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |   { | 
					
						
							|  |  |  |     Values newVariables; | 
					
						
							|  |  |  |     NonlinearFactorGraph newFactors; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     // Collect measurements and new variables for the current step
 | 
					
						
							|  |  |  |     gttic_(Collect_measurements); | 
					
						
							|  |  |  |     while(nextMeasurement < datasetMeasurements.size()) { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |       NonlinearFactor::shared_ptr measurementf = datasetMeasurements[nextMeasurement]; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2018-11-07 02:28:47 +08:00
										 |  |  |       if(BetweenFactor<Pose>::shared_ptr factor = | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |         boost::dynamic_pointer_cast<BetweenFactor<Pose> >(measurementf)) | 
					
						
							|  |  |  |       { | 
					
						
							|  |  |  |         // Stop collecting measurements that are for future steps
 | 
					
						
							| 
									
										
										
										
											2018-11-07 02:28:47 +08:00
										 |  |  |         if(factor->key1() > step || factor->key2() > step) | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |           break; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |         // Require that one of the nodes is the current one
 | 
					
						
							| 
									
										
										
										
											2018-11-07 02:28:47 +08:00
										 |  |  |         if(factor->key1() != step && factor->key2() != step) | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |           throw runtime_error("Problem in data file, out-of-sequence measurements"); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |         // Add a new factor
 | 
					
						
							| 
									
										
										
										
											2018-11-07 02:28:47 +08:00
										 |  |  |         newFactors.push_back(factor); | 
					
						
							|  |  |  |         const auto& measured = factor->measured(); | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |         // Initialize the new variable
 | 
					
						
							| 
									
										
										
										
											2018-11-07 02:28:47 +08:00
										 |  |  |         if(factor->key1() > factor->key2()) { | 
					
						
							|  |  |  |           if(!newVariables.exists(factor->key1())) { // Only need to check newVariables since loop closures come after odometry
 | 
					
						
							| 
									
										
										
										
											2013-08-12 03:26:29 +08:00
										 |  |  |             if(step == 1) | 
					
						
							| 
									
										
										
										
											2018-11-07 02:28:47 +08:00
										 |  |  |               newVariables.insert(factor->key1(), measured.inverse()); | 
					
						
							| 
									
										
										
										
											2013-08-12 03:26:29 +08:00
										 |  |  |             else { | 
					
						
							| 
									
										
										
										
											2018-11-07 02:28:47 +08:00
										 |  |  |               Pose prevPose = isam2.calculateEstimate<Pose>(factor->key2()); | 
					
						
							|  |  |  |               newVariables.insert(factor->key1(), prevPose * measured.inverse()); | 
					
						
							| 
									
										
										
										
											2013-08-12 03:26:29 +08:00
										 |  |  |             } | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |           } | 
					
						
							|  |  |  |         } else { | 
					
						
							| 
									
										
										
										
											2018-11-07 02:28:47 +08:00
										 |  |  |           if(!newVariables.exists(factor->key2())) { // Only need to check newVariables since loop closures come after odometry
 | 
					
						
							| 
									
										
										
										
											2013-08-12 03:26:29 +08:00
										 |  |  |             if(step == 1) | 
					
						
							| 
									
										
										
										
											2018-11-07 02:28:47 +08:00
										 |  |  |               newVariables.insert(factor->key2(), measured); | 
					
						
							| 
									
										
										
										
											2013-08-12 03:26:29 +08:00
										 |  |  |             else { | 
					
						
							| 
									
										
										
										
											2018-11-07 02:28:47 +08:00
										 |  |  |               Pose prevPose = isam2.calculateEstimate<Pose>(factor->key1()); | 
					
						
							|  |  |  |               newVariables.insert(factor->key2(), prevPose * measured); | 
					
						
							| 
									
										
										
										
											2013-08-12 03:26:29 +08:00
										 |  |  |             } | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |           } | 
					
						
							|  |  |  |         } | 
					
						
							|  |  |  |       } | 
					
						
							| 
									
										
										
										
											2018-11-07 02:28:47 +08:00
										 |  |  |       else if(BearingRangeFactor<Pose, Point2>::shared_ptr factor = | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |         boost::dynamic_pointer_cast<BearingRangeFactor<Pose, Point2> >(measurementf)) | 
					
						
							|  |  |  |       { | 
					
						
							| 
									
										
										
										
											2018-11-07 02:28:47 +08:00
										 |  |  |         Key poseKey = factor->keys()[0], lmKey = factor->keys()[1]; | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |         // Stop collecting measurements that are for future steps
 | 
					
						
							|  |  |  |         if(poseKey > step) | 
					
						
							|  |  |  |           throw runtime_error("Problem in data file, out-of-sequence measurements"); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |         // Add new factor
 | 
					
						
							| 
									
										
										
										
											2018-11-07 02:28:47 +08:00
										 |  |  |         newFactors.push_back(factor); | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |         // Initialize new landmark
 | 
					
						
							|  |  |  |         if(!isam2.getLinearizationPoint().exists(lmKey)) | 
					
						
							|  |  |  |         { | 
					
						
							|  |  |  |           Pose pose; | 
					
						
							|  |  |  |           if(isam2.getLinearizationPoint().exists(poseKey)) | 
					
						
							|  |  |  |             pose = isam2.calculateEstimate<Pose>(poseKey); | 
					
						
							|  |  |  |           else | 
					
						
							|  |  |  |             pose = newVariables.at<Pose>(poseKey); | 
					
						
							| 
									
										
										
										
											2018-11-07 02:28:47 +08:00
										 |  |  |           const auto& measured = factor->measured(); | 
					
						
							|  |  |  |           Rot2 measuredBearing = measured.bearing(); | 
					
						
							|  |  |  |           double measuredRange = measured.range(); | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |           newVariables.insert(lmKey,  | 
					
						
							|  |  |  |             pose.transform_from(measuredBearing.rotate(Point2(measuredRange, 0.0)))); | 
					
						
							|  |  |  |         } | 
					
						
							|  |  |  |       } | 
					
						
							|  |  |  |       else | 
					
						
							|  |  |  |       { | 
					
						
							|  |  |  |         throw std::runtime_error("Unknown factor type read from data file"); | 
					
						
							|  |  |  |       } | 
					
						
							|  |  |  |       ++ nextMeasurement; | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |     gttoc_(Collect_measurements); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     // Update iSAM2
 | 
					
						
							| 
									
										
										
										
											2013-08-16 04:16:59 +08:00
										 |  |  |     try { | 
					
						
							|  |  |  |       gttic_(Update_ISAM2); | 
					
						
							|  |  |  |       isam2.update(newFactors, newVariables); | 
					
						
							|  |  |  |       gttoc_(Update_ISAM2); | 
					
						
							|  |  |  |     } catch(std::exception& e) { | 
					
						
							|  |  |  |       cout << e.what() << endl; | 
					
						
							|  |  |  |       exit(1); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     if((step - firstPose) % 1000 == 0) { | 
					
						
							|  |  |  |       try { | 
					
						
							|  |  |  |         gttic_(chi2); | 
					
						
							|  |  |  |         Values estimate(isam2.calculateEstimate()); | 
					
						
							|  |  |  |         double chi2 = chi2_red(isam2.getFactorsUnsafe(), estimate); | 
					
						
							|  |  |  |         cout << "chi2 = " << chi2 << endl; | 
					
						
							|  |  |  |         gttoc_(chi2); | 
					
						
							|  |  |  |       } catch(std::exception& e) { | 
					
						
							|  |  |  |         cout << e.what() << endl; | 
					
						
							|  |  |  |         exit(1); | 
					
						
							|  |  |  |       } | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     tictoc_finishedIteration_(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     if((step - firstPose) % 1000 == 0) { | 
					
						
							|  |  |  |       cout << "Step " << step << endl; | 
					
						
							|  |  |  |       tictoc_print_(); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   if(!outputFile.empty()) | 
					
						
							|  |  |  |   { | 
					
						
							|  |  |  |     try { | 
					
						
							|  |  |  |       cout << "Writing output file " << outputFile << endl; | 
					
						
							| 
									
										
										
										
											2013-08-02 21:33:23 +08:00
										 |  |  |       std::ofstream writerStream(outputFile.c_str(), ios::binary); | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |       boost::archive::binary_oarchive writer(writerStream); | 
					
						
							| 
									
										
										
										
											2013-08-02 21:33:23 +08:00
										 |  |  |       Values estimates = isam2.calculateEstimate(); | 
					
						
							|  |  |  |       writer << estimates; | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |     } catch(std::exception& e) { | 
					
						
							|  |  |  |       cout << e.what() << endl; | 
					
						
							|  |  |  |       exit(1); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-12 03:26:29 +08:00
										 |  |  |   tictoc_print_(); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |   // Compute marginals
 | 
					
						
							|  |  |  |   //try {
 | 
					
						
							|  |  |  |   //  Marginals marginals(graph, values);
 | 
					
						
							|  |  |  |   //  int i=0;
 | 
					
						
							| 
									
										
										
										
											2016-05-23 05:11:42 +08:00
										 |  |  |   //  for (Key key1: boost::adaptors::reverse(values.keys())) {
 | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |   //    int j=0;
 | 
					
						
							| 
									
										
										
										
											2016-05-23 05:11:42 +08:00
										 |  |  |   //    for (Key key12: boost::adaptors::reverse(values.keys())) {
 | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |   //      if(i != j) {
 | 
					
						
							|  |  |  |   //        gttic_(jointMarginalInformation);
 | 
					
						
							|  |  |  |   //        std::vector<Key> keys(2);
 | 
					
						
							|  |  |  |   //        keys[0] = key1;
 | 
					
						
							|  |  |  |   //        keys[1] = key2;
 | 
					
						
							|  |  |  |   //        JointMarginal info = marginals.jointMarginalInformation(keys);
 | 
					
						
							|  |  |  |   //        gttoc_(jointMarginalInformation);
 | 
					
						
							|  |  |  |   //        tictoc_finishedIteration_();
 | 
					
						
							|  |  |  |   //      }
 | 
					
						
							|  |  |  |   //      ++j;
 | 
					
						
							|  |  |  |   //      if(j >= 50)
 | 
					
						
							|  |  |  |   //        break;
 | 
					
						
							|  |  |  |   //    }
 | 
					
						
							|  |  |  |   //    ++i;
 | 
					
						
							|  |  |  |   //    if(i >= 50)
 | 
					
						
							|  |  |  |   //      break;
 | 
					
						
							|  |  |  |   //  }
 | 
					
						
							|  |  |  |   //  tictoc_print_();
 | 
					
						
							| 
									
										
										
										
											2016-05-20 21:20:03 +08:00
										 |  |  |   //  for(Key key: values.keys()) {
 | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |   //    gttic_(marginalInformation);
 | 
					
						
							|  |  |  |   //    Matrix info = marginals.marginalInformation(key);
 | 
					
						
							|  |  |  |   //    gttoc_(marginalInformation);
 | 
					
						
							|  |  |  |   //    tictoc_finishedIteration_();
 | 
					
						
							|  |  |  |   //    ++i;
 | 
					
						
							|  |  |  |   //  }
 | 
					
						
							|  |  |  |   //} catch(std::exception& e) {
 | 
					
						
							|  |  |  |   //  cout << e.what() << endl;
 | 
					
						
							|  |  |  |   //}
 | 
					
						
							|  |  |  |   //tictoc_print_();
 | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | void runBatch() | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  |   cout << "Creating batch optimizer..." << endl; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-01 23:38:15 +08:00
										 |  |  |   NonlinearFactorGraph measurements = datasetMeasurements; | 
					
						
							| 
									
										
										
										
											2014-12-29 00:13:11 +08:00
										 |  |  |   measurements.push_back(boost::make_shared<PriorFactor<Pose> >(0, Pose(), noiseModel::Unit::Create(3))); | 
					
						
							| 
									
										
										
										
											2013-08-01 23:38:15 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |   gttic_(Create_optimizer); | 
					
						
							| 
									
										
										
										
											2013-08-02 05:57:55 +08:00
										 |  |  |   GaussNewtonParams params; | 
					
						
							| 
									
										
										
										
											2013-10-26 03:16:15 +08:00
										 |  |  |   params.linearSolverType = NonlinearOptimizerParams::MULTIFRONTAL_CHOLESKY; | 
					
						
							| 
									
										
										
										
											2013-08-02 05:57:55 +08:00
										 |  |  |   GaussNewtonOptimizer optimizer(measurements, initial, params); | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |   gttoc_(Create_optimizer); | 
					
						
							|  |  |  |   double lastError; | 
					
						
							|  |  |  |   do { | 
					
						
							|  |  |  |     lastError = optimizer.error(); | 
					
						
							|  |  |  |     gttic_(Iterate_optimizer); | 
					
						
							|  |  |  |     optimizer.iterate(); | 
					
						
							|  |  |  |     gttoc_(Iterate_optimizer); | 
					
						
							| 
									
										
										
										
											2013-08-01 23:38:15 +08:00
										 |  |  |     cout << "Error: " << lastError << " -> " << optimizer.error() /*<< ", lambda: " << optimizer.lambda()*/ << endl; | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |     gttic_(chi2); | 
					
						
							| 
									
										
										
										
											2013-08-01 23:38:15 +08:00
										 |  |  |     double chi2 = chi2_red(measurements, optimizer.values()); | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |     cout << "chi2 = " << chi2 << endl; | 
					
						
							|  |  |  |     gttoc_(chi2); | 
					
						
							|  |  |  |   } while(!checkConvergence(optimizer.params().relativeErrorTol, | 
					
						
							|  |  |  |     optimizer.params().absoluteErrorTol, optimizer.params().errorTol, | 
					
						
							|  |  |  |     lastError, optimizer.error(), optimizer.params().verbosity)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   tictoc_finishedIteration_(); | 
					
						
							|  |  |  |   tictoc_print_(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   if(!outputFile.empty()) | 
					
						
							|  |  |  |   { | 
					
						
							|  |  |  |     try { | 
					
						
							|  |  |  |       cout << "Writing output file " << outputFile << endl; | 
					
						
							| 
									
										
										
										
											2013-08-02 21:33:23 +08:00
										 |  |  |       std::ofstream writerStream(outputFile.c_str(), ios::binary); | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |       boost::archive::binary_oarchive writer(writerStream); | 
					
						
							| 
									
										
										
										
											2013-08-01 23:38:15 +08:00
										 |  |  |       writer << optimizer.values(); | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |     } catch(std::exception& e) { | 
					
						
							|  |  |  |       cout << e.what() << endl; | 
					
						
							|  |  |  |       exit(1); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | void runCompare() | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  |   Values soln1, soln2; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   cout << "Reading solution file " << compareFile1 << endl; | 
					
						
							|  |  |  |   { | 
					
						
							| 
									
										
										
										
											2013-08-02 21:33:23 +08:00
										 |  |  |     std::ifstream readerStream(compareFile1.c_str(), ios::binary); | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |     boost::archive::binary_iarchive reader(readerStream); | 
					
						
							| 
									
										
										
										
											2013-08-01 23:38:15 +08:00
										 |  |  |     reader >> soln1; | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   cout << "Reading solution file " << compareFile2 << endl; | 
					
						
							|  |  |  |   { | 
					
						
							| 
									
										
										
										
											2013-08-02 21:33:23 +08:00
										 |  |  |     std::ifstream readerStream(compareFile2.c_str(), ios::binary); | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |     boost::archive::binary_iarchive reader(readerStream); | 
					
						
							| 
									
										
										
										
											2013-08-01 23:38:15 +08:00
										 |  |  |     reader >> soln2; | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Check solution for equality
 | 
					
						
							|  |  |  |   cout << "Comparing solutions..." << endl; | 
					
						
							|  |  |  |   vector<Key> missingKeys; | 
					
						
							|  |  |  |   br::set_symmetric_difference(soln1.keys(), soln2.keys(), std::back_inserter(missingKeys)); | 
					
						
							|  |  |  |   if(!missingKeys.empty()) { | 
					
						
							|  |  |  |     cout << "  Keys unique to one solution file: "; | 
					
						
							|  |  |  |     for(size_t i = 0; i < missingKeys.size(); ++i) { | 
					
						
							|  |  |  |       cout << DefaultKeyFormatter(missingKeys[i]); | 
					
						
							|  |  |  |       if(i != missingKeys.size() - 1) | 
					
						
							|  |  |  |         cout << ", "; | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |     cout << endl; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  |   vector<Key> commonKeys; | 
					
						
							|  |  |  |   br::set_intersection(soln1.keys(), soln2.keys(), std::back_inserter(commonKeys)); | 
					
						
							|  |  |  |   double maxDiff = 0.0; | 
					
						
							| 
									
										
										
										
											2016-05-20 21:20:03 +08:00
										 |  |  |   for(Key j: commonKeys) | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |     maxDiff = std::max(maxDiff, soln1.at(j).localCoordinates_(soln2.at(j)).norm()); | 
					
						
							|  |  |  |   cout << "  Maximum solution difference (norm of logmap): " << maxDiff << endl; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | void runPerturb() | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  |   // Set up random number generator
 | 
					
						
							| 
									
										
										
										
											2014-02-13 05:38:45 +08:00
										 |  |  |   boost::mt19937 rng; | 
					
						
							|  |  |  |   boost::normal_distribution<double> normal(0.0, perturbationNoise); | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Perturb values
 | 
					
						
							|  |  |  |   VectorValues noise; | 
					
						
							| 
									
										
										
										
											2016-05-20 21:20:03 +08:00
										 |  |  |   for(const Values::KeyValuePair& key_val: initial) | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |   { | 
					
						
							|  |  |  |     Vector noisev(key_val.value.dim()); | 
					
						
							|  |  |  |     for(Vector::Index i = 0; i < noisev.size(); ++i) | 
					
						
							|  |  |  |       noisev(i) = normal(rng); | 
					
						
							| 
									
										
										
										
											2013-08-02 05:57:55 +08:00
										 |  |  |     noise.insert(key_val.key, noisev); | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |   } | 
					
						
							| 
									
										
										
										
											2013-08-02 05:57:55 +08:00
										 |  |  |   Values perturbed = initial.retract(noise); | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Write results
 | 
					
						
							|  |  |  |   try { | 
					
						
							|  |  |  |     cout << "Writing output file " << outputFile << endl; | 
					
						
							| 
									
										
										
										
											2013-08-02 21:33:23 +08:00
										 |  |  |     std::ofstream writerStream(outputFile.c_str(), ios::binary); | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |     boost::archive::binary_oarchive writer(writerStream); | 
					
						
							| 
									
										
										
										
											2013-08-01 23:38:15 +08:00
										 |  |  |     writer << perturbed; | 
					
						
							| 
									
										
										
										
											2013-08-01 02:53:26 +08:00
										 |  |  |   } catch(std::exception& e) { | 
					
						
							|  |  |  |     cout << e.what() << endl; | 
					
						
							|  |  |  |     exit(1); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-11-08 05:41:23 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | void runStats() | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  |   cout << "Gathering statistics..." << endl; | 
					
						
							|  |  |  |   GaussianFactorGraph linear = *datasetMeasurements.linearize(initial); | 
					
						
							| 
									
										
										
										
											2015-02-22 02:16:03 +08:00
										 |  |  |   GaussianJunctionTree jt(GaussianEliminationTree(linear, Ordering::Colamd(linear))); | 
					
						
							| 
									
										
										
										
											2013-11-08 05:41:23 +08:00
										 |  |  |   treeTraversal::ForestStatistics statistics = treeTraversal::GatherStatistics(jt); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   ofstream file; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   cout << "Writing SolverComparer_Stats_problemSizeHistogram.txt..." << endl; | 
					
						
							|  |  |  |   file.open("SolverComparer_Stats_problemSizeHistogram.txt"); | 
					
						
							|  |  |  |   treeTraversal::ForestStatistics::Write(file, statistics.problemSizeHistogram); | 
					
						
							|  |  |  |   file.close(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   cout << "Writing SolverComparer_Stats_numberOfChildrenHistogram.txt..." << endl; | 
					
						
							|  |  |  |   file.open("SolverComparer_Stats_numberOfChildrenHistogram.txt"); | 
					
						
							|  |  |  |   treeTraversal::ForestStatistics::Write(file, statistics.numberOfChildrenHistogram); | 
					
						
							|  |  |  |   file.close(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   cout << "Writing SolverComparer_Stats_problemSizeOfSecondLargestChildHistogram.txt..." << endl; | 
					
						
							|  |  |  |   file.open("SolverComparer_Stats_problemSizeOfSecondLargestChildHistogram.txt"); | 
					
						
							|  |  |  |   treeTraversal::ForestStatistics::Write(file, statistics.problemSizeOfSecondLargestChildHistogram); | 
					
						
							|  |  |  |   file.close(); | 
					
						
							|  |  |  | } |