| 
									
										
										
										
											2015-02-19 14:21:20 +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 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * @file   Similarity3.h | 
					
						
							|  |  |  |  * @brief  Implementation of Similarity3 transform | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  |  * @author Paul Drews | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  | #pragma once
 | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam/geometry/Rot3.h>
 | 
					
						
							|  |  |  | #include <gtsam/geometry/Point3.h>
 | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  | #include <gtsam/base/Lie.h>
 | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | #include <gtsam/base/Manifold.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | namespace gtsam { | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  | // Forward declarations
 | 
					
						
							|  |  |  | class Pose3; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | /**
 | 
					
						
							|  |  |  |  * 3D similarity transform | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | class Similarity3: public LieGroup<Similarity3, 7> { | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-03-03 12:09:44 +08:00
										 |  |  |   /// @name Pose Concept
 | 
					
						
							|  |  |  |   /// @{
 | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  |   typedef Rot3 Rotation; | 
					
						
							|  |  |  |   typedef Point3 Translation; | 
					
						
							| 
									
										
										
										
											2015-03-03 12:09:44 +08:00
										 |  |  |   /// @}
 | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | private: | 
					
						
							| 
									
										
										
										
											2015-03-03 12:09:44 +08:00
										 |  |  |   Rot3 R_; | 
					
						
							|  |  |  |   Point3 t_; | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  |   double s_; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | public: | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  |   /// @name Constructors
 | 
					
						
							|  |  |  |   /// @{
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-03-03 23:42:31 +08:00
										 |  |  |   /// Default constructor
 | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  |   Similarity3(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// Construct pure scaling
 | 
					
						
							|  |  |  |   Similarity3(double s); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// Construct from GTSAM types
 | 
					
						
							| 
									
										
										
										
											2015-03-03 12:09:44 +08:00
										 |  |  |   Similarity3(const Rot3& R, const Point3& t, double s); | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /// Construct from Eigen types
 | 
					
						
							|  |  |  |   Similarity3(const Matrix3& R, const Vector3& t, double s); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-02-08 07:02:07 +08:00
										 |  |  |   /// Construct from matrix [R t; 0 s^-1]
 | 
					
						
							|  |  |  |   Similarity3(const Matrix4& T); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  |   /// @}
 | 
					
						
							|  |  |  |   /// @name Testable
 | 
					
						
							|  |  |  |   /// @{
 | 
					
						
							| 
									
										
										
										
											2015-02-25 23:59:25 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  |   /// Compare with tolerance
 | 
					
						
							|  |  |  |   bool equals(const Similarity3& sim, double tol) const; | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-02-08 06:05:59 +08:00
										 |  |  |   /// Exact equality
 | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  |   bool operator==(const Similarity3& other) const; | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  |   /// Print with optional string
 | 
					
						
							|  |  |  |   void print(const std::string& s) const; | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-04-13 03:38:40 +08:00
										 |  |  |   GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &os, const Similarity3& p); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  |   /// @}
 | 
					
						
							|  |  |  |   /// @name Group
 | 
					
						
							|  |  |  |   /// @{
 | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  |   /// Return an identity transform
 | 
					
						
							|  |  |  |   static Similarity3 identity(); | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-03-03 23:42:31 +08:00
										 |  |  |   /// Composition
 | 
					
						
							|  |  |  |   Similarity3 operator*(const Similarity3& T) const; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  |   /// Return the inverse
 | 
					
						
							|  |  |  |   Similarity3 inverse() const; | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-03-03 23:42:31 +08:00
										 |  |  |   /// @}
 | 
					
						
							|  |  |  |   /// @name Group action on Point3
 | 
					
						
							|  |  |  |   /// @{
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-02-08 06:05:59 +08:00
										 |  |  |   /// Action on a point p is s*(R*p+t)
 | 
					
						
							| 
									
										
										
										
											2015-03-03 12:34:56 +08:00
										 |  |  |   Point3 transform_from(const Point3& p, //
 | 
					
						
							|  |  |  |       OptionalJacobian<3, 7> H1 = boost::none, //
 | 
					
						
							|  |  |  |       OptionalJacobian<3, 3> H2 = boost::none) const; | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  |   /** syntactic sugar for transform_from */ | 
					
						
							| 
									
										
										
										
											2015-03-03 12:09:44 +08:00
										 |  |  |   Point3 operator*(const Point3& p) const; | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-03-03 23:42:31 +08:00
										 |  |  |   /// @}
 | 
					
						
							|  |  |  |   /// @name Lie Group
 | 
					
						
							|  |  |  |   /// @{
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-06-27 03:44:08 +08:00
										 |  |  |   /** Log map at the identity
 | 
					
						
							|  |  |  |    * \f$ [R_x,R_y,R_z, t_x, t_y, t_z, \lambda] \f$ | 
					
						
							|  |  |  |    */ | 
					
						
							| 
									
										
										
										
											2015-03-03 23:42:31 +08:00
										 |  |  |   static Vector7 Logmap(const Similarity3& s, //
 | 
					
						
							|  |  |  |       OptionalJacobian<7, 7> Hm = boost::none); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-06-27 03:44:08 +08:00
										 |  |  |   /** Exponential map at the identity
 | 
					
						
							|  |  |  |    */ | 
					
						
							| 
									
										
										
										
											2015-03-03 23:42:31 +08:00
										 |  |  |   static Similarity3 Expmap(const Vector7& v, //
 | 
					
						
							|  |  |  |       OptionalJacobian<7, 7> Hm = boost::none); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-06-27 03:44:08 +08:00
										 |  |  |   /// Chart at the origin
 | 
					
						
							| 
									
										
										
										
											2015-03-03 23:42:31 +08:00
										 |  |  |   struct ChartAtOrigin { | 
					
						
							| 
									
										
										
										
											2015-06-27 03:44:08 +08:00
										 |  |  |     static Similarity3 Retract(const Vector7& v, ChartJacobian H = boost::none) { | 
					
						
							| 
									
										
										
										
											2016-02-08 07:02:07 +08:00
										 |  |  |       return Similarity3::Expmap(v, H); | 
					
						
							| 
									
										
										
										
											2015-06-27 03:44:08 +08:00
										 |  |  |     } | 
					
						
							|  |  |  |     static Vector7 Local(const Similarity3& other, ChartJacobian H = boost::none) { | 
					
						
							| 
									
										
										
										
											2016-02-08 07:02:07 +08:00
										 |  |  |       return Similarity3::Logmap(other, H); | 
					
						
							| 
									
										
										
										
											2015-06-27 03:44:08 +08:00
										 |  |  |     } | 
					
						
							| 
									
										
										
										
											2015-03-03 23:42:31 +08:00
										 |  |  |   }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-02-08 06:05:59 +08:00
										 |  |  |   using LieGroup<Similarity3, 7>::inverse; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /**
 | 
					
						
							|  |  |  |    * wedge for Similarity3: | 
					
						
							|  |  |  |    * @param xi 7-dim twist (w,u,lambda) where | 
					
						
							|  |  |  |    * @return 4*4 element of Lie algebra that can be exponentiated | 
					
						
							|  |  |  |    * TODO(frank): rename to Hat, make part of traits | 
					
						
							|  |  |  |    */ | 
					
						
							|  |  |  |   static Matrix4 wedge(const Vector7& xi); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-03-03 23:42:31 +08:00
										 |  |  |   /// Project from one tangent space to another
 | 
					
						
							|  |  |  |   Matrix7 AdjointMap() const; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  |   /// @}
 | 
					
						
							|  |  |  |   /// @name Standard interface
 | 
					
						
							|  |  |  |   /// @{
 | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-03-03 13:08:23 +08:00
										 |  |  |   /// Calculate 4*4 matrix group equivalent
 | 
					
						
							|  |  |  |   const Matrix4 matrix() const; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  |   /// Return a GTSAM rotation
 | 
					
						
							| 
									
										
										
										
											2015-03-03 12:09:44 +08:00
										 |  |  |   const Rot3& rotation() const { | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  |     return R_; | 
					
						
							| 
									
										
										
										
											2015-03-03 12:34:56 +08:00
										 |  |  |   } | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  |   /// Return a GTSAM translation
 | 
					
						
							| 
									
										
										
										
											2015-03-03 12:09:44 +08:00
										 |  |  |   const Point3& translation() const { | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  |     return t_; | 
					
						
							| 
									
										
										
										
											2015-03-03 12:34:56 +08:00
										 |  |  |   } | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  |   /// Return the scale
 | 
					
						
							|  |  |  |   double scale() const { | 
					
						
							|  |  |  |     return s_; | 
					
						
							| 
									
										
										
										
											2015-03-03 12:34:56 +08:00
										 |  |  |   } | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-03-03 13:08:41 +08:00
										 |  |  |   /// Convert to a rigid body pose (R, s*t)
 | 
					
						
							| 
									
										
										
										
											2016-02-08 06:05:59 +08:00
										 |  |  |   /// TODO(frank): why is this here? Red flag! Definitely don't have it as a cast.
 | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  |   operator Pose3() const; | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /// Dimensionality of tangent space = 7 DOF - used to autodetect sizes
 | 
					
						
							|  |  |  |   inline static size_t Dim() { | 
					
						
							|  |  |  |     return 7; | 
					
						
							| 
									
										
										
										
											2015-03-03 12:34:56 +08:00
										 |  |  |   } | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /// Dimensionality of tangent space = 7 DOF
 | 
					
						
							|  |  |  |   inline size_t dim() const { | 
					
						
							|  |  |  |     return 7; | 
					
						
							| 
									
										
										
										
											2015-03-03 12:34:56 +08:00
										 |  |  |   } | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  |   /// @}
 | 
					
						
							| 
									
										
										
										
											2015-06-11 04:36:56 +08:00
										 |  |  |   /// @name Helper functions
 | 
					
						
							|  |  |  |   /// @{
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// Calculate expmap and logmap coefficients.
 | 
					
						
							|  |  |  | private: | 
					
						
							| 
									
										
										
										
											2016-02-08 06:05:59 +08:00
										 |  |  |   static Matrix3 GetV(Vector3 w, double lambda); | 
					
						
							| 
									
										
										
										
											2015-06-11 04:36:56 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /// @}
 | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | template<> | 
					
						
							| 
									
										
										
										
											2016-02-08 07:02:07 +08:00
										 |  |  | inline Matrix wedge<Similarity3>(const Vector& xi) { | 
					
						
							|  |  |  |   return Similarity3::wedge(xi); | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2015-06-27 06:24:30 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | template<> | 
					
						
							| 
									
										
										
										
											2016-02-08 07:02:07 +08:00
										 |  |  | struct traits<Similarity3> : public internal::LieGroup<Similarity3> {}; | 
					
						
							| 
									
										
										
										
											2015-06-27 06:24:30 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-02-08 07:02:07 +08:00
										 |  |  | template<> | 
					
						
							|  |  |  | struct traits<const Similarity3> : public internal::LieGroup<Similarity3> {}; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | } // namespace gtsam
 |