| 
									
										
										
										
											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-03-05 23:09:09 +08:00
										 |  |  | /**
 | 
					
						
							|  |  |  |  * @file    Factorization | 
					
						
							|  |  |  |  * @brief   Template Linear solver class that uses a Gaussian Factor Graph | 
					
						
							|  |  |  |  * @author  Kai Ni | 
					
						
							|  |  |  |  * @author  Frank Dellaert | 
					
						
							|  |  |  |  */  | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // $Id: GaussianFactorGraph.h,v 1.24 2009/08/14 20:48:51 acunning Exp $
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #pragma once
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <stdexcept>
 | 
					
						
							| 
									
										
										
										
											2010-08-20 01:23:19 +08:00
										 |  |  | #include <gtsam/linear/GaussianFactorGraph.h>
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | #include <gtsam/inference/inference-inl.h>
 | 
					
						
							| 
									
										
										
										
											2010-03-05 23:09:09 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | namespace gtsam { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	class Ordering; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /**
 | 
					
						
							|  |  |  |    * A linear system solver using factorization | 
					
						
							|  |  |  |    */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   template <class NonlinearGraph, class Values> | 
					
						
							| 
									
										
										
										
											2010-03-05 23:09:09 +08:00
										 |  |  |   class Factorization { | 
					
						
							|  |  |  |   private: | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   	boost::shared_ptr<Ordering> ordering_; | 
					
						
							| 
									
										
										
										
											2010-03-05 23:09:09 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   public: | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   	Factorization(boost::shared_ptr<Ordering> ordering) | 
					
						
							|  |  |  | 		: ordering_(ordering) { | 
					
						
							| 
									
										
										
										
											2010-03-05 23:09:09 +08:00
										 |  |  |   		if (!ordering) throw std::invalid_argument("Factorization constructor: ordering = NULL"); | 
					
						
							|  |  |  |   	} | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   	/**
 | 
					
						
							|  |  |  |   	 * 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(GaussianFactorGraph& fg) const { | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   	  return gtsam::optimize(*Inference::Eliminate(fg)); | 
					
						
							| 
									
										
										
										
											2010-03-05 23:09:09 +08:00
										 |  |  |   	} | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 		/**
 | 
					
						
							|  |  |  | 		 * linearize the non-linear graph around the current config | 
					
						
							|  |  |  | 		 */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   	boost::shared_ptr<GaussianFactorGraph> linearize(const NonlinearGraph& g, const Values& config) const { | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   		return g.linearize(config, *ordering_); | 
					
						
							| 
									
										
										
										
											2010-03-05 23:09:09 +08:00
										 |  |  |   	} | 
					
						
							| 
									
										
										
										
											2010-05-31 10:21:37 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   	/**
 | 
					
						
							| 
									
										
										
										
											2010-06-06 04:46:16 +08:00
										 |  |  |   	 * Does not do anything here in Factorization. | 
					
						
							| 
									
										
										
										
											2010-05-31 10:21:37 +08:00
										 |  |  |   	 */ | 
					
						
							| 
									
										
										
										
											2010-06-06 04:46:16 +08:00
										 |  |  |   	boost::shared_ptr<Factorization> prepareLinear(const GaussianFactorGraph& fg) const { | 
					
						
							|  |  |  |   		return boost::shared_ptr<Factorization>(new Factorization(*this)); | 
					
						
							| 
									
										
										
										
											2010-05-31 10:21:37 +08:00
										 |  |  |   	} | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   	/** expmap the Values given the stored Ordering */ | 
					
						
							|  |  |  |   	Values expmap(const Values& config, const VectorValues& delta) const { | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   	  return config.expmap(delta, *ordering_); | 
					
						
							|  |  |  |   	} | 
					
						
							| 
									
										
										
										
											2010-05-31 10:21:37 +08:00
										 |  |  |   }; | 
					
						
							| 
									
										
										
										
											2010-06-06 04:46:16 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-03-05 23:09:09 +08:00
										 |  |  | } |