GTSAM  4.0.2
C++ library for smoothing and mapping (SAM)
Classes | Public Types | Public Member Functions | Static Public Member Functions | Protected Types | Protected Attributes | List of all members
gtsam::SO< N > Class Template Reference

#include <SOn.h>

Inheritance diagram for gtsam::SO< N >:
Inheritance graph
[legend]
Collaboration diagram for gtsam::SO< N >:
Collaboration graph
[legend]

Classes

struct  ChartAtOrigin
 

Public Types

enum  { dimension = internal::DimensionSO(N) }
 
using MatrixNN = Eigen::Matrix< double, N, N >
 
using VectorN2 = Eigen::Matrix< double, internal::NSquaredSO(N), 1 >
 
using MatrixDD = Eigen::Matrix< double, dimension, dimension >
 
enum  
 
typedef Eigen::Matrix< double, N, N > Jacobian
 

Public Member Functions

const SO< N > & derived () const
 
SO< N > compose (const SO< N > &g) const
 
SO< N > compose (const SO< N > &g, ChartJacobian H1, ChartJacobian H2={}) const
 
GTSAM_EXPORT SOn compose (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const
 
SO< N > between (const SO< N > &g) const
 
SO< N > between (const SO< N > &g, ChartJacobian H1, ChartJacobian H2={}) const
 
GTSAM_EXPORT SOn between (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const
 
SO< N > inverse (ChartJacobian H) const
 
SO< N > expmap (const TangentVector &v) const
 
SO< N > expmap (const TangentVector &v, ChartJacobian H1, ChartJacobian H2={}) const
 expmap with optional derivatives
 
TangentVector logmap (const SO< N > &g) const
 
TangentVector logmap (const SO< N > &g, ChartJacobian H1, ChartJacobian H2={}) const
 logmap with optional derivatives
 
SO< N > retract (const TangentVector &v) const
 retract as required by manifold concept: applies v at *this
 
SO< N > retract (const TangentVector &v, ChartJacobian H1, ChartJacobian H2={}) const
 retract with optional derivatives
 
TangentVector localCoordinates (const SO< N > &g) const
 localCoordinates as required by manifold concept: finds tangent vector between *this and g
 
TangentVector localCoordinates (const SO< N > &g, ChartJacobian H1, ChartJacobian H2={}) const
 localCoordinates with optional derivatives
 
Standard methods
const MatrixNN & matrix () const
 Return matrix.
 
size_t rows () const
 
size_t cols () const
 
Testable
void print (const std::string &s=std::string()) const
 
bool equals (const SO &other, double tol) const
 

Static Public Member Functions

static SO< N > Retract (const TangentVector &v)
 Retract at origin: possible in Lie group because it has an identity.
 
static SO< N > Retract (const TangentVector &v, ChartJacobian H)
 Retract at origin with optional derivative.
 
static TangentVector LocalCoordinates (const SO< N > &g)
 LocalCoordinates at origin: possible in Lie group because it has an identity.
 
static TangentVector LocalCoordinates (const SO< N > &g, ChartJacobian H)
 LocalCoordinates at origin with optional derivative.
 

Protected Types

template<int N_>
using IsDynamic = typename std::enable_if< N_==Eigen::Dynamic, void >::type
 
template<int N_>
using IsFixed = typename std::enable_if< N_ >=2, void >::type
 
template<int N_>
using IsSO3 = typename std::enable_if< N_==3, void >::type
 

Protected Attributes

MatrixNN matrix_
 Rotation matrix.
 

Constructors

template<int N_ = N, typename = IsFixed<N_>>
 SO ()
 Construct SO<N> identity for N >= 2.
 
template<int N_ = N, typename = IsDynamic<N_>>
 SO (size_t n=0)
 Construct SO<N> identity for N == Eigen::Dynamic.
 
template<typename Derived >
 SO (const Eigen::MatrixBase< Derived > &R)
 Constructor from Eigen Matrix, dynamic version.
 
template<int M, int N_ = N, typename = IsDynamic<N_>>
 SO (const SO< M > &R)
 Construct dynamic SO(n) from Fixed SO<M>
 
template<int N_ = N, typename = IsSO3<N_>>
 SO (const Eigen::AngleAxisd &angleAxis)
 Constructor from AngleAxisd.
 
template<typename Derived >
static SO FromMatrix (const Eigen::MatrixBase< Derived > &R)
 Named constructor from Eigen Matrix.
 
template<typename Derived , int N_ = N, typename = IsDynamic<N_>>
static SO Lift (size_t n, const Eigen::MatrixBase< Derived > &R)
 Named constructor from lower dimensional matrix.
 
static SO AxisAngle (const Vector3 &axis, double theta)
 Constructor from axis and angle. Only defined for SO3.
 
static SO ClosestTo (const MatrixNN &M)
 
static SO ChordalMean (const std::vector< SO > &rotations)
 
template<int N_ = N, typename = IsDynamic<N_>>
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.cpp.
 
template<int N_ = N, typename = IsFixed<N_>>
static SO Random (std::mt19937 &rng)
 Random SO(N) element (no big claims about uniformity)
 

Group

SO operator* (const SO &other) const
 Multiplication.
 
SO inverse () const
 inverse of a rotation = transpose
 
template<int N_ = N, typename = IsFixed<N_>>
static SO Identity ()
 SO<N> identity for N >= 2.
 
template<int N_ = N, typename = IsDynamic<N_>>
static SO Identity (size_t n=0)
 SO<N> identity for N == Eigen::Dynamic.
 

Manifold

using TangentVector = Eigen::Matrix< double, dimension, 1 >
 
using ChartJacobian = OptionalJacobian< dimension, dimension >
 
size_t dim () const
 
static int Dim ()
 Return compile-time dimensionality: fixed size N or Eigen::Dynamic.
 
static size_t Dimension (size_t n)
 
static size_t AmbientDim (size_t d)
 
static MatrixNN Hat (const TangentVector &xi)
 
static void Hat (const Vector &xi, Eigen::Ref< MatrixNN > X)
 In-place version of Hat (see details there), implements recursion.
 
static TangentVector Vee (const MatrixNN &X)
 Inverse of Hat. See note about xi element order in Hat.
 
template<int N_ = N, typename = IsDynamic<N_>>
static MatrixDD IdentityJacobian (size_t n)
 

Lie Group

MatrixDD AdjointMap () const
 Adjoint map.
 
static SO Expmap (const TangentVector &omega, ChartJacobian H={})
 
static MatrixDD ExpmapDerivative (const TangentVector &omega)
 Derivative of Expmap, currently only defined for SO3.
 
static TangentVector Logmap (const SO &R, ChartJacobian H={})
 
static MatrixDD LogmapDerivative (const TangentVector &omega)
 Derivative of Logmap, currently only defined for SO3.
 

Other methods

VectorN2 vec (OptionalJacobian< internal::NSquaredSO(N), dimension > H={}) const
 
template<int N_ = N, typename = IsFixed<N_>>
static Matrix VectorizedGenerators ()
 Calculate N^2 x dim matrix of vectorized Lie algebra generators for SO(N)
 
template<int N_ = N, typename = IsDynamic<N_>>
static Matrix VectorizedGenerators (size_t n=0)
 Calculate n^2 x dim matrix of vectorized Lie algebra generators for SO(n)
 

Detailed Description

template<int N>
class gtsam::SO< N >

Manifold of special orthogonal rotation matrices SO<N>. Template paramater N can be a fixed integer or can be Eigen::Dynamic

Member Function Documentation

◆ ChordalMean()

template<int N>
static SO gtsam::SO< N >::ChordalMean ( const std::vector< SO< N > > &  rotations)
static

Named constructor that finds chordal mean \( mu = argmin_R \sum sqr(|R-R_i|_F) \), currently only defined for SO3.

◆ ClosestTo()

template<int N>
static SO gtsam::SO< N >::ClosestTo ( const MatrixNN &  M)
static

Named constructor that finds SO(n) matrix closest to M in Frobenius norm, currently only defined for SO3.

◆ expmap()

SO< N > gtsam::LieGroup< SO< N > , N >::expmap ( const TangentVector &  v) const
inlineinherited

expmap as required by manifold concept Applies exponential map to v and composes with *this

◆ Expmap()

template<int N>
SO< N > gtsam::SO< N >::Expmap ( const TangentVector &  omega,
ChartJacobian  H = {} 
)
static

Exponential map at identity - create a rotation from canonical coordinates

◆ Hat()

template<int N>
SO< N >::MatrixNN gtsam::SO< N >::Hat ( const TangentVector &  xi)
static

Hat operator creates Lie algebra element corresponding to d-vector, where d is the dimensionality of the manifold. This function is implemented recursively, and the d-vector is assumed to laid out such that the last element corresponds to so(2), the last 3 to so(3), the last 6 to so(4) etc... For example, the vector-space isomorphic to so(5) is laid out as: a b c d | u v w | x y | z where the latter elements correspond to "telescoping" sub-algebras: 0 -z y w -d z 0 -x -v c -y x 0 u -b -w v -u 0 a d -c b -a 0 This scheme behaves exactly as expected for SO(2) and SO(3).

◆ logmap()

TangentVector gtsam::LieGroup< SO< N > , N >::logmap ( const SO< N > &  g) const
inlineinherited

logmap as required by manifold concept Applies logarithmic map to group element that takes *this to g

◆ Logmap()

template<int N>
SO< N >::TangentVector gtsam::SO< N >::Logmap ( const SO< N > &  R,
ChartJacobian  H = {} 
)
static

Log map at identity - returns the canonical coordinates of this rotation

◆ vec()

template<int N>
SO< N >::VectorN2 gtsam::SO< N >::vec ( OptionalJacobian< internal::NSquaredSO< N >(N), dimension >  H = {}) const

Return vectorized rotation matrix in column order. Will use dynamic matrices as intermediate results, but returns a fixed size X and fixed-size Jacobian if dimension is known at compile time.


The documentation for this class was generated from the following files: