2014-06-01 02:37:29 +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
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * -------------------------------------------------------------------------- */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/**
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * @file    timeVirtual.cpp
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * @brief   Time the overhead of using virtual destructors and methods
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * @author  Richard Roberts
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * @date    Dec 3, 2010
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/slam/dataset.h>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/slam/PriorFactor.h>
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-02 00:25:23 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/slam/lago.h>
							 | 
						
					
						
							
								
									
										
										
										
											2015-05-26 15:10:26 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/geometry/Pose2.h>
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-01 02:37:29 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/nonlinear/GaussNewtonOptimizer.h>
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-01 05:15:29 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/linear/Sampler.h>
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-01 02:37:29 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/base/timing.h>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <iostream>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								using namespace std;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								using namespace gtsam;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								int main(int argc, char *argv[]) {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-01 04:24:50 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  size_t trials = 1;
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-01 02:37:29 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // read graph
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-01 05:15:29 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Values::shared_ptr solution;
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-01 04:24:50 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  NonlinearFactorGraph::shared_ptr g;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  string inputFile = findExampleDataFile("w10000");
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-23 10:07:27 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  SharedDiagonal model = noiseModel::Diagonal::Sigmas((Vector(3) << 0.05, 0.05, 5.0 * M_PI / 180.0).finished());
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-01 05:15:29 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  boost::tie(g, solution) = load2D(inputFile, model);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // add noise to create initial estimate
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Values initial;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Sampler sampler(42u);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Values::ConstFiltered<Pose2> poses = solution->filter<Pose2>();
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-23 10:07:27 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  SharedDiagonal noise = noiseModel::Diagonal::Sigmas((Vector(3) << 0.5, 0.5, 15.0 * M_PI / 180.0).finished());
							 | 
						
					
						
							
								
									
										
										
										
											2016-05-21 09:22:30 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  for(const Values::ConstFiltered<Pose2>::KeyValuePair& it: poses)
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-01 05:15:29 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    initial.insert(it.key, it.value.retract(sampler.sampleNewModel(noise)));
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-01 02:37:29 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // Add prior on the pose having index (key) = 0
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  noiseModel::Diagonal::shared_ptr priorModel = //
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-01 04:24:50 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      noiseModel::Diagonal::Sigmas(Vector3(1e-6, 1e-6, 1e-8));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  g->add(PriorFactor<Pose2>(0, Pose2(), priorModel));
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-01 02:37:29 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // LAGO
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  for (size_t i = 0; i < trials; i++) {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      gttic_(lago);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      gttic_(init);
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-01 04:24:50 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      Values lagoInitial = lago::initialize(*g);
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-01 02:37:29 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      gttoc_(init);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      gttic_(refine);
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-01 04:24:50 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      GaussNewtonOptimizer optimizer(*g, lagoInitial);
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-01 02:37:29 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      Values result = optimizer.optimize();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      gttoc_(refine);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      gttic_(optimize);
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-01 05:15:29 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      GaussNewtonOptimizer optimizer(*g, initial);
							 | 
						
					
						
							
								
									
										
										
										
											2014-06-01 02:37:29 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      Values result = optimizer.optimize();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    tictoc_finishedIteration_();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  tictoc_print_();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  return 0;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 |