| 
									
										
										
										
											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    GaussianFactor.cpp | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  |  * @brief   Linear Factor....A Gaussian | 
					
						
							|  |  |  |  * @brief   linearFactor | 
					
						
							|  |  |  |  * @author  Christian Potthast | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <boost/foreach.hpp>
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | #include <boost/format.hpp>
 | 
					
						
							|  |  |  | #include <boost/make_shared.hpp>
 | 
					
						
							|  |  |  | #include <boost/pool/pool_alloc.hpp>
 | 
					
						
							|  |  |  | #include <boost/lambda/bind.hpp>
 | 
					
						
							|  |  |  | #include <boost/lambda/lambda.hpp>
 | 
					
						
							|  |  |  | #include <boost/tuple/tuple.hpp>
 | 
					
						
							| 
									
										
										
										
											2009-11-02 11:50:30 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | #include <boost/numeric/ublas/triangular.hpp>
 | 
					
						
							|  |  |  | #include <boost/numeric/ublas/io.hpp>
 | 
					
						
							|  |  |  | #include <boost/numeric/ublas/matrix_proxy.hpp>
 | 
					
						
							|  |  |  | #include <boost/numeric/ublas/vector_proxy.hpp>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam/base/timing.h>
 | 
					
						
							| 
									
										
										
										
											2010-08-20 01:23:19 +08:00
										 |  |  | #include <gtsam/base/Matrix.h>
 | 
					
						
							|  |  |  | #include <gtsam/linear/GaussianConditional.h>
 | 
					
						
							|  |  |  | #include <gtsam/linear/GaussianFactor.h>
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | #include <gtsam/linear/GaussianFactorGraph.h>
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							| 
									
										
										
										
											2010-10-22 05:12:37 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | namespace ublas = boost::numeric::ublas; | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | using namespace boost::lambda; | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | namespace gtsam { | 
					
						
							| 
									
										
										
										
											2010-01-19 05:17:25 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-02-26 11:20:15 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-14 04:43:58 +08:00
										 |  |  | inline void GaussianFactor::assertInvariants() const { | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | #ifndef NDEBUG
 | 
					
						
							| 
									
										
										
										
											2010-10-20 05:31:13 +08:00
										 |  |  |   IndexFactor::assertInvariants(); | 
					
						
							| 
									
										
										
										
											2010-10-14 04:43:58 +08:00
										 |  |  |   assert((keys_.size() == 0 && Ab_.size1() == 0 && Ab_.nBlocks() == 0) || keys_.size()+1 == Ab_.nBlocks()); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | #endif
 | 
					
						
							| 
									
										
										
										
											2010-02-26 11:20:15 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | GaussianFactor::GaussianFactor(const GaussianFactor& gf) : | 
					
						
							| 
									
										
										
										
											2010-10-20 05:31:13 +08:00
										 |  |  |     IndexFactor(gf), model_(gf.model_), firstNonzeroBlocks_(gf.firstNonzeroBlocks_), Ab_(matrix_) { | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   Ab_.assignNoalias(gf.Ab_); | 
					
						
							| 
									
										
										
										
											2010-10-14 04:43:58 +08:00
										 |  |  |   assertInvariants(); | 
					
						
							| 
									
										
										
										
											2010-02-26 11:20:15 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-14 04:43:58 +08:00
										 |  |  | GaussianFactor::GaussianFactor() : Ab_(matrix_) { assertInvariants(); } | 
					
						
							| 
									
										
										
										
											2010-02-26 11:20:15 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | GaussianFactor::GaussianFactor(const Vector& b_in) : firstNonzeroBlocks_(b_in.size(), 0), Ab_(matrix_) { | 
					
						
							|  |  |  |   size_t dims[] = { 1 }; | 
					
						
							| 
									
										
										
										
											2010-10-23 02:39:04 +08:00
										 |  |  |   Ab_.copyStructureFrom(BlockAb(matrix_, dims, dims+1, b_in.size())); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   getb() = b_in; | 
					
						
							| 
									
										
										
										
											2010-10-14 04:43:58 +08:00
										 |  |  |   assertInvariants(); | 
					
						
							| 
									
										
										
										
											2010-02-26 11:20:15 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  | GaussianFactor::GaussianFactor(Index i1, const Matrix& A1, | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |     const Vector& b, const SharedDiagonal& model) : | 
					
						
							| 
									
										
										
										
											2010-10-20 05:31:13 +08:00
										 |  |  | 		IndexFactor(i1), model_(model), firstNonzeroBlocks_(b.size(), 0), Ab_(matrix_) { | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   size_t dims[] = { A1.size2(), 1}; | 
					
						
							| 
									
										
										
										
											2010-10-23 02:39:04 +08:00
										 |  |  |   Ab_.copyStructureFrom(BlockAb(matrix_, dims, dims+2, b.size())); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 	Ab_(0) = A1; | 
					
						
							|  |  |  | 	getb() = b; | 
					
						
							| 
									
										
										
										
											2010-10-14 04:43:58 +08:00
										 |  |  | 	assertInvariants(); | 
					
						
							| 
									
										
										
										
											2010-02-26 11:20:15 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  | GaussianFactor::GaussianFactor(Index i1, const Matrix& A1, Index i2, const Matrix& A2, | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 		const Vector& b, const SharedDiagonal& model) : | 
					
						
							| 
									
										
										
										
											2010-10-20 05:31:13 +08:00
										 |  |  | 		IndexFactor(i1,i2), model_(model), firstNonzeroBlocks_(b.size(), 0), Ab_(matrix_) { | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   size_t dims[] = { A1.size2(), A2.size2(), 1}; | 
					
						
							| 
									
										
										
										
											2010-10-23 02:39:04 +08:00
										 |  |  |   Ab_.copyStructureFrom(BlockAb(matrix_, dims, dims+3, b.size())); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   Ab_(0) = A1; | 
					
						
							|  |  |  |   Ab_(1) = A2; | 
					
						
							|  |  |  |   getb() = b; | 
					
						
							| 
									
										
										
										
											2010-10-14 04:43:58 +08:00
										 |  |  |   assertInvariants(); | 
					
						
							| 
									
										
										
										
											2010-02-26 11:20:15 +08:00
										 |  |  | } | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-11-02 11:50:30 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  | GaussianFactor::GaussianFactor(Index i1, const Matrix& A1, Index i2, const Matrix& A2, | 
					
						
							|  |  |  |     Index i3, const Matrix& A3,	const Vector& b, const SharedDiagonal& model) : | 
					
						
							| 
									
										
										
										
											2010-10-20 05:31:13 +08:00
										 |  |  |     IndexFactor(i1,i2,i3), model_(model), firstNonzeroBlocks_(b.size(), 0), Ab_(matrix_) { | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   size_t dims[] = { A1.size2(), A2.size2(), A3.size2(), 1}; | 
					
						
							| 
									
										
										
										
											2010-10-23 02:39:04 +08:00
										 |  |  |   Ab_.copyStructureFrom(BlockAb(matrix_, dims, dims+4, b.size())); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   Ab_(0) = A1; | 
					
						
							|  |  |  |   Ab_(1) = A2; | 
					
						
							|  |  |  |   Ab_(2) = A3; | 
					
						
							|  |  |  |   getb() = b; | 
					
						
							| 
									
										
										
										
											2010-10-14 04:43:58 +08:00
										 |  |  |   assertInvariants(); | 
					
						
							| 
									
										
										
										
											2009-11-02 11:50:30 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  | GaussianFactor::GaussianFactor(const std::vector<std::pair<Index, Matrix> > &terms, | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |     const Vector &b, const SharedDiagonal& model) : | 
					
						
							|  |  |  |     model_(model), firstNonzeroBlocks_(b.size(), 0), Ab_(matrix_) { | 
					
						
							|  |  |  |   keys_.resize(terms.size()); | 
					
						
							|  |  |  |   size_t dims[terms.size()+1]; | 
					
						
							|  |  |  |   for(size_t j=0; j<terms.size(); ++j) { | 
					
						
							|  |  |  |     keys_[j] = terms[j].first; | 
					
						
							|  |  |  |     dims[j] = terms[j].second.size2(); | 
					
						
							|  |  |  | 	} | 
					
						
							|  |  |  |   dims[terms.size()] = 1; | 
					
						
							| 
									
										
										
										
											2010-10-23 02:39:04 +08:00
										 |  |  |   Ab_.copyStructureFrom(BlockAb(matrix_, dims, dims+terms.size()+1, b.size())); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   for(size_t j=0; j<terms.size(); ++j) | 
					
						
							|  |  |  |     Ab_(j) = terms[j].second; | 
					
						
							|  |  |  |   getb() = b; | 
					
						
							| 
									
										
										
										
											2010-10-14 04:43:58 +08:00
										 |  |  |   assertInvariants(); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | } | 
					
						
							| 
									
										
										
										
											2010-01-27 12:39:35 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  | GaussianFactor::GaussianFactor(const std::list<std::pair<Index, Matrix> > &terms, | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |     const Vector &b, const SharedDiagonal& model) : | 
					
						
							|  |  |  |     model_(model), firstNonzeroBlocks_(b.size(), 0), Ab_(matrix_) { | 
					
						
							|  |  |  |   keys_.resize(terms.size()); | 
					
						
							|  |  |  |   size_t dims[terms.size()+1]; | 
					
						
							|  |  |  |   size_t j=0; | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  |   for(std::list<std::pair<Index, Matrix> >::const_iterator term=terms.begin(); term!=terms.end(); ++term) { | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |     keys_[j] = term->first; | 
					
						
							|  |  |  |     dims[j] = term->second.size2(); | 
					
						
							|  |  |  |     ++ j; | 
					
						
							| 
									
										
										
										
											2009-10-23 01:23:24 +08:00
										 |  |  |   } | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   dims[j] = 1; | 
					
						
							|  |  |  |   firstNonzeroBlocks_.resize(b.size(), 0); | 
					
						
							| 
									
										
										
										
											2010-10-23 02:39:04 +08:00
										 |  |  |   Ab_.copyStructureFrom(BlockAb(matrix_, dims, dims+terms.size()+1, b.size())); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   j = 0; | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  |   for(std::list<std::pair<Index, Matrix> >::const_iterator term=terms.begin(); term!=terms.end(); ++term) { | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |     Ab_(j) = term->second; | 
					
						
							|  |  |  |     ++ j; | 
					
						
							| 
									
										
										
										
											2010-01-27 12:39:35 +08:00
										 |  |  |   } | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   getb() = b; | 
					
						
							| 
									
										
										
										
											2010-10-14 04:43:58 +08:00
										 |  |  |   assertInvariants(); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-20 05:31:13 +08:00
										 |  |  | GaussianFactor::GaussianFactor(const GaussianConditional& cg) : IndexFactor(cg), model_(noiseModel::Diagonal::Sigmas(cg.get_sigmas(), true)), Ab_(matrix_) { | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   Ab_.assignNoalias(cg.rsd_); | 
					
						
							|  |  |  |   // todo SL: make firstNonzeroCols triangular?
 | 
					
						
							|  |  |  |   firstNonzeroBlocks_.resize(cg.get_d().size(), 0);	// set sigmas from precisions
 | 
					
						
							| 
									
										
										
										
											2010-10-14 04:43:58 +08:00
										 |  |  |   assertInvariants(); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2009-11-13 00:16:32 +08:00
										 |  |  | void GaussianFactor::print(const string& s) const { | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   cout << s << "\n"; | 
					
						
							|  |  |  |   if (empty()) { | 
					
						
							|  |  |  |     cout << " empty, keys: "; | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  |     BOOST_FOREACH(const Index key, keys_) { cout << key << " "; } | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |     cout << endl; | 
					
						
							|  |  |  |   } else { | 
					
						
							|  |  |  |   	for(const_iterator key=begin(); key!=end(); ++key) | 
					
						
							|  |  |  |   		gtsam::print(getA(key), (boost::format("A[%1%]=\n")%*key).str()); | 
					
						
							|  |  |  |     gtsam::print(getb(),"b="); | 
					
						
							| 
									
										
										
										
											2010-01-19 12:39:28 +08:00
										 |  |  |     model_->print("model"); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | // Check if two linear factors are equal
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | bool GaussianFactor::equals(const GaussianFactor& f, double tol) const { | 
					
						
							|  |  |  |   if (empty()) return (f.empty()); | 
					
						
							|  |  |  |   if(keys_!=f.keys_ /*|| !model_->equals(lf->model_, tol)*/) | 
					
						
							|  |  |  |     return false; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   assert(Ab_.size1() == f.Ab_.size1() && Ab_.size2() == f.Ab_.size2()); | 
					
						
							| 
									
										
										
										
											2009-10-23 01:23:24 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-23 02:39:04 +08:00
										 |  |  |   constABlock Ab1(Ab_.range(0, Ab_.nBlocks())); | 
					
						
							|  |  |  |   constABlock Ab2(f.Ab_.range(0, f.Ab_.nBlocks())); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   for(size_t row=0; row<Ab1.size1(); ++row) | 
					
						
							|  |  |  |     if(!equal_with_abs_tol(ublas::row(Ab1, row), ublas::row(Ab2, row), tol) && | 
					
						
							|  |  |  |         !equal_with_abs_tol(-ublas::row(Ab1, row), ublas::row(Ab2, row), tol)) | 
					
						
							|  |  |  |       return false; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   return true; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | void GaussianFactor::permuteWithInverse(const Permutation& inversePermutation) { | 
					
						
							| 
									
										
										
										
											2010-10-14 04:43:58 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Build a map from the new variable indices to the old slot positions.
 | 
					
						
							|  |  |  |   typedef map<size_t, size_t, std::less<size_t>, boost::fast_pool_allocator<std::pair<const size_t, size_t> > > SourceSlots; | 
					
						
							|  |  |  |   SourceSlots sourceSlots; | 
					
						
							|  |  |  |   for(size_t j=0; j<keys_.size(); ++j) | 
					
						
							|  |  |  |     sourceSlots.insert(make_pair(inversePermutation[keys_[j]], j)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Build a vector of variable dimensions in the new order
 | 
					
						
							|  |  |  |   vector<size_t> dimensions(keys_.size() + 1); | 
					
						
							|  |  |  |   size_t j = 0; | 
					
						
							|  |  |  |   BOOST_FOREACH(const SourceSlots::value_type& sourceSlot, sourceSlots) { | 
					
						
							|  |  |  |     dimensions[j++] = Ab_(sourceSlot.second).size2(); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  |   assert(j == keys_.size()); | 
					
						
							|  |  |  |   dimensions.back() = 1; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Copy the variables and matrix into the new order
 | 
					
						
							|  |  |  |   vector<Index> oldKeys(keys_.size()); | 
					
						
							|  |  |  |   keys_.swap(oldKeys); | 
					
						
							| 
									
										
										
										
											2010-10-23 02:39:04 +08:00
										 |  |  |   AbMatrix oldMatrix; | 
					
						
							|  |  |  |   BlockAb oldAb(oldMatrix, dimensions.begin(), dimensions.end(), Ab_.size1()); | 
					
						
							| 
									
										
										
										
											2010-10-14 04:43:58 +08:00
										 |  |  |   Ab_.swap(oldAb); | 
					
						
							|  |  |  |   j = 0; | 
					
						
							|  |  |  |   BOOST_FOREACH(const SourceSlots::value_type& sourceSlot, sourceSlots) { | 
					
						
							|  |  |  |     keys_[j] = sourceSlot.first; | 
					
						
							|  |  |  |     ublas::noalias(Ab_(j++)) = oldAb(sourceSlot.second); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  |   ublas::noalias(Ab_(j)) = oldAb(j); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   // Since we're permuting the variables, ensure that entire rows from this
 | 
					
						
							|  |  |  |   // factor are copied when Combine is called
 | 
					
						
							|  |  |  |   BOOST_FOREACH(size_t& varpos, firstNonzeroBlocks_) { varpos = 0; } | 
					
						
							| 
									
										
										
										
											2010-10-14 04:43:58 +08:00
										 |  |  |   assertInvariants(); | 
					
						
							| 
									
										
										
										
											2009-10-23 01:23:24 +08:00
										 |  |  | } | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-10-23 01:23:24 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | Vector GaussianFactor::unweighted_error(const VectorValues& c) const { | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   Vector e = -getb(); | 
					
						
							| 
									
										
										
										
											2009-12-12 01:42:54 +08:00
										 |  |  |   if (empty()) return e; | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   for(size_t pos=0; pos<keys_.size(); ++pos) | 
					
						
							|  |  |  |     e += ublas::prod(Ab_(pos), c[keys_[pos]]); | 
					
						
							| 
									
										
										
										
											2009-12-12 02:03:43 +08:00
										 |  |  |   return e; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | Vector GaussianFactor::error_vector(const VectorValues& c) const { | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 	if (empty()) return model_->whiten(-getb()); | 
					
						
							| 
									
										
										
										
											2010-01-19 12:39:28 +08:00
										 |  |  | 	return model_->whiten(unweighted_error(c)); | 
					
						
							| 
									
										
										
										
											2009-12-12 01:42:54 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | double GaussianFactor::error(const VectorValues& c) const { | 
					
						
							| 
									
										
										
										
											2009-12-12 01:42:54 +08:00
										 |  |  |   if (empty()) return 0; | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   Vector weighted = error_vector(c); | 
					
						
							| 
									
										
										
										
											2009-11-05 04:59:16 +08:00
										 |  |  |   return 0.5 * inner_prod(weighted,weighted); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-12-27 20:13:31 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | Vector GaussianFactor::operator*(const VectorValues& x) const { | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 	Vector Ax = zero(Ab_.size1()); | 
					
						
							| 
									
										
										
										
											2009-12-27 20:13:31 +08:00
										 |  |  |   if (empty()) return Ax; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Just iterate over all A matrices and multiply in correct config part
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   for(size_t pos=0; pos<keys_.size(); ++pos) | 
					
						
							|  |  |  |     Ax += ublas::prod(Ab_(pos), x[keys_[pos]]); | 
					
						
							| 
									
										
										
										
											2009-12-27 20:13:31 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-19 12:39:28 +08:00
										 |  |  |   return model_->whiten(Ax); | 
					
						
							| 
									
										
										
										
											2009-12-27 20:13:31 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-31 11:33:53 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | void GaussianFactor::transposeMultiplyAdd(double alpha, const Vector& e, | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 		VectorValues& x) const { | 
					
						
							| 
									
										
										
										
											2010-01-31 11:33:53 +08:00
										 |  |  | 	Vector E = alpha * model_->whiten(e); | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	// Just iterate over all A matrices and insert Ai^e into VectorValues
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   for(size_t pos=0; pos<keys_.size(); ++pos) | 
					
						
							|  |  |  |     gtsam::transposeMultiplyAdd(1.0, Ab_(pos), E, x[keys_[pos]]); | 
					
						
							| 
									
										
										
										
											2010-01-31 11:33:53 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | /* ************************************************************************* */   | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | pair<Matrix,Vector> GaussianFactor::matrix(bool weight) const { | 
					
						
							|  |  |  |   Matrix A(Ab_.range(0, keys_.size())); | 
					
						
							|  |  |  |   Vector b(getb()); | 
					
						
							| 
									
										
										
										
											2009-11-11 22:42:09 +08:00
										 |  |  | 	// divide in sigma so error is indeed 0.5*|Ax-b|
 | 
					
						
							| 
									
										
										
										
											2010-01-19 12:39:28 +08:00
										 |  |  | 	if (weight) model_->WhitenSystem(A,b); | 
					
						
							| 
									
										
										
										
											2009-11-06 21:43:39 +08:00
										 |  |  | 	return make_pair(A, b); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-11-05 23:08:58 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | Matrix GaussianFactor::matrix_augmented(bool weight) const { | 
					
						
							|  |  |  | 	if (weight) { Matrix Ab(Ab_.range(0,Ab_.nBlocks())); model_->WhitenInPlace(Ab); return Ab; } | 
					
						
							|  |  |  | 	else return Ab_.range(0, Ab_.nBlocks()); | 
					
						
							| 
									
										
										
										
											2009-11-05 23:08:58 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-11-06 13:43:03 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | boost::tuple<list<int>, list<int>, list<double> > | 
					
						
							| 
									
										
										
										
											2009-12-12 14:18:29 +08:00
										 |  |  | GaussianFactor::sparse(const Dimensions& columnIndices) const { | 
					
						
							| 
									
										
										
										
											2009-11-06 13:43:03 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// declare return values
 | 
					
						
							|  |  |  | 	list<int> I,J; | 
					
						
							|  |  |  | 	list<double> S; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-12-12 14:18:29 +08:00
										 |  |  | 	// iterate over all matrices in the factor
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   for(size_t pos=0; pos<keys_.size(); ++pos) { | 
					
						
							| 
									
										
										
										
											2010-10-23 02:39:04 +08:00
										 |  |  |     constABlock A(Ab_(pos)); | 
					
						
							| 
									
										
										
										
											2009-12-12 14:18:29 +08:00
										 |  |  | 		// find first column index for this key
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 		int column_start = columnIndices.at(keys_[pos]); | 
					
						
							|  |  |  | 		for (size_t i = 0; i < A.size1(); i++) { | 
					
						
							| 
									
										
										
										
											2010-01-19 12:39:28 +08:00
										 |  |  | 			double sigma_i = model_->sigma(i); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 			for (size_t j = 0; j < A.size2(); j++) | 
					
						
							|  |  |  | 				if (A(i, j) != 0.0) { | 
					
						
							| 
									
										
										
										
											2009-12-12 14:18:29 +08:00
										 |  |  | 					I.push_back(i + 1); | 
					
						
							|  |  |  | 					J.push_back(j + column_start); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 					S.push_back(A(i, j) / sigma_i); | 
					
						
							| 
									
										
										
										
											2009-12-12 14:18:29 +08:00
										 |  |  | 				} | 
					
						
							|  |  |  | 		} | 
					
						
							| 
									
										
										
										
											2009-11-06 13:43:03 +08:00
										 |  |  | 	} | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// return the result
 | 
					
						
							|  |  |  | 	return boost::tuple<list<int>, list<int>, list<double> >(I,J,S); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | GaussianConditional::shared_ptr GaussianFactor::eliminateFirst() { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   assert(Ab_.rowStart() == 0 && Ab_.rowEnd() == matrix_.size1() && Ab_.firstBlock() == 0); | 
					
						
							|  |  |  |   assert(!keys_.empty()); | 
					
						
							| 
									
										
										
										
											2010-10-14 04:43:58 +08:00
										 |  |  |   assertInvariants(); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   static const bool debug = false; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   tic("eliminateFirst"); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   if(debug) print("Eliminating GaussianFactor: "); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   tic("eliminateFirst: stairs"); | 
					
						
							|  |  |  |   // Translate the left-most nonzero column indices into top-most zero row indices
 | 
					
						
							|  |  |  |   vector<long> firstZeroRows(Ab_.size2()); | 
					
						
							|  |  |  |   { | 
					
						
							|  |  |  |     size_t lastNonzeroRow = 0; | 
					
						
							|  |  |  |     vector<long>::iterator firstZeroRowsIt = firstZeroRows.begin(); | 
					
						
							|  |  |  |     for(size_t var=0; var<keys().size(); ++var) { | 
					
						
							|  |  |  |       while(lastNonzeroRow < this->numberOfRows() && firstNonzeroBlocks_[lastNonzeroRow] <= var) | 
					
						
							|  |  |  |         ++ lastNonzeroRow; | 
					
						
							|  |  |  |       fill(firstZeroRowsIt, firstZeroRowsIt+Ab_(var).size2(), lastNonzeroRow); | 
					
						
							|  |  |  |       firstZeroRowsIt += Ab_(var).size2(); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |     assert(firstZeroRowsIt+1 == firstZeroRows.end()); | 
					
						
							|  |  |  |     *firstZeroRowsIt = this->numberOfRows(); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  |   toc("eliminateFirst: stairs"); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #ifndef NDEBUG
 | 
					
						
							|  |  |  |   for(size_t col=0; col<Ab_.size2(); ++col) { | 
					
						
							|  |  |  |     if(debug) cout << "Staircase[" << col << "] = " << firstZeroRows[col] << endl; | 
					
						
							|  |  |  |     if(col != 0) assert(firstZeroRows[col] >= firstZeroRows[col-1]); | 
					
						
							|  |  |  |     assert(firstZeroRows[col] <= (long)this->numberOfRows()); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | #endif
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   if(debug) gtsam::print(matrix_, "Augmented Ab: "); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Use in-place QR on dense Ab appropriate to NoiseModel
 | 
					
						
							|  |  |  |   tic("eliminateFirst: QR"); | 
					
						
							|  |  |  |   SharedDiagonal noiseModel = model_->QRColumnWise(matrix_, firstZeroRows); | 
					
						
							|  |  |  |   toc("eliminateFirst: QR"); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   if(matrix_.size1() > 0) { | 
					
						
							|  |  |  |     for(size_t j=0; j<matrix_.size2(); ++j) | 
					
						
							|  |  |  |       for(size_t i=j+1; i<noiseModel->dim(); ++i) | 
					
						
							|  |  |  |         matrix_(i,j) = 0.0; | 
					
						
							| 
									
										
										
										
											2010-10-22 05:12:37 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   if(debug) gtsam::print(matrix_, "QR result: "); | 
					
						
							| 
									
										
										
										
											2009-11-05 04:59:16 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   size_t firstVarDim = Ab_(0).size2(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Check for singular factor
 | 
					
						
							|  |  |  |   if(noiseModel->dim() < firstVarDim) { | 
					
						
							|  |  |  |     throw domain_error((boost::format( | 
					
						
							|  |  |  |         "GaussianFactor is singular in variable %1%, discovered while attempting\n" | 
					
						
							|  |  |  |         "to eliminate this variable.") % keys_.front()).str()); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Extract conditional
 | 
					
						
							|  |  |  |   // todo SL: are we pulling Householder vectors into the conditional and does it matter?
 | 
					
						
							|  |  |  |   tic("eliminateFirst: cond Rd"); | 
					
						
							|  |  |  |   // Temporarily restrict the matrix view to the conditional blocks of the
 | 
					
						
							|  |  |  |   // eliminated Ab matrix to create the GaussianConditional from it.
 | 
					
						
							|  |  |  |   Ab_.rowStart() = 0; | 
					
						
							|  |  |  |   Ab_.rowEnd() = firstVarDim; | 
					
						
							|  |  |  |   Ab_.firstBlock() = 0; | 
					
						
							|  |  |  |   const ublas::vector_range<const Vector> sigmas(noiseModel->sigmas(), ublas::range(0, firstVarDim)); | 
					
						
							|  |  |  |   GaussianConditional::shared_ptr conditional(new GaussianConditional( | 
					
						
							|  |  |  |       keys_.begin(), keys_.end(), 1, Ab_, sigmas)); | 
					
						
							|  |  |  |   toc("eliminateFirst: cond Rd"); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   if(debug) conditional->print("Extracted conditional: "); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   tic("eliminateFirst: remaining factor"); | 
					
						
							|  |  |  |   // Take lower-right block of Ab to get the new factor
 | 
					
						
							|  |  |  |   Ab_.rowStart() = firstVarDim; | 
					
						
							|  |  |  |   Ab_.rowEnd() = noiseModel->dim(); | 
					
						
							|  |  |  |   Ab_.firstBlock() = 1; | 
					
						
							|  |  |  |   keys_.erase(keys_.begin()); | 
					
						
							|  |  |  |   // Set sigmas with the right model
 | 
					
						
							|  |  |  |   if (noiseModel->isConstrained()) | 
					
						
							|  |  |  |     model_ = noiseModel::Constrained::MixedSigmas(sub(noiseModel->sigmas(), firstVarDim, noiseModel->dim())); | 
					
						
							|  |  |  |   else | 
					
						
							|  |  |  |     model_ = noiseModel::Diagonal::Sigmas(sub(noiseModel->sigmas(), firstVarDim, noiseModel->dim())); | 
					
						
							|  |  |  |   assert(Ab_.size1() <= Ab_.size2()-1); | 
					
						
							|  |  |  |   toc("eliminateFirst: remaining factor"); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // todo SL: deal with "dead" pivot columns!!!
 | 
					
						
							|  |  |  |   tic("eliminateFirst: rowstarts"); | 
					
						
							|  |  |  |   size_t varpos = 0; | 
					
						
							|  |  |  |   firstNonzeroBlocks_.resize(this->numberOfRows()); | 
					
						
							|  |  |  |   for(size_t row=0; row<numberOfRows(); ++row) { | 
					
						
							|  |  |  |     while(varpos < this->keys_.size() && Ab_.offset(varpos+1) <= row) | 
					
						
							|  |  |  |       ++ varpos; | 
					
						
							|  |  |  |     firstNonzeroBlocks_[row] = varpos; | 
					
						
							|  |  |  |     if(debug) cout << "firstNonzeroVars_[" << row << "] = " << firstNonzeroBlocks_[row] << endl; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  |   toc("eliminateFirst: rowstarts"); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   if(debug) print("Eliminated factor: "); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   toc("eliminateFirst"); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-14 04:43:58 +08:00
										 |  |  |   assertInvariants(); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   return conditional; | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-12 08:14:50 +08:00
										 |  |  | GaussianBayesNet::shared_ptr GaussianFactor::eliminate(size_t nrFrontals) { | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   assert(Ab_.rowStart() == 0 && Ab_.rowEnd() == matrix_.size1() && Ab_.firstBlock() == 0); | 
					
						
							| 
									
										
										
										
											2010-10-12 08:14:50 +08:00
										 |  |  |   assert(keys_.size() >= nrFrontals); | 
					
						
							| 
									
										
										
										
											2010-10-14 04:43:58 +08:00
										 |  |  |   assertInvariants(); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   static const bool debug = false; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   tic("eliminate"); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   if(debug) this->print("Eliminating GaussianFactor: "); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   tic("eliminate: stairs"); | 
					
						
							|  |  |  |   // Translate the left-most nonzero column indices into top-most zero row indices
 | 
					
						
							|  |  |  |   vector<long> firstZeroRows(Ab_.size2()); | 
					
						
							|  |  |  |   { | 
					
						
							|  |  |  |     size_t lastNonzeroRow = 0; | 
					
						
							|  |  |  |     vector<long>::iterator firstZeroRowsIt = firstZeroRows.begin(); | 
					
						
							|  |  |  |     for(size_t var=0; var<keys().size(); ++var) { | 
					
						
							|  |  |  |       while(lastNonzeroRow < this->numberOfRows() && firstNonzeroBlocks_[lastNonzeroRow] <= var) | 
					
						
							|  |  |  |         ++ lastNonzeroRow; | 
					
						
							|  |  |  |       fill(firstZeroRowsIt, firstZeroRowsIt+Ab_(var).size2(), lastNonzeroRow); | 
					
						
							|  |  |  |       firstZeroRowsIt += Ab_(var).size2(); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |     assert(firstZeroRowsIt+1 == firstZeroRows.end()); | 
					
						
							|  |  |  |     *firstZeroRowsIt = this->numberOfRows(); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  |   toc("eliminate: stairs"); | 
					
						
							| 
									
										
										
										
											2010-01-21 02:32:48 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | #ifndef NDEBUG
 | 
					
						
							|  |  |  |   for(size_t col=0; col<Ab_.size2(); ++col) { | 
					
						
							|  |  |  |     if(debug) cout << "Staircase[" << col << "] = " << firstZeroRows[col] << endl; | 
					
						
							|  |  |  |     if(col != 0) assert(firstZeroRows[col] >= firstZeroRows[col-1]); | 
					
						
							|  |  |  |     assert(firstZeroRows[col] <= (long)this->numberOfRows()); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | #endif
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   if(debug) gtsam::print(matrix_, "Augmented Ab: "); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Use in-place QR on dense Ab appropriate to NoiseModel
 | 
					
						
							|  |  |  |   tic("eliminate: QR"); | 
					
						
							|  |  |  |   SharedDiagonal noiseModel = model_->QRColumnWise(matrix_, firstZeroRows); | 
					
						
							|  |  |  |   toc("eliminate: QR"); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Zero the lower-left triangle.  todo: not all of these entries actually
 | 
					
						
							|  |  |  |   // need to be zeroed if we are careful to start copying rows after the last
 | 
					
						
							|  |  |  |   // structural zero.
 | 
					
						
							|  |  |  |   if(matrix_.size1() > 0) { | 
					
						
							|  |  |  |     for(size_t j=0; j<matrix_.size2(); ++j) | 
					
						
							|  |  |  |       for(size_t i=j+1; i<noiseModel->dim(); ++i) | 
					
						
							|  |  |  |         matrix_(i,j) = 0.0; | 
					
						
							|  |  |  |   } | 
					
						
							| 
									
										
										
										
											2010-01-21 02:32:48 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   if(debug) gtsam::print(matrix_, "QR result: "); | 
					
						
							| 
									
										
										
										
											2010-01-21 02:32:48 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-12 08:14:50 +08:00
										 |  |  |   size_t frontalDim = Ab_.range(0,nrFrontals).size2(); | 
					
						
							| 
									
										
										
										
											2010-01-21 02:32:48 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   // Check for singular factor
 | 
					
						
							|  |  |  |   if(noiseModel->dim() < frontalDim) { | 
					
						
							|  |  |  |     throw domain_error((boost::format( | 
					
						
							|  |  |  |         "GaussianFactor is singular in variable %1%, discovered while attempting\n" | 
					
						
							|  |  |  |         "to eliminate this variable.") % keys_.front()).str()); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Extract conditionals
 | 
					
						
							|  |  |  |   tic("eliminate: cond Rd"); | 
					
						
							|  |  |  |   GaussianBayesNet::shared_ptr conditionals(new GaussianBayesNet()); | 
					
						
							| 
									
										
										
										
											2010-10-12 08:14:50 +08:00
										 |  |  |   for(size_t j=0; j<nrFrontals; ++j) { | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |     // Temporarily restrict the matrix view to the conditional blocks of the
 | 
					
						
							|  |  |  |     // eliminated Ab matrix to create the GaussianConditional from it.
 | 
					
						
							|  |  |  |     size_t varDim = Ab_(0).size2(); | 
					
						
							|  |  |  |     Ab_.rowEnd() = Ab_.rowStart() + varDim; | 
					
						
							|  |  |  |     const ublas::vector_range<const Vector> sigmas(noiseModel->sigmas(), ublas::range(Ab_.rowStart(), Ab_.rowEnd())); | 
					
						
							|  |  |  |     conditionals->push_back(boost::make_shared<Conditional>(keys_.begin()+j, keys_.end(), 1, Ab_, sigmas)); | 
					
						
							|  |  |  |     if(debug) conditionals->back()->print("Extracted conditional: "); | 
					
						
							|  |  |  |     Ab_.rowStart() += varDim; | 
					
						
							|  |  |  |     Ab_.firstBlock() += 1; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  |   toc("eliminate: cond Rd"); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   if(debug) conditionals->print("Extracted conditionals: "); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   tic("eliminate: remaining factor"); | 
					
						
							|  |  |  |   // Take lower-right block of Ab to get the new factor
 | 
					
						
							|  |  |  |   Ab_.rowEnd() = noiseModel->dim(); | 
					
						
							| 
									
										
										
										
											2010-10-12 08:14:50 +08:00
										 |  |  |   keys_.assign(keys_.begin() + nrFrontals, keys_.end()); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   // Set sigmas with the right model
 | 
					
						
							|  |  |  |   if (noiseModel->isConstrained()) | 
					
						
							|  |  |  |     model_ = noiseModel::Constrained::MixedSigmas(sub(noiseModel->sigmas(), frontalDim, noiseModel->dim())); | 
					
						
							|  |  |  |   else | 
					
						
							|  |  |  |     model_ = noiseModel::Diagonal::Sigmas(sub(noiseModel->sigmas(), frontalDim, noiseModel->dim())); | 
					
						
							|  |  |  |   assert(Ab_.size1() <= Ab_.size2()-1); | 
					
						
							|  |  |  |   if(debug) this->print("Eliminated factor: "); | 
					
						
							|  |  |  |   toc("eliminate: remaining factor"); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // todo SL: deal with "dead" pivot columns!!!
 | 
					
						
							|  |  |  |   tic("eliminate: rowstarts"); | 
					
						
							|  |  |  |   size_t varpos = 0; | 
					
						
							|  |  |  |   firstNonzeroBlocks_.resize(this->numberOfRows()); | 
					
						
							|  |  |  |   for(size_t row=0; row<numberOfRows(); ++row) { | 
					
						
							|  |  |  |     if(debug) cout << "row " << row << " varpos " << varpos << " Ab_.offset(varpos)=" << Ab_.offset(varpos) << " Ab_.offset(varpos+1)=" << Ab_.offset(varpos+1) << endl; | 
					
						
							|  |  |  |     while(varpos < this->keys_.size() && Ab_.offset(varpos+1) <= row) | 
					
						
							|  |  |  |       ++ varpos; | 
					
						
							|  |  |  |     firstNonzeroBlocks_[row] = varpos; | 
					
						
							|  |  |  |     if(debug) cout << "firstNonzeroVars_[" << row << "] = " << firstNonzeroBlocks_[row] << endl; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  |   toc("eliminate: rowstarts"); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   if(debug) print("Eliminated factor: "); | 
					
						
							| 
									
										
										
										
											2009-11-05 04:59:16 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   toc("eliminate"); | 
					
						
							| 
									
										
										
										
											2009-11-05 04:59:16 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-14 04:43:58 +08:00
										 |  |  |   assertInvariants(); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   return conditionals; | 
					
						
							| 
									
										
										
										
											2010-07-11 15:30:27 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-07-11 15:30:27 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | /* Used internally by GaussianFactor::Combine for sorting */ | 
					
						
							|  |  |  | struct _RowSource { | 
					
						
							|  |  |  |   size_t firstNonzeroVar; | 
					
						
							|  |  |  |   size_t factorI; | 
					
						
							|  |  |  |   size_t factorRowI; | 
					
						
							|  |  |  |   _RowSource(size_t _firstNonzeroVar, size_t _factorI, size_t _factorRowI) : | 
					
						
							|  |  |  |     firstNonzeroVar(_firstNonzeroVar), factorI(_factorI), factorRowI(_factorRowI) {} | 
					
						
							|  |  |  |   bool operator<(const _RowSource& o) const { return firstNonzeroVar < o.firstNonzeroVar; } | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-02-22 01:06:11 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | // Helper functions for Combine
 | 
					
						
							| 
									
										
										
										
											2010-10-23 02:39:04 +08:00
										 |  |  | static boost::tuple<vector<size_t>, size_t, size_t> countDims(const std::vector<GaussianFactor::shared_ptr>& factors, const VariableSlots& variableSlots) { | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | #ifndef NDEBUG
 | 
					
						
							|  |  |  |   vector<size_t> varDims(variableSlots.size(), numeric_limits<size_t>::max()); | 
					
						
							|  |  |  | #else
 | 
					
						
							|  |  |  |   vector<size_t> varDims(variableSlots.size()); | 
					
						
							|  |  |  | #endif
 | 
					
						
							|  |  |  |   size_t m = 0; | 
					
						
							|  |  |  |   size_t n = 0; | 
					
						
							|  |  |  |   { | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  |     Index jointVarpos = 0; | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |     BOOST_FOREACH(const VariableSlots::value_type& slots, variableSlots) { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |       assert(slots.second.size() == factors.size()); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  |       Index sourceFactorI = 0; | 
					
						
							|  |  |  |       BOOST_FOREACH(const Index sourceVarpos, slots.second) { | 
					
						
							|  |  |  |         if(sourceVarpos < numeric_limits<Index>::max()) { | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |           const GaussianFactor& sourceFactor = *factors[sourceFactorI]; | 
					
						
							|  |  |  |           size_t vardim = sourceFactor.getDim(sourceFactor.begin() + sourceVarpos); | 
					
						
							|  |  |  | #ifndef NDEBUG
 | 
					
						
							|  |  |  |           if(varDims[jointVarpos] == numeric_limits<size_t>::max()) { | 
					
						
							|  |  |  |             varDims[jointVarpos] = vardim; | 
					
						
							|  |  |  |             n += vardim; | 
					
						
							|  |  |  |           } else | 
					
						
							|  |  |  |             assert(varDims[jointVarpos] == vardim); | 
					
						
							|  |  |  | #else
 | 
					
						
							|  |  |  |           varDims[jointVarpos] = vardim; | 
					
						
							|  |  |  |           n += vardim; | 
					
						
							|  |  |  |           break; | 
					
						
							|  |  |  | #endif
 | 
					
						
							|  |  |  |         } | 
					
						
							|  |  |  |         ++ sourceFactorI; | 
					
						
							|  |  |  |       } | 
					
						
							|  |  |  |       ++ jointVarpos; | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |     BOOST_FOREACH(const GaussianFactor::shared_ptr& factor, factors) { | 
					
						
							|  |  |  |       m += factor->numberOfRows(); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  |   return boost::make_tuple(varDims, m, n); | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2010-02-01 01:49:33 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-23 02:39:04 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-20 05:31:13 +08:00
										 |  |  | GaussianFactor::shared_ptr GaussianFactor::Combine(const FactorGraph<GaussianFactor>& factors, const VariableSlots& variableSlots) { | 
					
						
							| 
									
										
										
										
											2010-02-01 01:49:33 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   static const bool verbose = false; | 
					
						
							|  |  |  |   static const bool debug = false; | 
					
						
							|  |  |  |   if (verbose) std::cout << "GaussianFactor::GaussianFactor (factors)" << std::endl; | 
					
						
							| 
									
										
										
										
											2010-02-01 01:49:33 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   if(debug) variableSlots.print(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Determine dimensions
 | 
					
						
							|  |  |  |   tic("Combine 1: countDims"); | 
					
						
							|  |  |  |   vector<size_t> varDims; | 
					
						
							|  |  |  |   size_t m; | 
					
						
							|  |  |  |   size_t n; | 
					
						
							|  |  |  |   boost::tie(varDims, m, n) = countDims(factors, variableSlots); | 
					
						
							|  |  |  |   if(debug) { | 
					
						
							|  |  |  |     cout << "Dims: " << m << " x " << n << "\n"; | 
					
						
							|  |  |  |     BOOST_FOREACH(const size_t dim, varDims) { cout << dim << " "; } | 
					
						
							|  |  |  |     cout << endl; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  |   toc("Combine 1: countDims"); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Sort rows
 | 
					
						
							|  |  |  |   tic("Combine 2: sort rows"); | 
					
						
							|  |  |  |   vector<_RowSource> rowSources; rowSources.reserve(m); | 
					
						
							|  |  |  |   bool anyConstrained = false; | 
					
						
							|  |  |  |   for(size_t sourceFactorI = 0; sourceFactorI < factors.size(); ++sourceFactorI) { | 
					
						
							|  |  |  |     const GaussianFactor& sourceFactor(*factors[sourceFactorI]); | 
					
						
							|  |  |  |     for(size_t sourceFactorRow = 0; sourceFactorRow < sourceFactor.numberOfRows(); ++sourceFactorRow) { | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  |       Index firstNonzeroVar; | 
					
						
							| 
									
										
										
										
											2010-10-14 04:43:58 +08:00
										 |  |  |       firstNonzeroVar = sourceFactor.keys_[sourceFactor.firstNonzeroBlocks_[sourceFactorRow]]; | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |       rowSources.push_back(_RowSource(firstNonzeroVar, sourceFactorI, sourceFactorRow)); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |     if(sourceFactor.model_->isConstrained()) anyConstrained = true; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  |   assert(rowSources.size() == m); | 
					
						
							|  |  |  |   std::sort(rowSources.begin(), rowSources.end()); | 
					
						
							|  |  |  |   toc("Combine 2: sort rows"); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Allocate new factor
 | 
					
						
							|  |  |  |   tic("Combine 3: allocate"); | 
					
						
							|  |  |  |   shared_ptr combined(new GaussianFactor()); | 
					
						
							|  |  |  |   combined->keys_.resize(variableSlots.size()); | 
					
						
							|  |  |  |   std::transform(variableSlots.begin(), variableSlots.end(), combined->keys_.begin(), bind(&VariableSlots::const_iterator::value_type::first, boost::lambda::_1)); | 
					
						
							|  |  |  |   varDims.push_back(1); | 
					
						
							| 
									
										
										
										
											2010-10-23 02:39:04 +08:00
										 |  |  |   combined->Ab_.copyStructureFrom(BlockAb(combined->matrix_, varDims.begin(), varDims.end(), m)); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   combined->firstNonzeroBlocks_.resize(m); | 
					
						
							|  |  |  |   Vector sigmas(m); | 
					
						
							|  |  |  |   toc("Combine 3: allocate"); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Copy rows
 | 
					
						
							|  |  |  |   tic("Combine 4: copy rows"); | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  |   Index combinedSlot = 0; | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   BOOST_FOREACH(const VariableSlots::value_type& varslot, variableSlots) { | 
					
						
							|  |  |  |     for(size_t row = 0; row < m; ++row) { | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  |       const Index sourceSlot = varslot.second[rowSources[row].factorI]; | 
					
						
							| 
									
										
										
										
											2010-10-23 02:39:04 +08:00
										 |  |  |       ABlock combinedBlock(combined->Ab_(combinedSlot)); | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  |       if(sourceSlot != numeric_limits<Index>::max()) { | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |         const GaussianFactor& source(*factors[rowSources[row].factorI]); | 
					
						
							|  |  |  |         const size_t sourceRow = rowSources[row].factorRowI; | 
					
						
							|  |  |  |         if(source.firstNonzeroBlocks_[sourceRow] <= sourceSlot) { | 
					
						
							| 
									
										
										
										
											2010-10-23 02:39:04 +08:00
										 |  |  |           const constABlock sourceBlock(source.Ab_(sourceSlot)); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |           ublas::noalias(ublas::row(combinedBlock, row)) = ublas::row(sourceBlock, sourceRow); | 
					
						
							|  |  |  |         } else | 
					
						
							|  |  |  |           ublas::noalias(ublas::row(combinedBlock, row)) = ublas::zero_vector<double>(combinedBlock.size2()); | 
					
						
							|  |  |  |       } else | 
					
						
							|  |  |  |         ublas::noalias(ublas::row(combinedBlock, row)) = ublas::zero_vector<double>(combinedBlock.size2()); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |     ++ combinedSlot; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  |   toc("Combine 4: copy rows"); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Copy rhs (b), sigma, and firstNonzeroBlocks
 | 
					
						
							|  |  |  |   tic("Combine 5: copy vectors"); | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  |   Index firstNonzeroSlot = 0; | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   for(size_t row = 0; row < m; ++row) { | 
					
						
							|  |  |  |     const GaussianFactor& source(*factors[rowSources[row].factorI]); | 
					
						
							|  |  |  |     const size_t sourceRow = rowSources[row].factorRowI; | 
					
						
							|  |  |  |     combined->getb()(row) = source.getb()(sourceRow); | 
					
						
							|  |  |  |     sigmas(row) = source.get_sigmas()(sourceRow); | 
					
						
							|  |  |  |     while(firstNonzeroSlot < variableSlots.size() && rowSources[row].firstNonzeroVar > combined->keys_[firstNonzeroSlot]) | 
					
						
							|  |  |  |       ++ firstNonzeroSlot; | 
					
						
							|  |  |  |     combined->firstNonzeroBlocks_[row] = firstNonzeroSlot; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  |   toc("Combine 5: copy vectors"); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Create noise model from sigmas
 | 
					
						
							|  |  |  |   tic("Combine 6: noise model"); | 
					
						
							|  |  |  |   if(anyConstrained) combined->model_ = noiseModel::Constrained::MixedSigmas(sigmas); | 
					
						
							|  |  |  |   else combined->model_ = noiseModel::Diagonal::Sigmas(sigmas); | 
					
						
							|  |  |  |   toc("Combine 6: noise model"); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-14 04:43:58 +08:00
										 |  |  |   combined->assertInvariants(); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   return combined; | 
					
						
							| 
									
										
										
										
											2010-02-01 01:49:33 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-10-27 21:33:44 +08:00
										 |  |  | } |