SOn.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010-2019, 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 #include <gtsam/geometry/SOn.h>
21 
22 namespace gtsam {
23 
24 template <>
25 GTSAM_EXPORT void SOn::Hat(const Vector &xi, Eigen::Ref<Matrix> X) {
26  size_t n = AmbientDim(xi.size());
27  if (n < 2)
28  throw std::invalid_argument("SO<N>::Hat: n<2 not supported");
29  else if (n == 2) {
30  // Handle SO(2) case as recursion bottom
31  assert(xi.size() == 1);
32  X << 0, -xi(0), xi(0), 0;
33  } else {
34  // Recursively call SO(n-1) call for top-left block
35  const size_t dmin = (n - 1) * (n - 2) / 2;
36  Hat(xi.tail(dmin), X.topLeftCorner(n - 1, n - 1));
37 
38  // determine sign of last element (signs alternate)
39  double sign = pow(-1.0, xi.size());
40  // Now fill last row and column
41  for (size_t i = 0; i < n - 1; i++) {
42  const size_t j = n - 2 - i;
43  X(n - 1, j) = -sign * xi(i);
44  X(j, n - 1) = -X(n - 1, j);
45  sign = -sign;
46  }
47  X(n - 1, n - 1) = 0; // bottom-right
48  }
49 }
50 
51 template <> GTSAM_EXPORT Matrix SOn::Hat(const Vector &xi) {
52  size_t n = AmbientDim(xi.size());
53  Matrix X(n, n); // allocate space for n*n skew-symmetric matrix
54  SOn::Hat(xi, X);
55  return X;
56 }
57 
58 template <>
59 GTSAM_EXPORT
60 Vector SOn::Vee(const Matrix& X) {
61  const size_t n = X.rows();
62  if (n < 2) throw std::invalid_argument("SO<N>::Hat: n<2 not supported");
63 
64  if (n == 2) {
65  // Handle SO(2) case as recursion bottom
66  Vector xi(1);
67  xi(0) = X(1, 0);
68  return xi;
69  } else {
70  // Calculate dimension and allocate space
71  const size_t d = n * (n - 1) / 2;
72  Vector xi(d);
73 
74  // Fill first n-1 spots from last row of X
75  double sign = pow(-1.0, xi.size());
76  for (size_t i = 0; i < n - 1; i++) {
77  const size_t j = n - 2 - i;
78  xi(i) = -sign * X(n - 1, j);
79  sign = -sign;
80  }
81 
82  // Recursively call Vee to fill remainder of x
83  const size_t dmin = (n - 1) * (n - 2) / 2;
84  xi.tail(dmin) = Vee(X.topLeftCorner(n - 1, n - 1));
85  return xi;
86  }
87 }
88 
89 template <>
91  DynamicJacobian H2) const {
92  if (H1) *H1 = g.inverse().AdjointMap();
93  if (H2) *H2 = SOn::IdentityJacobian(g.rows());
94  return derived() * g;
95 }
96 
97 template <>
99  DynamicJacobian H2) const {
100  SOn result = derived().inverse() * g;
101  if (H1) *H1 = -result.inverse().AdjointMap();
102  if (H2) *H2 = SOn::IdentityJacobian(g.rows());
103  return result;
104 }
105 
106 // Dynamic version of vec
107 template <> typename SOn::VectorN2 SOn::vec(DynamicJacobian H) const {
108  const size_t n = rows(), n2 = n * n;
109 
110  // Vectorize
111  VectorN2 X(n2);
112  X << Eigen::Map<const Matrix>(matrix_.data(), n2, 1);
113 
114  // If requested, calculate H as (I \oplus Q) * P,
115  // where Q is the N*N rotation matrix, and P is calculated below.
116  if (H) {
117  // Calculate P matrix of vectorized generators
118  // TODO(duy): Should we refactor this as the jacobian of Hat?
120  const size_t d = dim();
121  H->resize(n2, d);
122  for (size_t i = 0; i < n; i++) {
123  H->block(i * n, 0, n, d) = matrix_ * P.block(i * n, 0, n, d);
124  }
125  }
126  return X;
127 }
128 
129 } // namespace gtsam
static MatrixNN Hat(const TangentVector &xi)
Definition: SOn-inl.h:29
VectorN2 vec(OptionalJacobian< internal::NSquaredSO(N), dimension > H=boost::none) const
Definition: SOn-inl.h:88
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index rows() const
size_t dim() const
Definition: SOn.h:211
int n
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar * data() const
static Matrix VectorizedGenerators()
Calculate N^2 x dim matrix of vectorized Lie algebra generators for SO(N)
Definition: SOn.h:297
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
SO inverse() const
inverse of a rotation = transpose
Definition: SOn.h:190
Definition: SOn.h:50
void g(const string &key, int i)
Definition: testBTree.cpp:43
MatrixNN matrix_
Rotation matrix.
Definition: SOn.h:60
static size_t AmbientDim(size_t d)
Definition: SOn.h:207
MatrixDD AdjointMap() const
Adjoint map.
Definition: SO4.cpp:159
Class compose(const Class &g) const
Definition: Lie.h:47
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void resize(Index rows, Index cols)
Eigen::VectorXd Vector
Definition: Vector.h:38
EIGEN_DEVICE_FUNC const SignReturnType sign() const
Values result
size_t rows() const
Definition: SOn.h:154
#define dmin(a, b)
Definition: datatypes.h:21
Vector xi
Definition: testPose2.cpp:150
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:192
traits
Definition: chartTesting.h:28
Class between(const Class &g) const
Definition: Lie.h:51
static MatrixDD IdentityJacobian(size_t n)
Definition: SOn.h:252
Jet< T, N > pow(const Jet< T, N > &f, double g)
Definition: jet.h:570
The matrix class, also used for vectors and row-vectors.
#define X
Definition: icosphere.cpp:20
static TangentVector Vee(const MatrixNN &X)
Inverse of Hat. See note about xi element order in Hat.
Definition: SOn-inl.h:35
N*N matrix representation of SO(N). N can be Eigen::Dynamic.
std::ptrdiff_t j
Eigen::Matrix< double, internal::NSquaredSO(N), 1 > VectorN2
Definition: SOn.h:54


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