| 
									
										
										
										
											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.cpp | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  |  * @brief   Linear Factor Graph where all factors are Gaussians | 
					
						
							|  |  |  |  * @author  Kai Ni | 
					
						
							|  |  |  |  * @author  Christian Potthast | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <boost/foreach.hpp>
 | 
					
						
							|  |  |  | #include <boost/tuple/tuple.hpp>
 | 
					
						
							|  |  |  | #include <boost/numeric/ublas/lu.hpp>
 | 
					
						
							|  |  |  | #include <boost/numeric/ublas/io.hpp>
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-20 01:23:19 +08:00
										 |  |  | #include <gtsam/linear/GaussianFactorGraph.h>
 | 
					
						
							|  |  |  | #include <gtsam/linear/GaussianFactorSet.h>
 | 
					
						
							|  |  |  | #include <gtsam/inference/FactorGraph-inl.h>
 | 
					
						
							|  |  |  | #include <gtsam/inference/inference-inl.h>
 | 
					
						
							|  |  |  | #include <gtsam/linear/iterative.h>
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //#include <gtsam/linear/GaussianJunctionTree.h>
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							| 
									
										
										
										
											2010-02-01 01:49:33 +08:00
										 |  |  | using namespace boost::assign; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-11-06 13:43:03 +08:00
										 |  |  | // trick from some reading group
 | 
					
						
							|  |  |  | #define FOREACH_PAIR( KEY, VAL, COL) BOOST_FOREACH (boost::tie(KEY,VAL),COL)
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-07-08 05:41:50 +08:00
										 |  |  | namespace gtsam { | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-10-30 13:45:22 +08:00
										 |  |  | // Explicitly instantiate so we don't have to include everywhere
 | 
					
						
							| 
									
										
										
										
											2009-11-13 00:16:32 +08:00
										 |  |  | template class FactorGraph<GaussianFactor>; | 
					
						
							| 
									
										
										
										
											2009-10-30 13:45:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2009-11-13 00:16:32 +08:00
										 |  |  | GaussianFactorGraph::GaussianFactorGraph(const GaussianBayesNet& CBN) : | 
					
						
							|  |  |  | 	FactorGraph<GaussianFactor> (CBN) { | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  | std::set<Index, std::less<Index>, boost::fast_pool_allocator<Index> > | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | GaussianFactorGraph::keys() const { | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  |   std::set<Index, std::less<Index>, boost::fast_pool_allocator<Index> > keys; | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   BOOST_FOREACH(const sharedFactor& factor, *this) { | 
					
						
							|  |  |  |     if(factor) keys.insert(factor->begin(), factor->end()); } | 
					
						
							|  |  |  |   return keys; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | void GaussianFactorGraph::permuteWithInverse(const Permutation& inversePermutation) { | 
					
						
							|  |  |  |   BOOST_FOREACH(const sharedFactor& factor, factors_) { | 
					
						
							|  |  |  |     factor->permuteWithInverse(inversePermutation); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-12-27 06:48:41 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | double GaussianFactorGraph::error(const VectorValues& x) const { | 
					
						
							| 
									
										
										
										
											2009-12-27 06:48:41 +08:00
										 |  |  | 	double total_error = 0.; | 
					
						
							|  |  |  | 	BOOST_FOREACH(sharedFactor factor,factors_) | 
					
						
							|  |  |  | 		total_error += factor->error(x); | 
					
						
							|  |  |  | 	return total_error; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | Errors GaussianFactorGraph::errors(const VectorValues& x) const { | 
					
						
							| 
									
										
										
										
											2010-01-19 18:46:12 +08:00
										 |  |  | 	return *errors_(x); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | boost::shared_ptr<Errors> GaussianFactorGraph::errors_(const VectorValues& x) const { | 
					
						
							| 
									
										
										
										
											2010-01-19 18:46:12 +08:00
										 |  |  | 	boost::shared_ptr<Errors> e(new Errors); | 
					
						
							| 
									
										
										
										
											2010-02-22 01:06:11 +08:00
										 |  |  | 	BOOST_FOREACH(const sharedFactor& factor,factors_) | 
					
						
							| 
									
										
										
										
											2010-01-19 18:46:12 +08:00
										 |  |  | 		e->push_back(factor->error_vector(x)); | 
					
						
							| 
									
										
										
										
											2009-12-27 06:48:41 +08:00
										 |  |  | 	return e; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-12-27 20:13:31 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | Errors GaussianFactorGraph::operator*(const VectorValues& x) const { | 
					
						
							| 
									
										
										
										
											2009-12-27 20:13:31 +08:00
										 |  |  | 	Errors e; | 
					
						
							| 
									
										
										
										
											2010-02-22 01:06:11 +08:00
										 |  |  | 	BOOST_FOREACH(const sharedFactor& Ai,factors_) | 
					
						
							| 
									
										
										
										
											2009-12-27 20:13:31 +08:00
										 |  |  | 		e.push_back((*Ai)*x); | 
					
						
							|  |  |  | 	return e; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-31 01:31:05 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | void GaussianFactorGraph::multiplyInPlace(const VectorValues& x, Errors& e) const { | 
					
						
							| 
									
										
										
										
											2010-01-31 01:31:05 +08:00
										 |  |  | 	multiplyInPlace(x,e.begin()); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | void GaussianFactorGraph::multiplyInPlace(const VectorValues& x, | 
					
						
							| 
									
										
										
										
											2010-01-31 01:31:05 +08:00
										 |  |  | 		const Errors::iterator& e) const { | 
					
						
							|  |  |  | 	Errors::iterator ei = e; | 
					
						
							| 
									
										
										
										
											2010-02-22 01:06:11 +08:00
										 |  |  | 	BOOST_FOREACH(const sharedFactor& Ai,factors_) { | 
					
						
							| 
									
										
										
										
											2010-01-31 01:31:05 +08:00
										 |  |  | 		*ei = (*Ai)*x; | 
					
						
							|  |  |  | 		ei++; | 
					
						
							|  |  |  | 	} | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | ///* ************************************************************************* */
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | //VectorValues GaussianFactorGraph::operator^(const Errors& e) const {
 | 
					
						
							|  |  |  | //	VectorValues x;
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //	// For each factor add the gradient contribution
 | 
					
						
							|  |  |  | //	Errors::const_iterator it = e.begin();
 | 
					
						
							|  |  |  | //	BOOST_FOREACH(const sharedFactor& Ai,factors_) {
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | //		VectorValues xi = (*Ai)^(*(it++));
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //		x.insertAdd(xi);
 | 
					
						
							|  |  |  | //	}
 | 
					
						
							|  |  |  | //	return x;
 | 
					
						
							|  |  |  | //}
 | 
					
						
							| 
									
										
										
										
											2009-12-27 20:13:31 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-31 07:59:29 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | // x += alpha*A'*e
 | 
					
						
							|  |  |  | void GaussianFactorGraph::transposeMultiplyAdd(double alpha, const Errors& e, | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 		VectorValues& x) const { | 
					
						
							| 
									
										
										
										
											2010-01-31 07:59:29 +08:00
										 |  |  | 	// For each factor add the gradient contribution
 | 
					
						
							| 
									
										
										
										
											2010-01-31 11:33:53 +08:00
										 |  |  | 	Errors::const_iterator ei = e.begin(); | 
					
						
							| 
									
										
										
										
											2010-02-22 01:06:11 +08:00
										 |  |  | 	BOOST_FOREACH(const sharedFactor& Ai,factors_) | 
					
						
							| 
									
										
										
										
											2010-01-31 11:33:53 +08:00
										 |  |  | 		Ai->transposeMultiplyAdd(alpha,*(ei++),x); | 
					
						
							| 
									
										
										
										
											2010-01-31 07:59:29 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-15 00:08:16 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | VectorValues GaussianFactorGraph::gradient(const VectorValues& x) const { | 
					
						
							|  |  |  | 	// It is crucial for performance to make a zero-valued clone of x
 | 
					
						
							|  |  |  | 	VectorValues g = VectorValues::zero(x); | 
					
						
							|  |  |  | 	transposeMultiplyAdd(1.0, errors(x), g); | 
					
						
							|  |  |  | 	return g; | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | ///* ************************************************************************* */
 | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  | //set<Index> GaussianFactorGraph::find_separator(Index key) const
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //{
 | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  | //	set<Index> separator;
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //	BOOST_FOREACH(const sharedFactor& factor,factors_)
 | 
					
						
							|  |  |  | //		factor->tally_separator(key,separator);
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	return separator;
 | 
					
						
							|  |  |  | //}
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | ///* ************************************************************************* */
 | 
					
						
							|  |  |  | //template <class Factors>
 | 
					
						
							|  |  |  | //std::pair<Matrix, SharedDiagonal> combineFactorsAndCreateMatrix(
 | 
					
						
							|  |  |  | //		const Factors& factors,
 | 
					
						
							|  |  |  | //		const Ordering& order, const Dimensions& dimensions) {
 | 
					
						
							|  |  |  | //	// find the size of Ab
 | 
					
						
							|  |  |  | //	size_t m = 0, n = 1;
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	// number of rows
 | 
					
						
							|  |  |  | //	BOOST_FOREACH(GaussianFactor::shared_ptr factor, factors) {
 | 
					
						
							|  |  |  | //		m += factor->numberOfRows();
 | 
					
						
							|  |  |  | //	}
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	// find the number of columns
 | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  | //	BOOST_FOREACH(Index key, order) {
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //		n += dimensions.at(key);
 | 
					
						
							|  |  |  | //	}
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	// Allocate the new matrix
 | 
					
						
							|  |  |  | //	Matrix Ab = zeros(m,n);
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	// Allocate a sigmas vector to make into a full noisemodel
 | 
					
						
							|  |  |  | //	Vector sigmas = ones(m);
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	// copy data over
 | 
					
						
							|  |  |  | //	size_t cur_m = 0;
 | 
					
						
							|  |  |  | //	bool constrained = false;
 | 
					
						
							|  |  |  | //	bool unit = true;
 | 
					
						
							|  |  |  | //	BOOST_FOREACH(GaussianFactor::shared_ptr factor, factors) {
 | 
					
						
							|  |  |  | //		// loop through ordering
 | 
					
						
							|  |  |  | //		size_t cur_n = 0;
 | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  | //		BOOST_FOREACH(Index key, order) {
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //			// copy over matrix if it exists
 | 
					
						
							|  |  |  | //			if (factor->involves(key)) {
 | 
					
						
							|  |  |  | //				insertSub(Ab, factor->get_A(key), cur_m, cur_n);
 | 
					
						
							|  |  |  | //			}
 | 
					
						
							|  |  |  | //			// move onto next element
 | 
					
						
							|  |  |  | //			cur_n += dimensions.at(key);
 | 
					
						
							|  |  |  | //		}
 | 
					
						
							|  |  |  | //		// copy over the RHS
 | 
					
						
							|  |  |  | //		insertColumn(Ab, factor->get_b(), cur_m, n-1);
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //		// check if the model is unit already
 | 
					
						
							|  |  |  | //		if (!boost::shared_dynamic_cast<noiseModel::Unit>(factor->get_model())) {
 | 
					
						
							|  |  |  | //			unit = false;
 | 
					
						
							|  |  |  | //			const Vector& subsigmas = factor->get_model()->sigmas();
 | 
					
						
							|  |  |  | //			subInsert(sigmas, subsigmas, cur_m);
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //			// check for constraint
 | 
					
						
							|  |  |  | //			if (boost::shared_dynamic_cast<noiseModel::Constrained>(factor->get_model()))
 | 
					
						
							|  |  |  | //				constrained = true;
 | 
					
						
							|  |  |  | //		}
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //		// move to next row
 | 
					
						
							|  |  |  | //		cur_m += factor->numberOfRows();
 | 
					
						
							|  |  |  | //	}
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	// combine the noisemodels
 | 
					
						
							|  |  |  | //	SharedDiagonal model;
 | 
					
						
							|  |  |  | //	if (unit) {
 | 
					
						
							|  |  |  | //		model = noiseModel::Unit::Create(m);
 | 
					
						
							|  |  |  | //	} else if (constrained) {
 | 
					
						
							|  |  |  | //		model = noiseModel::Constrained::MixedSigmas(sigmas);
 | 
					
						
							|  |  |  | //	} else {
 | 
					
						
							|  |  |  | //		model = noiseModel::Diagonal::Sigmas(sigmas);
 | 
					
						
							|  |  |  | //	}
 | 
					
						
							|  |  |  | //	return make_pair(Ab, model);
 | 
					
						
							|  |  |  | //}
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | ///* ************************************************************************* */
 | 
					
						
							|  |  |  | //GaussianConditional::shared_ptr
 | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  | //GaussianFactorGraph::eliminateOneMatrixJoin(Index key) {
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //	// find and remove all factors connected to key
 | 
					
						
							|  |  |  | //	vector<GaussianFactor::shared_ptr> factors = findAndRemoveFactors(key);
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	// Collect all dimensions as well as the set of separator keys
 | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  | //	set<Index> separator;
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //	Dimensions dimensions;
 | 
					
						
							|  |  |  | //	BOOST_FOREACH(const sharedFactor& factor, factors) {
 | 
					
						
							|  |  |  | //		Dimensions factor_dim = factor->dimensions();
 | 
					
						
							|  |  |  | //		dimensions.insert(factor_dim.begin(), factor_dim.end());
 | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  | //		BOOST_FOREACH(Index k, factor->keys())
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //			if (!k == key)
 | 
					
						
							|  |  |  | //				separator.insert(k);
 | 
					
						
							|  |  |  | //	}
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	// add the keys to the rendering
 | 
					
						
							|  |  |  | //	Ordering render; render += key;
 | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  | //	BOOST_FOREACH(Index k, separator)
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //			if (k != key) render += k;
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	// combine the factors to get a noisemodel and a combined matrix
 | 
					
						
							|  |  |  | //	Matrix Ab; SharedDiagonal model;
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	boost::tie(Ab, model) =	combineFactorsAndCreateMatrix(factors,render,dimensions);
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	// eliminate that joint factor
 | 
					
						
							|  |  |  | //	GaussianFactor::shared_ptr factor;
 | 
					
						
							|  |  |  | //	GaussianConditional::shared_ptr conditional;
 | 
					
						
							|  |  |  | //	render.pop_front();
 | 
					
						
							|  |  |  | //	boost::tie(conditional, factor) =
 | 
					
						
							|  |  |  | //			GaussianFactor::eliminateMatrix(Ab, model, key, render, dimensions);
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	// add new factor on separator back into the graph
 | 
					
						
							|  |  |  | //	if (!factor->empty()) push_back(factor);
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	// return the conditional Gaussian
 | 
					
						
							|  |  |  | //	return conditional;
 | 
					
						
							|  |  |  | //}
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | ///* ************************************************************************* */
 | 
					
						
							|  |  |  | //GaussianBayesNet
 | 
					
						
							|  |  |  | //GaussianFactorGraph::eliminateFrontals(const Ordering& frontals)
 | 
					
						
							|  |  |  | //{
 | 
					
						
							|  |  |  | //	// find the factors that contain at least one of the frontal variables
 | 
					
						
							|  |  |  | //	Dimensions dimensions = this->dimensions();
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	// collect separator
 | 
					
						
							|  |  |  | //	Ordering separator;
 | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  | //	set<Index> frontal_set(frontals.begin(), frontals.end());
 | 
					
						
							|  |  |  | //	BOOST_FOREACH(Index key, this->keys()) {
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //		if (frontal_set.find(key) == frontal_set.end())
 | 
					
						
							|  |  |  | //			separator.push_back(key);
 | 
					
						
							|  |  |  | //	}
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	Matrix Ab; SharedDiagonal model;
 | 
					
						
							|  |  |  | //	Ordering ord = frontals;
 | 
					
						
							|  |  |  | //	ord.insert(ord.end(), separator.begin(), separator.end());
 | 
					
						
							|  |  |  | //	boost::tie(Ab, model) = combineFactorsAndCreateMatrix(*this, ord, dimensions);
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	// eliminate that joint factor
 | 
					
						
							|  |  |  | //	GaussianFactor::shared_ptr factor;
 | 
					
						
							|  |  |  | //	GaussianBayesNet bn;
 | 
					
						
							|  |  |  | //	boost::tie(bn, factor) =
 | 
					
						
							|  |  |  | //			GaussianFactor::eliminateMatrix(Ab, model, frontals, separator, dimensions);
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	// add new factor on separator back into the graph
 | 
					
						
							|  |  |  | //	*this = GaussianFactorGraph();
 | 
					
						
							|  |  |  | //	if (!factor->empty()) push_back(factor);
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	return bn;
 | 
					
						
							|  |  |  | //}
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | ///* ************************************************************************* */
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | //VectorValues GaussianFactorGraph::optimize(const Ordering& ordering, bool old)
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //{
 | 
					
						
							|  |  |  | //	// eliminate all nodes in the given ordering -> chordal Bayes net
 | 
					
						
							|  |  |  | //	GaussianBayesNet chordalBayesNet = eliminate(ordering, old);
 | 
					
						
							|  |  |  | //
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | //	// calculate new values structure (using backsubstitution)
 | 
					
						
							|  |  |  | //	VectorValues delta = ::optimize(chordalBayesNet);
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //	return delta;
 | 
					
						
							|  |  |  | //}
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | ///* ************************************************************************* */
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | //VectorValues GaussianFactorGraph::optimizeMultiFrontals(const Ordering& ordering)
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //{
 | 
					
						
							|  |  |  | //	GaussianJunctionTree junctionTree(*this, ordering);
 | 
					
						
							|  |  |  | //
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | //	// calculate new values structure (using backsubstitution)
 | 
					
						
							|  |  |  | //	VectorValues delta = junctionTree.optimize();
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //	return delta;
 | 
					
						
							|  |  |  | //}
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | ///* ************************************************************************* */
 | 
					
						
							|  |  |  | //boost::shared_ptr<GaussianBayesNet>
 | 
					
						
							|  |  |  | //GaussianFactorGraph::eliminate_(const Ordering& ordering)
 | 
					
						
							|  |  |  | //{
 | 
					
						
							|  |  |  | //	boost::shared_ptr<GaussianBayesNet> chordalBayesNet(new GaussianBayesNet); // empty
 | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  | //	BOOST_FOREACH(Index key, ordering) {
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //		GaussianConditional::shared_ptr cg = eliminateOne(key);
 | 
					
						
							|  |  |  | //		chordalBayesNet->push_back(cg);
 | 
					
						
							|  |  |  | //	}
 | 
					
						
							|  |  |  | //	return chordalBayesNet;
 | 
					
						
							|  |  |  | //}
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | ///* ************************************************************************* */
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | //boost::shared_ptr<VectorValues>
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //GaussianFactorGraph::optimize_(const Ordering& ordering) {
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | //	return boost::shared_ptr<VectorValues>(new VectorValues(optimize(ordering)));
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //}
 | 
					
						
							| 
									
										
										
										
											2009-11-11 15:14:13 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2009-11-13 00:16:32 +08:00
										 |  |  | void GaussianFactorGraph::combine(const GaussianFactorGraph &lfg){ | 
					
						
							| 
									
										
										
										
											2009-08-31 10:40:26 +08:00
										 |  |  | 	for(const_iterator factor=lfg.factors_.begin(); factor!=lfg.factors_.end(); factor++){ | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 		push_back(*factor); | 
					
						
							|  |  |  | 	} | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2009-11-13 00:16:32 +08:00
										 |  |  | GaussianFactorGraph GaussianFactorGraph::combine2(const GaussianFactorGraph& lfg1, | 
					
						
							|  |  |  | 		const GaussianFactorGraph& lfg2) { | 
					
						
							| 
									
										
										
										
											2009-11-05 12:56:59 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-25 10:36:30 +08:00
										 |  |  | 	// create new linear factor graph equal to the first one
 | 
					
						
							| 
									
										
										
										
											2009-11-13 00:16:32 +08:00
										 |  |  | 	GaussianFactorGraph fg = lfg1; | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-31 10:40:26 +08:00
										 |  |  | 	// add the second factors_ in the graph
 | 
					
						
							|  |  |  | 	for (const_iterator factor = lfg2.factors_.begin(); factor | 
					
						
							|  |  |  | 			!= lfg2.factors_.end(); factor++) { | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 		fg.push_back(*factor); | 
					
						
							|  |  |  | 	} | 
					
						
							|  |  |  | 	return fg; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //
 | 
					
						
							|  |  |  | ///* ************************************************************************* */
 | 
					
						
							|  |  |  | //Dimensions GaussianFactorGraph::dimensions() const {
 | 
					
						
							|  |  |  | //	Dimensions result;
 | 
					
						
							|  |  |  | //	BOOST_FOREACH(const sharedFactor& factor,factors_) {
 | 
					
						
							|  |  |  | //		Dimensions vs = factor->dimensions();
 | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  | //		Index key; size_t dim;
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //		FOREACH_PAIR(key,dim,vs) result.insert(make_pair(key,dim));
 | 
					
						
							|  |  |  | //	}
 | 
					
						
							|  |  |  | //	return result;
 | 
					
						
							|  |  |  | //}
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */   | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | GaussianFactorGraph GaussianFactorGraph::add_priors(double sigma, const GaussianVariableIndex<>& variableIndex) const { | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// start with this factor graph
 | 
					
						
							| 
									
										
										
										
											2009-11-13 00:16:32 +08:00
										 |  |  | 	GaussianFactorGraph result = *this; | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// for each of the variables, add a prior
 | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  | 	for(Index var=0; var<variableIndex.size(); ++var) { | 
					
						
							| 
									
										
										
										
											2010-10-14 04:43:58 +08:00
										 |  |  | 	  size_t dim = variableIndex.dim(var); | 
					
						
							| 
									
										
										
										
											2009-11-06 13:43:03 +08:00
										 |  |  | 		Matrix A = eye(dim); | 
					
						
							|  |  |  | 		Vector b = zero(dim); | 
					
						
							| 
									
										
										
										
											2010-01-23 01:36:57 +08:00
										 |  |  | 		SharedDiagonal model = noiseModel::Isotropic::Sigma(dim,sigma); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 		sharedFactor prior(new GaussianFactor(var,A,b, model)); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 		result.push_back(prior); | 
					
						
							|  |  |  | 	} | 
					
						
							|  |  |  | 	return result; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | ///* ************************************************************************* */
 | 
					
						
							|  |  |  | //Errors GaussianFactorGraph::rhs() const {
 | 
					
						
							|  |  |  | //	Errors e;
 | 
					
						
							|  |  |  | //	BOOST_FOREACH(const sharedFactor& factor,factors_)
 | 
					
						
							|  |  |  | //		e.push_back(ediv(factor->get_b(),factor->get_sigmas()));
 | 
					
						
							|  |  |  | //	return e;
 | 
					
						
							|  |  |  | //}
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | ///* ************************************************************************* */
 | 
					
						
							|  |  |  | //Vector GaussianFactorGraph::rhsVector() const {
 | 
					
						
							|  |  |  | //	Errors e = rhs();
 | 
					
						
							|  |  |  | //	return concatVectors(e);
 | 
					
						
							|  |  |  | //}
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | ///* ************************************************************************* */
 | 
					
						
							|  |  |  | //pair<Matrix,Vector> GaussianFactorGraph::matrix(const Ordering& ordering) const {
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	// get all factors
 | 
					
						
							|  |  |  | //	GaussianFactorSet found;
 | 
					
						
							|  |  |  | //	BOOST_FOREACH(const sharedFactor& factor,factors_)
 | 
					
						
							|  |  |  | //		found.push_back(factor);
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	// combine them
 | 
					
						
							|  |  |  | //	GaussianFactor lf(found);
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	// Return Matrix and Vector
 | 
					
						
							|  |  |  | //	return lf.matrix(ordering);
 | 
					
						
							|  |  |  | //}
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | ///* ************************************************************************* */
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | //VectorValues GaussianFactorGraph::assembleValues(const Vector& vs, const Ordering& ordering) const {
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //	Dimensions dims = dimensions();
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | //	VectorValues config;
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //	Vector::const_iterator itSrc = vs.begin();
 | 
					
						
							|  |  |  | //	Vector::iterator itDst;
 | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  | //	BOOST_FOREACH(Index key, ordering){
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //		int dim = dims.find(key)->second;
 | 
					
						
							|  |  |  | //		Vector v(dim);
 | 
					
						
							|  |  |  | //		for (itDst=v.begin(); itDst!=v.end(); itDst++, itSrc++)
 | 
					
						
							|  |  |  | //			*itDst = *itSrc;
 | 
					
						
							|  |  |  | //		config.insert(key, v);
 | 
					
						
							|  |  |  | //	}
 | 
					
						
							|  |  |  | //	if (itSrc != vs.end())
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | //		throw runtime_error("assembleValues: input vector and ordering are not compatible with the graph");
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //	return config;
 | 
					
						
							|  |  |  | //}
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | ///* ************************************************************************* */
 | 
					
						
							|  |  |  | //pair<Dimensions, size_t> GaussianFactorGraph::columnIndices_(const Ordering& ordering) const {
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	// get the dimensions for all variables
 | 
					
						
							|  |  |  | //	Dimensions variableSet = dimensions();
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	// Find the starting index and dimensions for all variables given the order
 | 
					
						
							|  |  |  | //	size_t j = 1;
 | 
					
						
							|  |  |  | //	Dimensions result;
 | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  | //	BOOST_FOREACH(Index key, ordering) {
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //		// associate key with first column index
 | 
					
						
							|  |  |  | //		result.insert(make_pair(key,j));
 | 
					
						
							|  |  |  | //		// find dimension for this key
 | 
					
						
							|  |  |  | //		Dimensions::const_iterator it = variableSet.find(key);
 | 
					
						
							|  |  |  | //		if (it==variableSet.end()) // key not found, now what ?
 | 
					
						
							|  |  |  | //				throw invalid_argument("ColumnIndices: this ordering contains keys not in the graph");
 | 
					
						
							|  |  |  | //		// advance column index to next block by adding dim(key)
 | 
					
						
							|  |  |  | //		j += it->second;
 | 
					
						
							|  |  |  | //	}
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	return make_pair(result, j-1);
 | 
					
						
							|  |  |  | //}
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | ///* ************************************************************************* */
 | 
					
						
							|  |  |  | //Dimensions GaussianFactorGraph::columnIndices(const Ordering& ordering) const {
 | 
					
						
							|  |  |  | //	return columnIndices_(ordering).first;
 | 
					
						
							|  |  |  | //}
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | ///* ************************************************************************* */
 | 
					
						
							|  |  |  | //pair<size_t, size_t> GaussianFactorGraph::sizeOfA() const {
 | 
					
						
							|  |  |  | //	size_t m = 0, n = 0;
 | 
					
						
							|  |  |  | //	Dimensions variableSet = dimensions();
 | 
					
						
							|  |  |  | //	BOOST_FOREACH(const Dimensions::value_type value, variableSet)
 | 
					
						
							|  |  |  | //		n += value.second;
 | 
					
						
							|  |  |  | //	BOOST_FOREACH(const sharedFactor& factor,factors_)
 | 
					
						
							|  |  |  | //		m += factor->numberOfRows();
 | 
					
						
							|  |  |  | //	return make_pair(m, n);
 | 
					
						
							|  |  |  | //}
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | ///* ************************************************************************* */
 | 
					
						
							|  |  |  | //Matrix GaussianFactorGraph::sparse(const Ordering& ordering) const {
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	// get the starting column indices for all variables
 | 
					
						
							|  |  |  | //	Dimensions indices = columnIndices(ordering);
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	return sparse(indices);
 | 
					
						
							|  |  |  | //}
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | ///* ************************************************************************* */
 | 
					
						
							|  |  |  | //Matrix GaussianFactorGraph::sparse(const Dimensions& indices) const {
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	// return values
 | 
					
						
							|  |  |  | //	list<int> I,J;
 | 
					
						
							|  |  |  | //	list<double> S;
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	// Collect the I,J,S lists for all factors
 | 
					
						
							|  |  |  | //	int row_index = 0;
 | 
					
						
							|  |  |  | //	BOOST_FOREACH(const sharedFactor& factor,factors_) {
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //		// get sparse lists for the factor
 | 
					
						
							|  |  |  | //		list<int> i1,j1;
 | 
					
						
							|  |  |  | //		list<double> s1;
 | 
					
						
							|  |  |  | //		boost::tie(i1,j1,s1) = factor->sparse(indices);
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //		// add row_start to every row index
 | 
					
						
							|  |  |  | //		transform(i1.begin(), i1.end(), i1.begin(), bind2nd(plus<int>(), row_index));
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //		// splice lists from factor to the end of the global lists
 | 
					
						
							|  |  |  | //		I.splice(I.end(), i1);
 | 
					
						
							|  |  |  | //		J.splice(J.end(), j1);
 | 
					
						
							|  |  |  | //		S.splice(S.end(), s1);
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //		// advance row start
 | 
					
						
							|  |  |  | //		row_index += factor->numberOfRows();
 | 
					
						
							|  |  |  | //	}
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	// Convert them to vectors for MATLAB
 | 
					
						
							|  |  |  | //	// TODO: just create a sparse matrix class already
 | 
					
						
							|  |  |  | //	size_t nzmax = S.size();
 | 
					
						
							|  |  |  | //	Matrix ijs(3,nzmax);
 | 
					
						
							|  |  |  | //	copy(I.begin(),I.end(),ijs.begin2());
 | 
					
						
							|  |  |  | //	copy(J.begin(),J.end(),ijs.begin2()+nzmax);
 | 
					
						
							|  |  |  | //	copy(S.begin(),S.end(),ijs.begin2()+2*nzmax);
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //	// return the result
 | 
					
						
							|  |  |  | //	return ijs;
 | 
					
						
							|  |  |  | //}
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | ///* ************************************************************************* */
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | //VectorValues GaussianFactorGraph::steepestDescent(const VectorValues& x0,
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //		bool verbose, double epsilon, size_t maxIterations) const {
 | 
					
						
							|  |  |  | //	return gtsam::steepestDescent(*this, x0, verbose, epsilon, maxIterations);
 | 
					
						
							|  |  |  | //}
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | ///* ************************************************************************* */
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | //boost::shared_ptr<VectorValues> GaussianFactorGraph::steepestDescent_(
 | 
					
						
							|  |  |  | //		const VectorValues& x0, bool verbose, double epsilon, size_t maxIterations) const {
 | 
					
						
							|  |  |  | //	return boost::shared_ptr<VectorValues>(new VectorValues(
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //			gtsam::conjugateGradientDescent(*this, x0, verbose, epsilon,
 | 
					
						
							|  |  |  | //					maxIterations)));
 | 
					
						
							|  |  |  | //}
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | ///* ************************************************************************* */
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | //VectorValues GaussianFactorGraph::conjugateGradientDescent(
 | 
					
						
							|  |  |  | //		const VectorValues& x0, bool verbose, double epsilon, size_t maxIterations) const {
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //	return gtsam::conjugateGradientDescent(*this, x0, verbose, epsilon,
 | 
					
						
							|  |  |  | //			maxIterations);
 | 
					
						
							|  |  |  | //}
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | ///* ************************************************************************* */
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | //boost::shared_ptr<VectorValues> GaussianFactorGraph::conjugateGradientDescent_(
 | 
					
						
							|  |  |  | //		const VectorValues& x0, bool verbose, double epsilon, size_t maxIterations) const {
 | 
					
						
							|  |  |  | //	return boost::shared_ptr<VectorValues>(new VectorValues(
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //			gtsam::conjugateGradientDescent(*this, x0, verbose, epsilon,
 | 
					
						
							|  |  |  | //					maxIterations)));
 | 
					
						
							|  |  |  | //}
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | //template std::pair<Matrix, SharedDiagonal> combineFactorsAndCreateMatrix<vector<GaussianFactor::shared_ptr> >(
 | 
					
						
							|  |  |  | //		const vector<GaussianFactor::shared_ptr>& factors,	const Ordering& order, const Dimensions& dimensions);
 | 
					
						
							|  |  |  | //
 | 
					
						
							|  |  |  | //template std::pair<Matrix, SharedDiagonal> combineFactorsAndCreateMatrix<GaussianFactorGraph>(
 | 
					
						
							|  |  |  | //		const GaussianFactorGraph& factors,	const Ordering& order, const Dimensions& dimensions);
 | 
					
						
							| 
									
										
										
										
											2010-07-08 05:41:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | } // namespace gtsam
 |