| 
									
										
										
										
											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
										 |  |  | /**
 | 
					
						
							| 
									
										
										
										
											2010-02-17 11:29:12 +08:00
										 |  |  |  * @file    VectorMap.cpp | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |  * @brief   Factor Graph Values | 
					
						
							| 
									
										
										
										
											2010-02-17 11:29:12 +08:00
										 |  |  |  * @brief   VectorMap | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  |  * @author  Carlos Nieto | 
					
						
							|  |  |  |  * @author  Christian Potthast | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <boost/foreach.hpp>
 | 
					
						
							|  |  |  | #include <boost/tuple/tuple.hpp>
 | 
					
						
							| 
									
										
										
										
											2010-08-20 01:23:19 +08:00
										 |  |  | #include <gtsam/linear/VectorMap.h>
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | // trick from some reading group
 | 
					
						
							|  |  |  | #define FOREACH_PAIR( KEY, VAL, COL) BOOST_FOREACH (boost::tie(KEY,VAL),COL) 
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | using namespace std; | 
					
						
							| 
									
										
										
										
											2009-12-12 05:38:08 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | namespace gtsam { | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  | void check_size(Index key, const Vector & vj, const Vector & dj) { | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  |   if (dj.size()!=vj.size()) { | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |     cout << "For key \"" << key << "\"" << endl; | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  |     cout << "vj.size = " << vj.size() << endl; | 
					
						
							|  |  |  |     cout << "dj.size = " << dj.size() << endl; | 
					
						
							| 
									
										
										
										
											2010-02-17 11:29:12 +08:00
										 |  |  |     throw(std::invalid_argument("VectorMap::+ mismatched dimensions")); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-11-20 13:10:55 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  | std::vector<Index> VectorMap::get_names() const { | 
					
						
							|  |  |  |   std::vector<Index> names; | 
					
						
							| 
									
										
										
										
											2009-12-12 05:38:08 +08:00
										 |  |  |   for(const_iterator it=values.begin(); it!=values.end(); it++) | 
					
						
							|  |  |  |     names.push_back(it->first); | 
					
						
							|  |  |  |   return names; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-19 04:17:31 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  | VectorMap& VectorMap::insert(Index name, const Vector& v) { | 
					
						
							| 
									
										
										
										
											2010-02-17 11:29:12 +08:00
										 |  |  |   values.insert(std::make_pair(name,v)); | 
					
						
							|  |  |  |   return *this; | 
					
						
							| 
									
										
										
										
											2010-01-19 04:17:31 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-12-12 05:38:08 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  | VectorMap& VectorMap::insertAdd(Index j, const Vector& a) { | 
					
						
							| 
									
										
										
										
											2009-12-12 05:38:08 +08:00
										 |  |  | 	Vector& vj = values[j]; | 
					
						
							|  |  |  | 	if (vj.size()==0) vj = a; else vj += a; | 
					
						
							| 
									
										
										
										
											2010-02-17 11:29:12 +08:00
										 |  |  | 	return *this; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | void VectorMap::insert(const VectorMap& config) { | 
					
						
							|  |  |  | 	for (const_iterator it = config.begin(); it!=config.end(); it++) | 
					
						
							|  |  |  | 		insert(it->first, it->second); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | void VectorMap::insertAdd(const VectorMap& config) { | 
					
						
							|  |  |  | 	for (const_iterator it = config.begin(); it!=config.end(); it++) | 
					
						
							|  |  |  |     insertAdd(it->first,it->second); | 
					
						
							| 
									
										
										
										
											2009-12-12 05:38:08 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-02-17 11:29:12 +08:00
										 |  |  | size_t VectorMap::dim() const { | 
					
						
							| 
									
										
										
										
											2009-12-12 05:38:08 +08:00
										 |  |  | 	size_t result=0; | 
					
						
							| 
									
										
										
										
											2010-02-17 11:29:12 +08:00
										 |  |  | 	for (const_iterator it = begin(); it != end(); it++) | 
					
						
							|  |  |  | 		result += it->second.size(); | 
					
						
							| 
									
										
										
										
											2009-12-12 05:38:08 +08:00
										 |  |  | 	return result; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  | const Vector& VectorMap::operator[](Index name) const { | 
					
						
							| 
									
										
										
										
											2010-02-17 11:29:12 +08:00
										 |  |  |   return values.at(name); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  | Vector& VectorMap::operator[](Index name) { | 
					
						
							| 
									
										
										
										
											2010-02-17 11:29:12 +08:00
										 |  |  |   return values.at(name); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | VectorMap VectorMap::scale(double s) const { | 
					
						
							|  |  |  | 	VectorMap scaled; | 
					
						
							|  |  |  | 	for (const_iterator it = begin(); it != end(); it++) | 
					
						
							|  |  |  | 		scaled.insert(it->first, s*it->second); | 
					
						
							| 
									
										
										
										
											2009-11-20 13:10:55 +08:00
										 |  |  | 	return scaled; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-12-12 05:38:08 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-02-17 11:29:12 +08:00
										 |  |  | VectorMap VectorMap::operator*(double s) const { | 
					
						
							| 
									
										
										
										
											2009-12-12 05:38:08 +08:00
										 |  |  | 	return scale(s); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-12-28 16:15:09 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-02-17 11:29:12 +08:00
										 |  |  | VectorMap VectorMap::operator-() const { | 
					
						
							|  |  |  | 	VectorMap result; | 
					
						
							|  |  |  | 	for (const_iterator it = begin(); it != end(); it++) | 
					
						
							|  |  |  | 		result.insert(it->first, - it->second); | 
					
						
							| 
									
										
										
										
											2009-12-28 16:15:09 +08:00
										 |  |  | 	return result; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-12-27 20:13:31 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-02-17 11:29:12 +08:00
										 |  |  | void VectorMap::operator+=(const VectorMap& b) { | 
					
						
							|  |  |  | 	insertAdd(b); | 
					
						
							| 
									
										
										
										
											2009-12-27 20:13:31 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-12-12 05:38:08 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-02-17 11:29:12 +08:00
										 |  |  | VectorMap VectorMap::operator+(const VectorMap& b) const { | 
					
						
							|  |  |  | 	VectorMap result = *this; | 
					
						
							| 
									
										
										
										
											2009-12-27 20:13:31 +08:00
										 |  |  | 	result += b; | 
					
						
							| 
									
										
										
										
											2009-12-12 05:38:08 +08:00
										 |  |  | 	return result; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-02-17 11:29:12 +08:00
										 |  |  | VectorMap VectorMap::operator-(const VectorMap& b) const { | 
					
						
							|  |  |  | 	VectorMap result; | 
					
						
							|  |  |  | 	for (const_iterator it = begin(); it != end(); it++) | 
					
						
							|  |  |  | 		result.insert(it->first, it->second - b[it->first]); | 
					
						
							| 
									
										
										
										
											2009-12-12 05:38:08 +08:00
										 |  |  | 	return result; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-02-17 11:29:12 +08:00
										 |  |  | VectorMap& VectorMap::zero() { | 
					
						
							|  |  |  | 	for (iterator it = begin(); it != end(); it++) | 
					
						
							|  |  |  | 		std::fill(it->second.begin(), it->second.end(), 0.0); | 
					
						
							|  |  |  | 	return *this; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | VectorMap VectorMap::zero(const VectorMap& x) { | 
					
						
							|  |  |  | 	VectorMap cloned(x); | 
					
						
							|  |  |  | 	return cloned.zero(); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-04-23 14:11:51 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | Vector VectorMap::vector() const { | 
					
						
							|  |  |  | 	Vector result(dim()); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	size_t cur_dim = 0; | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  | 	Index j; Vector vj; | 
					
						
							| 
									
										
										
										
											2010-04-23 14:11:51 +08:00
										 |  |  | 	FOREACH_PAIR(j, vj, values) { | 
					
						
							|  |  |  | 		subInsert(result, vj, cur_dim); | 
					
						
							|  |  |  | 		cur_dim += vj.size(); | 
					
						
							|  |  |  | 	} | 
					
						
							|  |  |  | 	return result; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-02-17 11:29:12 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | VectorMap expmap(const VectorMap& original, const VectorMap& delta) | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	VectorMap newValues; | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  | 	Index j; Vector vj; // rtodo: copying vector?
 | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  | 	FOREACH_PAIR(j, vj, original.values) { | 
					
						
							| 
									
										
										
										
											2009-11-29 05:44:07 +08:00
										 |  |  | 		if (delta.contains(j)) { | 
					
						
							|  |  |  | 			const Vector& dj = delta[j]; | 
					
						
							|  |  |  | 			check_size(j,vj,dj); | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 			newValues.insert(j, vj + dj); | 
					
						
							| 
									
										
										
										
											2009-11-29 05:44:07 +08:00
										 |  |  | 		} else { | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 			newValues.insert(j, vj); | 
					
						
							| 
									
										
										
										
											2009-11-29 05:44:07 +08:00
										 |  |  | 		} | 
					
						
							|  |  |  | 	} | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	return newValues; | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-12-12 06:43:34 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-02-17 11:29:12 +08:00
										 |  |  | VectorMap expmap(const VectorMap& original, const Vector& delta) | 
					
						
							| 
									
										
										
										
											2009-12-12 06:43:34 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	VectorMap newValues; | 
					
						
							| 
									
										
										
										
											2009-12-12 06:43:34 +08:00
										 |  |  | 	size_t i = 0; | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  | 	Index j; Vector vj; // rtodo: copying vector?
 | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  | 	FOREACH_PAIR(j, vj, original.values) { | 
					
						
							| 
									
										
										
										
											2009-12-12 06:43:34 +08:00
										 |  |  | 		size_t mj = vj.size(); | 
					
						
							|  |  |  | 		Vector dj = sub(delta, i, i+mj); | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 		newValues.insert(j, vj + dj); | 
					
						
							| 
									
										
										
										
											2009-12-12 06:43:34 +08:00
										 |  |  | 		i += mj; | 
					
						
							|  |  |  | 	} | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	return newValues; | 
					
						
							| 
									
										
										
										
											2009-12-12 06:43:34 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-02-17 11:29:12 +08:00
										 |  |  | void VectorMap::print(const string& name) const { | 
					
						
							|  |  |  |   odprintf("VectorMap %s\n", name.c_str()); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  |   odprintf("size: %d\n", values.size()); | 
					
						
							| 
									
										
										
										
											2010-02-17 11:29:12 +08:00
										 |  |  |   for (const_iterator it = begin(); it != end(); it++) { | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |     odprintf("%d:", it->first); | 
					
						
							| 
									
										
										
										
											2010-02-17 11:29:12 +08:00
										 |  |  |     gtsam::print(it->second); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-02-17 11:29:12 +08:00
										 |  |  | bool VectorMap::equals(const VectorMap& expected, double tol) const { | 
					
						
							| 
									
										
										
										
											2009-11-05 04:59:16 +08:00
										 |  |  |   if( values.size() != expected.size() ) return false; | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // iterate over all nodes
 | 
					
						
							| 
									
										
										
										
											2010-02-17 11:29:12 +08:00
										 |  |  |   for (const_iterator it = begin(); it != end(); it++) { | 
					
						
							|  |  |  |     Vector vExpected = expected[it->first]; | 
					
						
							|  |  |  |     if(!equal_with_abs_tol(vExpected,it->second,tol)) | 
					
						
							| 
									
										
										
										
											2009-11-05 04:59:16 +08:00
										 |  |  |     	return false; | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  |   } | 
					
						
							|  |  |  |   return true; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-12-12 05:38:08 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-02-17 11:29:12 +08:00
										 |  |  | double VectorMap::dot(const VectorMap& b) const { | 
					
						
							|  |  |  |   double result = 0.0; // rtodo: copying vector
 | 
					
						
							|  |  |  |   for (const_iterator it = begin(); it != end(); it++) | 
					
						
							|  |  |  |   	result += gtsam::dot(it->second,b[it->first]); | 
					
						
							| 
									
										
										
										
											2009-12-12 05:38:08 +08:00
										 |  |  | 	return result; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-02-17 11:29:12 +08:00
										 |  |  | double dot(const VectorMap& a, const VectorMap& b) { | 
					
						
							| 
									
										
										
										
											2009-12-12 05:38:08 +08:00
										 |  |  | 	return a.dot(b); | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2010-01-30 10:04:37 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-30 12:01:49 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-02-17 11:29:12 +08:00
										 |  |  | void scal(double alpha, VectorMap& x) { | 
					
						
							|  |  |  | 	for (VectorMap::iterator xj = x.begin(); xj != x.end(); xj++) | 
					
						
							| 
									
										
										
										
											2010-01-30 12:01:49 +08:00
										 |  |  | 		scal(alpha, xj->second); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-30 10:04:37 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-02-17 11:29:12 +08:00
										 |  |  | void axpy(double alpha, const VectorMap& x, VectorMap& y) { | 
					
						
							|  |  |  | 	VectorMap::const_iterator xj = x.begin(); | 
					
						
							|  |  |  | 	for (VectorMap::iterator yj = y.begin(); yj != y.end(); yj++, xj++) | 
					
						
							| 
									
										
										
										
											2010-01-30 10:04:37 +08:00
										 |  |  | 		axpy(alpha, xj->second, yj->second); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-02-17 11:29:12 +08:00
										 |  |  | void print(const VectorMap& v, const std::string& s){ | 
					
						
							| 
									
										
										
										
											2010-01-11 16:32:59 +08:00
										 |  |  | 	v.print(s); | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2010-02-17 11:29:12 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-11 16:32:59 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-12-12 05:38:08 +08:00
										 |  |  | } // gtsam
 |