| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | /**
 | 
					
						
							|  |  |  |  * @file    Point2.h | 
					
						
							|  |  |  |  * @brief   2D Point | 
					
						
							|  |  |  |  * @author  Frank Dellaert | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #pragma once
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-09-07 12:19:03 +08:00
										 |  |  | #include <boost/serialization/nvp.hpp>
 | 
					
						
							| 
									
										
										
										
											2009-09-07 11:35:32 +08:00
										 |  |  | #include "Vector.h"
 | 
					
						
							| 
									
										
										
										
											2010-01-10 14:35:16 +08:00
										 |  |  | #include "Matrix.h"
 | 
					
						
							| 
									
										
										
										
											2009-10-22 22:43:36 +08:00
										 |  |  | #include "Testable.h"
 | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  | #include "Lie.h"
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | namespace gtsam { | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-10-22 22:43:36 +08:00
										 |  |  |   /**
 | 
					
						
							|  |  |  |    * A 2D point | 
					
						
							|  |  |  |    * Derived from testable so has standard print and equals, and assert_equals works | 
					
						
							|  |  |  |    * Functional, so no set functions: once created, a point is constant. | 
					
						
							|  |  |  |    */ | 
					
						
							| 
									
										
										
										
											2010-01-10 07:15:06 +08:00
										 |  |  |   class Point2: Testable<Point2>, public Lie<Point2> { | 
					
						
							| 
									
										
										
										
											2010-02-16 00:37:37 +08:00
										 |  |  |   public: | 
					
						
							|  |  |  | 	  /// dimension of the variable - used to autodetect sizes
 | 
					
						
							|  |  |  | 	  static inline size_t dim() {return 2;} | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  |   private: | 
					
						
							| 
									
										
										
										
											2009-10-22 22:43:36 +08:00
										 |  |  |     double x_, y_; | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 		 | 
					
						
							|  |  |  |   public: | 
					
						
							|  |  |  |     Point2(): x_(0), y_(0) {} | 
					
						
							|  |  |  |     Point2(const Point2 &p) : x_(p.x_), y_(p.y_) {} | 
					
						
							|  |  |  |     Point2(double x, double y): x_(x), y_(y) {} | 
					
						
							|  |  |  |     Point2(const Vector& v) : x_(v(0)), y_(v(1)) {} | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-10-22 22:43:36 +08:00
										 |  |  |     /** print with optional string */ | 
					
						
							|  |  |  |     void print(const std::string& s = "") const; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-12-14 11:02:05 +08:00
										 |  |  |     /** equals with an tolerance, prints out message if unequal*/ | 
					
						
							|  |  |  |     bool equals(const Point2& q, double tol = 1e-9) const; | 
					
						
							| 
									
										
										
										
											2009-10-22 22:43:36 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  |     /** get functions for x, y */ | 
					
						
							|  |  |  |     double x() const {return x_;} | 
					
						
							|  |  |  |     double y() const {return y_;} | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** return vectorized form (column-wise) */ | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |     Vector vector() const { return Vector_(2, x_, y_); } | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     /** operators */ | 
					
						
							| 
									
										
										
										
											2010-03-01 09:30:15 +08:00
										 |  |  |     inline Point2 operator- () const {return Point2(-x_,-y_);} | 
					
						
							| 
									
										
										
										
											2009-08-26 23:25:47 +08:00
										 |  |  |     inline bool   operator ==(const Point2& q) const {return x_==q.x_ && q.y_==q.y_;} | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  |     inline Point2 operator + (const Point2& q) const {return Point2(x_+q.x_,y_+q.y_);} | 
					
						
							|  |  |  |     inline Point2 operator - (const Point2& q) const {return Point2(x_-q.x_,y_-q.y_);} | 
					
						
							| 
									
										
										
										
											2009-09-12 04:49:28 +08:00
										 |  |  |     inline Point2 operator / (double q) const {return Point2(x_/q,y_/q);} | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-12 10:09:03 +08:00
										 |  |  |     /** norm of point */ | 
					
						
							|  |  |  |     double norm() const; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  |     /** distance between two points */ | 
					
						
							| 
									
										
										
										
											2010-01-12 10:09:03 +08:00
										 |  |  |     inline double dist(const Point2& p2) const { | 
					
						
							|  |  |  | 			return (p2 - *this).norm(); | 
					
						
							|  |  |  | 		} | 
					
						
							| 
									
										
										
										
											2009-09-07 11:35:32 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-09-07 12:19:03 +08:00
										 |  |  |   private: | 
					
						
							|  |  |  |     /** Serialization function */ | 
					
						
							|  |  |  |     friend class boost::serialization::access; | 
					
						
							|  |  |  |     template<class Archive> | 
					
						
							|  |  |  |       void serialize(Archive & ar, const unsigned int version) | 
					
						
							|  |  |  |     { | 
					
						
							|  |  |  |       ar & BOOST_SERIALIZATION_NVP(x_); | 
					
						
							|  |  |  |       ar & BOOST_SERIALIZATION_NVP(y_); | 
					
						
							|  |  |  |     } | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  |   }; | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-11 06:41:23 +08:00
										 |  |  |   /** Lie group functions */ | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-11 06:41:23 +08:00
										 |  |  |   /** Global print calls member function */ | 
					
						
							| 
									
										
										
										
											2010-02-17 07:20:39 +08:00
										 |  |  |   inline void print(const Point2& p, const std::string& s = "Point2") { p.print(s); } | 
					
						
							| 
									
										
										
										
											2010-01-11 06:41:23 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /** Dimensionality of the tangent space */ | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |   inline size_t dim(const Point2& obj) { return 2; } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-11 06:41:23 +08:00
										 |  |  |   /** Exponential map around identity - just create a Point2 from a vector */ | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |   template<> inline Point2 expmap(const Vector& dp) { return Point2(dp); } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-11 06:41:23 +08:00
										 |  |  |   /** Log map around identity - just return the Point2 as a vector */ | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |   inline Vector logmap(const Point2& dp) { return Vector_(2, dp.x(), dp.y()); } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-11 06:41:23 +08:00
										 |  |  |   /** "Compose", just adds the coordinates of two points. */ | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |   inline Point2 compose(const Point2& p1, const Point2& p0) { return p0+p1; } | 
					
						
							|  |  |  |   inline Matrix Dcompose1(const Point2& p1, const Point2& p0) { | 
					
						
							|  |  |  |     return Matrix_(2,2, | 
					
						
							|  |  |  |         1.0, 0.0, | 
					
						
							|  |  |  |         0.0, 1.0); } | 
					
						
							|  |  |  |   inline Matrix Dcompose2(const Point2& p1, const Point2& p0) { | 
					
						
							|  |  |  |     return Matrix_(2,2, | 
					
						
							|  |  |  |         1.0, 0.0, | 
					
						
							|  |  |  |         0.0, 1.0); } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-11 06:41:23 +08:00
										 |  |  |   /** "Inverse" - negates each coordinate such that compose(p,inverse(p))=Point2() */ | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |   inline Point2 inverse(const Point2& p) { return Point2(-p.x(), -p.y()); } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 |