| 
									
										
										
										
											2009-08-29 09:24:26 +08:00
										 |  |  | /**
 | 
					
						
							|  |  |  |  * @file  Pose2.h | 
					
						
							| 
									
										
										
										
											2009-12-14 11:02:05 +08:00
										 |  |  |  * @brief 2D Pose | 
					
						
							| 
									
										
										
										
											2009-08-29 09:24:26 +08:00
										 |  |  |  * @author: Frank Dellaert | 
					
						
							| 
									
										
										
										
											2009-12-14 11:02:05 +08:00
										 |  |  |  * @author: Richard Roberts | 
					
						
							| 
									
										
										
										
											2009-08-29 09:24:26 +08:00
										 |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // \callgraph
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #pragma once
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-12 10:08:41 +08:00
										 |  |  | #include <boost/optional.hpp>
 | 
					
						
							| 
									
										
										
										
											2009-12-09 03:12:20 +08:00
										 |  |  | #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"
 | 
					
						
							| 
									
										
										
										
											2010-01-10 07:15:06 +08:00
										 |  |  | #include "Point2.h"
 | 
					
						
							|  |  |  | #include "Rot2.h"
 | 
					
						
							| 
									
										
										
										
											2009-08-29 09:24:26 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | namespace gtsam { | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-12-14 11:02:05 +08:00
										 |  |  |   /**
 | 
					
						
							| 
									
										
										
										
											2009-12-15 08:00:02 +08:00
										 |  |  |    * A 2D pose (Point2,Rot2) | 
					
						
							| 
									
										
										
										
											2009-12-14 11:02:05 +08:00
										 |  |  |    */ | 
					
						
							| 
									
										
										
										
											2010-01-10 07:15:06 +08:00
										 |  |  |   class Pose2: Testable<Pose2>, public Lie<Pose2>  { | 
					
						
							| 
									
										
										
										
											2009-12-15 08:00:02 +08:00
										 |  |  |   private: | 
					
						
							|  |  |  |     Point2 t_; | 
					
						
							|  |  |  |     Rot2 r_; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   public: | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** default constructor = origin */ | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |     Pose2() : t_(0.0, 0.0), r_(0) {} // default is origin
 | 
					
						
							| 
									
										
										
										
											2009-12-15 08:00:02 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     /** copy constructor */ | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |     Pose2(const Pose2& pose) : t_(pose.t_), r_(pose.r_) {} | 
					
						
							| 
									
										
										
										
											2009-12-15 08:00:02 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     /**
 | 
					
						
							|  |  |  |      * construct from (x,y,theta) | 
					
						
							|  |  |  |      * @param x x coordinate | 
					
						
							|  |  |  |      * @param y y coordinate | 
					
						
							|  |  |  |      * @param theta angle with positive X-axis | 
					
						
							|  |  |  |      */ | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |     Pose2(double x, double y, double theta) : t_(x,y), r_(theta) {} | 
					
						
							| 
									
										
										
										
											2009-12-15 08:00:02 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     /** construct from rotation and translation */ | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |     Pose2(double theta, const Point2& t) : t_(t), r_(theta) {} | 
					
						
							|  |  |  |     Pose2(const Rot2& r, const Point2& t) : t_(t), r_(r) {} | 
					
						
							| 
									
										
										
										
											2009-12-15 08:00:02 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     /** print with optional string */ | 
					
						
							|  |  |  |     void print(const std::string& s = "") const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** assert equality up to a tolerance */ | 
					
						
							|  |  |  |     bool equals(const Pose2& pose, double tol = 1e-9) const; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-02-19 00:27:01 +08:00
										 |  |  |     /** return transformation matrix */ | 
					
						
							|  |  |  |     Matrix matrix() const; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-12-15 08:00:02 +08:00
										 |  |  |     /** get functions for x, y, theta */ | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |     double x()     const { return t_.x(); } | 
					
						
							|  |  |  |     double y()     const { return t_.y(); } | 
					
						
							|  |  |  |     double theta() const { return r_.theta(); } | 
					
						
							| 
									
										
										
										
											2009-12-15 08:00:02 +08:00
										 |  |  |     Point2 t()     const { return t_; } | 
					
						
							|  |  |  |     Rot2 r()       const { return r_; } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-20 10:28:23 +08:00
										 |  |  |     static inline size_t dim() { return 3; }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |   }; // Pose2
 | 
					
						
							| 
									
										
										
										
											2009-12-18 08:09:54 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-12-15 08:00:02 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |   /** return DOF, dimensionality of tangent space = 3 */ | 
					
						
							|  |  |  |   inline size_t dim(const Pose2&) { return 3; } | 
					
						
							| 
									
										
										
										
											2009-12-15 08:00:02 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |   /** inverse transformation */ | 
					
						
							|  |  |  |   inline Pose2 inverse(const Pose2& pose) { | 
					
						
							|  |  |  |     return Pose2(inverse(pose.r()), | 
					
						
							|  |  |  |         pose.r().unrotate(Point2(-pose.t().x(), -pose.t().y()))); } | 
					
						
							| 
									
										
										
										
											2009-12-15 08:00:02 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |   /** compose this transformation onto another (pre-multiply this*p1) */ | 
					
						
							| 
									
										
										
										
											2010-01-27 04:00:17 +08:00
										 |  |  |   inline Pose2 compose(const Pose2& p0, const Pose2& p1) { | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |     return Pose2(p0.r()*p1.r(), p0.t() + p0.r()*p1.t()); } | 
					
						
							| 
									
										
										
										
											2009-12-15 08:00:02 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-10 07:15:06 +08:00
										 |  |  |   /** exponential and log maps around identity */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** Create an incremental pose from x,y,theta */ | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |   template<> inline Pose2 expmap(const Vector& v) { return Pose2(v[0], v[1], v[2]); } | 
					
						
							| 
									
										
										
										
											2010-01-10 07:15:06 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /** Return the x,y,theta of this pose */ | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |   inline Vector logmap(const Pose2& p) { return Vector_(3, p.x(), p.y(), p.theta()); } | 
					
						
							| 
									
										
										
										
											2009-12-15 08:00:02 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-10 14:35:16 +08:00
										 |  |  |   /** print using member print function, currently used by LieConfig */ | 
					
						
							|  |  |  |   inline void print(const Pose2& obj, const std::string& str = "") { obj.print(str); } | 
					
						
							| 
									
										
										
										
											2009-12-15 08:00:02 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |   /** Return point coordinates in pose coordinate frame */ | 
					
						
							|  |  |  |   inline Point2 transform_to(const Pose2& pose, const Point2& point) { | 
					
						
							|  |  |  |     return unrotate(pose.r(), point-pose.t()); } | 
					
						
							| 
									
										
										
										
											2010-01-12 10:08:41 +08:00
										 |  |  |   Point2 transform_to(const Pose2& pose, const Point2& point, | 
					
						
							|  |  |  | 			boost::optional<Matrix&> H1, boost::optional<Matrix&> H2); | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |   Matrix Dtransform_to1(const Pose2& pose, const Point2& point); | 
					
						
							|  |  |  |   Matrix Dtransform_to2(const Pose2& pose, const Point2& point); | 
					
						
							| 
									
										
										
										
											2009-12-15 08:00:02 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |   /** Return point coordinates in global frame */ | 
					
						
							|  |  |  |   inline Point2 transform_from(const Pose2& pose, const Point2& point) { | 
					
						
							|  |  |  |     return rotate(pose.r(), point)+pose.t(); } | 
					
						
							| 
									
										
										
										
											2009-12-15 08:00:02 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |   /** Return relative pose between p1 and p2, in p1 coordinate frame */ | 
					
						
							| 
									
										
										
										
											2010-01-16 09:16:59 +08:00
										 |  |  |   Pose2 between(const Pose2& p1, const Pose2& p2, | 
					
						
							|  |  |  |   		boost::optional<Matrix&> H1, boost::optional<Matrix&> H2); | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /** same as compose (pre-multiply this*p1) */ | 
					
						
							|  |  |  |   inline Pose2 operator*(const Pose2& p1, const Pose2& p0) { return compose(p1, p0); } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** Transform a point in this coordinate frame to global coordinates,
 | 
					
						
							|  |  |  |    * same as transform_from */ | 
					
						
							|  |  |  |   inline Point2 operator*(const Pose2& pose, const Point2& point) { | 
					
						
							|  |  |  |     return transform_from(pose, point); } | 
					
						
							| 
									
										
										
										
											2009-12-14 11:02:05 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-16 09:16:59 +08:00
										 |  |  | 	/**
 | 
					
						
							|  |  |  | 	 * Calculate bearing to a landmark | 
					
						
							|  |  |  | 	 * @param pose 2D pose of robot | 
					
						
							|  |  |  | 	 * @param point 2D location of landmark | 
					
						
							|  |  |  | 	 * @return 2D rotation \in SO(2) | 
					
						
							|  |  |  | 	 */ | 
					
						
							|  |  |  | 	Rot2 bearing(const Pose2& pose, const Point2& point); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	/**
 | 
					
						
							|  |  |  | 	 * Calculate bearing and optional derivative(s) | 
					
						
							|  |  |  | 	 */ | 
					
						
							|  |  |  | 	Rot2 bearing(const Pose2& pose, const Point2& point, | 
					
						
							|  |  |  | 			boost::optional<Matrix&> H1, boost::optional<Matrix&> H2); | 
					
						
							| 
									
										
										
										
											2010-01-10 07:15:06 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-16 09:16:59 +08:00
										 |  |  | 	/**
 | 
					
						
							|  |  |  | 	 * Calculate range to a landmark | 
					
						
							|  |  |  | 	 * @param pose 2D pose of robot | 
					
						
							|  |  |  | 	 * @param point 2D location of landmark | 
					
						
							|  |  |  | 	 * @return range (double) | 
					
						
							|  |  |  | 	 */ | 
					
						
							|  |  |  | 	double range(const Pose2& pose, const Point2& point); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	/**
 | 
					
						
							|  |  |  | 	 * Calculate range and optional derivative(s) | 
					
						
							|  |  |  | 	 */ | 
					
						
							|  |  |  | 	double range(const Pose2& pose, const Point2& point, | 
					
						
							|  |  |  | 			boost::optional<Matrix&> H1, boost::optional<Matrix&> H2); | 
					
						
							| 
									
										
										
										
											2010-01-10 07:15:06 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-29 09:24:26 +08:00
										 |  |  | } // namespace gtsam
 | 
					
						
							| 
									
										
										
										
											2010-01-10 07:15:06 +08:00
										 |  |  | 
 |