Similarity3.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
20 
21 #include <gtsam/geometry/Pose3.h>
22 #include <gtsam/base/Manifold.h>
24 
25 namespace gtsam {
26 
27 using std::vector;
28 
29 namespace {
31 static Point3Pairs subtractCentroids(const Point3Pairs &abPointPairs,
32  const Point3Pair &centroids) {
33  Point3Pairs d_abPointPairs;
34  for (const Point3Pair& abPair : abPointPairs) {
35  Point3 da = abPair.first - centroids.first;
36  Point3 db = abPair.second - centroids.second;
37  d_abPointPairs.emplace_back(da, db);
38  }
39  return d_abPointPairs;
40 }
41 
43 static const double calculateScale(const Point3Pairs &d_abPointPairs,
44  const Rot3 &aRb) {
45  double x = 0, y = 0;
46  Point3 da, db;
47  for (const Point3Pair& d_abPair : d_abPointPairs) {
48  std::tie(da, db) = d_abPair;
49  const Vector3 da_prime = aRb * db;
50  y += da.transpose() * da_prime;
51  x += da_prime.transpose() * da_prime;
52  }
53  const double s = y / x;
54  return s;
55 }
56 
58 static Matrix3 calculateH(const Point3Pairs &d_abPointPairs) {
59  Matrix3 H = Z_3x3;
60  for (const Point3Pair& d_abPair : d_abPointPairs) {
61  H += d_abPair.first * d_abPair.second.transpose();
62  }
63  return H;
64 }
65 
67 // given a known or estimated rotation and point centroids.
68 static Similarity3 align(const Point3Pairs &d_abPointPairs, const Rot3 &aRb,
69  const Point3Pair &centroids) {
70  const double s = calculateScale(d_abPointPairs, aRb);
71  // dividing aTb by s is required because the registration cost function
72  // minimizes ||a - sRb - t||, whereas Sim(3) computes s(Rb + t)
73  const Point3 aTb = (centroids.first - s * (aRb * centroids.second)) / s;
74  return Similarity3(aRb, aTb, s);
75 }
76 
78 // Refer to: http://www5.informatik.uni-erlangen.de/Forschung/Publikationen/2005/Zinsser05-PSR.pdf Chapter 3
79 static Similarity3 alignGivenR(const Point3Pairs &abPointPairs,
80  const Rot3 &aRb) {
81  auto centroids = means(abPointPairs);
82  auto d_abPointPairs = subtractCentroids(abPointPairs, centroids);
83  return align(d_abPointPairs, aRb, centroids);
84 }
85 } // namespace
86 
88  t_(0,0,0), s_(1) {
89 }
90 
92  t_(0,0,0), s_(s) {
93 }
94 
95 Similarity3::Similarity3(const Rot3& R, const Point3& t, double s) :
96  R_(R), t_(t), s_(s) {
97 }
98 
99 Similarity3::Similarity3(const Matrix3& R, const Vector3& t, double s) :
100  R_(R), t_(t), s_(s) {
101 }
102 
103 Similarity3::Similarity3(const Matrix4& T) :
104  R_(T.topLeftCorner<3, 3>()), t_(T.topRightCorner<3, 1>()), s_(1.0 / T(3, 3)) {
105 }
106 
107 bool Similarity3::equals(const Similarity3& other, double tol) const {
108  return R_.equals(other.R_, tol) && traits<Point3>::Equals(t_, other.t_, tol)
109  && s_ < (other.s_ + tol) && s_ > (other.s_ - tol);
110 }
111 
112 bool Similarity3::operator==(const Similarity3& other) const {
113  return R_.matrix() == other.R_.matrix() && t_ == other.t_ && s_ == other.s_;
114 }
115 
116 void Similarity3::print(const std::string& s) const {
117  std::cout << std::endl;
118  std::cout << s;
119  rotation().print("\nR:\n");
120  std::cout << "t: " << translation().transpose() << " s: " << scale() << std::endl;
121 }
122 
124  return Similarity3();
125 }
127  return Similarity3(R_ * S.R_, ((1.0 / S.s_) * t_) + R_ * S.t_, s_ * S.s_);
128 }
129 
131  const Rot3 Rt = R_.inverse();
132  const Point3 sRt = Rt * (-s_ * t_);
133  return Similarity3(Rt, sRt, 1.0 / s_);
134 }
135 
138  const Point3 q = R_ * p + t_;
139  if (H1) {
140  // For this derivative, see LieGroups.pdf
141  const Matrix3 sR = s_ * R_.matrix();
142  const Matrix3 DR = sR * skewSymmetric(-p.x(), -p.y(), -p.z());
143  *H1 << DR, sR, sR * p;
144  }
145  if (H2)
146  *H2 = s_ * R_.matrix(); // just 3*3 sub-block of matrix()
147  return s_ * q;
148 }
149 
151  Rot3 R = R_.compose(T.rotation());
152  Point3 t = Point3(s_ * (R_ * T.translation() + t_));
153  return Pose3(R, t);
154 }
155 
157  return transformFrom(p);
158 }
159 
161  // Refer to Chapter 3 of
162  // http://www5.informatik.uni-erlangen.de/Forschung/Publikationen/2005/Zinsser05-PSR.pdf
163  if (abPointPairs.size() < 3)
164  throw std::runtime_error("input should have at least 3 pairs of points");
165  auto centroids = means(abPointPairs);
166  auto d_abPointPairs = subtractCentroids(abPointPairs, centroids);
167  Matrix3 H = calculateH(d_abPointPairs);
168  // ClosestTo finds rotation matrix closest to H in Frobenius sense
169  Rot3 aRb = Rot3::ClosestTo(H);
170  return align(d_abPointPairs, aRb, centroids);
171 }
172 
173 Similarity3 Similarity3::Align(const vector<Pose3Pair> &abPosePairs) {
174  const size_t n = abPosePairs.size();
175  if (n < 2)
176  throw std::runtime_error("input should have at least 2 pairs of poses");
177 
178  // calculate rotation
179  vector<Rot3> rotations;
180  Point3Pairs abPointPairs;
181  rotations.reserve(n);
182  abPointPairs.reserve(n);
183  // Below denotes the pose of the i'th object/camera/etc in frame "a" or frame "b"
184  Pose3 aTi, bTi;
185  for (const Pose3Pair &abPair : abPosePairs) {
186  std::tie(aTi, bTi) = abPair;
187  const Rot3 aRb = aTi.rotation().compose(bTi.rotation().inverse());
188  rotations.emplace_back(aRb);
189  abPointPairs.emplace_back(aTi.translation(), bTi.translation());
190  }
191  const Rot3 aRb_estimate = FindKarcherMean<Rot3>(rotations);
192 
193  return alignGivenR(abPointPairs, aRb_estimate);
194 }
195 
196 Matrix4 Similarity3::wedge(const Vector7 &xi) {
197  // http://www.ethaneade.org/latex2html/lie/node29.html
198  const auto w = xi.head<3>();
199  const auto u = xi.segment<3>(3);
200  const double lambda = xi[6];
201  Matrix4 W;
202  W << skewSymmetric(w), u, 0, 0, 0, -lambda;
203  return W;
204 }
205 
206 Matrix7 Similarity3::AdjointMap() const {
207  // http://www.ethaneade.org/latex2html/lie/node30.html
208  const Matrix3 R = R_.matrix();
209  const Vector3 t = t_;
210  const Matrix3 A = s_ * skewSymmetric(t) * R;
211  Matrix7 adj;
212  adj << R, Z_3x3, Matrix31::Zero(), // 3*7
213  A, s_ * R, -s_ * t, // 3*7
214  Matrix16::Zero(), 1; // 1*7
215  return adj;
216 }
217 
218 Matrix3 Similarity3::GetV(Vector3 w, double lambda) {
219  // http://www.ethaneade.org/latex2html/lie/node29.html
220  const double theta2 = w.transpose() * w;
221  double Y, Z, W;
222  if (theta2 > 1e-9) {
223  const double theta = sqrt(theta2);
224  const double X = sin(theta) / theta;
225  Y = (1 - cos(theta)) / theta2;
226  Z = (1 - X) / theta2;
227  W = (0.5 - Y) / theta2;
228  } else {
229  // Taylor series expansion for theta=0, X not needed (as is 1)
230  Y = 0.5 - theta2 / 24.0;
231  Z = 1.0 / 6.0 - theta2 / 120.0;
232  W = 1.0 / 24.0 - theta2 / 720.0;
233  }
234  const double lambda2 = lambda * lambda, lambda3 = lambda2 * lambda;
235  const double expMinLambda = exp(-lambda);
236  double A, alpha = 0.0, beta, mu;
237  if (lambda2 > 1e-9) {
238  A = (1.0 - expMinLambda) / lambda;
239  alpha = 1.0 / (1.0 + theta2 / lambda2);
240  beta = (expMinLambda - 1 + lambda) / lambda2;
241  mu = (1 - lambda + (0.5 * lambda2) - expMinLambda) / lambda3;
242  } else {
243  A = 1.0 - lambda / 2.0 + lambda2 / 6.0;
244  beta = 0.5 - lambda / 6.0 + lambda2 / 24.0 - lambda3 / 120.0;
245  mu = 1.0 / 6.0 - lambda / 24.0 + lambda2 / 120.0 - lambda3 / 720.0;
246  }
247  const double gamma = Y - (lambda * Z), upsilon = Z - (lambda * W);
248  const double B = alpha * (beta - gamma) + gamma;
249  const double C = alpha * (mu - upsilon) + upsilon;
250  const Matrix3 Wx = skewSymmetric(w[0], w[1], w[2]);
251  return A * I_3x3 + B * Wx + C * Wx * Wx;
252 }
253 
255  // To get the logmap, calculate w and lambda, then solve for u as shown by Ethan at
256  // www.ethaneade.org/latex2html/lie/node29.html
257  const Vector3 w = Rot3::Logmap(T.R_);
258  const double lambda = log(T.s_);
259  Vector7 result;
260  result << w, GetV(w, lambda).inverse() * T.t_, lambda;
261  if (Hm) {
262  throw std::runtime_error("Similarity3::Logmap: derivative not implemented");
263  }
264  return result;
265 }
266 
268  const auto w = v.head<3>();
269  const auto u = v.segment<3>(3);
270  const double lambda = v[6];
271  if (Hm) {
272  throw std::runtime_error("Similarity3::Expmap: derivative not implemented");
273  }
274  const Matrix3 V = GetV(w, lambda);
275  return Similarity3(Rot3::Expmap(w), Point3(V * u), exp(lambda));
276 }
277 
278 std::ostream &operator<<(std::ostream &os, const Similarity3& p) {
279  os << "[" << p.rotation().xyz().transpose() << " "
280  << p.translation().transpose() << " " << p.scale() << "]\';";
281  return os;
282 }
283 
284 const Matrix4 Similarity3::matrix() const {
285  Matrix4 T;
286  T.topRows<3>() << R_.matrix(), t_;
287  T.bottomRows<1>() << 0, 0, 0, 1.0 / s_;
288  return T;
289 }
290 
291 Similarity3::operator Pose3() const {
292  return Pose3(R_, s_ * t_);
293 }
294 
295 } // namespace gtsam
GTSAM_EXPORT bool operator==(const Similarity3 &other) const
Exact equality.
GTSAM_EXPORT const Matrix4 matrix() const
Calculate 4*4 matrix group equivalent.
Scalar * y
static GTSAM_EXPORT Vector7 Logmap(const Similarity3 &s, OptionalJacobian< 7, 7 > Hm=boost::none)
Eigen::Vector3d Vector3
Definition: Vector.h:43
static GTSAM_EXPORT Similarity3 Expmap(const Vector7 &v, OptionalJacobian< 7, 7 > Hm=boost::none)
static GTSAM_EXPORT Similarity3 identity()
Return an identity transform.
EIGEN_DEVICE_FUNC const ExpReturnType exp() const
double mu
ArrayXcf v
Definition: Cwise_arg.cpp:1
int n
Rot2 R(Rot2::fromAngle(0.1))
EIGEN_DEVICE_FUNC const LogReturnType log() const
double scale() const
Return the scale.
Definition: Similarity3.h:196
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
Key W(std::uint64_t j)
std::vector< Point3Pair > Point3Pairs
Definition: Point3.h:41
static GTSAM_EXPORT Matrix4 wedge(const Vector7 &xi)
Matrix3 matrix() const
Definition: Rot3M.cpp:219
const Point3 & translation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get translation
Definition: Pose3.cpp:259
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
GTSAM_EXPORT bool equals(const Similarity3 &sim, double tol) const
Compare with tolerance.
Rot2 theta
Matrix< SCALARB, Dynamic, Dynamic > B
Definition: bench_gemm.cpp:36
Rot3 inverse() const
inverse of a rotation
Definition: Rot3.h:311
mat1 topRightCorner(size/2, size/2)
Vector3 xyz(OptionalJacobian< 3, 3 > H=boost::none) const
Definition: Rot3.cpp:161
EIGEN_DEVICE_FUNC const CosReturnType cos() const
#define Z
Definition: icosphere.cpp:21
Class compose(const Class &g) const
Definition: Lie.h:47
Values result
const mpreal gamma(const mpreal &x, mp_rnd_t r=mpreal::get_default_rnd())
Definition: mpreal.h:2262
Key S(std::uint64_t j)
bool equals(const Rot3 &p, double tol=1e-9) const
Definition: Rot3.cpp:100
GTSAM_EXPORT Similarity3 operator*(const Similarity3 &S) const
Composition.
Base class and basic functions for Manifold types.
GTSAM_EXPORT Similarity3()
Default constructor.
Definition: Similarity3.cpp:87
void print(const std::string &s="") const
Definition: Rot3.cpp:34
GTSAM_EXPORT void print(const std::string &s) const
Print with optional string.
const Point3 & translation() const
Return a GTSAM translation.
Definition: Similarity3.h:191
Eigen::Triplet< double > T
RealScalar alpha
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
EIGEN_DEVICE_FUNC const Scalar & q
static GTSAM_EXPORT Similarity3 Align(const std::vector< Point3Pair > &abPointPairs)
static Rot3 Expmap(const Vector3 &v, OptionalJacobian< 3, 3 > H=boost::none)
Definition: Rot3.h:377
RowVector3d w
cout<< "The eigenvalues of A are:"<< endl<< ces.eigenvalues()<< endl;cout<< "The matrix of eigenvectors, V, is:"<< endl<< ces.eigenvectors()<< endl<< endl;complex< float > lambda
Matrix< Scalar, Dynamic, Dynamic > C
Definition: bench_gemm.cpp:37
Vector xi
Definition: testPose2.cpp:150
traits
Definition: chartTesting.h:28
boost::optional< Pose2 > align(const vector< Point2Pair > &pairs)
Definition: Pose2.cpp:314
Matrix3 skewSymmetric(double wx, double wy, double wz)
Definition: base/Matrix.h:404
GTSAM_EXPORT Similarity3 inverse() const
Return the inverse.
const Rot3 & rotation() const
Return a GTSAM rotation.
Definition: Similarity3.h:186
ofstream os("timeSchurFactors.csv")
static Vector3 Logmap(const Rot3 &R, OptionalJacobian< 3, 3 > H=boost::none)
Definition: Rot3M.cpp:158
GTSAM_EXPORT Point3 transformFrom(const Point3 &p, OptionalJacobian< 3, 7 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
Action on a point p is s*(R*p+t)
Point3Pair means(const std::vector< Point3Pair > &abPointPairs)
Calculate the two means of a set of Point3 pairs.
Definition: Point3.cpp:78
float * p
static Matrix3 GetV(Vector3 w, double lambda)
Calculate expmap and logmap coefficients.
static Rot3 ClosestTo(const Matrix3 &M)
Definition: Rot3.h:274
EIGEN_DEVICE_FUNC const SinReturnType sin() const
const G double tol
Definition: Group.h:83
Vector3 Point3
Definition: Point3.h:35
std::pair< Pose3, Pose3 > Pose3Pair
Definition: Pose3.h:391
#define X
Definition: icosphere.cpp:20
Implementation of Similarity3 transform.
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
3D Pose
Point2 t(10, 10)
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get rotation
Definition: Pose3.cpp:266
GTSAM_EXPORT Matrix7 AdjointMap() const
Project from one tangent space to another.
Eigen::Block< Derived > topLeftCorner(MatrixBase< Derived > &m, int rows, int cols)
Definition: class_Block.cpp:8
std::pair< Point3, Point3 > Point3Pair
Definition: Point3.h:38
GTSAM_EXPORT friend std::ostream & operator<<(std::ostream &os, const Similarity3 &p)


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:44:02