| 
									
										
										
										
											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 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | /**
 | 
					
						
							| 
									
										
										
										
											2009-11-13 00:16:32 +08:00
										 |  |  |  * @file    GaussianFactorGraph.h | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  |  * @brief   Linear Factor Graph where all factors are Gaussians | 
					
						
							|  |  |  |  * @author  Kai Ni | 
					
						
							|  |  |  |  * @author  Christian Potthast | 
					
						
							|  |  |  |  * @author  Alireza Fathi | 
					
						
							|  |  |  |  */  | 
					
						
							|  |  |  |   | 
					
						
							|  |  |  | #pragma once
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <boost/shared_ptr.hpp>
 | 
					
						
							| 
									
										
										
										
											2010-05-31 10:21:37 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-20 01:23:19 +08:00
										 |  |  | #include <gtsam/inference/FactorGraph.h>
 | 
					
						
							|  |  |  | #include <gtsam/linear/Errors.h>
 | 
					
						
							|  |  |  | #include <gtsam/linear/GaussianFactor.h>
 | 
					
						
							|  |  |  | #include <gtsam/linear/GaussianBayesNet.h>
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | namespace gtsam { | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-10-07 02:25:04 +08:00
										 |  |  |   /**
 | 
					
						
							|  |  |  |    * A Linear Factor Graph is a factor graph where all factors are Gaussian, i.e. | 
					
						
							| 
									
										
										
										
											2009-11-13 00:16:32 +08:00
										 |  |  |    *   Factor == GaussianFactor | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |    *   VectorValues = A values structure of vectors | 
					
						
							| 
									
										
										
										
											2009-10-07 02:25:04 +08:00
										 |  |  |    * Most of the time, linear factor graphs arise by linearizing a non-linear factor graph. | 
					
						
							|  |  |  |    */ | 
					
						
							| 
									
										
										
										
											2009-11-13 00:16:32 +08:00
										 |  |  |   class GaussianFactorGraph : public FactorGraph<GaussianFactor> { | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  |   public: | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |     typedef boost::shared_ptr<GaussianFactorGraph> shared_ptr; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  |     /**
 | 
					
						
							|  |  |  |      * Default constructor  | 
					
						
							|  |  |  |      */ | 
					
						
							| 
									
										
										
										
											2009-11-13 00:16:32 +08:00
										 |  |  |     GaussianFactorGraph() {} | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     /**
 | 
					
						
							| 
									
										
										
										
											2009-11-13 00:16:32 +08:00
										 |  |  |      * Constructor that receives a Chordal Bayes Net and returns a GaussianFactorGraph | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  |      */ | 
					
						
							| 
									
										
										
										
											2009-11-13 00:16:32 +08:00
										 |  |  |     GaussianFactorGraph(const GaussianBayesNet& CBN); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-22 06:59:54 +08:00
										 |  |  |     /** Constructor from a factor graph of GaussianFactor or a derived type */ | 
					
						
							|  |  |  |     template<class DERIVEDFACTOR> | 
					
						
							|  |  |  |     GaussianFactorGraph(const FactorGraph<DERIVEDFACTOR>& fg) { | 
					
						
							|  |  |  |       push_back(fg); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-12-10 23:33:52 +08:00
										 |  |  |   	/** Add a null factor */ | 
					
						
							| 
									
										
										
										
											2010-10-18 01:22:02 +08:00
										 |  |  |     void add(const Vector& b) { | 
					
						
							| 
									
										
										
										
											2009-12-10 23:33:52 +08:00
										 |  |  |     	push_back(sharedFactor(new GaussianFactor(b))); | 
					
						
							|  |  |  |   	} | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   	/** Add a unary factor */ | 
					
						
							| 
									
										
										
										
											2010-10-18 01:22:02 +08:00
										 |  |  |     void add(Index key1, const Matrix& A1, | 
					
						
							| 
									
										
										
										
											2010-01-23 01:36:57 +08:00
										 |  |  |   			const Vector& b, const SharedDiagonal& model) { | 
					
						
							| 
									
										
										
										
											2010-01-21 02:32:48 +08:00
										 |  |  |     	push_back(sharedFactor(new GaussianFactor(key1,A1,b,model))); | 
					
						
							| 
									
										
										
										
											2009-12-10 23:33:52 +08:00
										 |  |  |   	} | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   	/** Add a binary factor */ | 
					
						
							| 
									
										
										
										
											2010-10-18 01:22:02 +08:00
										 |  |  |     void add(Index key1, const Matrix& A1, | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  |   			Index key2, const Matrix& A2, | 
					
						
							| 
									
										
										
										
											2010-01-23 01:36:57 +08:00
										 |  |  |   			const Vector& b, const SharedDiagonal& model) { | 
					
						
							| 
									
										
										
										
											2010-01-21 02:32:48 +08:00
										 |  |  |     	push_back(sharedFactor(new GaussianFactor(key1,A1,key2,A2,b,model))); | 
					
						
							| 
									
										
										
										
											2009-12-10 23:33:52 +08:00
										 |  |  |   	} | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   	/** Add a ternary factor */ | 
					
						
							| 
									
										
										
										
											2010-10-18 01:22:02 +08:00
										 |  |  |     void add(Index key1, const Matrix& A1, | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  |   			Index key2, const Matrix& A2, | 
					
						
							|  |  |  |   			Index key3, const Matrix& A3, | 
					
						
							| 
									
										
										
										
											2010-01-23 01:36:57 +08:00
										 |  |  |   			const Vector& b, const SharedDiagonal& model) { | 
					
						
							| 
									
										
										
										
											2010-01-21 02:32:48 +08:00
										 |  |  |     	push_back(sharedFactor(new GaussianFactor(key1,A1,key2,A2,key3,A3,b,model))); | 
					
						
							| 
									
										
										
										
											2009-12-10 23:33:52 +08:00
										 |  |  |   	} | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   	/** Add an n-ary factor */ | 
					
						
							| 
									
										
										
										
											2010-10-18 01:22:02 +08:00
										 |  |  |     void add(const std::vector<std::pair<Index, Matrix> > &terms, | 
					
						
							| 
									
										
										
										
											2010-01-23 01:36:57 +08:00
										 |  |  |   	    const Vector &b, const SharedDiagonal& model) { | 
					
						
							| 
									
										
										
										
											2010-01-21 02:32:48 +08:00
										 |  |  |     	push_back(sharedFactor(new GaussianFactor(terms,b,model))); | 
					
						
							| 
									
										
										
										
											2009-12-10 23:33:52 +08:00
										 |  |  |   	} | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |     /**
 | 
					
						
							|  |  |  |      * Return the set of variables involved in the factors (computes a set | 
					
						
							|  |  |  |      * union). | 
					
						
							|  |  |  |      */ | 
					
						
							| 
									
										
										
										
											2010-10-18 01:22:02 +08:00
										 |  |  |     typedef std::set<Index, std::less<Index>, boost::fast_pool_allocator<Index> > Keys; | 
					
						
							|  |  |  |     Keys keys() const; | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     /** Permute the variables in the factors */ | 
					
						
							|  |  |  |     void permuteWithInverse(const Permutation& inversePermutation); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-12-27 20:13:31 +08:00
										 |  |  | 		/** return A*x-b */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 		Errors errors(const VectorValues& x) const; | 
					
						
							| 
									
										
										
										
											2009-12-27 20:13:31 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-19 18:46:12 +08:00
										 |  |  | 		/** shared pointer version */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 		boost::shared_ptr<Errors> errors_(const VectorValues& x) const; | 
					
						
							| 
									
										
										
										
											2010-01-19 18:46:12 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-12-27 20:13:31 +08:00
										 |  |  | 			/** unnormalized error */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 		double error(const VectorValues& x) const; | 
					
						
							| 
									
										
										
										
											2009-10-29 12:11:23 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-12-27 06:48:41 +08:00
										 |  |  | 		/** return A*x */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 		Errors operator*(const VectorValues& x) const; | 
					
						
							| 
									
										
										
										
											2009-10-29 12:11:23 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-31 01:31:05 +08:00
										 |  |  | 		/* In-place version e <- A*x that overwrites e. */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 		void multiplyInPlace(const VectorValues& x, Errors& e) const; | 
					
						
							| 
									
										
										
										
											2010-01-31 01:31:05 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 		/* In-place version e <- A*x that takes an iterator. */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 		void multiplyInPlace(const VectorValues& x, const Errors::iterator& e) const; | 
					
						
							| 
									
										
										
										
											2010-01-31 01:31:05 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-31 07:59:29 +08:00
										 |  |  | 		/** x += alpha*A'*e */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 		void transposeMultiplyAdd(double alpha, const Errors& e, VectorValues& x) const; | 
					
						
							| 
									
										
										
										
											2010-01-31 07:59:29 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-15 00:08:16 +08:00
										 |  |  | 		/**
 | 
					
						
							|  |  |  | 		 * Calculate Gradient of A^(A*x-b) for a given config | 
					
						
							|  |  |  | 		 * @param x: VectorValues specifying where to calculate gradient | 
					
						
							|  |  |  | 		 * @return gradient, as a VectorValues as well | 
					
						
							|  |  |  | 		 */ | 
					
						
							|  |  |  | 		VectorValues gradient(const VectorValues& x) const; | 
					
						
							| 
									
										
										
										
											2009-12-27 20:13:31 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-10-29 12:11:23 +08:00
										 |  |  | 		/** Unnormalized probability. O(n) */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 		double probPrime(const VectorValues& c) const { | 
					
						
							| 
									
										
										
										
											2009-10-29 12:11:23 +08:00
										 |  |  | 			return exp(-0.5 * error(c)); | 
					
						
							|  |  |  | 		} | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  |     /**
 | 
					
						
							| 
									
										
										
										
											2009-08-25 10:36:30 +08:00
										 |  |  |      * static function that combines two factor graphs | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  |      * @param const &lfg1 Linear factor graph | 
					
						
							|  |  |  |      * @param const &lfg2 Linear factor graph | 
					
						
							|  |  |  |      * @return a new combined factor graph | 
					
						
							|  |  |  |      */ | 
					
						
							| 
									
										
										
										
											2009-11-13 00:16:32 +08:00
										 |  |  |     static GaussianFactorGraph combine2(const GaussianFactorGraph& lfg1, | 
					
						
							|  |  |  | 				const GaussianFactorGraph& lfg2); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 		 | 
					
						
							|  |  |  |     /**
 | 
					
						
							|  |  |  |      * combine two factor graphs | 
					
						
							|  |  |  |      * @param *lfg Linear factor graph | 
					
						
							|  |  |  |      */ | 
					
						
							| 
									
										
										
										
											2009-11-13 00:16:32 +08:00
										 |  |  |     void combine(const GaussianFactorGraph &lfg); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /**
 | 
					
						
							|  |  |  |      * Add zero-mean i.i.d. Gaussian prior terms to each variable | 
					
						
							|  |  |  |      * @param sigma Standard deviation of Gaussian | 
					
						
							|  |  |  |      */ | 
					
						
							| 
									
										
										
										
											2010-10-23 02:02:55 +08:00
										 |  |  |     GaussianFactorGraph add_priors(double sigma, const std::vector<size_t>& dimensions) const; | 
					
						
							| 
									
										
										
										
											2010-10-19 03:23:15 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-05-31 10:21:37 +08:00
										 |  |  |   }; | 
					
						
							| 
									
										
										
										
											2010-07-08 05:41:50 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-03-05 23:09:09 +08:00
										 |  |  | } // namespace gtsam
 |