| 
									
										
										
										
											2010-01-10 14:35:16 +08:00
										 |  |  | /*
 | 
					
						
							|  |  |  |  * LieConfig.h | 
					
						
							|  |  |  |  * | 
					
						
							|  |  |  |  *  Created on: Jan 5, 2010 | 
					
						
							|  |  |  |  *      Author: Richard Roberts | 
					
						
							|  |  |  |  * | 
					
						
							|  |  |  |  *  A templated config for Lie-group elements | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #pragma once
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <map>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include "Vector.h"
 | 
					
						
							| 
									
										
										
										
											2010-01-11 01:26:44 +08:00
										 |  |  | #include "Testable.h"
 | 
					
						
							| 
									
										
										
										
											2010-02-17 11:29:12 +08:00
										 |  |  | #include "VectorConfig.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-01-16 09:16:59 +08:00
										 |  |  | namespace gtsam { class VectorConfig; } | 
					
						
							| 
									
										
										
										
											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
										 |  |  | 	/**
 | 
					
						
							|  |  |  | 	 * Lie type configuration | 
					
						
							|  |  |  | 	 */ | 
					
						
							|  |  |  |   template<class J, class T> | 
					
						
							|  |  |  |   class LieConfig : public Testable<LieConfig<J,T> > { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   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-01-14 10:58:29 +08:00
										 |  |  |     typedef J Key; | 
					
						
							|  |  |  |     typedef T Value; | 
					
						
							|  |  |  |     typedef std::map<J, T> 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
										 |  |  |     typedef typename Values::iterator iterator; | 
					
						
							|  |  |  |     typedef typename Values::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
										 |  |  | 
 | 
					
						
							|  |  |  |     Values values_; | 
					
						
							| 
									
										
										
										
											2010-01-10 14:35:16 +08:00
										 |  |  |     size_t dim_; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   public: | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     LieConfig() : dim_(0) {} | 
					
						
							|  |  |  |     LieConfig(const LieConfig& config) : | 
					
						
							| 
									
										
										
										
											2010-01-16 09:16:59 +08:00
										 |  |  |       values_(config.values_), dim_(config.dim_) {} | 
					
						
							| 
									
										
										
										
											2010-01-10 14:35:16 +08:00
										 |  |  |     virtual ~LieConfig() {} | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
											  
											
												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 */ | 
					
						
							|  |  |  |     bool equals(const LieConfig& expected, double tol=1e-9) const; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  |     /** Retrieve a variable by j, throws std::invalid_argument if not found */ | 
					
						
							|  |  |  |     const T& 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-01-14 10:58:29 +08:00
										 |  |  | 		const T& 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
										 |  |  | 
 | 
					
						
							|  |  |  | 	  /** Check if a variable exists */ | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | 	  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
										 |  |  | 
 | 
					
						
							|  |  |  |     /** 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-01-16 09:16:59 +08:00
										 |  |  |     /**
 | 
					
						
							|  |  |  |      * The dimensionality of the tangent space | 
					
						
							|  |  |  |      */ | 
					
						
							|  |  |  |     size_t dim() const { return 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
										 |  |  |     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
										 |  |  | 
 | 
					
						
							| 
									
										
											  
											
												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-01-14 10:58:29 +08:00
										 |  |  |     /** Add a variable with the given j */ | 
					
						
							|  |  |  |     void insert(const J& j, const T& 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-02-25 10:50:01 +08:00
										 |  |  |     /** Add a set of variables */ | 
					
						
							|  |  |  |     void insert(const LieConfig& cfg); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
											  
											
												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
										 |  |  | 
 | 
					
						
							|  |  |  |     /** Replace all keys and variables */ | 
					
						
							|  |  |  |     LieConfig& operator=(const LieConfig& rhs) { | 
					
						
							|  |  |  |       values_ = rhs.values_; | 
					
						
							| 
									
										
										
										
											2010-01-16 09:16:59 +08:00
										 |  |  |       dim_ = rhs.dim_; | 
					
						
							| 
									
										
										
										
											2010-01-10 14:35:16 +08:00
										 |  |  |       return (*this); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** Remove all variables from the config */ | 
					
						
							|  |  |  |     void clear() { | 
					
						
							|  |  |  |       values_.clear(); | 
					
						
							|  |  |  |       dim_ = 0; | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** Dimensionality of the tangent space */ | 
					
						
							| 
									
										
											  
											
												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
										 |  |  |   template<class J, class T> | 
					
						
							| 
									
										
										
										
											2010-01-16 09:16:59 +08:00
										 |  |  |   inline size_t dim(const LieConfig<J,T>& c) { return c.dim(); } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** Add a delta config */ | 
					
						
							|  |  |  |   template<class J, class T> | 
					
						
							|  |  |  |   LieConfig<J,T> expmap(const LieConfig<J,T>& c, const VectorConfig& delta); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** Add a delta vector, uses iterator order */ | 
					
						
							|  |  |  |   template<class J, class T> | 
					
						
							|  |  |  |   LieConfig<J,T> expmap(const LieConfig<J,T>& c, const Vector& delta); | 
					
						
							| 
									
										
										
										
											2010-01-23 09:53:04 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /** Get a delta config about a linearization point c0 */ | 
					
						
							|  |  |  |   template<class J, class T> | 
					
						
							|  |  |  |   VectorConfig logmap(const LieConfig<J,T>& c0, const LieConfig<J,T>& cp); | 
					
						
							| 
									
										
										
										
											2010-01-10 14:35:16 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 |