Public Types | Public Member Functions | Static Public Member Functions | List of all members
gtsam::LieGroup< Class, N > Struct Template Reference

#include <Lie.h>

Public Types

enum  { dimension = N }
 
typedef OptionalJacobian< N, NChartJacobian
 
typedef Eigen::Matrix< double, N, NJacobian
 
typedef Eigen::Matrix< double, N, 1 > TangentVector
 

Public Member Functions

Class between (const Class &g) const
 
Class between (const Class &g, ChartJacobian H1, ChartJacobian H2={}) const
 
template<>
SOn between (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const
 
template<>
GTSAM_EXPORT SOn between (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const
 
Class compose (const Class &g) const
 
Class compose (const Class &g, ChartJacobian H1, ChartJacobian H2={}) const
 
template<>
SOn compose (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const
 
template<>
GTSAM_EXPORT SOn compose (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const
 
const Classderived () const
 
Class expmap (const TangentVector &v) const
 
Class expmap (const TangentVector &v, ChartJacobian H1, ChartJacobian H2={}) const
 expmap with optional derivatives More...
 
Class inverse (ChartJacobian H) const
 
TangentVector localCoordinates (const Class &g) const
 localCoordinates as required by manifold concept: finds tangent vector between *this and g More...
 
TangentVector localCoordinates (const Class &g, ChartJacobian H1, ChartJacobian H2={}) const
 localCoordinates with optional derivatives More...
 
TangentVector logmap (const Class &g) const
 
TangentVector logmap (const Class &g, ChartJacobian H1, ChartJacobian H2={}) const
 logmap with optional derivatives More...
 
Class retract (const TangentVector &v) const
 retract as required by manifold concept: applies v at *this More...
 
Class retract (const TangentVector &v, ChartJacobian H1, ChartJacobian H2={}) const
 retract with optional derivatives More...
 

Static Public Member Functions

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

Detailed Description

template<class Class, int N>
struct gtsam::LieGroup< Class, N >

A CRTP helper class that implements Lie group methods Prerequisites: methods operator*, inverse, and AdjointMap, as well as a ChartAtOrigin struct that will be used to define the manifold Chart To use, simply derive, but also say "using LieGroup<Class,N>::inverse" For derivative math, see doc/math.pdf

Definition at line 37 of file Lie.h.

Member Typedef Documentation

◆ ChartJacobian

template<class Class, int N>
typedef OptionalJacobian<N, N> gtsam::LieGroup< Class, N >::ChartJacobian

Definition at line 40 of file Lie.h.

◆ Jacobian

template<class Class, int N>
typedef Eigen::Matrix<double, N, N> gtsam::LieGroup< Class, N >::Jacobian

Definition at line 41 of file Lie.h.

◆ TangentVector

template<class Class, int N>
typedef Eigen::Matrix<double, N, 1> gtsam::LieGroup< Class, N >::TangentVector

Definition at line 42 of file Lie.h.

Member Enumeration Documentation

◆ anonymous enum

template<class Class, int N>
anonymous enum
Enumerator
dimension 

Definition at line 39 of file Lie.h.

Member Function Documentation

◆ between() [1/4]

template<class Class, int N>
Class gtsam::LieGroup< Class, N >::between ( const Class g) const
inline

Definition at line 52 of file Lie.h.

◆ between() [2/4]

template<class Class, int N>
Class gtsam::LieGroup< Class, N >::between ( const Class g,
ChartJacobian  H1,
ChartJacobian  H2 = {} 
) const
inline

Definition at line 63 of file Lie.h.

◆ between() [3/4]

template<>
SOn gtsam::LieGroup< SOn, Eigen::Dynamic >::between ( const SOn g,
DynamicJacobian  H1,
DynamicJacobian  H2 
) const

Definition at line 97 of file SOn.cpp.

◆ between() [4/4]

template<>
GTSAM_EXPORT SOn gtsam::LieGroup< SOn, Eigen::Dynamic >::between ( const SOn g,
DynamicJacobian  H1,
DynamicJacobian  H2 
) const

◆ compose() [1/4]

template<class Class, int N>
Class gtsam::LieGroup< Class, N >::compose ( const Class g) const
inline

Definition at line 48 of file Lie.h.

◆ compose() [2/4]

template<class Class, int N>
Class gtsam::LieGroup< Class, N >::compose ( const Class g,
ChartJacobian  H1,
ChartJacobian  H2 = {} 
) const
inline

Definition at line 56 of file Lie.h.

◆ compose() [3/4]

template<>
SOn gtsam::LieGroup< SOn, Eigen::Dynamic >::compose ( const SOn g,
DynamicJacobian  H1,
DynamicJacobian  H2 
) const

Definition at line 89 of file SOn.cpp.

◆ compose() [4/4]

template<>
GTSAM_EXPORT SOn gtsam::LieGroup< SOn, Eigen::Dynamic >::compose ( const SOn g,
DynamicJacobian  H1,
DynamicJacobian  H2 
) const

◆ derived()

template<class Class, int N>
const Class& gtsam::LieGroup< Class, N >::derived ( ) const
inline

Definition at line 44 of file Lie.h.

◆ expmap() [1/2]

template<class Class, int N>
Class gtsam::LieGroup< Class, N >::expmap ( const TangentVector v) const
inline

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

Definition at line 78 of file Lie.h.

◆ expmap() [2/2]

template<class Class, int N>
Class gtsam::LieGroup< Class, N >::expmap ( const TangentVector v,
ChartJacobian  H1,
ChartJacobian  H2 = {} 
) const
inline

expmap with optional derivatives

Definition at line 89 of file Lie.h.

◆ inverse()

template<class Class, int N>
Class gtsam::LieGroup< Class, N >::inverse ( ChartJacobian  H) const
inline

Definition at line 71 of file Lie.h.

◆ LocalCoordinates() [1/2]

template<class Class, int N>
static TangentVector gtsam::LieGroup< Class, N >::LocalCoordinates ( const Class g)
inlinestatic

LocalCoordinates at origin: possible in Lie group because it has an identity.

Definition at line 116 of file Lie.h.

◆ LocalCoordinates() [2/2]

template<class Class, int N>
static TangentVector gtsam::LieGroup< Class, N >::LocalCoordinates ( const Class g,
ChartJacobian  H 
)
inlinestatic

LocalCoordinates at origin with optional derivative.

Definition at line 126 of file Lie.h.

◆ localCoordinates() [1/2]

template<class Class, int N>
TangentVector gtsam::LieGroup< Class, N >::localCoordinates ( const Class g) const
inline

localCoordinates as required by manifold concept: finds tangent vector between *this and g

Definition at line 136 of file Lie.h.

◆ localCoordinates() [2/2]

template<class Class, int N>
TangentVector gtsam::LieGroup< Class, N >::localCoordinates ( const Class g,
ChartJacobian  H1,
ChartJacobian  H2 = {} 
) const
inline

localCoordinates with optional derivatives

Definition at line 152 of file Lie.h.

◆ logmap() [1/2]

template<class Class, int N>
TangentVector gtsam::LieGroup< Class, N >::logmap ( const Class g) const
inline

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

Definition at line 84 of file Lie.h.

◆ logmap() [2/2]

template<class Class, int N>
TangentVector gtsam::LieGroup< Class, N >::logmap ( const Class g,
ChartJacobian  H1,
ChartJacobian  H2 = {} 
) const
inline

logmap with optional derivatives

Definition at line 100 of file Lie.h.

◆ Retract() [1/2]

template<class Class, int N>
static Class gtsam::LieGroup< Class, N >::Retract ( const TangentVector v)
inlinestatic

Retract at origin: possible in Lie group because it has an identity.

Definition at line 111 of file Lie.h.

◆ Retract() [2/2]

template<class Class, int N>
static Class gtsam::LieGroup< Class, N >::Retract ( const TangentVector v,
ChartJacobian  H 
)
inlinestatic

Retract at origin with optional derivative.

Definition at line 121 of file Lie.h.

◆ retract() [1/2]

template<class Class, int N>
Class gtsam::LieGroup< Class, N >::retract ( const TangentVector v) const
inline

retract as required by manifold concept: applies v at *this

Definition at line 131 of file Lie.h.

◆ retract() [2/2]

template<class Class, int N>
Class gtsam::LieGroup< Class, N >::retract ( const TangentVector v,
ChartJacobian  H1,
ChartJacobian  H2 = {} 
) const
inline

retract with optional derivatives

Definition at line 141 of file Lie.h.


The documentation for this struct was generated from the following file:


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:46:22