| 
									
										
										
										
											2010-10-26 23:01:34 +08:00
										 |  |  | /* ----------------------------------------------------------------------------
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * GTSAM Copyright 2010, Georgia Tech Research Corporation, | 
					
						
							|  |  |  |  * Atlanta, Georgia 30332-0415 | 
					
						
							|  |  |  |  * All Rights Reserved | 
					
						
							|  |  |  |  * Authors: Frank Dellaert, et al. (see THANKS for the full author list) | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * See LICENSE for the license information | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-22 06:51:20 +08:00
										 |  |  | /*
 | 
					
						
							|  |  |  |  * ISAMLoop.cpp | 
					
						
							|  |  |  |  * | 
					
						
							|  |  |  |  *  Created on: Jan 19, 2010 | 
					
						
							|  |  |  |  *      Author: Viorela Ila and Richard Roberts | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #pragma once
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam/linear/GaussianFactorGraph.h>
 | 
					
						
							|  |  |  | #include <gtsam/inference/ISAM-inl.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/Ordering.h>
 | 
					
						
							|  |  |  | #include <boost/foreach.hpp>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include "ISAMLoop.h"
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | template<class Values> | 
					
						
							|  |  |  | void ISAMLoop<Values>::update(const Factors& newFactors, const Values& initialValues) { | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-22 11:40:47 +08:00
										 |  |  |   if(newFactors.size() > 0) { | 
					
						
							| 
									
										
										
										
											2010-10-22 06:51:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-26 23:01:34 +08:00
										 |  |  |     // Reorder and relinearize every reorderInterval updates
 | 
					
						
							|  |  |  |     if(reorderInterval_ > 0 && ++reorderCounter_ >= reorderInterval_) { | 
					
						
							|  |  |  |       reorder_relinearize(); | 
					
						
							|  |  |  |       reorderCounter_ = 0; | 
					
						
							|  |  |  |     } | 
					
						
							| 
									
										
										
										
											2010-10-22 06:51:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-26 23:01:34 +08:00
										 |  |  |     factors_.push_back(newFactors); | 
					
						
							| 
									
										
										
										
											2010-10-22 06:51:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-26 23:01:34 +08:00
										 |  |  |     // Linearize new factors and insert them
 | 
					
						
							|  |  |  |     // TODO: optimize for whole config?
 | 
					
						
							|  |  |  |     linPoint_.insert(initialValues); | 
					
						
							| 
									
										
										
										
											2010-10-22 06:51:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-26 23:01:34 +08:00
										 |  |  |     // Augment ordering
 | 
					
						
							|  |  |  |     BOOST_FOREACH(const typename Factors::sharedFactor& factor, newFactors) { | 
					
						
							|  |  |  |       BOOST_FOREACH(const Symbol& key, factor->keys()) { | 
					
						
							|  |  |  |         ordering_.tryInsert(key, ordering_.nVars()); | 
					
						
							| 
									
										
										
										
											2010-10-22 11:40:47 +08:00
										 |  |  |       } | 
					
						
							| 
									
										
										
										
											2010-10-26 23:01:34 +08:00
										 |  |  |     } | 
					
						
							| 
									
										
										
										
											2010-10-22 06:51:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-26 23:01:34 +08:00
										 |  |  |     boost::shared_ptr<GaussianFactorGraph> linearizedNewFactors(newFactors.linearize(linPoint_, ordering_)); | 
					
						
							| 
									
										
										
										
											2010-10-22 07:32:51 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-26 23:01:34 +08:00
										 |  |  |     // Update ISAM
 | 
					
						
							|  |  |  |     isam.update(*linearizedNewFactors); | 
					
						
							| 
									
										
										
										
											2010-10-22 06:51:20 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | template<class Values> | 
					
						
							|  |  |  | void ISAMLoop<Values>::reorder_relinearize() { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   cout << "Reordering, relinearizing..." << endl; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Obtain the new linearization point
 | 
					
						
							|  |  |  |   const Values newLinPoint = estimate(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   isam.clear(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Compute an ordering
 | 
					
						
							|  |  |  |   ordering_ = *factors_.orderingCOLAMD(newLinPoint); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Create a linear factor graph at the new linearization point
 | 
					
						
							|  |  |  |   boost::shared_ptr<GaussianFactorGraph> gfg(factors_.linearize(newLinPoint, ordering_)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Just recreate the whole BayesTree
 | 
					
						
							|  |  |  |   isam.update(*gfg); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-22 11:40:47 +08:00
										 |  |  |   // Update linearization point
 | 
					
						
							| 
									
										
										
										
											2010-10-22 06:51:20 +08:00
										 |  |  |   linPoint_ = newLinPoint; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | template<class Values> | 
					
						
							|  |  |  | Values ISAMLoop<Values>::estimate() { | 
					
						
							|  |  |  |   if(isam.size() > 0) | 
					
						
							|  |  |  |     return linPoint_.expmap(optimize(isam), ordering_); | 
					
						
							|  |  |  |   else | 
					
						
							|  |  |  |     return linPoint_; | 
					
						
							|  |  |  | } |