| 
									
										
										
										
											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 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | /**
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  |  * @file LieValues.cpp | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  |  * @author Richard Roberts | 
					
						
							| 
									
										
										
										
											2010-01-10 14:35:16 +08:00
										 |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-02-05 00:08:59 +08:00
										 |  |  | #pragma once
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-10 14:35:16 +08:00
										 |  |  | #include <boost/foreach.hpp>
 | 
					
						
							|  |  |  | #include <boost/tuple/tuple.hpp>
 | 
					
						
							| 
									
										
										
										
											2010-01-11 01:26:44 +08:00
										 |  |  | #include <utility>
 | 
					
						
							|  |  |  | #include <iostream>
 | 
					
						
							|  |  |  | #include <stdexcept>
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | #include <gtsam/linear/VectorValues.h>
 | 
					
						
							| 
									
										
										
										
											2010-08-23 05:45:53 +08:00
										 |  |  | #include <gtsam/base/LieVector.h>
 | 
					
						
							| 
									
										
										
										
											2010-08-20 01:23:19 +08:00
										 |  |  | #include <gtsam/base/Lie-inl.h>
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | #include <gtsam/nonlinear/Ordering.h>
 | 
					
						
							| 
									
										
										
										
											2010-01-16 09:16:59 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  | #include <gtsam/nonlinear/LieValues.h>
 | 
					
						
							| 
									
										
										
										
											2010-01-16 09:16:59 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-24 03:44:17 +08:00
										 |  |  | #define INSTANTIATE_LIE_CONFIG(J) \
 | 
					
						
							| 
									
										
										
										
											2010-01-16 09:16:59 +08:00
										 |  |  |   /*INSTANTIATE_LIE(T);*/ \ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   /*template LieValues<J> expmap(const LieValues<J>&, const VectorValues&);*/ \ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  |   /*template LieValues<J> expmap(const LieValues<J>&, const Vector&);*/ \ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   /*template VectorValues logmap(const LieValues<J>&, const LieValues<J>&);*/ \ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  |   template class LieValues<J>; | 
					
						
							| 
									
										
										
										
											2010-01-10 14:35:16 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | namespace gtsam { | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-08-24 03:44:17 +08:00
										 |  |  |   template<class J> | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  |   void LieValues<J>::print(const string &s) const { | 
					
						
							|  |  |  |        cout << "LieValues " << s << ", size " << values_.size() << "\n"; | 
					
						
							| 
									
										
										
										
											2010-10-09 01:37:59 +08:00
										 |  |  |        BOOST_FOREACH(const KeyValuePair& v, values_) { | 
					
						
							| 
									
										
											  
											
												Large gtsam refactoring
To support faster development *and* better performance Richard and I pushed through a large refactoring of NonlinearFactors.
The following are the biggest changes:
1) NonLinearFactor1 and NonLinearFactor2 are now templated on Config, Key type, and X type, where X is the argument to the measurement function.
2) The measurement itself is no longer kept in the nonlinear factor. Instead, a derived class (see testVSLAMFactor, testNonlinearEquality, testPose3Factor etc...) has to implement a function to compute the errors, "evaluateErrors". Instead of (h(x)-z), it needs to return (z-h(x)), so Ax-b is an approximation of the error. IMPORTANT: evaluateErrors needs - if asked - *combine* the calculation of the function value h(x) and the derivatives dh(x)/dx. This was a major performance issue. To do this, boost::optional<Matrix&> arguments are provided, and tin EvaluateErrors you just  says something like
	if (H) *H = Matrix_(3,6,....);
3) We are no longer using int or strings for nonlinear factors. Instead, the preferred key type is now Symbol, defined in Key.h. This is both fast and cool: you can construct it from an int, and cast it to a strong. It also does type checking: a Symbol<Pose3,'x'> will not match a Symbol<Pose2,'x'>
4) minor: take a look at LieConfig.h: it help you avoid writing a lot of code bu automatically creating configs for a certain type. See e.g. Pose3Config.h. A "double" LieConfig is on the way - Thanks Richard and Manohar !
											
										 
											2010-01-14 06:25:03 +08:00
										 |  |  |          gtsam::print(v.second, (string)(v.first)); | 
					
						
							| 
									
										
										
										
											2010-08-20 04:03:06 +08:00
										 |  |  |        } | 
					
						
							| 
									
										
										
										
											2010-01-10 14:35:16 +08:00
										 |  |  |      } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  |   /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-08-24 03:44:17 +08:00
										 |  |  |   template<class J> | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  |   bool LieValues<J>::equals(const LieValues<J>& expected, double tol) const { | 
					
						
							| 
									
										
										
										
											2010-01-10 14:35:16 +08:00
										 |  |  |     if (values_.size() != expected.values_.size()) return false; | 
					
						
							| 
									
										
										
										
											2010-10-09 01:37:59 +08:00
										 |  |  |     BOOST_FOREACH(const KeyValuePair& v, values_) { | 
					
						
							| 
									
										
										
										
											2010-03-07 14:29:23 +08:00
										 |  |  |     	if (!expected.exists(v.first)) return false; | 
					
						
							| 
									
										
											  
											
												Large gtsam refactoring
To support faster development *and* better performance Richard and I pushed through a large refactoring of NonlinearFactors.
The following are the biggest changes:
1) NonLinearFactor1 and NonLinearFactor2 are now templated on Config, Key type, and X type, where X is the argument to the measurement function.
2) The measurement itself is no longer kept in the nonlinear factor. Instead, a derived class (see testVSLAMFactor, testNonlinearEquality, testPose3Factor etc...) has to implement a function to compute the errors, "evaluateErrors". Instead of (h(x)-z), it needs to return (z-h(x)), so Ax-b is an approximation of the error. IMPORTANT: evaluateErrors needs - if asked - *combine* the calculation of the function value h(x) and the derivatives dh(x)/dx. This was a major performance issue. To do this, boost::optional<Matrix&> arguments are provided, and tin EvaluateErrors you just  says something like
	if (H) *H = Matrix_(3,6,....);
3) We are no longer using int or strings for nonlinear factors. Instead, the preferred key type is now Symbol, defined in Key.h. This is both fast and cool: you can construct it from an int, and cast it to a strong. It also does type checking: a Symbol<Pose3,'x'> will not match a Symbol<Pose2,'x'>
4) minor: take a look at LieConfig.h: it help you avoid writing a lot of code bu automatically creating configs for a certain type. See e.g. Pose3Config.h. A "double" LieConfig is on the way - Thanks Richard and Manohar !
											
										 
											2010-01-14 06:25:03 +08:00
										 |  |  |       if(!gtsam::equal(v.second, expected[v.first], tol)) | 
					
						
							| 
									
										
										
										
											2010-01-10 14:35:16 +08:00
										 |  |  |         return false; | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |     return true; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  |   /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-08-24 03:44:17 +08:00
										 |  |  |   template<class J> | 
					
						
							| 
									
										
										
										
											2010-10-09 11:53:27 +08:00
										 |  |  |   const typename J::Value& LieValues<J>::at(const J& j) const { | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  |     const_iterator it = values_.find(j); | 
					
						
							|  |  |  |     if (it == values_.end()) throw std::invalid_argument("invalid j: " + (string)j); | 
					
						
							| 
									
										
										
										
											2010-01-11 01:26:44 +08:00
										 |  |  |     else return it->second; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  |   /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-08-24 03:44:17 +08:00
										 |  |  |   template<class J> | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  |   size_t LieValues<J>::dim() const { | 
					
						
							| 
									
										
										
										
											2010-03-10 08:20:12 +08:00
										 |  |  |   	size_t n = 0; | 
					
						
							| 
									
										
										
										
											2010-10-09 01:37:59 +08:00
										 |  |  |   	BOOST_FOREACH(const KeyValuePair& value, values_) | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  |   		n += value.second.dim(); | 
					
						
							| 
									
										
										
										
											2010-03-10 08:20:12 +08:00
										 |  |  |   	return n; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  |   /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-08-24 03:44:17 +08:00
										 |  |  |   template<class J> | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   VectorValues LieValues<J>::zero(const Ordering& ordering) const { | 
					
						
							|  |  |  |   	VectorValues z(this->dims(ordering)); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   	z.makeZero(); | 
					
						
							| 
									
										
										
										
											2010-03-10 08:20:12 +08:00
										 |  |  |   	return z; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  |   /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-08-24 03:44:17 +08:00
										 |  |  |   template<class J> | 
					
						
							| 
									
										
										
										
											2010-10-09 11:53:27 +08:00
										 |  |  |   void LieValues<J>::insert(const J& name, const typename J::Value& val) { | 
					
						
							| 
									
										
										
										
											2010-01-11 01:26:44 +08:00
										 |  |  |     values_.insert(make_pair(name, val)); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  |   /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-08-24 03:44:17 +08:00
										 |  |  |   template<class J> | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  |   void LieValues<J>::insert(const LieValues<J>& cfg) { | 
					
						
							| 
									
										
										
										
											2010-10-09 01:37:59 +08:00
										 |  |  | 	  BOOST_FOREACH(const KeyValuePair& v, cfg.values_) | 
					
						
							| 
									
										
										
										
											2010-02-25 10:50:01 +08:00
										 |  |  | 		 insert(v.first, v.second); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  |   /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-08-24 03:44:17 +08:00
										 |  |  |   template<class J> | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  |   void LieValues<J>::update(const LieValues<J>& cfg) { | 
					
						
							| 
									
										
										
										
											2010-10-09 01:37:59 +08:00
										 |  |  | 	  BOOST_FOREACH(const KeyValuePair& v, values_) { | 
					
						
							| 
									
										
										
										
											2010-10-09 11:53:27 +08:00
										 |  |  | 	  	boost::optional<typename J::Value> t = cfg.exists_(v.first); | 
					
						
							| 
									
										
										
										
											2010-04-29 10:16:18 +08:00
										 |  |  | 	  	if (t) values_[v.first] = *t; | 
					
						
							| 
									
										
										
										
											2010-04-09 14:55:54 +08:00
										 |  |  | 	  } | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  |   /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-08-24 03:44:17 +08:00
										 |  |  |   template<class J> | 
					
						
							| 
									
										
										
										
											2010-10-09 11:53:27 +08:00
										 |  |  |   void LieValues<J>::update(const J& j, const typename J::Value& val) { | 
					
						
							| 
									
										
										
										
											2010-05-04 02:07:27 +08:00
										 |  |  | 	  	values_[j] = val; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  |   /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-08-24 03:44:17 +08:00
										 |  |  |   template<class J> | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  |   std::list<J> LieValues<J>::keys() const { | 
					
						
							| 
									
										
										
										
											2010-03-04 21:21:48 +08:00
										 |  |  | 	  std::list<J> ret; | 
					
						
							| 
									
										
										
										
											2010-10-09 01:37:59 +08:00
										 |  |  | 	  BOOST_FOREACH(const KeyValuePair& v, values_) | 
					
						
							| 
									
										
										
										
											2010-03-04 21:21:48 +08:00
										 |  |  | 		  ret.push_back(v.first); | 
					
						
							|  |  |  | 	  return ret; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  |   /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-08-24 03:44:17 +08:00
										 |  |  |   template<class J> | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  |   void LieValues<J>::erase(const J& j) { | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  |     size_t dim; // unused
 | 
					
						
							|  |  |  |     erase(j, dim); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  |   /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-08-24 03:44:17 +08:00
										 |  |  |   template<class J> | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  |   void LieValues<J>::erase(const J& j, size_t& dim) { | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  |     iterator it = values_.find(j); | 
					
						
							|  |  |  |     if (it == values_.end()) throw std::invalid_argument("invalid j: " + (string)j); | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  |     dim = it->second.dim(); | 
					
						
							| 
									
										
											  
											
												Large gtsam refactoring
To support faster development *and* better performance Richard and I pushed through a large refactoring of NonlinearFactors.
The following are the biggest changes:
1) NonLinearFactor1 and NonLinearFactor2 are now templated on Config, Key type, and X type, where X is the argument to the measurement function.
2) The measurement itself is no longer kept in the nonlinear factor. Instead, a derived class (see testVSLAMFactor, testNonlinearEquality, testPose3Factor etc...) has to implement a function to compute the errors, "evaluateErrors". Instead of (h(x)-z), it needs to return (z-h(x)), so Ax-b is an approximation of the error. IMPORTANT: evaluateErrors needs - if asked - *combine* the calculation of the function value h(x) and the derivatives dh(x)/dx. This was a major performance issue. To do this, boost::optional<Matrix&> arguments are provided, and tin EvaluateErrors you just  says something like
	if (H) *H = Matrix_(3,6,....);
3) We are no longer using int or strings for nonlinear factors. Instead, the preferred key type is now Symbol, defined in Key.h. This is both fast and cool: you can construct it from an int, and cast it to a strong. It also does type checking: a Symbol<Pose3,'x'> will not match a Symbol<Pose2,'x'>
4) minor: take a look at LieConfig.h: it help you avoid writing a lot of code bu automatically creating configs for a certain type. See e.g. Pose3Config.h. A "double" LieConfig is on the way - Thanks Richard and Manohar !
											
										 
											2010-01-14 06:25:03 +08:00
										 |  |  |     values_.erase(it); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  |   /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-01-11 01:48:55 +08:00
										 |  |  |   // todo: insert for every element is inefficient
 | 
					
						
							| 
									
										
										
										
											2010-08-24 03:44:17 +08:00
										 |  |  |   template<class J> | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   LieValues<J> LieValues<J>::expmap(const VectorValues& delta, const Ordering& ordering) const { | 
					
						
							|  |  |  | 		LieValues<J> newValues; | 
					
						
							| 
									
										
										
										
											2010-10-09 11:53:27 +08:00
										 |  |  | 		typedef pair<J,typename J::Value> KeyValue; | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 		BOOST_FOREACH(const KeyValue& value, this->values_) { | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | 			const J& j = value.first; | 
					
						
							| 
									
										
										
										
											2010-10-09 11:53:27 +08:00
										 |  |  | 			const typename J::Value& pj = value.second; | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 			const Vector& dj = delta[ordering[j]]; | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 			newValues.insert(j, pj.expmap(dj)); | 
					
						
							| 
									
										
										
										
											2010-01-11 00:16:03 +08:00
										 |  |  | 		} | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 		return newValues; | 
					
						
							| 
									
										
										
										
											2010-01-11 00:16:03 +08:00
										 |  |  | 	} | 
					
						
							| 
									
										
										
										
											2010-01-10 14:35:16 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  |   /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-08-24 03:44:17 +08:00
										 |  |  |   template<class J> | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  |   std::vector<size_t> LieValues<J>::dims(const Ordering& ordering) const { | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |     _ValuesDimensionCollector dimCollector(ordering); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |     this->apply(dimCollector); | 
					
						
							|  |  |  |     return dimCollector.dimensions; | 
					
						
							| 
									
										
										
										
											2010-01-11 01:26:44 +08:00
										 |  |  |   } | 
					
						
							| 
									
										
										
										
											2010-01-23 09:53:04 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   /* ************************************************************************* */ | 
					
						
							|  |  |  |   template<class J> | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  |   Ordering::shared_ptr LieValues<J>::orderingArbitrary(Index firstVar) const { | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |     // Generate an initial key ordering in iterator order
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |     _ValuesKeyOrderer keyOrderer(firstVar); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |     this->apply(keyOrderer); | 
					
						
							|  |  |  |     return keyOrderer.ordering; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | //  /* ************************************************************************* */
 | 
					
						
							|  |  |  | //  // todo: insert for every element is inefficient
 | 
					
						
							|  |  |  | //  template<class J>
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  | //  LieValues<J> LieValues<J>::expmap(const Vector& delta) const {
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //    if(delta.size() != dim()) {
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  | //    	cout << "LieValues::dim (" << dim() << ") <> delta.size (" << delta.size() << ")" << endl;
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //      throw invalid_argument("Delta vector length does not match config dimensionality.");
 | 
					
						
							|  |  |  | //    }
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | //    LieValues<J> newValues;
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //    int delta_offset = 0;
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:53:27 +08:00
										 |  |  | //		typedef pair<J,typename J::Value> KeyValue;
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //		BOOST_FOREACH(const KeyValue& value, this->values_) {
 | 
					
						
							|  |  |  | //			const J& j = value.first;
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:53:27 +08:00
										 |  |  | //			const typename J::Value& pj = value.second;
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //      int cur_dim = pj.dim();
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | //      newValues.insert(j,pj.expmap(sub(delta, delta_offset, delta_offset+cur_dim)));
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //      delta_offset += cur_dim;
 | 
					
						
							|  |  |  | //    }
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | //    return newValues;
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | //  }
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  |   /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-01-23 09:53:04 +08:00
										 |  |  |   // todo: insert for every element is inefficient
 | 
					
						
							|  |  |  |   // todo: currently only logmaps elements in both configs
 | 
					
						
							| 
									
										
										
										
											2010-08-24 03:44:17 +08:00
										 |  |  |   template<class J> | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   inline VectorValues LieValues<J>::logmap(const LieValues<J>& cp, const Ordering& ordering) const { | 
					
						
							|  |  |  |   	VectorValues delta(this->dims(ordering)); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   	logmap(cp, ordering, delta); | 
					
						
							| 
									
										
										
										
											2010-01-23 09:53:04 +08:00
										 |  |  |   	return delta; | 
					
						
							|  |  |  |   } | 
					
						
							| 
									
										
										
										
											2010-03-10 08:20:12 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   /* ************************************************************************* */ | 
					
						
							|  |  |  |   template<class J> | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   void LieValues<J>::logmap(const LieValues<J>& cp, const Ordering& ordering, VectorValues& delta) const { | 
					
						
							| 
									
										
										
										
											2010-10-09 11:53:27 +08:00
										 |  |  |     typedef pair<J,typename J::Value> KeyValue; | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |     BOOST_FOREACH(const KeyValue& value, cp) { | 
					
						
							|  |  |  |       assert(this->exists(value.first)); | 
					
						
							|  |  |  |       delta[ordering[value.first]] = this->at(value.first).logmap(value.second); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-10 14:35:16 +08:00
										 |  |  | } | 
					
						
							| 
									
										
											  
											
												Large gtsam refactoring
To support faster development *and* better performance Richard and I pushed through a large refactoring of NonlinearFactors.
The following are the biggest changes:
1) NonLinearFactor1 and NonLinearFactor2 are now templated on Config, Key type, and X type, where X is the argument to the measurement function.
2) The measurement itself is no longer kept in the nonlinear factor. Instead, a derived class (see testVSLAMFactor, testNonlinearEquality, testPose3Factor etc...) has to implement a function to compute the errors, "evaluateErrors". Instead of (h(x)-z), it needs to return (z-h(x)), so Ax-b is an approximation of the error. IMPORTANT: evaluateErrors needs - if asked - *combine* the calculation of the function value h(x) and the derivatives dh(x)/dx. This was a major performance issue. To do this, boost::optional<Matrix&> arguments are provided, and tin EvaluateErrors you just  says something like
	if (H) *H = Matrix_(3,6,....);
3) We are no longer using int or strings for nonlinear factors. Instead, the preferred key type is now Symbol, defined in Key.h. This is both fast and cool: you can construct it from an int, and cast it to a strong. It also does type checking: a Symbol<Pose3,'x'> will not match a Symbol<Pose2,'x'>
4) minor: take a look at LieConfig.h: it help you avoid writing a lot of code bu automatically creating configs for a certain type. See e.g. Pose3Config.h. A "double" LieConfig is on the way - Thanks Richard and Manohar !
											
										 
											2010-01-14 06:25:03 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 
 |