| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | /**
 | 
					
						
							|  |  |  |  * @file   Point3.h | 
					
						
							|  |  |  |  * @brief  3D Point | 
					
						
							|  |  |  |  * @author Alireza Fathi | 
					
						
							|  |  |  |  * @author Christian Potthast | 
					
						
							|  |  |  |  * @author Frank Dellaert | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // \callgraph
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #pragma once
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <boost/serialization/nvp.hpp>
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-20 01:23:19 +08:00
										 |  |  | #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 { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** A 3D point */ | 
					
						
							| 
									
										
										
										
											2010-01-10 07:15:06 +08:00
										 |  |  |   class Point3: Testable<Point3>, public Lie<Point3> { | 
					
						
							| 
									
										
										
										
											2010-02-17 04:21:03 +08:00
										 |  |  |   public: | 
					
						
							|  |  |  | 	  /// dimension of the variable - used to autodetect sizes
 | 
					
						
							| 
									
										
										
										
											2010-08-20 04:03:06 +08:00
										 |  |  | 	  static const size_t dimension = 3; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  |   private: | 
					
						
							|  |  |  |     double x_, y_, z_;   | 
					
						
							|  |  |  | 		 | 
					
						
							|  |  |  |   public: | 
					
						
							|  |  |  |     Point3(): x_(0), y_(0), z_(0) {} | 
					
						
							|  |  |  |     Point3(const Point3 &p) : x_(p.x_), y_(p.y_), z_(p.z_) {} | 
					
						
							|  |  |  |     Point3(double x, double y, double z): x_(x), y_(y), z_(z) {} | 
					
						
							|  |  |  |     Point3(const Vector& v) : x_(v(0)), y_(v(1)), z_(v(2)) {} | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-10-27 03:26:51 +08:00
										 |  |  |     /** print with optional string */ | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |     void print(const std::string& s = "") const; | 
					
						
							| 
									
										
										
										
											2009-10-27 03:26:51 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     /** equals with an tolerance */ | 
					
						
							|  |  |  |     bool equals(const Point3& p, double tol = 1e-9) const; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-20 04:03:06 +08:00
										 |  |  |     /** dimension of the variable - used to autodetect sizes */ | 
					
						
							|  |  |  |     inline static size_t Dim() { return dimension; } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** Lie requirements */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** return DOF, dimensionality of tangent space */ | 
					
						
							|  |  |  |     inline size_t dim() const { return dimension; } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** "Inverse" - negates the coordinates such that compose(p, inverse(p)) = Point3() */ | 
					
						
							|  |  |  |     inline Point3 inverse() const { return Point3(-x_, -y_, -z_); } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** "Compose" - just adds coordinates of two points */ | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  |     inline Point3 compose(const Point3& p2, | 
					
						
							|  |  |  |     		boost::optional<Matrix&> H1=boost::none, | 
					
						
							|  |  |  |     		boost::optional<Matrix&> H2=boost::none) const { | 
					
						
							|  |  |  |   	  if (H1) *H1 = eye(3); | 
					
						
							|  |  |  |   	  if (H2) *H2 = eye(3); | 
					
						
							|  |  |  |   	  return *this+p2; | 
					
						
							|  |  |  |     } | 
					
						
							| 
									
										
										
										
											2010-08-20 04:03:06 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     /** Exponential map at identity - just create a Point3 from x,y,z */ | 
					
						
							|  |  |  |     static inline Point3 Expmap(const Vector& v) { return Point3(v); } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** Log map at identity - return the x,y,z of this point */ | 
					
						
							|  |  |  |     static inline Vector Logmap(const Point3& dp) { return Vector_(3, dp.x(), dp.y(), dp.z()); } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  |     /** default implementations of binary functions */ | 
					
						
							|  |  |  |     inline Point3 expmap(const Vector& v) const { return gtsam::expmap_default(*this, v); } | 
					
						
							|  |  |  |     inline Vector logmap(const Point3& p2) const { return gtsam::logmap_default(*this, p2);} | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** Between using the default implementation */ | 
					
						
							|  |  |  |     inline Point3 between(const Point3& p2) const { return between_default(*this, p2); } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  |     /** return vectorized form (column-wise)*/ | 
					
						
							|  |  |  |     Vector vector() const { | 
					
						
							|  |  |  |       //double r[] = { x_, y_, z_ };
 | 
					
						
							|  |  |  |       Vector v(3); v(0)=x_; v(1)=y_; v(2)=z_; | 
					
						
							|  |  |  |       return v; | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** get functions for x, y, z */ | 
					
						
							| 
									
										
										
										
											2010-02-24 14:14:43 +08:00
										 |  |  |     inline double x() const {return x_;} | 
					
						
							|  |  |  |     inline double y() const {return y_;} | 
					
						
							|  |  |  |     inline double z() const {return z_;} | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     /** operators */ | 
					
						
							|  |  |  |     Point3 operator - () const { return Point3(-x_,-y_,-z_);} | 
					
						
							|  |  |  |     bool   operator ==(const Point3& q) const; | 
					
						
							|  |  |  |     Point3 operator + (const Point3& q) const; | 
					
						
							|  |  |  |     Point3 operator - (const Point3& q) const; | 
					
						
							|  |  |  |     Point3 operator * (double s) const; | 
					
						
							|  |  |  |     Point3 operator / (double s) const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** distance between two points */ | 
					
						
							|  |  |  |     double dist(const Point3& p2) const { | 
					
						
							|  |  |  |       return sqrt(pow(x()-p2.x(),2.0) + pow(y()-p2.y(),2.0) + pow(z()-p2.z(),2.0)); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-23 05:45:53 +08:00
										 |  |  |     /** add two points, add(this,q) is same as this + q */ | 
					
						
							|  |  |  |     Point3 add (const Point3 &q, | 
					
						
							|  |  |  |   	      boost::optional<Matrix&> H1=boost::none, boost::optional<Matrix&> H2=boost::none) const; | 
					
						
							| 
									
										
										
										
											2010-08-21 05:47:30 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-23 05:45:53 +08:00
										 |  |  |     /** subtract two points, sub(this,q) is same as this - q */ | 
					
						
							|  |  |  |     Point3 sub (const Point3 &q, | 
					
						
							|  |  |  |   	      boost::optional<Matrix&> H1=boost::none, boost::optional<Matrix&> H2=boost::none) const; | 
					
						
							| 
									
										
										
										
											2010-08-21 05:47:30 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-23 05:45:53 +08:00
										 |  |  |     /** cross product @return this x q */ | 
					
						
							|  |  |  |     Point3 cross(const Point3 &q) const; | 
					
						
							| 
									
										
										
										
											2010-08-21 05:47:30 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-23 05:45:53 +08:00
										 |  |  |     /** dot product @return this * q*/ | 
					
						
							|  |  |  |     double dot(const Point3 &q) const; | 
					
						
							| 
									
										
										
										
											2010-08-21 05:47:30 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     /** dot product */ | 
					
						
							| 
									
										
										
										
											2010-08-23 05:45:53 +08:00
										 |  |  |     double norm() const; | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +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_); | 
					
						
							|  |  |  |       ar & BOOST_SERIALIZATION_NVP(z_); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |   }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-11 06:41:23 +08:00
										 |  |  |   /** Syntactic sugar for multiplying coordinates by a scalar s*p */ | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |   inline Point3 operator*(double s, const Point3& p) { return p*s;} | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | } |