| 
									
										
										
										
											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>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include "Matrix.h"
 | 
					
						
							| 
									
										
										
										
											2009-10-27 03:26:51 +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 { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** 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
 | 
					
						
							|  |  |  | 	  static inline size_t dim() {return 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; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											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)); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** friends */ | 
					
						
							| 
									
										
										
										
											2009-08-26 23:25:47 +08:00
										 |  |  |     friend Point3 cross(const Point3 &p1, const Point3 &p2); | 
					
						
							| 
									
										
										
										
											2009-09-14 04:07:00 +08:00
										 |  |  |     friend double dot(const Point3 &p1, const Point3 &p2); | 
					
						
							|  |  |  |     friend double norm(const Point3 &p1); | 
					
						
							| 
									
										
										
										
											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-08 08:40:17 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-11 06:41:23 +08:00
										 |  |  |   /** Global print calls member function */ | 
					
						
							| 
									
										
											  
											
												Large gtsam refactoring
To support faster development *and* better performance Richard and I pushed through a large refactoring of NonlinearFactors.
The following are the biggest changes:
1) NonLinearFactor1 and NonLinearFactor2 are now templated on Config, Key type, and X type, where X is the argument to the measurement function.
2) The measurement itself is no longer kept in the nonlinear factor. Instead, a derived class (see testVSLAMFactor, testNonlinearEquality, testPose3Factor etc...) has to implement a function to compute the errors, "evaluateErrors". Instead of (h(x)-z), it needs to return (z-h(x)), so Ax-b is an approximation of the error. IMPORTANT: evaluateErrors needs - if asked - *combine* the calculation of the function value h(x) and the derivatives dh(x)/dx. This was a major performance issue. To do this, boost::optional<Matrix&> arguments are provided, and tin EvaluateErrors you just  says something like
	if (H) *H = Matrix_(3,6,....);
3) We are no longer using int or strings for nonlinear factors. Instead, the preferred key type is now Symbol, defined in Key.h. This is both fast and cool: you can construct it from an int, and cast it to a strong. It also does type checking: a Symbol<Pose3,'x'> will not match a Symbol<Pose2,'x'>
4) minor: take a look at LieConfig.h: it help you avoid writing a lot of code bu automatically creating configs for a certain type. See e.g. Pose3Config.h. A "double" LieConfig is on the way - Thanks Richard and Manohar !
											
										 
											2010-01-14 06:25:03 +08:00
										 |  |  |   inline void print(const Point3& p, const std::string& s) { p.print(s); } | 
					
						
							| 
									
										
										
										
											2010-01-11 06:41:23 +08:00
										 |  |  |   inline void print(const Point3& p) { p.print(); } | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-11 06:41:23 +08:00
										 |  |  |   /** return DOF, dimensionality of tangent space */ | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |   inline size_t dim(const Point3&) { return 3; } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-11 06:41:23 +08:00
										 |  |  |   /** Exponential map at identity - just create a Point3 from x,y,z */ | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |   template<> inline Point3 expmap(const Vector& dp) { return Point3(dp); } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-11 06:41:23 +08:00
										 |  |  |   /** Log map at identity - return the x,y,z of this point */ | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |   inline Vector logmap(const Point3& dp) { return Vector_(3, dp.x(), dp.y(), dp.z()); } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-11 06:41:23 +08:00
										 |  |  |   /** "Compose" - just adds coordinates of two points */ | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |   inline Point3 compose(const Point3& p1, const Point3& p0) { return p0+p1; } | 
					
						
							|  |  |  |   inline Matrix Dcompose1(const Point3& p1, const Point3& p0) { | 
					
						
							|  |  |  |     return Matrix_(3,3, | 
					
						
							|  |  |  |         1.0, 0.0, 0.0, | 
					
						
							|  |  |  |         0.0, 1.0, 0.0, | 
					
						
							|  |  |  |         0.0, 0.0, 1.0); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  |   inline Matrix Dcompose2(const Point3& p1, const Point3& p0) { | 
					
						
							|  |  |  |     return Matrix_(3,3, | 
					
						
							|  |  |  |         1.0, 0.0, 0.0, | 
					
						
							|  |  |  |         0.0, 1.0, 0.0, | 
					
						
							|  |  |  |         0.0, 0.0, 1.0); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-11 06:41:23 +08:00
										 |  |  |   /** "Inverse" - negates the coordinates such that compose(p, inverse(p)) = Point3() */ | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |   inline Point3 inverse(const Point3& p) { return Point3(-p.x(), -p.y(), -p.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
										 |  |  | 
 | 
					
						
							|  |  |  |   /** add two points, add(p,q) is same as p+q */ | 
					
						
							|  |  |  |   Point3   add (const Point3 &p, const Point3 &q); | 
					
						
							|  |  |  |   Matrix Dadd1(const Point3 &p, const Point3 &q); | 
					
						
							|  |  |  |   Matrix Dadd2(const Point3 &p, const Point3 &q); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** subtract two points, sub(p,q) is same as p-q */ | 
					
						
							|  |  |  |   Point3   sub (const Point3 &p, const Point3 &q); | 
					
						
							|  |  |  |   Matrix Dsub1(const Point3 &p, const Point3 &q); | 
					
						
							|  |  |  |   Matrix Dsub2(const Point3 &p, const Point3 &q); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** cross product */ | 
					
						
							|  |  |  |   Point3 cross(const Point3 &p, const Point3 &q);  | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-09-14 04:07:00 +08:00
										 |  |  |   /** dot product */ | 
					
						
							|  |  |  |   double dot(const Point3 &p, const Point3 &q); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** dot product */ | 
					
						
							|  |  |  |   double norm(const Point3 &p); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | } |