SOn.h
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 
19 #pragma once
20 
21 #include <gtsam/base/Lie.h>
22 #include <gtsam/base/Manifold.h>
23 #include <gtsam/base/make_shared.h>
24 #include <gtsam/dllexport.h>
25 #include <Eigen/Core>
26 
27 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
28 #include <boost/serialization/nvp.hpp>
29 #endif
30 
31 #include <iostream> // TODO(frank): how to avoid?
32 #include <string>
33 #include <type_traits>
34 #include <vector>
35 #include <random>
36 #include <cassert>
37 
38 namespace gtsam {
39 
40 namespace internal {
42 constexpr int DimensionSO(int N) {
43  return (N < 0) ? Eigen::Dynamic : N * (N - 1) / 2;
44 }
45 
46 // Calculate N^2 at compile time, or return Dynamic if so
47 constexpr int NSquaredSO(int N) { return (N < 0) ? Eigen::Dynamic : N * N; }
48 } // namespace internal
49 
54 template <int N>
55 class SO : public LieGroup<SO<N>, internal::DimensionSO(N)> {
56  public:
57  inline constexpr static auto dimension = internal::DimensionSO(N);
61 
63 
64  protected:
66 
67  // enable_if_t aliases, used to specialize constructors/methods, see
68  // https://www.fluentcpp.com/2018/05/18/make-sfinae-pretty-2-hidden-beauty-sfinae/
69  template <int N_>
70  using IsDynamic = typename std::enable_if<N_ == Eigen::Dynamic, void>::type;
71  template <int N_>
72  using IsFixed = typename std::enable_if<N_ >= 2, void>::type;
73  template <int N_>
74  using IsSO3 = typename std::enable_if<N_ == 3, void>::type;
75 
76  public:
79 
81  template <int N_ = N, typename = IsFixed<N_>>
83 
85  template <int N_ = N, typename = IsDynamic<N_>>
86  explicit SO(size_t n = 0) {
87  // We allow for n=0 as the default constructor, needed for serialization,
88  // wrappers etc.
89  matrix_ = Eigen::MatrixXd::Identity(n, n);
90  }
91 
93  template <typename Derived>
94  explicit SO(const Eigen::MatrixBase<Derived>& R) : matrix_(R.eval()) {}
95 
97  template <typename Derived>
99  return SO(R);
100  }
101 
103  template <typename Derived, int N_ = N, typename = IsDynamic<N_>>
104  static SO Lift(size_t n, const Eigen::MatrixBase<Derived> &R) {
105  Matrix Q = Matrix::Identity(n, n);
106  const int p = R.rows();
107  assert(p >= 0 && p <= static_cast<int>(n) && R.cols() == p);
108  Q.topLeftCorner(p, p) = R;
109  return SO(Q);
110  }
111 
113  template <int M, int N_ = N, typename = IsDynamic<N_>>
114  explicit SO(const SO<M>& R) : matrix_(R.matrix()) {}
115 
117  template <int N_ = N, typename = IsSO3<N_>>
118  explicit SO(const Eigen::AngleAxisd& angleAxis) : matrix_(angleAxis) {}
119 
121  static SO AxisAngle(const Vector3& axis, double theta);
122 
125  static SO ClosestTo(const MatrixNN& M);
126 
130  static SO ChordalMean(const std::vector<SO>& rotations);
131 
133  template <int N_ = N, typename = IsDynamic<N_>>
134  static SO Random(std::mt19937& rng, size_t n = 0) {
135  if (n == 0) throw std::runtime_error("SO: Dimensionality not known.");
136  // TODO(frank): this might need to be re-thought
137  static std::uniform_real_distribution<double> randomAngle(-M_PI, M_PI);
138  const size_t d = SO::Dimension(n);
139  Vector xi(d);
140  for (size_t j = 0; j < d; j++) {
141  xi(j) = randomAngle(rng);
142  }
143  return SO::Retract(xi);
144  }
145 
147  template <int N_ = N, typename = IsFixed<N_>>
148  static SO Random(std::mt19937& rng) {
149  // By default, use dynamic implementation above. Specialized for SO(3).
151  }
152 
156 
158  const MatrixNN& matrix() const { return matrix_; }
159 
160  size_t rows() const { return matrix_.rows(); }
161  size_t cols() const { return matrix_.cols(); }
162 
166 
167  void print(const std::string& s = std::string()) const;
168 
169  bool equals(const SO& other, double tol) const {
170  return equal_with_abs_tol(matrix_, other.matrix_, tol);
171  }
172 
176 
178  SO operator*(const SO& other) const {
179  assert(dim() == other.dim());
180  return SO(matrix_ * other.matrix_);
181  }
182 
184  template <int N_ = N, typename = IsFixed<N_>>
185  static SO Identity() {
186  return SO();
187  }
188 
190  template <int N_ = N, typename = IsDynamic<N_>>
191  static SO Identity(size_t n = 0) {
192  return SO(n);
193  }
194 
196  SO inverse() const { return SO(matrix_.transpose()); }
197 
201 
204 
206  static int Dim() { return dimension; }
207 
208  // Calculate manifold dimensionality for SO(n).
209  // Available as dimension or Dim() for fixed N.
210  static size_t Dimension(size_t n) { return n * (n - 1) / 2; }
211 
212  // Calculate ambient dimension n from manifold dimensionality d.
213  static size_t AmbientDim(size_t d) { return (1 + std::sqrt(1 + 8 * d)) / 2; }
214 
215  // Calculate run-time dimensionality of manifold.
216  // Available as dimension or Dim() for fixed N.
217  size_t dim() const { return Dimension(static_cast<size_t>(matrix_.rows())); }
218 
234  static MatrixNN Hat(const TangentVector& xi);
235 
237  static void Hat(const Vector &xi, Eigen::Ref<MatrixNN> X);
238 
240  static TangentVector Vee(const MatrixNN& X);
241 
242  // Chart at origin
243  struct ChartAtOrigin {
248  static SO Retract(const TangentVector& xi, ChartJacobian H = {});
249 
253  static TangentVector Local(const SO& R, ChartJacobian H = {});
254  };
255 
256  // Return dynamic identity DxD Jacobian for given SO(n)
257  template <int N_ = N, typename = IsDynamic<N_>>
258  static MatrixDD IdentityJacobian(size_t n) {
259  const size_t d = Dimension(n);
260  return MatrixDD::Identity(d, d);
261  }
262 
266 
268  MatrixDD AdjointMap() const;
269 
273  static SO Expmap(const TangentVector& omega, ChartJacobian H = {});
274 
277 
281  static TangentVector Logmap(const SO& R, ChartJacobian H = {});
282 
285 
286  // inverse with optional derivative
287  using LieGroup<SO<N>, internal::DimensionSO(N)>::inverse;
288 
292 
298  VectorN2 vec(OptionalJacobian<internal::NSquaredSO(N), dimension> H =
299  {}) const;
300 
302  template <int N_ = N, typename = IsFixed<N_>>
304  constexpr size_t N2 = static_cast<size_t>(N * N);
306  for (size_t j = 0; j < dimension; j++) {
307  const auto X = Hat(Vector::Unit(dimension, j));
308  G.col(j) = Eigen::Map<const VectorN2>(X.data());
309  }
310  return G;
311  }
312 
314  template <int N_ = N, typename = IsDynamic<N_>>
315  static Matrix VectorizedGenerators(size_t n = 0) {
316  const size_t n2 = n * n, dim = Dimension(n);
317  Matrix G(n2, dim);
318  for (size_t j = 0; j < dim; j++) {
319  const auto X = Hat(Vector::Unit(dim, j));
320  G.col(j) = Eigen::Map<const Matrix>(X.data(), n2, 1);
321  }
322  return G;
323  }
324 
328 
329 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
330  template <class Archive>
331  friend void save(Archive&, SO&, const unsigned int);
332  template <class Archive>
333  friend void load(Archive&, SO&, const unsigned int);
334  template <class Archive>
335  friend void serialize(Archive&, SO&, const unsigned int);
336  friend class boost::serialization::access;
337  friend class Rot3; // for serialize
338 #endif
339 
341 };
342 
344 
345 /*
346  * Specialize dynamic Hat and Vee, because recursion depends on dynamic nature.
347  * The definition is in SOn.cpp. Fixed-size SO3 and SO4 have their own version,
348  * and implementation for other fixed N is in SOn-inl.h.
349  */
350 
351 template <>
352 GTSAM_EXPORT
353 Matrix SOn::Hat(const Vector& xi);
354 
355 template <>
356 GTSAM_EXPORT
357 Vector SOn::Vee(const Matrix& X);
358 
359 /*
360  * Specialize dynamic compose and between, because the derivative is unknowable
361  * by the LieGroup implementations, who return a fixed-size matrix for H2.
362  */
363 
365 
366 template <>
367 GTSAM_EXPORT
369  DynamicJacobian H2) const;
370 
371 template <>
372 GTSAM_EXPORT
374  DynamicJacobian H2) const;
375 
376 /*
377  * Specialize dynamic vec.
378  */
379 template <>
380 GTSAM_EXPORT
381 typename SOn::VectorN2 SOn::vec(DynamicJacobian H) const;
382 
383 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
384 
385 template<class Archive>
386 void serialize(
387  Archive& ar, SOn& Q,
388  const unsigned int file_version
389 ) {
390  Matrix& M = Q.matrix_;
391  ar& BOOST_SERIALIZATION_NVP(M);
392 }
393 #endif
394 
395 /*
396  * Define the traits. internal::LieGroup provides both Lie group and Testable
397  */
398 
399 template <int N>
400 struct traits<SO<N>> : public internal::LieGroup<SO<N>> {};
401 
402 template <int N>
403 struct traits<const SO<N>> : public internal::LieGroup<SO<N>> {};
404 
405 } // namespace gtsam
406 
407 #include "SOn-inl.h"
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
gtsam::SO::AxisAngle
static SO AxisAngle(const Vector3 &axis, double theta)
Constructor from axis and angle. Only defined for SO3.
gtsam::SO< 3 >::IsDynamic
typename std::enable_if< N_==Eigen::Dynamic, void >::type IsDynamic
Definition: SOn.h:70
gtsam::SO::inverse
SO inverse() const
inverse of a rotation = transpose
Definition: SOn.h:196
gtsam::SO::ChartAtOrigin::Retract
static SO Retract(const TangentVector &xi, ChartJacobian H={})
Definition: SOn-inl.h:40
Eigen
Namespace containing all symbols from the Eigen library.
Definition: jet.h:637
rng
static std::mt19937 rng
Definition: timeFactorOverhead.cpp:31
gtsam::SO::equals
bool equals(const SO &other, double tol) const
Definition: SOn.h:169
gtsam::SO::ChordalMean
static SO ChordalMean(const std::vector< SO > &rotations)
s
RealScalar s
Definition: level1_cplx_impl.h:126
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::SO::MatrixDD
Eigen::Matrix< double, dimension, dimension > MatrixDD
Definition: SOn.h:60
gtsam::SO::Dimension
static size_t Dimension(size_t n)
Definition: SOn.h:210
SOn-inl.h
Template implementations for SO(n)
gtsam::SO::VectorizedGenerators
static Matrix VectorizedGenerators(size_t n=0)
Calculate n^2 x dim matrix of vectorized Lie algebra generators for SO(n)
Definition: SOn.h:315
gtsam::LieGroup::compose
Class compose(const Class &g) const
Definition: Lie.h:48
Eigen::AngleAxis
Represents a 3D rotation as a rotation angle around an arbitrary 3D axis.
Definition: ForwardDeclarations.h:290
gtsam::SO::ChartJacobian
OptionalJacobian< dimension, dimension > ChartJacobian
Definition: SOn.h:203
gtsam::SO::ExpmapDerivative
static MatrixDD ExpmapDerivative(const TangentVector &omega)
Derivative of Expmap, currently only defined for SO3.
Definition: SOn-inl.h:72
type
Definition: pytypes.h:1525
gtsam::equal_with_abs_tol
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
Definition: base/Matrix.h:80
gtsam::SO::SO
SO(const SO< M > &R)
Construct dynamic SO(n) from Fixed SO<M>
Definition: SOn.h:114
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
gtsam::SO::Identity
static SO Identity()
SO<N> identity for N >= 2.
Definition: SOn.h:185
X
#define X
Definition: icosphere.cpp:20
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:44
gtsam::SO::Expmap
static SO Expmap(const TangentVector &omega, ChartJacobian H={})
Definition: SOn-inl.h:67
gtsam::SO< 3 >::IsSO3
typename std::enable_if< N_==3, void >::type IsSO3
Definition: SOn.h:74
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
gtsam::SO::LogmapDerivative
static MatrixDD LogmapDerivative(const TangentVector &omega)
Derivative of Logmap, currently only defined for SO3.
Definition: SOn-inl.h:82
gtsam::SO::matrix_
MatrixNN matrix_
Rotation matrix.
Definition: SOn.h:65
biased_x_rotation::omega
const double omega
Definition: testPreintegratedRotation.cpp:32
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:303
gtsam::LieGroup< SO< N >, internal::DimensionSO(N)>::Retract
static SO< N > Retract(const TangentVector &v)
Retract at origin: possible in Lie group because it has an identity.
Definition: Lie.h:111
gtsam::internal::DimensionSO
constexpr int DimensionSO(int N)
Calculate dimensionality of SO<N> manifold, or return Dynamic if so.
Definition: SOn.h:42
benchmark.n2
n2
Definition: benchmark.py:85
gtsam::SO::Identity
static SO Identity(size_t n=0)
SO<N> identity for N == Eigen::Dynamic.
Definition: SOn.h:191
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
gtsam::SO::matrix
const MatrixNN & matrix() const
Return matrix.
Definition: SOn.h:158
gtsam::internal::LieGroup
Both LieGroupTraits and Testable.
Definition: Lie.h:229
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
gtsam::SO::MatrixNN
Eigen::Matrix< double, N, N > MatrixNN
Definition: SOn.h:58
Eigen::Dynamic
const int Dynamic
Definition: Constants.h:22
Eigen::PlainObjectBase::rows
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT
Definition: PlainObjectBase.h:143
gtsam::SO::SO
SO(const Eigen::AngleAxisd &angleAxis)
Constructor from AngleAxisd.
Definition: SOn.h:118
gtsam::SO::TangentVector
Eigen::Matrix< double, dimension, 1 > TangentVector
Definition: SOn.h:202
gtsam::SO::AmbientDim
static size_t AmbientDim(size_t d)
Definition: SOn.h:213
gtsam::SO::Lift
static SO Lift(size_t n, const Eigen::MatrixBase< Derived > &R)
Named constructor from lower dimensional matrix.
Definition: SOn.h:104
Manifold.h
Base class and basic functions for Manifold types.
make_shared.h
make_shared trampoline function to ensure proper alignment
gtsam::SO::SO
SO()
Construct SO<N> identity for N >= 2.
Definition: SOn.h:82
gtsam::SO::AdjointMap
MatrixDD AdjointMap() const
Adjoint map.
Definition: SO4.cpp:159
gtsam::SO::Random
static SO Random(std::mt19937 &rng, size_t n=0)
Random SO(n) element (no big claims about uniformity). SO(3) is specialized in SO3....
Definition: SOn.h:134
gtsam::SO::operator*
SO operator*(const SO &other) const
Multiplication.
Definition: SOn.h:178
Eigen::Map
A matrix or vector expression mapping an existing array of data.
Definition: Map.h:94
gtsam::SO::Logmap
static TangentVector Logmap(const SO &R, ChartJacobian H={})
Definition: SOn-inl.h:77
g
void g(const string &key, int i)
Definition: testBTree.cpp:41
gtsam::internal::NSquaredSO
constexpr int NSquaredSO(int N)
Definition: SOn.h:47
gtsam::SO< 3 >::IsFixed
typename std::enable_if< N_ >=2, void >::type IsFixed
Definition: SOn.h:72
gtsam::save
void save(const Matrix &A, const string &s, const string &filename)
Definition: Matrix.cpp:167
Eigen::Quaternion
The quaternion class used to represent 3D orientations and rotations.
Definition: ForwardDeclarations.h:293
gtsam::SO::print
void print(const std::string &s=std::string()) const
Definition: SOn-inl.h:108
Lie.h
Base class and basic functions for Lie types.
Eigen::Ref
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:281
gtsam
traits
Definition: SFMdata.h:40
Eigen::PlainObjectBase::cols
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT
Definition: PlainObjectBase.h:145
gtsam::SO::cols
size_t cols() const
Definition: SOn.h:161
gtsam::traits
Definition: Group.h:36
gtsam::OptionalJacobian
Definition: OptionalJacobian.h:38
gtsam::SO::SO
SO(const Eigen::MatrixBase< Derived > &R)
Constructor from Eigen Matrix, dynamic version.
Definition: SOn.h:94
std
Definition: BFloat16.h:88
gtsam::SO::dimension
constexpr static auto dimension
Definition: SOn.h:57
gtsam::SO::dim
size_t dim() const
Definition: SOn.h:217
p
float * p
Definition: Tutorial_Map_using.cpp:9
G
JacobiRotation< float > G
Definition: Jacobi_makeGivens.cpp:2
gtsam::SO::SO
SO(size_t n=0)
Construct SO<N> identity for N == Eigen::Dynamic.
Definition: SOn.h:86
gtsam::SO::FromMatrix
static SO FromMatrix(const Eigen::MatrixBase< Derived > &R)
Named constructor from Eigen Matrix.
Definition: SOn.h:98
gtsam::SO::ChartAtOrigin::Local
static TangentVector Local(const SO &R, ChartJacobian H={})
Definition: SOn-inl.h:50
gtsam::LieGroup
Definition: Lie.h:37
gtsam::SO
Definition: SOn.h:55
gtsam::tol
const G double tol
Definition: Group.h:79
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
gtsam::SO::ClosestTo
static SO ClosestTo(const MatrixNN &M)
Eigen::Matrix< double, N, N >
GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
Definition: types.h:288
gtsam::SO::VectorN2
Eigen::Matrix< double, internal::NSquaredSO(N), 1 > VectorN2
Definition: SOn.h:59
N
#define N
Definition: igam.h:9
internal
Definition: BandTriangularSolver.h:13
Eigen::MatrixBase
Base class for all dense matrices, vectors, and expressions.
Definition: MatrixBase.h:48
M_PI
#define M_PI
Definition: mconf.h:117
gtsam::SO::Random
static SO Random(std::mt19937 &rng)
Random SO(N) element (no big claims about uniformity)
Definition: SOn.h:148
gtsam::SO::rows
size_t rows() const
Definition: SOn.h:160
gtsam::SO::Dim
static int Dim()
Return compile-time dimensionality: fixed size N or Eigen::Dynamic.
Definition: SOn.h:206
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:258
eval
internal::nested_eval< T, 1 >::type eval(const T &xpr)
Definition: sparse_permutations.cpp:38
ceres::sqrt
Jet< T, N > sqrt(const Jet< T, N > &f)
Definition: jet.h:418
pybind_wrapper_test_script.other
other
Definition: pybind_wrapper_test_script.py:42
R
Rot2 R(Rot2::fromAngle(0.1))
gtsam::SO::ChartAtOrigin
Definition: SOn.h:243
M
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:51


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:13:29