| 
									
										
										
										
											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.cpp | 
					
						
							|  |  |  |  * @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
										 |  |  | #include <gtsam_unstable/geometry/Similarity3.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam/geometry/Pose3.h>
 | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | #include <gtsam/base/Manifold.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | namespace gtsam { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | Similarity3::Similarity3() : | 
					
						
							| 
									
										
										
										
											2016-02-11 09:48:52 +08:00
										 |  |  |     t_(0,0,0), s_(1) { | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-27 04:10:59 +08:00
										 |  |  | Similarity3::Similarity3(double s) : | 
					
						
							| 
									
										
										
										
											2016-02-11 09:48:52 +08:00
										 |  |  |     t_(0,0,0), s_(s) { | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-03-03 12:09:44 +08:00
										 |  |  | Similarity3::Similarity3(const Rot3& R, const Point3& t, double s) : | 
					
						
							|  |  |  |     R_(R), t_(t), s_(s) { | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-03-03 23:42:31 +08:00
										 |  |  | Similarity3::Similarity3(const Matrix3& R, const Vector3& t, double s) : | 
					
						
							|  |  |  |     R_(R), t_(t), s_(s) { | 
					
						
							| 
									
										
										
										
											2015-02-25 23:59:25 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-02-08 07:02:07 +08:00
										 |  |  | Similarity3::Similarity3(const Matrix4& T) : | 
					
						
							|  |  |  |     R_(T.topLeftCorner<3, 3>()), t_(T.topRightCorner<3, 1>()), s_(1.0 / T(3, 3)) { | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-02-08 06:05:59 +08:00
										 |  |  | bool Similarity3::equals(const Similarity3& other, double tol) const { | 
					
						
							| 
									
										
										
										
											2016-02-12 11:03:11 +08:00
										 |  |  |   return R_.equals(other.R_, tol) && traits<Point3>::Equals(t_, other.t_, tol) | 
					
						
							| 
									
										
										
										
											2016-02-08 06:05:59 +08:00
										 |  |  |       && s_ < (other.s_ + tol) && s_ > (other.s_ - tol); | 
					
						
							| 
									
										
										
										
											2015-03-03 12:09:44 +08:00
										 |  |  | } | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | bool Similarity3::operator==(const Similarity3& other) const { | 
					
						
							| 
									
										
										
										
											2016-02-08 06:05:59 +08:00
										 |  |  |   return R_.matrix() == other.R_.matrix() && t_ == other.t_ && s_ == other.s_; | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-03-03 23:42:31 +08:00
										 |  |  | void Similarity3::print(const std::string& s) const { | 
					
						
							|  |  |  |   std::cout << std::endl; | 
					
						
							|  |  |  |   std::cout << s; | 
					
						
							|  |  |  |   rotation().print("R:\n"); | 
					
						
							| 
									
										
										
										
											2016-02-12 11:03:11 +08:00
										 |  |  |   std::cout << "t: " << translation().transpose() << "s: " << scale() << std::endl; | 
					
						
							| 
									
										
										
										
											2015-03-03 23:42:31 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | Similarity3 Similarity3::identity() { | 
					
						
							|  |  |  |   return Similarity3(); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | Similarity3 Similarity3::operator*(const Similarity3& T) const { | 
					
						
							|  |  |  |   return Similarity3(R_ * T.R_, ((1.0 / T.s_) * t_) + R_ * T.t_, s_ * T.s_); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | Similarity3 Similarity3::inverse() const { | 
					
						
							| 
									
										
										
										
											2016-02-08 16:12:19 +08:00
										 |  |  |   const Rot3 Rt = R_.inverse(); | 
					
						
							|  |  |  |   const Point3 sRt = Rt * (-s_ * t_); | 
					
						
							| 
									
										
										
										
											2015-03-03 23:42:31 +08:00
										 |  |  |   return Similarity3(Rt, sRt, 1.0 / s_); | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2019-05-17 02:33:58 +08:00
										 |  |  | Point3 Similarity3::transformFrom(const Point3& p, //
 | 
					
						
							| 
									
										
										
										
											2015-03-03 12:34:56 +08:00
										 |  |  |     OptionalJacobian<3, 7> H1, OptionalJacobian<3, 3> H2) const { | 
					
						
							| 
									
										
										
										
											2016-02-08 16:12:19 +08:00
										 |  |  |   const Point3 q = R_ * p + t_; | 
					
						
							| 
									
										
										
										
											2015-03-03 13:58:54 +08:00
										 |  |  |   if (H1) { | 
					
						
							| 
									
										
										
										
											2016-02-08 14:26:10 +08:00
										 |  |  |     // For this derivative, see LieGroups.pdf
 | 
					
						
							|  |  |  |     const Matrix3 sR = s_ * R_.matrix(); | 
					
						
							| 
									
										
										
										
											2016-02-08 16:12:19 +08:00
										 |  |  |     const Matrix3 DR = sR * skewSymmetric(-p.x(), -p.y(), -p.z()); | 
					
						
							| 
									
										
										
										
											2016-02-12 11:03:11 +08:00
										 |  |  |     *H1 << DR, sR, sR * p; | 
					
						
							| 
									
										
										
										
											2015-03-03 13:58:54 +08:00
										 |  |  |   } | 
					
						
							| 
									
										
										
										
											2015-03-03 13:08:57 +08:00
										 |  |  |   if (H2) | 
					
						
							|  |  |  |     *H2 = s_ * R_.matrix(); // just 3*3 sub-block of matrix()
 | 
					
						
							| 
									
										
										
										
											2016-02-08 06:05:59 +08:00
										 |  |  |   return s_ * q; | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-03-03 23:42:31 +08:00
										 |  |  | Point3 Similarity3::operator*(const Point3& p) const { | 
					
						
							| 
									
										
										
										
											2019-05-17 02:33:58 +08:00
										 |  |  |   return transformFrom(p); | 
					
						
							| 
									
										
										
										
											2015-03-03 13:08:23 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-02-08 06:05:59 +08:00
										 |  |  | Matrix4 Similarity3::wedge(const Vector7& xi) { | 
					
						
							|  |  |  |   // http://www.ethaneade.org/latex2html/lie/node29.html
 | 
					
						
							|  |  |  |   const auto w = xi.head<3>(); | 
					
						
							|  |  |  |   const auto u = xi.segment<3>(3); | 
					
						
							| 
									
										
										
										
											2016-02-08 16:12:19 +08:00
										 |  |  |   const double lambda = xi[6]; | 
					
						
							| 
									
										
										
										
											2016-02-08 06:05:59 +08:00
										 |  |  |   Matrix4 W; | 
					
						
							|  |  |  |   W << skewSymmetric(w), u, 0, 0, 0, -lambda; | 
					
						
							|  |  |  |   return W; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-03-03 12:09:44 +08:00
										 |  |  | Matrix7 Similarity3::AdjointMap() const { | 
					
						
							| 
									
										
										
										
											2016-02-08 06:05:59 +08:00
										 |  |  |   // http://www.ethaneade.org/latex2html/lie/node30.html
 | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  |   const Matrix3 R = R_.matrix(); | 
					
						
							| 
									
										
										
										
											2016-02-12 11:03:11 +08:00
										 |  |  |   const Vector3 t = t_; | 
					
						
							| 
									
										
										
										
											2016-02-08 07:02:07 +08:00
										 |  |  |   const Matrix3 A = s_ * skewSymmetric(t) * R; | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  |   Matrix7 adj; | 
					
						
							| 
									
										
										
										
											2016-02-08 16:12:19 +08:00
										 |  |  |   adj << R, Z_3x3, Matrix31::Zero(), // 3*7
 | 
					
						
							|  |  |  |   A, s_ * R, -s_ * t, // 3*7
 | 
					
						
							|  |  |  |   Matrix16::Zero(), 1; // 1*7
 | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  |   return adj; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-02-08 06:05:59 +08:00
										 |  |  | Matrix3 Similarity3::GetV(Vector3 w, double lambda) { | 
					
						
							| 
									
										
										
										
											2016-02-08 07:02:07 +08:00
										 |  |  |   // http://www.ethaneade.org/latex2html/lie/node29.html
 | 
					
						
							| 
									
										
										
										
											2016-02-08 16:12:19 +08:00
										 |  |  |   const double theta2 = w.transpose() * w; | 
					
						
							|  |  |  |   double Y, Z, W; | 
					
						
							|  |  |  |   if (theta2 > 1e-9) { | 
					
						
							|  |  |  |     const double theta = sqrt(theta2); | 
					
						
							| 
									
										
										
										
											2016-02-08 07:02:07 +08:00
										 |  |  |     const double X = sin(theta) / theta; | 
					
						
							| 
									
										
										
										
											2016-02-08 16:12:19 +08:00
										 |  |  |     Y = (1 - cos(theta)) / theta2; | 
					
						
							|  |  |  |     Z = (1 - X) / theta2; | 
					
						
							|  |  |  |     W = (0.5 - Y) / theta2; | 
					
						
							|  |  |  |   } else { | 
					
						
							|  |  |  |     // Taylor series expansion for theta=0, X not needed (as is 1)
 | 
					
						
							|  |  |  |     Y = 0.5 - theta2 / 24.0; | 
					
						
							|  |  |  |     Z = 1.0 / 6.0 - theta2 / 120.0; | 
					
						
							|  |  |  |     W = 1.0 / 24.0 - theta2 / 720.0; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  |   const double lambda2 = lambda * lambda, lambda3 = lambda2 * lambda; | 
					
						
							|  |  |  |   double A, alpha = 0.0, beta, mu; | 
					
						
							|  |  |  |   if (lambda2 > 1e-9) { | 
					
						
							|  |  |  |     A = (1.0 - exp(-lambda)) / lambda; | 
					
						
							|  |  |  |     alpha = 1.0 / (1.0 + theta2 / lambda2); | 
					
						
							|  |  |  |     beta = (exp(-lambda) - 1 + lambda) / lambda2; | 
					
						
							|  |  |  |     mu = (1 - lambda + (0.5 * lambda2) - exp(-lambda)) / lambda3; | 
					
						
							| 
									
										
										
										
											2016-02-08 06:05:59 +08:00
										 |  |  |   } else { | 
					
						
							| 
									
										
										
										
											2016-02-08 16:12:19 +08:00
										 |  |  |     A = 1.0 - lambda / 2.0 + lambda2 / 6.0; | 
					
						
							|  |  |  |     beta = 0.5 - lambda / 6.0 + lambda2 / 24.0 - lambda3 / 120.0; | 
					
						
							|  |  |  |     mu = 1.0 / 6.0 - lambda / 24.0 + lambda2 / 120.0 - lambda3 / 720.0; | 
					
						
							| 
									
										
										
										
											2015-06-11 04:36:56 +08:00
										 |  |  |   } | 
					
						
							| 
									
										
										
										
											2016-02-08 16:12:19 +08:00
										 |  |  |   const double gamma = Y - (lambda * Z), upsilon = Z - (lambda * W); | 
					
						
							|  |  |  |   const double B = alpha * (beta - gamma) + gamma; | 
					
						
							|  |  |  |   const double C = alpha * (mu - upsilon) + upsilon; | 
					
						
							| 
									
										
										
										
											2016-02-08 07:02:07 +08:00
										 |  |  |   const Matrix3 Wx = skewSymmetric(w[0], w[1], w[2]); | 
					
						
							|  |  |  |   return A * I_3x3 + B * Wx + C * Wx * Wx; | 
					
						
							| 
									
										
										
										
											2015-06-11 04:36:56 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-02-08 07:02:07 +08:00
										 |  |  | Vector7 Similarity3::Logmap(const Similarity3& T, OptionalJacobian<7, 7> Hm) { | 
					
						
							|  |  |  |   // To get the logmap, calculate w and lambda, then solve for u as shown by Ethan at
 | 
					
						
							| 
									
										
										
										
											2015-06-10 23:01:34 +08:00
										 |  |  |   // www.ethaneade.org/latex2html/lie/node29.html
 | 
					
						
							| 
									
										
										
										
											2016-02-08 07:02:07 +08:00
										 |  |  |   const Vector3 w = Rot3::Logmap(T.R_); | 
					
						
							|  |  |  |   const double lambda = log(T.s_); | 
					
						
							| 
									
										
										
										
											2015-06-10 23:01:34 +08:00
										 |  |  |   Vector7 result; | 
					
						
							| 
									
										
										
										
											2016-02-12 11:03:11 +08:00
										 |  |  |   result << w, GetV(w, lambda).inverse() * T.t_, lambda; | 
					
						
							| 
									
										
										
										
											2015-06-27 04:01:26 +08:00
										 |  |  |   if (Hm) { | 
					
						
							| 
									
										
										
										
											2016-02-08 07:02:07 +08:00
										 |  |  |     throw std::runtime_error("Similarity3::Logmap: derivative not implemented"); | 
					
						
							| 
									
										
										
										
											2015-06-27 04:01:26 +08:00
										 |  |  |   } | 
					
						
							| 
									
										
										
										
											2015-06-10 23:01:34 +08:00
										 |  |  |   return result; | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-03-03 23:42:31 +08:00
										 |  |  | Similarity3 Similarity3::Expmap(const Vector7& v, OptionalJacobian<7, 7> Hm) { | 
					
						
							| 
									
										
										
										
											2016-02-08 06:05:59 +08:00
										 |  |  |   const auto w = v.head<3>(); | 
					
						
							|  |  |  |   const auto u = v.segment<3>(3); | 
					
						
							| 
									
										
										
										
											2016-02-08 07:02:07 +08:00
										 |  |  |   const double lambda = v[6]; | 
					
						
							| 
									
										
										
										
											2015-06-27 04:01:26 +08:00
										 |  |  |   if (Hm) { | 
					
						
							| 
									
										
										
										
											2016-02-08 07:02:07 +08:00
										 |  |  |     throw std::runtime_error("Similarity3::Expmap: derivative not implemented"); | 
					
						
							| 
									
										
										
										
											2015-06-27 04:01:26 +08:00
										 |  |  |   } | 
					
						
							| 
									
										
										
										
											2016-02-08 06:05:59 +08:00
										 |  |  |   const Matrix3 V = GetV(w, lambda); | 
					
						
							|  |  |  |   return Similarity3(Rot3::Expmap(w), Point3(V * u), exp(lambda)); | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-04-13 03:38:40 +08:00
										 |  |  | std::ostream &operator<<(std::ostream &os, const Similarity3& p) { | 
					
						
							| 
									
										
										
										
											2016-02-08 06:05:59 +08:00
										 |  |  |   os << "[" << p.rotation().xyz().transpose() << " " | 
					
						
							| 
									
										
										
										
											2016-02-12 11:03:11 +08:00
										 |  |  |       << p.translation().transpose() << " " << p.scale() << "]\';"; | 
					
						
							| 
									
										
										
										
											2015-04-13 03:38:40 +08:00
										 |  |  |   return os; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-03-03 23:42:31 +08:00
										 |  |  | const Matrix4 Similarity3::matrix() const { | 
					
						
							|  |  |  |   Matrix4 T; | 
					
						
							| 
									
										
										
										
											2016-02-12 11:03:11 +08:00
										 |  |  |   T.topRows<3>() << R_.matrix(), t_; | 
					
						
							| 
									
										
										
										
											2016-02-08 16:12:19 +08:00
										 |  |  |   T.bottomRows<1>() << 0, 0, 0, 1.0 / s_; | 
					
						
							| 
									
										
										
										
											2015-03-03 23:42:31 +08:00
										 |  |  |   return T; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | Similarity3::operator Pose3() const { | 
					
						
							|  |  |  |   return Pose3(R_, s_ * t_); | 
					
						
							| 
									
										
										
										
											2015-02-19 14:21:20 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-02-08 16:12:19 +08:00
										 |  |  | } // namespace gtsam
 |