| 
									
										
										
										
											2020-06-20 11:33: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    timeFrobeniusFactor.cpp | 
					
						
							|  |  |  |  * @brief   time FrobeniusFactor with BAL file | 
					
						
							|  |  |  |  * @author  Frank Dellaert | 
					
						
							| 
									
										
										
										
											2020-08-02 03:43:55 +08:00
										 |  |  |  * @date    2019 | 
					
						
							| 
									
										
										
										
											2020-06-20 11:33:29 +08:00
										 |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam/base/timing.h>
 | 
					
						
							|  |  |  | #include <gtsam/geometry/Pose3.h>
 | 
					
						
							|  |  |  | #include <gtsam/linear/NoiseModel.h>
 | 
					
						
							|  |  |  | #include <gtsam/linear/PCGSolver.h>
 | 
					
						
							|  |  |  | #include <gtsam/linear/SubgraphPreconditioner.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/NonlinearEquality.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/NonlinearFactorGraph.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/Values.h>
 | 
					
						
							|  |  |  | #include <gtsam/slam/PriorFactor.h>
 | 
					
						
							|  |  |  | #include <gtsam/slam/dataset.h>
 | 
					
						
							|  |  |  | #include <gtsam/slam/FrobeniusFactor.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <iostream>
 | 
					
						
							| 
									
										
										
										
											2020-07-24 02:05:23 +08:00
										 |  |  | #include <random>
 | 
					
						
							| 
									
										
										
										
											2020-06-20 11:33:29 +08:00
										 |  |  | #include <string>
 | 
					
						
							|  |  |  | #include <vector>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | static SharedNoiseModel gNoiseModel = noiseModel::Unit::Create(2); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | int main(int argc, char* argv[]) { | 
					
						
							|  |  |  |   // primitive argument parsing:
 | 
					
						
							|  |  |  |   if (argc > 3) { | 
					
						
							|  |  |  |     throw runtime_error("Usage: timeFrobeniusFactor [g2oFile]"); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   string g2oFile; | 
					
						
							|  |  |  |   try { | 
					
						
							|  |  |  |     if (argc > 1) | 
					
						
							|  |  |  |       g2oFile = argv[argc - 1]; | 
					
						
							|  |  |  |     else | 
					
						
							| 
									
										
										
										
											2020-08-02 03:43:55 +08:00
										 |  |  |       g2oFile = findExampleDataFile("sphere_smallnoise.graph"); | 
					
						
							| 
									
										
										
										
											2020-06-20 11:33:29 +08:00
										 |  |  |   } catch (const exception& e) { | 
					
						
							|  |  |  |     cerr << e.what() << '\n'; | 
					
						
							|  |  |  |     exit(1); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Read G2O file
 | 
					
						
							|  |  |  |   const auto factors = parse3DFactors(g2oFile); | 
					
						
							|  |  |  |   const auto poses = parse3DPoses(g2oFile); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Build graph
 | 
					
						
							|  |  |  |   NonlinearFactorGraph graph; | 
					
						
							| 
									
										
										
										
											2020-08-02 03:43:55 +08:00
										 |  |  |   // graph.add(NonlinearEquality<SOn>(0, SOn::identity(4)));
 | 
					
						
							| 
									
										
										
										
											2020-06-20 11:33:29 +08:00
										 |  |  |   auto priorModel = noiseModel::Isotropic::Sigma(6, 10000); | 
					
						
							| 
									
										
										
										
											2020-08-02 03:43:55 +08:00
										 |  |  |   graph.add(PriorFactor<SOn>(0, SOn::identity(4), priorModel)); | 
					
						
							|  |  |  |   auto G = boost::make_shared<Matrix>(SOn::VectorizedGenerators(4)); | 
					
						
							| 
									
										
										
										
											2020-06-20 11:33:29 +08:00
										 |  |  |   for (const auto& factor : factors) { | 
					
						
							|  |  |  |     const auto& keys = factor->keys(); | 
					
						
							|  |  |  |     const auto& Tij = factor->measured(); | 
					
						
							|  |  |  |     const auto& model = factor->noiseModel(); | 
					
						
							|  |  |  |     graph.emplace_shared<FrobeniusWormholeFactor>( | 
					
						
							| 
									
										
										
										
											2020-08-02 03:43:55 +08:00
										 |  |  |         keys[0], keys[1], Rot3(Tij.rotation().matrix()), 4, model, G); | 
					
						
							| 
									
										
										
										
											2020-06-20 11:33:29 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-07-24 02:05:23 +08:00
										 |  |  |   std::mt19937 rng(42); | 
					
						
							| 
									
										
										
										
											2020-06-20 11:33:29 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Set parameters to be similar to ceres
 | 
					
						
							|  |  |  |   LevenbergMarquardtParams params; | 
					
						
							|  |  |  |   LevenbergMarquardtParams::SetCeresDefaults(¶ms); | 
					
						
							|  |  |  |   params.setLinearSolverType("MULTIFRONTAL_QR"); | 
					
						
							|  |  |  |   // params.setVerbosityLM("SUMMARY");
 | 
					
						
							|  |  |  |   // params.linearSolverType = LevenbergMarquardtParams::Iterative;
 | 
					
						
							|  |  |  |   // auto pcg = boost::make_shared<PCGSolverParameters>();
 | 
					
						
							|  |  |  |   // pcg->preconditioner_ =
 | 
					
						
							|  |  |  |   // boost::make_shared<SubgraphPreconditionerParameters>();
 | 
					
						
							|  |  |  |   // boost::make_shared<BlockJacobiPreconditionerParameters>();
 | 
					
						
							|  |  |  |   // params.iterativeParams = pcg;
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Optimize
 | 
					
						
							|  |  |  |   for (size_t i = 0; i < 100; i++) { | 
					
						
							|  |  |  |     gttic_(optimize); | 
					
						
							|  |  |  |     Values initial; | 
					
						
							| 
									
										
										
										
											2020-08-02 03:43:55 +08:00
										 |  |  |     initial.insert(0, SOn::identity(4)); | 
					
						
							| 
									
										
										
										
											2020-06-20 11:33:29 +08:00
										 |  |  |     for (size_t j = 1; j < poses.size(); j++) { | 
					
						
							| 
									
										
										
										
											2020-08-02 03:43:55 +08:00
										 |  |  |       initial.insert(j, SOn::Random(rng, 4)); | 
					
						
							| 
									
										
										
										
											2020-06-20 11:33:29 +08:00
										 |  |  |     } | 
					
						
							|  |  |  |     LevenbergMarquardtOptimizer lm(graph, initial, params); | 
					
						
							|  |  |  |     Values result = lm.optimize(); | 
					
						
							|  |  |  |     cout << "cost = " << graph.error(result) << endl; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   tictoc_finishedIteration_(); | 
					
						
							|  |  |  |   tictoc_print_(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   return 0; | 
					
						
							|  |  |  | } |