| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | /*
 | 
					
						
							|  |  |  |  * TupleConfig.h | 
					
						
							|  |  |  |  * | 
					
						
							|  |  |  |  *  Created on: Jan 13, 2010 | 
					
						
							|  |  |  |  *      Author: Richard Roberts and Manohar Paluri | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-16 09:16:59 +08:00
										 |  |  | #include "LieConfig.h"
 | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | #pragma once
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | namespace gtsam { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /**
 | 
					
						
							|  |  |  |    * PairConfig:  a config that holds two data types. | 
					
						
							|  |  |  |    */ | 
					
						
							|  |  |  |   template<class J1, class X1, class J2, class X2> | 
					
						
							|  |  |  |   class PairConfig : public Testable<PairConfig<J1, X1, J2, X2> > { | 
					
						
							| 
									
										
										
										
											2010-01-16 09:16:59 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  |   public: | 
					
						
							| 
									
										
										
										
											2010-01-16 09:16:59 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   	// publicly available types
 | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  |     typedef LieConfig<J1, X1> Config1; | 
					
						
							|  |  |  |     typedef LieConfig<J2, X2> Config2; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-16 09:16:59 +08:00
										 |  |  |     // Two configs in the pair as in std:pair
 | 
					
						
							|  |  |  |     LieConfig<J1, X1> first; | 
					
						
							|  |  |  |     LieConfig<J2, X2> second; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  |   private: | 
					
						
							| 
									
										
										
										
											2010-01-16 09:16:59 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  |     size_t size_; | 
					
						
							|  |  |  |     size_t dim_; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     PairConfig(const LieConfig<J1,X1>& config1, const LieConfig<J2,X2>& config2) : | 
					
						
							| 
									
										
										
										
											2010-01-16 09:16:59 +08:00
										 |  |  |       first(config1), second(config2), | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  |       size_(config1.size()+config2.size()), dim_(gtsam::dim(config1)+gtsam::dim(config2)) {} | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   public: | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /**
 | 
					
						
							|  |  |  |      * Default constructor creates an empty config. | 
					
						
							|  |  |  |      */ | 
					
						
							|  |  |  |     PairConfig(): size_(0), dim_(0) {} | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /**
 | 
					
						
							|  |  |  |      * Copy constructor | 
					
						
							|  |  |  |      */ | 
					
						
							|  |  |  |     PairConfig(const PairConfig<J1, X1, J2, X2>& c): | 
					
						
							| 
									
										
										
										
											2010-01-16 09:16:59 +08:00
										 |  |  |       first(c.first), second(c.second), size_(c.size_), dim_(c.dim_) {} | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     /**
 | 
					
						
							|  |  |  |      * Print | 
					
						
							|  |  |  |      */ | 
					
						
							| 
									
										
										
										
											2010-01-16 09:16:59 +08:00
										 |  |  |     void print(const std::string& s = "") const; | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     /**
 | 
					
						
							|  |  |  |      * Test for equality in keys and values | 
					
						
							|  |  |  |      */ | 
					
						
							|  |  |  |     bool equals(const PairConfig<J1, X1, J2, X2>& c, double tol=1e-9) const { | 
					
						
							| 
									
										
										
										
											2010-01-16 09:16:59 +08:00
										 |  |  |       return first.equals(c.first, tol) && second.equals(c.second, tol); } | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     /**
 | 
					
						
							|  |  |  |      * operator[] syntax to get a value by j, throws invalid_argument if | 
					
						
							|  |  |  |      * value with specified j is not present.  Will generate compile-time | 
					
						
							|  |  |  |      * errors if j type does not match that on which the Config is templated. | 
					
						
							|  |  |  |      */ | 
					
						
							| 
									
										
										
										
											2010-01-16 09:16:59 +08:00
										 |  |  |     const X1& operator[](const J1& j) const { return first[j]; } | 
					
						
							|  |  |  |     const X2& operator[](const J2& j) const { return second[j]; } | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     /**
 | 
					
						
							|  |  |  |      * size is the total number of variables in this config. | 
					
						
							|  |  |  |      */ | 
					
						
							|  |  |  |     size_t size() const { return size_; } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /**
 | 
					
						
							|  |  |  |      * dim is the dimensionality of the tangent space | 
					
						
							|  |  |  |      */ | 
					
						
							|  |  |  |     size_t dim() const { return dim_; } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   private: | 
					
						
							|  |  |  |     template<class Config, class Key, class Value> | 
					
						
							|  |  |  |     void insert_helper(Config& config, const Key& j, const Value& value) { | 
					
						
							|  |  |  |       config.insert(j, value); | 
					
						
							|  |  |  |       size_ ++; | 
					
						
							|  |  |  |       dim_ += gtsam::dim(value); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     template<class Config, class Key> | 
					
						
							|  |  |  |     void erase_helper(Config& config, const Key& j) { | 
					
						
							|  |  |  |       size_t dim; | 
					
						
							|  |  |  |       config.erase(j, dim); | 
					
						
							|  |  |  |       dim_ -= dim; | 
					
						
							|  |  |  |       size_ --; | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   public: | 
					
						
							|  |  |  |     /**
 | 
					
						
							|  |  |  |      * expmap each element | 
					
						
							|  |  |  |      */ | 
					
						
							|  |  |  |     PairConfig<J1,X1,J2,X2> expmap(const VectorConfig& delta) { | 
					
						
							| 
									
										
										
										
											2010-01-16 09:16:59 +08:00
										 |  |  |       return PairConfig(gtsam::expmap(first, delta), gtsam::expmap(second, delta)); } | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     /**
 | 
					
						
							|  |  |  |      * Insert a variable with the given j | 
					
						
							|  |  |  |      */ | 
					
						
							| 
									
										
										
										
											2010-01-16 09:16:59 +08:00
										 |  |  |     void insert(const J1& j, const X1& value) { insert_helper(first, j, value); } | 
					
						
							|  |  |  |     void insert(const J2& j, const X2& value) { insert_helper(second, j, value); } | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-19 04:17:31 +08:00
										 |  |  |     void insert(const PairConfig& config); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  |     /**
 | 
					
						
							|  |  |  |      * Remove the variable with the given j.  Throws invalid_argument if the | 
					
						
							|  |  |  |      * j is not present in the config. | 
					
						
							|  |  |  |      */ | 
					
						
							| 
									
										
										
										
											2010-01-16 09:16:59 +08:00
										 |  |  |     void erase(const J1& j) { erase_helper(first, j); } | 
					
						
							|  |  |  |     void erase(const J2& j) { erase_helper(second, j); } | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     /**
 | 
					
						
							|  |  |  |      * Check if a variable exists | 
					
						
							|  |  |  |      */ | 
					
						
							| 
									
										
										
										
											2010-01-16 09:16:59 +08:00
										 |  |  |     bool exists(const J1& j) const { return first.exists(j); } | 
					
						
							|  |  |  |     bool exists(const J2& j) const { return second.exists(j); } | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   template<class J1, class X1, class J2, class X2> | 
					
						
							|  |  |  |   inline PairConfig<J1,X1,J2,X2> expmap(PairConfig<J1,X1,J2,X2> c, const VectorConfig& delta) { return c.expmap(delta); } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | } |