| 
									
										
										
										
											2010-10-14 12:54:38 +08:00
										 |  |  | /* ----------------------------------------------------------------------------
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * GTSAM Copyright 2010, Georgia Tech Research Corporation,  | 
					
						
							|  |  |  |  * Atlanta, Georgia 30332-0415 | 
					
						
							|  |  |  |  * All Rights Reserved | 
					
						
							|  |  |  |  * Authors: Frank Dellaert, et al. (see THANKS for the full author list) | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * See LICENSE for the license information | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											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>
 | 
					
						
							| 
									
										
										
										
											2010-08-20 01:23:19 +08:00
										 |  |  | #include <gtsam/base/Vector.h>
 | 
					
						
							|  |  |  | #include <gtsam/base/Matrix.h>
 | 
					
						
							|  |  |  | #include <gtsam/base/Testable.h>
 | 
					
						
							|  |  |  | #include <gtsam/base/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
 | 
					
						
							| 
									
										
										
										
											2010-08-20 04:03:06 +08:00
										 |  |  | 	  static const size_t dimension = 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) {} | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |     Point2(const Vector& v) : x_(v(0)), y_(v(1)) { assert(v.size() == 2); } | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-20 04:03:06 +08:00
										 |  |  |     /** dimension of the variable - used to autodetect sizes */ | 
					
						
							|  |  |  |     inline static size_t Dim() { return dimension; } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											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
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-20 04:03:06 +08:00
										 |  |  |     /** Lie requirements */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** Size of the tangent space of the Lie type */ | 
					
						
							|  |  |  |     inline size_t dim() const { return dimension; } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  |     /** "Compose", just adds the coordinates of two points. With optional derivatives */ | 
					
						
							|  |  |  |     inline Point2 compose(const Point2& p2, | 
					
						
							|  |  |  |         boost::optional<Matrix&> H1=boost::none, | 
					
						
							|  |  |  |         boost::optional<Matrix&> H2=boost::none) const { | 
					
						
							|  |  |  |       if(H1) *H1 = eye(2); | 
					
						
							|  |  |  |       if(H2) *H2 = eye(2); | 
					
						
							|  |  |  |       return *this+p2; | 
					
						
							|  |  |  |     } | 
					
						
							| 
									
										
										
										
											2010-08-20 04:03:06 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     /** "Inverse" - negates each coordinate such that compose(p,inverse(p))=Point2() */ | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  |     inline Point2 inverse() const { return Point2(-x_, -y_); } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** Binary expmap - just adds the points */ | 
					
						
							|  |  |  |     inline Point2 expmap(const Vector& v) const { return *this + Point2(v); } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** Binary Logmap - just subtracts the points */ | 
					
						
							|  |  |  |     inline Vector logmap(const Point2& p2) const { return Logmap(between(p2));} | 
					
						
							| 
									
										
										
										
											2010-08-20 04:03:06 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     /** Exponential map around identity - just create a Point2 from a vector */ | 
					
						
							|  |  |  |     static inline Point2 Expmap(const Vector& v) { return Point2(v); } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** Log map around identity - just return the Point2 as a vector */ | 
					
						
							|  |  |  |     static inline Vector Logmap(const Point2& dp) { return Vector_(2, dp.x(), dp.y()); } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  |     /** "Between", subtracts point coordinates */ | 
					
						
							|  |  |  |     inline Point2 between(const Point2& p2, | 
					
						
							|  |  |  |         boost::optional<Matrix&> H1=boost::none, | 
					
						
							|  |  |  |         boost::optional<Matrix&> H2=boost::none) const { | 
					
						
							|  |  |  |       if(H1) *H1 = -eye(2); | 
					
						
							|  |  |  |       if(H2) *H2 = eye(2); | 
					
						
							|  |  |  |       return p2- (*this); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											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-09-11 13:29:38 +08:00
										 |  |  |     inline void operator += (const Point2& q) {x_+=q.x_;y_+=q.y_;} | 
					
						
							|  |  |  |     inline void operator *= (double s) {x_*=s;y_*=s;} | 
					
						
							|  |  |  |     inline bool operator ==(const Point2& q) const {return x_==q.x_ && q.y_==q.y_;} | 
					
						
							| 
									
										
										
										
											2010-03-01 09:30:15 +08:00
										 |  |  |     inline Point2 operator- () const {return Point2(-x_,-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_);} | 
					
						
							| 
									
										
										
										
											2010-03-03 10:49:06 +08:00
										 |  |  |     inline Point2 operator * (double s) const {return Point2(x_*s,y_*s);} | 
					
						
							| 
									
										
										
										
											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; | 
					
						
							| 
									
										
										
										
											2010-10-22 02:02:17 +08:00
										 |  |  |     template<class ARCHIVE> | 
					
						
							|  |  |  |       void serialize(ARCHIVE & ar, const unsigned int version) | 
					
						
							| 
									
										
										
										
											2009-09-07 12:19:03 +08:00
										 |  |  |     { | 
					
						
							|  |  |  |       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-03-03 10:49:06 +08:00
										 |  |  |   /** multiply with scalar */ | 
					
						
							|  |  |  |   inline Point2 operator*(double s, const Point2& p) {return p*s;} | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 |