| 
									
										
										
										
											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> { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** Pose Concept requirements */ | 
					
						
							|  |  |  |   typedef Rot3 Rotation; | 
					
						
							|  |  |  |   typedef Point3 Translation; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | private: | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  |   Rotation R_; | 
					
						
							|  |  |  |   Translation t_; | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  |   double s_; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | public: | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  |   /// @name Constructors
 | 
					
						
							|  |  |  |   /// @{
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  |   Similarity3(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// Construct pure scaling
 | 
					
						
							|  |  |  |   Similarity3(double s); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// Construct from GTSAM types
 | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  |   Similarity3(const Rotation& R, const Translation& t, double s); | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /// Construct from Eigen types
 | 
					
						
							|  |  |  |   Similarity3(const Matrix3& R, const Vector3& t, double s); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											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
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  |   /// Compare with standard tolerance
 | 
					
						
							|  |  |  |   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-02-27 04:10:59 +08:00
										 |  |  |   /// Return the inverse
 | 
					
						
							|  |  |  |   Similarity3 inverse() const; | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  |   Translation transform_from(const Translation& p) const; | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  |   /** syntactic sugar for transform_from */ | 
					
						
							|  |  |  |   inline Translation operator*(const Translation& p) const; | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  |   Similarity3 operator*(const Similarity3& T) const; | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  |   /// @}
 | 
					
						
							|  |  |  |   /// @name Standard interface
 | 
					
						
							|  |  |  |   /// @{
 | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  |   /// Return a GTSAM rotation
 | 
					
						
							|  |  |  |   const Rotation& rotation() const { | 
					
						
							|  |  |  |     return R_; | 
					
						
							|  |  |  |   }; | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  |   /// Return a GTSAM translation
 | 
					
						
							|  |  |  |   const Translation& translation() const { | 
					
						
							|  |  |  |     return t_; | 
					
						
							|  |  |  |   }; | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  |   /// Return the scale
 | 
					
						
							|  |  |  |   double scale() const { | 
					
						
							|  |  |  |     return s_; | 
					
						
							|  |  |  |   }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// Convert to a rigid body pose
 | 
					
						
							|  |  |  |   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; | 
					
						
							|  |  |  |   }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// Dimensionality of tangent space = 7 DOF
 | 
					
						
							|  |  |  |   inline size_t dim() const { | 
					
						
							|  |  |  |     return 7; | 
					
						
							|  |  |  |   }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  |   /// @}
 | 
					
						
							|  |  |  |   /// @name Chart
 | 
					
						
							|  |  |  |   /// @{
 | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /// Update Similarity transform via 7-dim vector in tangent space
 | 
					
						
							|  |  |  |   struct ChartAtOrigin { | 
					
						
							|  |  |  |     static Similarity3 Retract(const Vector7& v,  ChartJacobian H = boost::none); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// 7-dimensional vector v in tangent space that makes other = this->retract(v)
 | 
					
						
							|  |  |  |   static Vector7 Local(const Similarity3& other,  ChartJacobian H = boost::none); | 
					
						
							|  |  |  |   }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  |   /// Project from one tangent space to another
 | 
					
						
							|  |  |  |   Matrix7 AdjointMap() const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// @}
 | 
					
						
							|  |  |  |   /// @name Stubs
 | 
					
						
							|  |  |  |   /// @{
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// Not currently implemented, required because this is a lie group
 | 
					
						
							|  |  |  |   static Vector7 Logmap(const Similarity3& s, OptionalJacobian<7, 7> Hm = boost::none); | 
					
						
							|  |  |  |   static Similarity3 Expmap(const Vector7& v, OptionalJacobian<7, 7> Hm = boost::none); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  |   using LieGroup<Similarity3, 7>::inverse; // version with derivative
 | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | template<> | 
					
						
							| 
									
										
										
										
											2015-05-26 13:04:04 +08:00
										 |  |  | struct traits<Similarity3> : public internal::LieGroup<Similarity3> {}; | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | } |