| 
									
										
										
										
											2009-12-10 05:50:27 +08:00
										 |  |  | /*
 | 
					
						
							|  |  |  |  * Rot2.h | 
					
						
							|  |  |  |  * | 
					
						
							|  |  |  |  *  Created on: Dec 9, 2009 | 
					
						
							|  |  |  |  *      Author: Frank Dellaert | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #ifndef ROT2_H_
 | 
					
						
							|  |  |  | #define ROT2_H_
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-15 00:57:48 +08:00
										 |  |  | #include <boost/optional.hpp>
 | 
					
						
							| 
									
										
										
										
											2009-12-10 05:50:27 +08:00
										 |  |  | #include "Testable.h"
 | 
					
						
							|  |  |  | #include "Point2.h"
 | 
					
						
							|  |  |  | #include "Matrix.h"
 | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  | #include "Lie.h"
 | 
					
						
							| 
									
										
										
										
											2009-12-10 05:50:27 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | namespace gtsam { | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-12-15 08:00:02 +08:00
										 |  |  |   /* Rotation matrix */ | 
					
						
							| 
									
										
										
										
											2010-01-10 07:15:06 +08:00
										 |  |  |   class Rot2: Testable<Rot2>, public Lie<Rot2> { | 
					
						
							| 
									
										
										
										
											2009-12-15 08:00:02 +08:00
										 |  |  |   private: | 
					
						
							|  |  |  |     /** we store cos(theta) and sin(theta) */ | 
					
						
							|  |  |  |     double c_, s_; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |   public: | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** constructor from cos/sin */ | 
					
						
							| 
									
										
										
										
											2010-02-24 14:14:43 +08:00
										 |  |  |     inline Rot2(double c, double s) : | 
					
						
							| 
									
										
										
										
											2009-12-15 08:00:02 +08:00
										 |  |  |       c_(c), s_(s) { | 
					
						
							| 
									
										
										
										
											2010-02-24 14:14:43 +08:00
										 |  |  | #ifdef ROT2_RENORMALIZE
 | 
					
						
							| 
									
										
										
										
											2010-02-10 06:44:02 +08:00
										 |  |  |     	// rtodo: Could do this scale correction only when creating from compose
 | 
					
						
							|  |  |  |     	// Don't let scale drift
 | 
					
						
							|  |  |  |     	double scale = c*c + s*s; | 
					
						
							|  |  |  |     	if(scale != 1.0) { | 
					
						
							|  |  |  |     		scale = pow(scale, -0.5); | 
					
						
							|  |  |  |     		c_ *= scale; | 
					
						
							|  |  |  |     		s_ *= scale; | 
					
						
							|  |  |  |     	} | 
					
						
							| 
									
										
										
										
											2010-02-24 14:14:43 +08:00
										 |  |  | #endif
 | 
					
						
							| 
									
										
										
										
											2009-12-15 08:00:02 +08:00
										 |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** default constructor, zero rotation */ | 
					
						
							|  |  |  |     Rot2() : c_(1.0), s_(0.0) {} | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** constructor from angle == exponential map at identity */ | 
					
						
							|  |  |  |     Rot2(double theta) : c_(cos(theta)), s_(sin(theta)) {} | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** return angle */ | 
					
						
							|  |  |  |     double theta() const { return atan2(s_,c_); } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** return cos */ | 
					
						
							| 
									
										
										
										
											2010-02-24 14:14:43 +08:00
										 |  |  |     inline double c() const { return c_; } | 
					
						
							| 
									
										
										
										
											2009-12-15 08:00:02 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     /** return sin */ | 
					
						
							| 
									
										
										
										
											2010-02-24 14:14:43 +08:00
										 |  |  |     inline double s() const { return s_; } | 
					
						
							| 
									
										
										
										
											2009-12-15 08:00:02 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     /** print */ | 
					
						
							|  |  |  |     void print(const std::string& s = "theta") const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** equals with an tolerance */ | 
					
						
							|  |  |  |     bool equals(const Rot2& R, double tol = 1e-9) const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** return 2*2 rotation matrix */ | 
					
						
							|  |  |  |     Matrix matrix() const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** return 2*2 transpose (inverse) rotation matrix   */ | 
					
						
							|  |  |  |     Matrix transpose() const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /** return 2*2 negative transpose */ | 
					
						
							|  |  |  |     Matrix negtranspose() const; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-15 00:57:48 +08:00
										 |  |  |     /** rotate from world to rotated = R*p */ | 
					
						
							|  |  |  |     Point2 rotate(const Point2& p) const; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-12-15 08:00:02 +08:00
										 |  |  |     /** rotate from world to rotated = R'*p */ | 
					
						
							|  |  |  |     Point2 unrotate(const Point2& p) const; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-03-02 05:56:13 +08:00
										 |  |  |     /** get the dimension by the type */ | 
					
						
							|  |  |  |     static inline size_t dim() { return 1; }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-12-15 08:00:02 +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(c_); | 
					
						
							|  |  |  |       ar & BOOST_SERIALIZATION_NVP(s_); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |   }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Lie group functions
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-11 06:41:23 +08:00
										 |  |  |   /** Global print calls member function */ | 
					
						
							| 
									
										
										
										
											2010-02-04 04:12:16 +08:00
										 |  |  |   inline void print(const Rot2& r, const std::string& s = "") { r.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 Rot2&) { return 1; } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-11 06:41:23 +08:00
										 |  |  |   /** Expmap around identity - create a rotation from an angle */ | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |   template<> inline Rot2 expmap(const Vector& v) { | 
					
						
							|  |  |  |     if (zero(v)) return (Rot2()); | 
					
						
							|  |  |  |     else return Rot2(v(0)); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-11 06:41:23 +08:00
										 |  |  |   /** Logmap around identity - return the angle of the rotation */ | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |   inline Vector logmap(const Rot2& r) { | 
					
						
							|  |  |  |     return Vector_(1, r.theta()); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-11 06:41:23 +08:00
										 |  |  |   /** Compose - make a new rotation by adding angles */ | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |   inline Rot2 compose(const Rot2& r0, const Rot2& r1) { | 
					
						
							|  |  |  |     return Rot2( | 
					
						
							|  |  |  |         r0.c() * r1.c() - r0.s() * r1.s(), | 
					
						
							|  |  |  |         r0.s() * r1.c() + r0.c() * r1.s()); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-11 06:41:23 +08:00
										 |  |  |   /** Syntactic sugar R1*R2 = compose(R1,R2) */ | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |   inline Rot2 operator*(const Rot2& r0, const Rot2& r1) { | 
					
						
							|  |  |  |     return compose(r0, r1); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-11 06:41:23 +08:00
										 |  |  |   /** The inverse rotation - negative angle */ | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |   inline Rot2 inverse(const Rot2& r) { return Rot2(r.c(), -r.s());} | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-11 06:41:23 +08:00
										 |  |  |   /** Shortcut to compose the inverse: invcompose(R0,R1) = inverse(R0)*R1 */ | 
					
						
							| 
									
										
										
										
											2010-01-08 08:40:17 +08:00
										 |  |  |   inline Rot2 invcompose(const Rot2& r0, const Rot2& r1) { | 
					
						
							|  |  |  |     return Rot2( | 
					
						
							|  |  |  |          r0.c() * r1.c() + r0.s() * r1.s(), | 
					
						
							|  |  |  |         -r0.s() * r1.c() + r0.c() * r1.s()); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-12-15 08:00:02 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /**
 | 
					
						
							|  |  |  |    * rotate point from rotated coordinate frame to | 
					
						
							|  |  |  |    * world = R*p | 
					
						
							|  |  |  |    */ | 
					
						
							| 
									
										
										
										
											2010-01-15 00:57:48 +08:00
										 |  |  |   inline Point2 operator*(const Rot2& R, const Point2& p) {return R.rotate(p);} | 
					
						
							|  |  |  | 	Point2 rotate(const Rot2 & R, const Point2& p, boost::optional<Matrix&> H1 = | 
					
						
							|  |  |  | 			boost::none, boost::optional<Matrix&> H2 = boost::none); | 
					
						
							| 
									
										
										
										
											2009-12-15 08:00:02 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /**
 | 
					
						
							|  |  |  |    * rotate point from world to rotated | 
					
						
							|  |  |  |    * frame = R'*p | 
					
						
							|  |  |  |    */ | 
					
						
							| 
									
										
										
										
											2010-01-15 00:57:48 +08:00
										 |  |  | 	Point2 unrotate(const Rot2 & R, const Point2& p, boost::optional<Matrix&> H1 = | 
					
						
							|  |  |  | 			boost::none, boost::optional<Matrix&> H2 = boost::none); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	/**
 | 
					
						
							|  |  |  | 	 * Calculate relative bearing to a landmark in local coordinate frame | 
					
						
							|  |  |  | 	 * @param point 2D location of landmark | 
					
						
							|  |  |  | 	 * @param H optional reference for Jacobian | 
					
						
							|  |  |  | 	 * @return 2D rotation \in SO(2) | 
					
						
							|  |  |  | 	 */ | 
					
						
							|  |  |  | 	Rot2 relativeBearing(const Point2& d); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	/**
 | 
					
						
							|  |  |  | 	 * Calculate relative bearing and optional derivative | 
					
						
							|  |  |  | 	 */ | 
					
						
							|  |  |  | 	Rot2 relativeBearing(const Point2& d, boost::optional<Matrix&> H); | 
					
						
							| 
									
										
										
										
											2009-12-10 05:50:27 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | } // gtsam
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #endif /* ROT2_H_ */
 |