| 
									
										
										
										
											2009-12-31 20:56:47 +08:00
										 |  |  | /*
 | 
					
						
							|  |  |  |  * SubgraphPreconditioner.h | 
					
						
							|  |  |  |  * Created on: Dec 31, 2009 | 
					
						
							|  |  |  |  * @author: Frank Dellaert | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #ifndef SUBGRAPHPRECONDITIONER_H_
 | 
					
						
							|  |  |  | #define SUBGRAPHPRECONDITIONER_H_
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include "GaussianFactorGraph.h"
 | 
					
						
							|  |  |  | #include "GaussianBayesNet.h"
 | 
					
						
							| 
									
										
										
										
											2010-01-18 17:24:38 +08:00
										 |  |  | #include "Ordering.h"
 | 
					
						
							| 
									
										
										
										
											2009-12-31 20:56:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | namespace gtsam { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	/**
 | 
					
						
							|  |  |  | 	 * Subgraph conditioner class, as explained in the RSS 2010 submission. | 
					
						
							|  |  |  | 	 * Starting with a graph A*x=b, we split it in two systems A1*x=b1 and A2*x=b2 | 
					
						
							|  |  |  | 	 * We solve R1*x=c1, and make the substitution y=R1*x-c1. | 
					
						
							|  |  |  | 	 * To use the class, give the Bayes Net R1*x=c1 and Graph A2*x=b2. | 
					
						
							|  |  |  | 	 * Then solve for yhat using CG, and solve for xhat = system.x(yhat). | 
					
						
							|  |  |  | 	 */ | 
					
						
							|  |  |  | 	class SubgraphPreconditioner { | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-19 18:46:12 +08:00
										 |  |  | 	public: | 
					
						
							|  |  |  | 		typedef boost::shared_ptr<const GaussianBayesNet> sharedBayesNet; | 
					
						
							|  |  |  | 		typedef boost::shared_ptr<const GaussianFactorGraph> sharedFG; | 
					
						
							|  |  |  | 		typedef boost::shared_ptr<const VectorConfig> sharedConfig; | 
					
						
							|  |  |  | 		typedef boost::shared_ptr<const Errors> sharedErrors; | 
					
						
							| 
									
										
										
										
											2009-12-31 20:56:47 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-19 18:46:12 +08:00
										 |  |  | 	private: | 
					
						
							|  |  |  | 		sharedBayesNet Rc1_; | 
					
						
							|  |  |  | 		sharedFG Ab2_; | 
					
						
							|  |  |  | 		sharedConfig xbar_; | 
					
						
							|  |  |  | 		sharedErrors b2bar_; /** b2 - A2*xbar */ | 
					
						
							| 
									
										
										
										
											2009-12-31 20:56:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	public: | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 		/**
 | 
					
						
							|  |  |  | 		 * Constructor | 
					
						
							|  |  |  | 		 * @param Rc1: the Bayes Net R1*x=c1 | 
					
						
							|  |  |  | 		 * @param Ab2: the Graph A2*x=b2 | 
					
						
							|  |  |  | 		 * @param xbar: the solution to R1*x=c1 | 
					
						
							|  |  |  | 		 */ | 
					
						
							| 
									
										
										
										
											2010-01-19 18:46:12 +08:00
										 |  |  | 		SubgraphPreconditioner(sharedBayesNet& Rc1,	sharedFG& Ab2, sharedConfig& xbar); | 
					
						
							| 
									
										
										
										
											2009-12-31 20:56:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 		/* x = xbar + inv(R1)*y */ | 
					
						
							|  |  |  | 		VectorConfig x(const VectorConfig& y) const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 		/* error, given y */ | 
					
						
							|  |  |  | 		double error(const VectorConfig& y) const; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-18 13:51:19 +08:00
										 |  |  | 		/** gradient = y + inv(R1')*A2'*(A2*inv(R1)*y-b2bar) */ | 
					
						
							| 
									
										
										
										
											2009-12-31 20:56:47 +08:00
										 |  |  | 		VectorConfig gradient(const VectorConfig& y) const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 		/** Apply operator A */ | 
					
						
							|  |  |  | 		Errors operator*(const VectorConfig& y) const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 		/** Apply operator A' */ | 
					
						
							|  |  |  | 		VectorConfig operator^(const Errors& e) const; | 
					
						
							| 
									
										
										
										
											2010-01-11 16:32:59 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 		/** print the object */ | 
					
						
							|  |  |  | 		void print(const std::string& s = "SubgraphPreconditioner") const; | 
					
						
							| 
									
										
										
										
											2009-12-31 20:56:47 +08:00
										 |  |  | 	}; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-18 13:51:19 +08:00
										 |  |  |   /**
 | 
					
						
							| 
									
										
										
										
											2010-01-19 18:46:12 +08:00
										 |  |  |    * A nonlinear system solver using subgraph preconditioning conjugate gradient | 
					
						
							| 
									
										
										
										
											2010-01-19 09:41:44 +08:00
										 |  |  |    * Concept NonLinearSolver<G,T,L> implements | 
					
						
							|  |  |  |    *   linearize: G * T -> L | 
					
						
							|  |  |  |    *   solve : L -> VectorConfig | 
					
						
							| 
									
										
										
										
											2010-01-18 13:51:19 +08:00
										 |  |  |    */ | 
					
						
							| 
									
										
										
										
											2010-01-19 18:46:12 +08:00
										 |  |  | 	template<class G, class T> | 
					
						
							| 
									
										
										
										
											2010-01-18 13:51:19 +08:00
										 |  |  | 	class SubgraphPCG { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	private: | 
					
						
							| 
									
										
										
										
											2010-01-19 18:46:12 +08:00
										 |  |  | 		typedef typename T::Key Key; | 
					
						
							|  |  |  | 		typedef typename G::Constraint Constraint; | 
					
						
							|  |  |  | 		typedef typename G::Pose Pose; | 
					
						
							| 
									
										
										
										
											2010-01-18 13:51:19 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 		const size_t maxIterations_; | 
					
						
							|  |  |  | 		const bool verbose_; | 
					
						
							|  |  |  | 		const double epsilon_, epsilon_abs_; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-18 17:24:38 +08:00
										 |  |  | 		/* the ordering derived from the spanning tree */ | 
					
						
							|  |  |  | 		boost::shared_ptr<Ordering> ordering_; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 		/* the solution computed from the first subgraph */ | 
					
						
							| 
									
										
										
										
											2010-01-19 18:46:12 +08:00
										 |  |  | 		boost::shared_ptr<T> theta_bar_; | 
					
						
							| 
									
										
										
										
											2010-01-18 17:24:38 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-19 18:46:12 +08:00
										 |  |  | 		G T_, C_; | 
					
						
							| 
									
										
										
										
											2010-01-18 13:51:19 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	public: | 
					
						
							| 
									
										
										
										
											2010-01-18 17:24:38 +08:00
										 |  |  | 		// kai: this constructor is for compatible with Factorization
 | 
					
						
							|  |  |  | 		SubgraphPCG() { throw std::runtime_error("SubgraphPCG: this constructor is only for compatibility!");} | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-19 21:29:40 +08:00
										 |  |  | 		SubgraphPCG(const G& g, const T& config); | 
					
						
							| 
									
										
										
										
											2010-01-18 13:51:19 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-18 17:24:38 +08:00
										 |  |  | 		boost::shared_ptr<Ordering> ordering() const { return ordering_; } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-19 18:46:12 +08:00
										 |  |  | 		boost::shared_ptr<T> theta_bar() const { return theta_bar_; } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 		/**
 | 
					
						
							|  |  |  | 		 * linearize the non-linear graph around the current config and build the subgraph preconditioner systme | 
					
						
							|  |  |  | 		 */ | 
					
						
							|  |  |  | 		SubgraphPreconditioner linearize(const G& g, const T& theta_bar) const; | 
					
						
							| 
									
										
										
										
											2010-01-18 17:24:38 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-18 13:51:19 +08:00
										 |  |  |   	/**
 | 
					
						
							|  |  |  |   	 * solve for the optimal displacement in the tangent space, and then solve | 
					
						
							|  |  |  |   	 * the resulted linear system | 
					
						
							|  |  |  |   	 */ | 
					
						
							| 
									
										
										
										
											2010-01-19 18:46:12 +08:00
										 |  |  |   	VectorConfig optimize(SubgraphPreconditioner& system, const Ordering& ordering) const; | 
					
						
							| 
									
										
										
										
											2010-01-18 13:51:19 +08:00
										 |  |  | 	}; | 
					
						
							| 
									
										
										
										
											2009-12-31 20:56:47 +08:00
										 |  |  | } // nsamespace gtsam
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #endif /* SUBGRAPHPRECONDITIONER_H_ */
 |