This guide explains how to create a MatrixLieGroup, a specific type of LieGroup that has a matrix representation. Please read Creating a Manifold Class and Creating a LieGroup first. This document focuses only on the additional requirements for a matrix Lie group.
A MatrixLieGroup has all the properties of a LieGroup, but its structure is tied to an underlying N x N matrix. This allows for additional operations specific to matrix algebra.
1. From Lie Group to Matrix Lie Group¶
To implement a MatrixLieGroup, you inherit from gtsam::MatrixLieGroup<MyGroup, D, N>, which in turn inherits from gtsam::LieGroup. This inheritance provides even more functionality for free.
2. Minimal Additional Requirements¶
You must implement everything from the LieGroup.md guide, plus the following:
MyGroup.h - Header File Additions¶
Class Definition and Inheritance:
Change your inheritance to
public gtsam::MatrixLieGroup<MyGroup, D, N>, whereNis the side-length of your matrix.
Lie Algebra Typedef:
using LieAlgebra = gtsam::MatrixN;: Defines the type of a Lie algebra element (which is anN x Nmatrix).
Matrix Lie Group Primitives:
const gtsam::MatrixN& matrix() const;: An accessor for the underlying matrix data member.static gtsam::MatrixN Hat(const gtsam::VectorD& xi);: Maps aD-dimensional tangent vector to itsN x Nmatrix representation in the Lie algebra.static gtsam::VectorD Vee(const gtsam::MatrixN& X);: The inverse ofHat, mapping anN x NLie algebra matrix back to aD-dimensional vector.
3. What You Get for Free (Additionally)¶
By inheriting from gtsam::MatrixLieGroup, you get:
Default group adjoint methods:
AdjointMap(),Adjoint(xi), andAdjointTranspose(x)are provided generically, including Jacobians for the latter two.Default Lie algebra methods:
adjointMap(xi),adjoint(xi, y), andadjointTranspose(xi, y)are provided generically, including Jacobians for the latter two.A
vec()method: This vectorizes theN x Nmatrix representation of your group element into an(N*N) x 1vector.
Performance Note: The generic implementation of AdjointMap() is correct but may be slower because it is derived via the Hat/Vee mappings. If a closed-form expression for AdjointMap() is available for your group, consider overriding the default implementation for better performance.
4. Traits and Concept Checking¶
Finally, the traits specialization in your header file must be updated to reflect that your class is now a MatrixLieGroup.
GTSAM Traits Specialization:
This is the final, crucial step. Specialize the
traitsstruct using theinternal::MatrixLieGrouphelper.
namespace gtsam { template <> struct traits<MyGroup> : public internal::MatrixLieGroup<MyGroup, N> {}; template <> struct traits<const MyGroup> : public internal::MatrixLieGroup<MyGroup, N> {}; }Concept Checking:
Update the macro in your unit test file to check the
MatrixLieGroupconcept.
#include <gtsam/base/TestableAssertions.h> #include <gtsam/base/MatrixLieGroup.h> // Your class include #include <gtsam/geometry/MyGroup.h> // This macro will fail to compile if MyGroup is not a valid MatrixLieGroup. GTSAM_CONCEPT_MATRIX_LIE_GROUP_INST(MyGroup) // ... your unit tests ...
This modular approach ensures that your class provides all the necessary components for full integration into the GTSAM framework.