| 
									
										
										
										
											2010-08-23 05:45:53 +08:00
										 |  |  | /**
 | 
					
						
							|  |  |  |  * @file LieVector.h | 
					
						
							|  |  |  |  * @brief A wrapper around vector providing Lie compatibility | 
					
						
							|  |  |  |  * @author Alex Cunningham | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #pragma once
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-25 01:26:56 +08:00
										 |  |  | #include <gtsam/base/Testable.h>
 | 
					
						
							| 
									
										
										
										
											2010-08-23 05:45:53 +08:00
										 |  |  | #include <gtsam/base/Lie.h>
 | 
					
						
							| 
									
										
										
										
											2010-08-25 01:26:56 +08:00
										 |  |  | #include <gtsam/base/Vector.h>
 | 
					
						
							| 
									
										
										
										
											2010-08-23 05:45:53 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | namespace gtsam { | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-25 01:26:56 +08:00
										 |  |  | 	/**
 | 
					
						
							|  |  |  | 	 * LieVector is a wrapper around vector to allow it to be a Lie type | 
					
						
							|  |  |  | 	 */ | 
					
						
							|  |  |  | 	struct LieVector : public Vector, public Lie<LieVector>, Testable<LieVector> { | 
					
						
							| 
									
										
										
										
											2010-08-23 05:45:53 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-25 01:26:56 +08:00
										 |  |  | 		/** default constructor - should be unnecessary */ | 
					
						
							|  |  |  | 		LieVector() {} | 
					
						
							| 
									
										
										
										
											2010-08-23 05:45:53 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-25 01:26:56 +08:00
										 |  |  | 		/** initialize from a normal vector */ | 
					
						
							|  |  |  | 		LieVector(const Vector& v) : Vector(v) {} | 
					
						
							| 
									
										
										
										
											2010-08-23 05:45:53 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 		/** wrap a double */ | 
					
						
							|  |  |  | 		LieVector(double d) : Vector(Vector_(1, d)) {} | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 		/** constructor with size and initial data, row order ! */ | 
					
						
							|  |  |  | 		LieVector(size_t m, const double* const data); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 		/** Specify arguments directly, as in Vector_() - always force these to be doubles */ | 
					
						
							|  |  |  | 		LieVector(size_t m, ...); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-25 01:26:56 +08:00
										 |  |  | 		/** get the underlying vector */ | 
					
						
							|  |  |  | 		inline Vector vector() const { | 
					
						
							|  |  |  | 			return static_cast<Vector>(*this); | 
					
						
							|  |  |  | 		} | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 		/** print @param s optional string naming the object */ | 
					
						
							|  |  |  | 		inline void print(const std::string& name="") const { | 
					
						
							|  |  |  | 			gtsam::print(vector(), name); | 
					
						
							|  |  |  | 		} | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 		/** equality up to tolerance */ | 
					
						
							|  |  |  | 		inline bool equals(const LieVector& expected, double tol=1e-5) const { | 
					
						
							|  |  |  | 			return gtsam::equal(vector(), expected.vector(), tol); | 
					
						
							|  |  |  | 		} | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	    /**
 | 
					
						
							|  |  |  | 	     * Returns dimensionality of the tangent space | 
					
						
							|  |  |  | 	     */ | 
					
						
							|  |  |  | 	    inline size_t dim() const { return this->size(); } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	    /**
 | 
					
						
							|  |  |  | 	     * Returns Exponential map update of T | 
					
						
							|  |  |  | 	     * Default implementation calls global binary function | 
					
						
							|  |  |  | 	     */ | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	    inline LieVector expmap(const Vector& v) const { return LieVector(vector() + v); } | 
					
						
							| 
									
										
										
										
											2010-08-25 01:26:56 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	    /** expmap around identity */ | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	    static inline LieVector Expmap(const Vector& v) { return LieVector(v); } | 
					
						
							| 
									
										
										
										
											2010-08-25 01:26:56 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	    /**
 | 
					
						
							|  |  |  | 	     * Returns Log map | 
					
						
							|  |  |  | 	     * Default Implementation calls global binary function | 
					
						
							|  |  |  | 	     */ | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	    inline Vector logmap(const LieVector& lp) const { | 
					
						
							|  |  |  | //	    	return Logmap(between(lp)); // works
 | 
					
						
							|  |  |  | 	    	return lp.vector() - vector(); | 
					
						
							|  |  |  | 	    } | 
					
						
							| 
									
										
										
										
											2010-08-25 01:26:56 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	    /** Logmap around identity - just returns with default cast back */ | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	    static inline Vector Logmap(const LieVector& p) { return p; } | 
					
						
							| 
									
										
										
										
											2010-08-25 01:26:56 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	    /** compose with another object */ | 
					
						
							|  |  |  | 	    inline LieVector compose(const LieVector& p) const { | 
					
						
							|  |  |  | 	    	return LieVector(vector() + p); | 
					
						
							|  |  |  | 	    } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	    /** between operation */ | 
					
						
							|  |  |  | 	    inline LieVector between(const LieVector& l2) const { | 
					
						
							|  |  |  | 	    	return LieVector(l2.vector() - vector()); | 
					
						
							|  |  |  | 	    } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-25 01:26:56 +08:00
										 |  |  | 	    /** invert the object and yield a new one */ | 
					
						
							|  |  |  | 	    inline LieVector inverse() const { | 
					
						
							|  |  |  | 	    	return LieVector(-1.0 * vector()); | 
					
						
							|  |  |  | 	    } | 
					
						
							|  |  |  | 	}; | 
					
						
							| 
									
										
										
										
											2010-08-23 05:45:53 +08:00
										 |  |  | } // \namespace gtsam
 |