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.
|
const Class & | derived () const |
|
Class | compose (const Class &g) const |
|
Class | between (const Class &g) const |
|
Class | compose (const Class &g, ChartJacobian H1, ChartJacobian H2=boost::none) const |
|
Class | between (const Class &g, ChartJacobian H1, ChartJacobian H2=boost::none) const |
|
Class | inverse (ChartJacobian H) const |
|
Class | expmap (const TangentVector &v) const |
| expmap as required by manifold concept Applies exponential map to v and composes with *this
|
|
TangentVector | logmap (const Class &g) const |
| logmap as required by manifold concept Applies logarithmic map to group element that takes *this to g
|
|
Class | expmap (const TangentVector &v, ChartJacobian H1, ChartJacobian H2=boost::none) const |
| expmap with optional derivatives
|
|
TangentVector | logmap (const Class &g, ChartJacobian H1, ChartJacobian H2=boost::none) const |
| logmap with optional derivatives
|
|
Class | retract (const TangentVector &v) const |
| retract as required by manifold concept: applies v at *this
|
|
TangentVector | localCoordinates (const Class &g) const |
| localCoordinates as required by manifold concept: finds tangent vector between *this and g
|
|
Class | retract (const TangentVector &v, ChartJacobian H1, ChartJacobian H2=boost::none) const |
| retract with optional derivatives
|
|
TangentVector | localCoordinates (const Class &g, ChartJacobian H1, ChartJacobian H2=boost::none) const |
| localCoordinates with optional derivatives
|
|
SOn | compose (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const |
|
SOn | between (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const |
|
SOn | compose (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const |
|
SOn | between (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const |
|
|
static Class | Retract (const TangentVector &v) |
| Retract at origin: possible in Lie group because it has an identity.
|
|
static TangentVector | LocalCoordinates (const Class &g) |
| LocalCoordinates at origin: possible in Lie group because it has an identity.
|
|
static Class | Retract (const TangentVector &v, ChartJacobian H) |
| Retract at origin with optional derivative.
|
|
static TangentVector | LocalCoordinates (const Class &g, ChartJacobian H) |
| LocalCoordinates at origin with optional derivative.
|
|