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 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 <> 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 Vector SOn::Vee(const Matrix& X) {
60  const size_t n = X.rows();
61  if (n < 2) throw std::invalid_argument("SO<N>::Hat: n<2 not supported");
62 
63  if (n == 2) {
64  // Handle SO(2) case as recursion bottom
65  Vector xi(1);
66  xi(0) = X(1, 0);
67  return xi;
68  } else {
69  // Calculate dimension and allocate space
70  const size_t d = n * (n - 1) / 2;
71  Vector xi(d);
72 
73  // Fill first n-1 spots from last row of X
74  double sign = pow(-1.0, xi.size());
75  for (size_t i = 0; i < n - 1; i++) {
76  const size_t j = n - 2 - i;
77  xi(i) = -sign * X(n - 1, j);
78  sign = -sign;
79  }
80 
81  // Recursively call Vee to fill remainder of x
82  const size_t dmin = (n - 1) * (n - 2) / 2;
83  xi.tail(dmin) = Vee(X.topLeftCorner(n - 1, n - 1));
84  return xi;
85  }
86 }
87 
88 template <>
90  DynamicJacobian H2) const {
91  if (H1) *H1 = g.inverse().AdjointMap();
92  if (H2) *H2 = SOn::IdentityJacobian(g.rows());
93  return derived() * g;
94 }
95 
96 template <>
98  DynamicJacobian H2) const {
99  SOn result = derived().inverse() * g;
100  if (H1) *H1 = -result.inverse().AdjointMap();
101  if (H2) *H2 = SOn::IdentityJacobian(g.rows());
102  return result;
103 }
104 
105 // Dynamic version of vec
106 template <>
107 typename SOn::VectorN2 SOn::vec(DynamicJacobian H) const
108 {
109  const size_t n = rows(), n2 = n * n;
110 
111  // Vectorize
112  VectorN2 X(n2);
113  X << Eigen::Map<const Matrix>(matrix_.data(), n2, 1);
114 
115  // If requested, calculate H as (I \oplus Q) * P,
116  // where Q is the N*N rotation matrix, and P is calculated below.
117  if (H) {
118  // Calculate P matrix of vectorized generators
119  // TODO(duy): Should we refactor this as the jacobian of Hat?
121  const size_t d = dim();
122  H->resize(n2, d);
123  for (size_t i = 0; i < n; i++) {
124  H->block(i * n, 0, n, d) = matrix_ * P.block(i * n, 0, n, d);
125  }
126  }
127  return X;
128 }
129 
130 } // namespace gtsam
SOn.h
N*N matrix representation of SO(N). N can be Eigen::Dynamic.
gtsam::OptionalJacobian< Eigen::Dynamic, Eigen::Dynamic >
Definition: OptionalJacobian.h:189
gtsam::LieGroup::between
Class between(const Class &g) const
Definition: Lie.h:52
H
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
Definition: gnuplot_common_settings.hh:74
d
static const double d[K][N]
Definition: igam.h:11
gtsam::SO::Hat
static MatrixNN Hat(const TangentVector &xi)
Definition: SOn-inl.h:29
screwPose2::xi
Vector xi
Definition: testPose2.cpp:148
gtsam::LieGroup::compose
Class compose(const Class &g) const
Definition: Lie.h:48
sign
const EIGEN_DEVICE_FUNC SignReturnType sign() const
Definition: ArrayCwiseUnaryOps.h:219
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
X
#define X
Definition: icosphere.cpp:20
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
result
Values result
Definition: OdometryOptimize.cpp:8
gtsam::SO::matrix_
MatrixNN matrix_
Rotation matrix.
Definition: SOn.h:64
n
int n
Definition: BiCGSTAB_simple.cpp:1
gtsam::SO::VectorizedGenerators
static Matrix VectorizedGenerators()
Calculate N^2 x dim matrix of vectorized Lie algebra generators for SO(N)
Definition: SOn.h:302
benchmark.n2
n2
Definition: benchmark.py:83
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
gtsam::SO::AmbientDim
static size_t AmbientDim(size_t d)
Definition: SOn.h:212
ceres::pow
Jet< T, N > pow(const Jet< T, N > &f, double g)
Definition: jet.h:570
g
void g(const string &key, int i)
Definition: testBTree.cpp:41
dmin
#define dmin(a, b)
Definition: datatypes.h:21
Eigen::Ref
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:281
gtsam
traits
Definition: chartTesting.h:28
gtsam::SO::dim
size_t dim() const
Definition: SOn.h:216
P
static double P[]
Definition: ellpe.c:68
Eigen::PlainObjectBase::data
EIGEN_DEVICE_FUNC const EIGEN_STRONG_INLINE Scalar * data() const
Definition: PlainObjectBase.h:247
gtsam::SO
Definition: SOn.h:54
gtsam::SO::Vee
static TangentVector Vee(const MatrixNN &X)
Inverse of Hat. See note about xi element order in Hat.
Definition: SOn-inl.h:35
Eigen::Matrix
The matrix class, also used for vectors and row-vectors.
Definition: 3rdparty/Eigen/Eigen/src/Core/Matrix.h:178
gtsam::SO::VectorN2
Eigen::Matrix< double, internal::NSquaredSO(N), 1 > VectorN2
Definition: SOn.h:58
gtsam::SO::rows
size_t rows() const
Definition: SOn.h:159
gtsam::SO::vec
VectorN2 vec(OptionalJacobian< internal::NSquaredSO(N), dimension > H={}) const
Definition: SOn-inl.h:88
gtsam::SO::IdentityJacobian
static MatrixDD IdentityJacobian(size_t n)
Definition: SOn.h:257
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9


gtsam
Author(s):
autogenerated on Thu Jun 13 2024 03:05:37