| 
									
										
											  
											
												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
										 |  |  | /*
 | 
					
						
							|  |  |  |  *  graph.h | 
					
						
							|  |  |  |  *  @brief Graph algorithm using boost library | 
					
						
							|  |  |  |  *  @author: Kai Ni | 
					
						
							|  |  |  |  *  Created on: Jan 11, 2010 | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #pragma once
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <map>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <boost/graph/graph_traits.hpp>
 | 
					
						
							|  |  |  | #include <boost/graph/adjacency_list.hpp>
 | 
					
						
							|  |  |  | #include <boost/shared_ptr.hpp>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | namespace gtsam { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// type definitions :
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	/**
 | 
					
						
							|  |  |  | 	 * SDGraph is undirected graph with variable keys and double edge weights | 
					
						
							|  |  |  | 	 */ | 
					
						
							|  |  |  | 	template<class Key> | 
					
						
							|  |  |  | 	class SDGraph: public boost::adjacency_list<boost::vecS, boost::vecS, boost::undirectedS, | 
					
						
							|  |  |  | 	boost::property<boost::vertex_name_t, Key>, boost::property< | 
					
						
							|  |  |  | 	boost::edge_weight_t, double> > { | 
					
						
							| 
									
										
										
										
											2010-01-14 11:21:07 +08:00
										 |  |  | 	public: | 
					
						
							|  |  |  | 		typedef typename boost::graph_traits<SDGraph<Key> >::vertex_descriptor Vertex; | 
					
						
							| 
									
										
											  
											
												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 09:25:40 +08:00
										 |  |  | 	template<class Key> | 
					
						
							|  |  |  | 	class SGraph : public boost::adjacency_list<boost::vecS, boost::vecS, boost::directedS, | 
					
						
							| 
									
										
										
										
											2010-01-14 11:21:07 +08:00
										 |  |  | 			boost::property<boost::vertex_name_t, Key> > { | 
					
						
							| 
									
										
										
										
											2010-01-14 10:07:14 +08:00
										 |  |  | 	public: | 
					
						
							| 
									
										
										
										
											2010-01-14 11:21:07 +08:00
										 |  |  | 		typedef typename boost::graph_traits<SGraph<Key> >::vertex_descriptor Vertex; | 
					
						
							| 
									
										
										
										
											2010-01-14 09:25:40 +08:00
										 |  |  | 	}; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	//typedef boost::graph_traits<SGraph>::vertex_descriptor SVertex;
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
											  
											
												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
										 |  |  | 	/**
 | 
					
						
							|  |  |  | 	 * Map from variable key to parent key | 
					
						
							|  |  |  | 	 */ | 
					
						
							| 
									
										
										
										
											2010-01-15 00:05:04 +08:00
										 |  |  | 	template<class Key> | 
					
						
							|  |  |  | 	class PredecessorMap: public std::map<Key, Key> { | 
					
						
							|  |  |  | 	public: | 
					
						
							| 
									
										
										
										
											2010-01-18 03:34:57 +08:00
										 |  |  | 		/** convenience insert so we can pass ints for TypedSymbol keys */ | 
					
						
							| 
									
										
										
										
											2010-01-15 00:05:04 +08:00
										 |  |  | 		inline void insert(const Key& key, const Key& parent) { | 
					
						
							|  |  |  | 			std::map<Key, Key>::insert(std::make_pair(key, parent)); | 
					
						
							|  |  |  | 		} | 
					
						
							|  |  |  | 	}; | 
					
						
							| 
									
										
											  
											
												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-19 03:11:22 +08:00
										 |  |  | 	/**
 | 
					
						
							|  |  |  | 	 * Generate a list of keys from a spanning tree represented by its predecessor map | 
					
						
							|  |  |  | 	 */ | 
					
						
							|  |  |  | 	template<class Key> | 
					
						
							|  |  |  | 	std::list<Key> predecessorMap2Keys(const PredecessorMap<Key>& p_map); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
											  
											
												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
										 |  |  | 	/**
 | 
					
						
							|  |  |  | 	 * Convert the factor graph to an SDGraph | 
					
						
							|  |  |  | 	 * G = Graph type | 
					
						
							|  |  |  | 	 * F = Factor type | 
					
						
							|  |  |  | 	 * Key = Key type | 
					
						
							|  |  |  | 	 */ | 
					
						
							|  |  |  | 	template<class G, class F, class Key> SDGraph<Key> toBoostGraph(const G& graph); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	/**
 | 
					
						
							|  |  |  | 	 * Build takes a predecessor map, and builds a directed graph corresponding to the tree. | 
					
						
							|  |  |  | 	 * G = Graph type | 
					
						
							|  |  |  | 	 * V = Vertex type | 
					
						
							|  |  |  | 	 */ | 
					
						
							| 
									
										
										
										
											2010-01-14 11:21:07 +08:00
										 |  |  | 	template<class G, class V, class Key> | 
					
						
							|  |  |  | 	boost::tuple<G, V, std::map<Key,V> >	predecessorMap2Graph(const PredecessorMap<Key>& p_map); | 
					
						
							| 
									
										
											  
											
												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
										 |  |  | 
 | 
					
						
							|  |  |  | 	/**
 | 
					
						
							|  |  |  | 	 * Compose the poses by following the chain specified by the spanning tree | 
					
						
							|  |  |  | 	 */ | 
					
						
							|  |  |  | 	template<class G, class Factor, class Pose, class Config> | 
					
						
							|  |  |  | 	boost::shared_ptr<Config> | 
					
						
							|  |  |  | 		composePoses(const G& graph, const PredecessorMap<typename Config::Key>& tree, const Pose& rootPose); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | } // namespace gtsam
 |