| 
									
										
										
										
											2010-10-14 12:54:38 +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 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-18 13:51:19 +08:00
										 |  |  | /*
 | 
					
						
							| 
									
										
										
										
											2010-03-13 03:19:21 +08:00
										 |  |  |  * SubgraphSolver-inl.h | 
					
						
							| 
									
										
										
										
											2010-01-18 13:51:19 +08:00
										 |  |  |  * | 
					
						
							|  |  |  |  *   Created on: Jan 17, 2010 | 
					
						
							|  |  |  |  *       Author: nikai | 
					
						
							|  |  |  |  *  Description: subgraph preconditioning conjugate gradient solver | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #pragma once
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <boost/tuple/tuple.hpp>
 | 
					
						
							| 
									
										
										
										
											2010-08-20 01:23:19 +08:00
										 |  |  | #include <gtsam/linear/SubgraphSolver.h>
 | 
					
						
							|  |  |  | #include <gtsam/linear/iterative-inl.h>
 | 
					
						
							| 
									
										
										
										
											2010-10-19 03:29:16 +08:00
										 |  |  | #include <gtsam/inference/graph-inl.h>
 | 
					
						
							| 
									
										
										
										
											2010-08-20 01:23:19 +08:00
										 |  |  | #include <gtsam/inference/FactorGraph-inl.h>
 | 
					
						
							| 
									
										
										
										
											2010-10-22 06:59:54 +08:00
										 |  |  | #include <gtsam/inference/EliminationTree-inl.h>
 | 
					
						
							| 
									
										
										
										
											2010-01-18 13:51:19 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | namespace gtsam { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	/* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-21 00:37:47 +08:00
										 |  |  | 	template<class GRAPH, class VALUES> | 
					
						
							|  |  |  | 	SubgraphSolver<GRAPH, VALUES>::SubgraphSolver(const GRAPH& G, const VALUES& theta0) { | 
					
						
							| 
									
										
										
										
											2010-03-13 06:00:55 +08:00
										 |  |  | 		initialize(G,theta0); | 
					
						
							| 
									
										
										
										
											2010-01-23 08:57:54 +08:00
										 |  |  | 	} | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	/* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-21 00:37:47 +08:00
										 |  |  | 	template<class GRAPH, class VALUES> | 
					
						
							|  |  |  | 	void SubgraphSolver<GRAPH, VALUES>::initialize(const GRAPH& G, const VALUES& theta0) { | 
					
						
							| 
									
										
										
										
											2010-01-18 13:51:19 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-20 10:28:23 +08:00
										 |  |  | 		// generate spanning tree
 | 
					
						
							| 
									
										
										
										
											2010-10-21 00:37:47 +08:00
										 |  |  | 		PredecessorMap<Key> tree = gtsam::findMinimumSpanningTree<GRAPH, Key, Constraint>(G); | 
					
						
							| 
									
										
										
										
											2010-01-18 13:51:19 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 		// split the graph
 | 
					
						
							|  |  |  | 		if (verbose_) cout << "generating spanning tree and split the graph ..."; | 
					
						
							| 
									
										
										
										
											2010-10-21 00:37:47 +08:00
										 |  |  | 		gtsam::split<GRAPH,Key,Constraint>(G, tree, T_, C_) ; | 
					
						
							| 
									
										
										
										
											2010-10-19 04:36:01 +08:00
										 |  |  | 		if (verbose_) cout << ",with " << T_.size() << " and " << C_.size() << " factors" << endl; | 
					
						
							| 
									
										
										
										
											2010-01-18 13:51:19 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-18 17:24:38 +08:00
										 |  |  | 		// make the ordering
 | 
					
						
							| 
									
										
										
										
											2010-10-19 03:29:16 +08:00
										 |  |  | 		list<Key> keys = predecessorMap2Keys(tree); | 
					
						
							|  |  |  | 		ordering_ = boost::shared_ptr<Ordering>(new Ordering(list<Symbol>(keys.begin(), keys.end()))); | 
					
						
							| 
									
										
										
										
											2010-01-18 17:24:38 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-19 03:29:16 +08:00
										 |  |  | 		// Add a HardConstraint to the root, otherwise the root will be singular
 | 
					
						
							| 
									
										
										
										
											2010-01-18 17:24:38 +08:00
										 |  |  | 		Key root = keys.back(); | 
					
						
							| 
									
										
										
										
											2010-10-19 03:29:16 +08:00
										 |  |  | 		T_.addHardConstraint(root, theta0[root]); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 		// compose the approximate solution
 | 
					
						
							| 
									
										
										
										
											2010-10-21 00:37:47 +08:00
										 |  |  | 		theta_bar_ = composePoses<GRAPH, Constraint, Pose, VALUES> (T_, tree, theta0[root]); | 
					
						
							| 
									
										
										
										
											2010-01-18 13:51:19 +08:00
										 |  |  | 	} | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	/* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-21 00:37:47 +08:00
										 |  |  | 	template<class GRAPH, class VALUES> | 
					
						
							|  |  |  | 	boost::shared_ptr<SubgraphPreconditioner> SubgraphSolver<GRAPH, VALUES>::linearize(const GRAPH& G, const VALUES& theta_bar) const { | 
					
						
							| 
									
										
										
										
											2010-10-19 03:29:16 +08:00
										 |  |  | 		SubgraphPreconditioner::sharedFG Ab1 = T_.linearize(theta_bar, *ordering_); | 
					
						
							|  |  |  | 		SubgraphPreconditioner::sharedFG Ab2 = C_.linearize(theta_bar, *ordering_); | 
					
						
							| 
									
										
										
										
											2010-01-23 08:57:54 +08:00
										 |  |  | #ifdef TIMING
 | 
					
						
							|  |  |  | 		SubgraphPreconditioner::sharedBayesNet Rc1; | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 		SubgraphPreconditioner::sharedValues xbar; | 
					
						
							| 
									
										
										
										
											2010-01-23 08:57:54 +08:00
										 |  |  | #else
 | 
					
						
							| 
									
										
										
										
											2010-02-22 05:17:47 +08:00
										 |  |  | 		GaussianFactorGraph sacrificialAb1 = *Ab1; // duplicate !!!!!
 | 
					
						
							| 
									
										
										
										
											2010-10-22 06:59:54 +08:00
										 |  |  | 		SubgraphPreconditioner::sharedBayesNet Rc1 = EliminationTree<GaussianFactor>::Create(sacrificialAb1)->eliminate(); | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 		SubgraphPreconditioner::sharedValues xbar = gtsam::optimize_(*Rc1); | 
					
						
							| 
									
										
										
										
											2010-01-23 08:57:54 +08:00
										 |  |  | #endif
 | 
					
						
							| 
									
										
										
										
											2010-02-22 05:17:47 +08:00
										 |  |  | 		// TODO: there does not seem to be a good reason to have Ab1_
 | 
					
						
							|  |  |  | 		// It seems only be used to provide an ordering for creating sparse matrices
 | 
					
						
							| 
									
										
										
										
											2010-01-23 08:57:54 +08:00
										 |  |  | 		return boost::shared_ptr<SubgraphPreconditioner>(new SubgraphPreconditioner(Ab1, Ab2, Rc1, xbar)); | 
					
						
							| 
									
										
										
										
											2010-01-19 18:46:12 +08:00
										 |  |  | 	} | 
					
						
							| 
									
										
										
										
											2010-01-18 13:51:19 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-19 18:46:12 +08:00
										 |  |  | 	/* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-21 00:37:47 +08:00
										 |  |  | 	template<class GRAPH, class VALUES> | 
					
						
							|  |  |  | 	VectorValues SubgraphSolver<GRAPH, VALUES>::optimize(SubgraphPreconditioner& system) const { | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 		VectorValues zeros = system.zero(); | 
					
						
							| 
									
										
										
										
											2010-01-18 13:51:19 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 		// Solve the subgraph PCG
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 		VectorValues ybar = conjugateGradients<SubgraphPreconditioner, VectorValues, | 
					
						
							| 
									
										
										
										
											2010-01-18 13:51:19 +08:00
										 |  |  | 				Errors> (system, zeros, verbose_, epsilon_, epsilon_abs_, maxIterations_); | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 		VectorValues xbar = system.x(ybar); | 
					
						
							| 
									
										
										
										
											2010-01-19 18:46:12 +08:00
										 |  |  | 		return xbar; | 
					
						
							| 
									
										
										
										
											2010-01-18 13:51:19 +08:00
										 |  |  | 	} | 
					
						
							| 
									
										
										
										
											2010-01-19 18:46:12 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-18 13:51:19 +08:00
										 |  |  | } |