2010-03-13 03:19:21 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/*
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * SubgraphSolver.h
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * Created on: Dec 31, 2009
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * @author: Frank Dellaert
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#pragma once
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2010-08-20 01:23:19 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/linear/GaussianFactorGraph.h>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/linear/GaussianBayesNet.h>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/inference/Ordering.h>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/linear/SubgraphPreconditioner.h>
							 | 
						
					
						
							
								
									
										
										
										
											2010-03-13 03:19:21 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								namespace gtsam {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /**
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								   * A nonlinear system solver using subgraph preconditioning conjugate gradient
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								   * Concept NonLinearSolver<G,T,L> implements
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								   *   linearize: G * T -> L
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								   *   solve : L -> VectorValues
							 | 
						
					
						
							
								
									
										
										
										
											2010-03-13 03:19:21 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								   */
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
									template<class Graph, class Values>
							 | 
						
					
						
							
								
									
										
										
										
											2010-03-13 03:19:21 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
									class SubgraphSolver {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
									private:
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
										typedef typename Values::Key Key;
							 | 
						
					
						
							
								
									
										
										
										
											2010-03-13 06:00:55 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
										typedef typename Graph::Constraint Constraint;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
										typedef typename Graph::Pose Pose;
							 | 
						
					
						
							
								
									
										
										
										
											2010-03-13 03:19:21 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
										// TODO not hardcode
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
										static const size_t maxIterations_=100;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
										static const bool verbose_=false;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
										static const double epsilon_=1e-4, epsilon_abs_=1e-5;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
										/* the ordering derived from the spanning tree */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
										boost::shared_ptr<Ordering> ordering_;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
										/* the solution computed from the first subgraph */
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
										boost::shared_ptr<Values> theta_bar_;
							 | 
						
					
						
							
								
									
										
										
										
											2010-03-13 03:19:21 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2010-03-13 06:00:55 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
										Graph T_, C_;
							 | 
						
					
						
							
								
									
										
										
										
											2010-03-13 03:19:21 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
									public:
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
										SubgraphSolver() {}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
										SubgraphSolver(const Graph& G, const Values& theta0);
							 | 
						
					
						
							
								
									
										
										
										
											2010-03-13 03:19:21 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
										void initialize(const Graph& G, const Values& theta0);
							 | 
						
					
						
							
								
									
										
										
										
											2010-03-13 03:19:21 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
										boost::shared_ptr<Ordering> ordering() const { return ordering_; }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
										boost::shared_ptr<Values> theta_bar() const { return theta_bar_; }
							 | 
						
					
						
							
								
									
										
										
										
											2010-03-13 03:19:21 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
										/**
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
										 * linearize the non-linear graph around the current config and build the subgraph preconditioner systme
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
										 */
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
										boost::shared_ptr<SubgraphPreconditioner> linearize(const Graph& G, const Values& theta_bar) const;
							 | 
						
					
						
							
								
									
										
										
										
											2010-03-13 03:19:21 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  	/**
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  	 * solve for the optimal displacement in the tangent space, and then solve
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  	 * the resulted linear system
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  	 */
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  	VectorValues optimize(SubgraphPreconditioner& system) const;
							 | 
						
					
						
							
								
									
										
										
										
											2010-06-11 02:28:07 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  	boost::shared_ptr<SubgraphSolver> prepareLinear(const SubgraphPreconditioner& fg) const {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  		return boost::shared_ptr<SubgraphSolver>(new SubgraphSolver(*this));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  	}
							 | 
						
					
						
							
								
									
										
										
										
											2010-03-13 03:19:21 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
									};
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
									template<class Graph, class Values> const size_t SubgraphSolver<Graph,Values>::maxIterations_;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
									template<class Graph, class Values> const bool SubgraphSolver<Graph,Values>::verbose_;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
									template<class Graph, class Values> const double SubgraphSolver<Graph,Values>::epsilon_;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
									template<class Graph, class Values> const double	SubgraphSolver<Graph,Values>::epsilon_abs_;
							 | 
						
					
						
							
								
									
										
										
										
											2010-03-13 03:19:21 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								} // nsamespace gtsam
							 |