| 
									
										
										
										
											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-10-09 01:38:01 +08:00
										 |  |  | /**
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  |  * @file LieValues.h | 
					
						
							| 
									
										
										
										
											2010-10-09 01:38:01 +08:00
										 |  |  |  * @Author: Richard Roberts | 
					
						
							| 
									
										
										
										
											2010-01-10 14:35:16 +08:00
										 |  |  |  * | 
					
						
							| 
									
										
										
										
											2010-10-09 01:38:01 +08:00
										 |  |  |  * @brief A templated config for Lie-group elements | 
					
						
							| 
									
										
										
										
											2010-07-02 03:57:20 +08:00
										 |  |  |  * | 
					
						
							|  |  |  |  *  Detailed story: | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |  *  A values structure is a map from keys to values. It is used to specify the value of a bunch | 
					
						
							|  |  |  |  *  of variables in a factor graph. A LieValues is a values structure which can hold variables that | 
					
						
							| 
									
										
										
										
											2010-07-02 03:57:20 +08:00
										 |  |  |  *  are elements of Lie groups, not just vectors. It then, as a whole, implements a aggregate type | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |  *  which is also a Lie group, and hence supports operations dim, expmap, and logmap. | 
					
						
							| 
									
										
										
										
											2010-01-10 14:35:16 +08:00
										 |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #pragma once
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <map>
 | 
					
						
							| 
									
										
										
										
											2010-03-04 21:21:48 +08:00
										 |  |  | #include <set>
 | 
					
						
							| 
									
										
										
										
											2010-01-10 14:35:16 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | #include <boost/pool/pool_alloc.hpp>
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-20 01:23:19 +08:00
										 |  |  | #include <gtsam/base/Vector.h>
 | 
					
						
							|  |  |  | #include <gtsam/base/Testable.h>
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | #include <gtsam/nonlinear/Ordering.h>
 | 
					
						
							| 
									
										
										
										
											2010-01-10 14:35:16 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-11 01:26:44 +08:00
										 |  |  | namespace boost { template<class T> class optional; } | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | namespace gtsam { class VectorValues; class Ordering; } | 
					
						
							| 
									
										
										
										
											2010-01-10 14:35:16 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | namespace gtsam { | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
											  
											
												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
										 |  |  | 	/**
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	 * Lie type values structure | 
					
						
							| 
									
										
										
										
											2010-07-02 03:57:20 +08:00
										 |  |  | 	 * Takes two template types | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	 *  J: a key type to look up values in the values structure (need to be sortable) | 
					
						
							| 
									
										
										
										
											2010-08-24 03:44:17 +08:00
										 |  |  | 	 * | 
					
						
							|  |  |  | 	 * Key concept: | 
					
						
							|  |  |  | 	 *  The key will be assumed to be sortable, and must have a | 
					
						
							| 
									
										
										
										
											2010-10-09 11:53:27 +08:00
										 |  |  | 	 *  typedef called "Value" with the type of the value the key | 
					
						
							| 
									
										
										
										
											2010-08-24 03:44:17 +08:00
										 |  |  | 	 *  labels (example: Pose2, Point2, etc) | 
					
						
							| 
									
										
											  
											
												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
										 |  |  | 	 */ | 
					
						
							| 
									
										
										
										
											2010-08-24 03:44:17 +08:00
										 |  |  |   template<class J> | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  |   class LieValues : public Testable<LieValues<J> > { | 
					
						
							| 
									
										
											  
											
												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
										 |  |  | 
 | 
					
						
							|  |  |  |   public: | 
					
						
							| 
									
										
										
										
											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
										 |  |  |     /**
 | 
					
						
							|  |  |  |      * Typedefs | 
					
						
							|  |  |  |      */ | 
					
						
							| 
									
										
										
										
											2010-07-02 03:57:20 +08:00
										 |  |  |   	typedef J Key; | 
					
						
							| 
									
										
										
										
											2010-10-09 11:53:27 +08:00
										 |  |  |   	typedef typename J::Value Value; | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |     typedef std::map<J,Value, std::less<J>, boost::fast_pool_allocator<std::pair<const J,Value> > > KeyValueMap; | 
					
						
							| 
									
										
										
										
											2010-10-09 01:37:59 +08:00
										 |  |  |     typedef typename KeyValueMap::value_type KeyValuePair; | 
					
						
							|  |  |  |     typedef typename KeyValueMap::iterator iterator; | 
					
						
							|  |  |  |     typedef typename KeyValueMap::const_iterator const_iterator; | 
					
						
							| 
									
										
										
										
											2010-01-10 14:35:16 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   private: | 
					
						
							| 
									
										
											  
											
												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
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 01:37:59 +08:00
										 |  |  |     KeyValueMap values_; | 
					
						
							| 
									
										
										
										
											2010-01-10 14:35:16 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   public: | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  |     LieValues() {} | 
					
						
							|  |  |  |     LieValues(const LieValues& config) : | 
					
						
							| 
									
										
										
										
											2010-03-10 08:20:12 +08:00
										 |  |  |       values_(config.values_) {} | 
					
						
							| 
									
										
										
										
											2010-10-21 00:37:47 +08:00
										 |  |  |     template<class J_ALT> | 
					
						
							|  |  |  |     LieValues(const LieValues<J_ALT>& other) {} // do nothing when initializing with wrong type
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  |     virtual ~LieValues() {} | 
					
						
							| 
									
										
										
										
											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
										 |  |  |     /** print */ | 
					
						
							| 
									
										
										
										
											2010-02-06 13:14:52 +08:00
										 |  |  |     void print(const std::string &s="") const; | 
					
						
							| 
									
										
											  
											
												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
										 |  |  | 
 | 
					
						
							|  |  |  |     /** Test whether configs are identical in keys and values */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  |     bool equals(const LieValues& expected, double tol=1e-9) const; | 
					
						
							| 
									
										
											  
											
												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
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  |     /** Retrieve a variable by j, throws std::invalid_argument if not found */ | 
					
						
							| 
									
										
										
										
											2010-08-24 03:44:17 +08:00
										 |  |  |     const Value& at(const J& j) const; | 
					
						
							| 
									
										
										
										
											2010-01-10 14:35:16 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-11 01:01:48 +08:00
										 |  |  |     /** operator[] syntax for get */ | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  |     const Value& operator[](const J& j) const { return at(j); } | 
					
						
							| 
									
										
											  
											
												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
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  |     /** Check if a variable exists */ | 
					
						
							|  |  |  |     bool exists(const J& i) const { return values_.find(i)!=values_.end(); } | 
					
						
							| 
									
										
											  
											
												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
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  |     /** Check if a variable exists and return it if so */ | 
					
						
							|  |  |  |     boost::optional<Value> exists_(const J& i) const { | 
					
						
							|  |  |  |     	const_iterator it = values_.find(i); | 
					
						
							|  |  |  |     	if (it==values_.end()) return boost::none; else	return it->second; | 
					
						
							|  |  |  |     } | 
					
						
							| 
									
										
										
										
											2010-04-09 14:55:54 +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
										 |  |  |     /** The number of variables in this config */ | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  |     size_t size() const { return values_.size(); } | 
					
						
							| 
									
										
											  
											
												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
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-03-10 06:26:24 +08:00
										 |  |  |     /** whether the config is empty */ | 
					
						
							|  |  |  |     bool empty() const { return values_.empty(); } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-03-10 08:20:12 +08:00
										 |  |  |     /** The dimensionality of the tangent space */ | 
					
						
							|  |  |  |     size_t dim() const; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |     /** Get a zero VectorValues of the correct structure */ | 
					
						
							|  |  |  |     VectorValues zero(const Ordering& ordering) const; | 
					
						
							| 
									
										
										
										
											2010-01-16 09:16:59 +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
										 |  |  |     const_iterator begin() const { return values_.begin(); } | 
					
						
							|  |  |  |     const_iterator end() const { return values_.end(); } | 
					
						
							|  |  |  |     iterator begin() { return values_.begin(); } | 
					
						
							|  |  |  |     iterator end() { return values_.end(); } | 
					
						
							| 
									
										
										
										
											2010-01-11 01:01:48 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  |     // Lie operations
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** Add a delta config to current config and returns a new config */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |     LieValues expmap(const VectorValues& delta, const Ordering& ordering) const; | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |     /** Get a delta config about a linearization point c0 (*this) */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |     VectorValues logmap(const LieValues& cp, const Ordering& ordering) const; | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     /** Get a delta config about a linearization point c0 (*this) */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |     void logmap(const LieValues& cp, const Ordering& ordering, VectorValues& delta) const; | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +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
										 |  |  |     // imperative methods:
 | 
					
						
							| 
									
										
										
										
											2010-01-10 14:35:16 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-07-20 03:55:24 +08:00
										 |  |  |     /** Add a variable with the given j - does not replace existing values */ | 
					
						
							| 
									
										
										
										
											2010-08-24 03:44:17 +08:00
										 |  |  |     void insert(const J& j, const Value& val); | 
					
						
							| 
									
										
											  
											
												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
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-07-20 03:55:24 +08:00
										 |  |  |     /** Add a set of variables - does note replace existing values */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  |     void insert(const LieValues& cfg); | 
					
						
							| 
									
										
										
										
											2010-02-25 10:50:01 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-04-09 14:55:54 +08:00
										 |  |  |     /** update the current available values without adding new ones */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  |     void update(const LieValues& cfg); | 
					
						
							| 
									
										
										
										
											2010-04-09 14:55:54 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-05-04 02:07:27 +08:00
										 |  |  |     /** single element change of existing element */ | 
					
						
							| 
									
										
										
										
											2010-08-24 03:44:17 +08:00
										 |  |  |     void update(const J& j, const Value& val); | 
					
						
							| 
									
										
										
										
											2010-05-04 02:07:27 +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
										 |  |  |     /** Remove a variable from the config */ | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  |     void erase(const J& j); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** Remove a variable from the config while returning the dimensionality of
 | 
					
						
							|  |  |  |      * the removed element (normally not needed by user code). | 
					
						
							|  |  |  |      */ | 
					
						
							|  |  |  |     void erase(const J& j, size_t& dim); | 
					
						
							| 
									
										
										
										
											2010-01-10 14:35:16 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-03-04 21:21:48 +08:00
										 |  |  |     /**
 | 
					
						
							|  |  |  |      * Returns a set of keys in the config | 
					
						
							|  |  |  |      * Note: by construction, the list is ordered | 
					
						
							|  |  |  |      */ | 
					
						
							|  |  |  |     std::list<J> keys() const; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-10 14:35:16 +08:00
										 |  |  |     /** Replace all keys and variables */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  |     LieValues& operator=(const LieValues& rhs) { | 
					
						
							| 
									
										
										
										
											2010-01-10 14:35:16 +08:00
										 |  |  |       values_ = rhs.values_; | 
					
						
							|  |  |  |       return (*this); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** Remove all variables from the config */ | 
					
						
							|  |  |  |     void clear() { | 
					
						
							|  |  |  |       values_.clear(); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |     /**
 | 
					
						
							|  |  |  |      * Apply a class with an application operator() to a const_iterator over | 
					
						
							|  |  |  |      * every <key,value> pair.  The operator must be able to handle such an | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |      * iterator for every type in the Values, (i.e. through templating). | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |      */ | 
					
						
							|  |  |  |     template<typename A> | 
					
						
							|  |  |  |     void apply(A& operation) { | 
					
						
							|  |  |  |       for(iterator it = begin(); it != end(); ++it) | 
					
						
							|  |  |  |         operation(it); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |     template<typename A> | 
					
						
							|  |  |  |     void apply(A& operation) const { | 
					
						
							|  |  |  |       for(const_iterator it = begin(); it != end(); ++it) | 
					
						
							|  |  |  |         operation(it); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** Create an array of variable dimensions using the given ordering */ | 
					
						
							|  |  |  |     std::vector<size_t> dims(const Ordering& ordering) const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /**
 | 
					
						
							|  |  |  |      * Generate a default ordering, simply in key sort order.  To instead | 
					
						
							|  |  |  |      * create a fill-reducing ordering, use | 
					
						
							|  |  |  |      * NonlinearFactorGraph::orderingCOLAMD().  Alternatively, you may permute | 
					
						
							|  |  |  |      * this ordering yourself (as orderingCOLAMD() does internally). | 
					
						
							|  |  |  |      */ | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  |     Ordering::shared_ptr orderingArbitrary(Index firstVar = 0) const; | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-04-08 01:22:10 +08:00
										 |  |  |   private: | 
					
						
							|  |  |  |   	/** Serialization function */ | 
					
						
							|  |  |  |   	friend class boost::serialization::access; | 
					
						
							| 
									
										
										
										
											2010-10-21 00:37:47 +08:00
										 |  |  |   	template<class ARCHIVE> | 
					
						
							|  |  |  |   	void serialize(ARCHIVE & ar, const unsigned int version) { | 
					
						
							| 
									
										
										
										
											2010-04-08 01:22:10 +08:00
										 |  |  |   		ar & BOOST_SERIALIZATION_NVP(values_); | 
					
						
							|  |  |  |   	} | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-10 14:35:16 +08:00
										 |  |  |   }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   struct _ValuesDimensionCollector { | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |     const Ordering& ordering; | 
					
						
							|  |  |  |     std::vector<size_t> dimensions; | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |     _ValuesDimensionCollector(const Ordering& _ordering) : ordering(_ordering), dimensions(_ordering.nVars()) {} | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |     template<typename I> void operator()(const I& key_value) { | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  |       Index var = ordering[key_value->first]; | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |       assert(var < dimensions.size()); | 
					
						
							|  |  |  |       dimensions[var] = key_value->second.dim(); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |   }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   struct _ValuesKeyOrderer { | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  |     Index var; | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |     Ordering::shared_ptr ordering; | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  |     _ValuesKeyOrderer(Index firstVar) : var(firstVar), ordering(new Ordering) {} | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |     template<typename I> void operator()(const I& key_value) { | 
					
						
							|  |  |  |       ordering->insert(key_value->first, var); | 
					
						
							|  |  |  |       ++ var; | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |   }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-10 14:35:16 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 |