Class inertialsim::geometry::MatrixLieGroup¶
template <typename Derived, int GroupDimension, int AlgebraDimension>
ClassList > inertialsim > geometry > MatrixLieGroup
Abstract base class for matrix Lie groups using CRTP. More...
#include <lie_group.h>
Inherited by the following classes: inertialsim::geometry::RigidTransformBase, inertialsim::geometry::RigidTransformBase, inertialsim::geometry::RigidTransformBase, inertialsim::geometry::RotationBase, inertialsim::geometry::RotationBase, inertialsim::geometry::VectorBase, inertialsim::geometry::VectorBase, inertialsim::geometry::VectorBase
Public Types¶
| Type | Name |
|---|---|
| typedef Eigen::Matrix< Scalar, AlgebraDimension, Eigen::Dynamic > | AlgebraArray Matrix of algebra elements (rows = axes, cols = samples). |
| typedef Eigen::Matrix< Scalar, AlgebraDimension, 1 > | AlgebraElement Algebra element type (vector). |
| typedef std::vector< GroupElement > | GroupArray Array of group elements. |
| typedef Eigen::Matrix< Scalar, GroupDimension, GroupDimension > | GroupElement Group element type (square matrix). |
| typedef Eigen::Matrix< Scalar, AlgebraDimension, AlgebraDimension > | JacobianMatrix Jacobian matrix (algebra to algebra). |
| typedef std::vector< JacobianMatrix > | JacobianMatrixArray Array of Jacobian matrices. |
Public Functions¶
| Type | Name |
|---|---|
| Vector3D | Apply (const Vector3D & vectors) const Apply the group action to an array of vectors. |
| Derived | Interpolate (const Timestamps & interp_time, Interpolator method=Interpolator::LINEAR) const Interpolate at given times. |
| Derived | Inverse () const Invert an instance. |
| Derived | Slice (int start, int end) const Get a slice of elements. |
| AlgebraArray | TimeDerivative (int order=1, int accuracy=4, const std::string & side="right") const Compute time derivative using finite differences. |
| int | num_elements () const Number of elements stored in the instance. |
| Derived | operator* (const Derived & rhs) const Composition operator on the matrix group. Supports broadcasting: if either lhs or rhs has size 1, it will be broadcast against all elements of the other operand. Derived classes may implement more efficient methods. |
| Derived | operator[] (int index) const Get a single element by index. |
| const std::optional< Timestamps > & | time () const Time array (or nullopt if not set). |
| virtual | ~MatrixLieGroup () = default |
Public Static Functions¶
| Type | Name |
|---|---|
| Derived | Compose (const std::vector< Derived > & instances) Compose a sequence of instances (first to last). |
| Derived | FromIdentity (int num_elements=1) Create identity elements. |
| Derived | FromRandom (int num_elements=1, std::optional< Eigen::numext::uint64_t > seed=std::nullopt) Create random elements. |
Protected Functions¶
| Type | Name |
|---|---|
| AlgebraArray | AsAlgebra () const Get the algebra elements. |
| GroupArray | AsGroup () const Get the group elements. |
| Derived | CubicHermiteInterpolate (const Timestamps & time) const Cubic Hermite spline interpolation. |
| Derived | LinearInterpolate (const Timestamps & time) const Linear interpolation implementation. |
| MatrixLieGroup (const std::optional< Timestamps > & time=std::nullopt) Constructor. |
|
| Derived & | derived () CRTP helper to access derived class. |
| const Derived & | derived () const |
| int | num_times () const |
Protected Static Functions¶
| Type | Name |
|---|---|
| GroupElement | Exp (const AlgebraElement & vector) Exponential map from algebra to group. |
| Derived | FromAlgebra (const AlgebraArray & elements, const std::optional< Timestamps > & time) Create instance from algebra elements. |
| Derived | FromGroup (const GroupArray & elements, const std::optional< Timestamps > & time) Create instance from group elements. |
| JacobianMatrixArray | Jacobian (const AlgebraArray & algebra, const std::string & side="left", bool inverse=false) Calculate the Jacobian given algebra elements. |
| AlgebraElement | Log (const GroupElement & element) Logarithm map from group to algebra. |
Detailed Description¶
Derived classes will inherit common Lie group operations such as composition, interpolation, etc.
See Reference [14], Reference [15], Reference [16], Reference [17], and Reference [18] for further details on Lie groups and their application to translations, rotations and rigid body motions.
Template parameters:
DerivedThe derived class type (CRTP pattern).GroupDimensionDimension of the group matrix representation (e.g., 3 for SO(3) & T(3), 4 for SE(3)).AlgebraDimensionDimension of the algebra representation (e.g., 3 for so(3) and t(4), 6 for se(3)).
Public Types Documentation¶
typedef AlgebraArray¶
Matrix of algebra elements (rows = axes, cols = samples).
using inertialsim::geometry::MatrixLieGroup< Derived, GroupDimension, AlgebraDimension >::AlgebraArray = Eigen::Matrix<Scalar, AlgebraDimension, Eigen::Dynamic>;
typedef AlgebraElement¶
Algebra element type (vector).
using inertialsim::geometry::MatrixLieGroup< Derived, GroupDimension, AlgebraDimension >::AlgebraElement = Eigen::Matrix<Scalar, AlgebraDimension, 1>;
typedef GroupArray¶
Array of group elements.
using inertialsim::geometry::MatrixLieGroup< Derived, GroupDimension, AlgebraDimension >::GroupArray = std::vector<GroupElement>;
typedef GroupElement¶
Group element type (square matrix).
using inertialsim::geometry::MatrixLieGroup< Derived, GroupDimension, AlgebraDimension >::GroupElement = Eigen::Matrix<Scalar, GroupDimension, GroupDimension>;
typedef JacobianMatrix¶
Jacobian matrix (algebra to algebra).
using inertialsim::geometry::MatrixLieGroup< Derived, GroupDimension, AlgebraDimension >::JacobianMatrix = Eigen::Matrix<Scalar, AlgebraDimension, AlgebraDimension>;
typedef JacobianMatrixArray¶
Array of Jacobian matrices.
using inertialsim::geometry::MatrixLieGroup< Derived, GroupDimension, AlgebraDimension >::JacobianMatrixArray = std::vector<JacobianMatrix>;
Public Functions Documentation¶
function Apply¶
Apply the group action to an array of vectors.
Parameters:
vectorsArray of vectors to apply the group action to.
Returns:
Array of transformed vectors.
function Interpolate¶
Interpolate at given times.
inline Derived inertialsim::geometry::MatrixLieGroup::Interpolate (
const Timestamps & interp_time,
Interpolator method=Interpolator::LINEAR
) const
Parameters:
interp_timeTimes at which to interpolate.methodInterpolation method (LINEAR or CUBIC).
Returns:
New instance with interpolated values.
function Inverse¶
Invert an instance.
Returns:
Inverted instance.
function Slice¶
Get a slice of elements.
Parameters:
startStart index (inclusive).endEnd index (exclusive).
Returns:
New instance containing the sliced elements.
function TimeDerivative¶
Compute time derivative using finite differences.
inline AlgebraArray inertialsim::geometry::MatrixLieGroup::TimeDerivative (
int order=1,
int accuracy=4,
const std::string & side="right"
) const
Parameters:
orderOrder of derivative (default 1).accuracyAccuracy of finite difference (default 4).side"right" for body frame, "left" for world frame.
Returns:
Matrix of algebra derivatives (rows = samples, cols = algebra dim).
function num_elements¶
Number of elements stored in the instance.
function operator*¶
Composition operator on the matrix group. Supports broadcasting: if either lhs or rhs has size 1, it will be broadcast against all elements of the other operand. Derived classes may implement more efficient methods.
Parameters:
rhsRight-hand side instance.
Returns:
New instance containing the composed elements.
function operator[]¶
Get a single element by index.
Parameters:
indexIndex of the element to retrieve.
Returns:
New instance containing a single element.
function time¶
Time array (or nullopt if not set).
function ~MatrixLieGroup¶
Public Static Functions Documentation¶
function Compose¶
Compose a sequence of instances (first to last).
static inline Derived inertialsim::geometry::MatrixLieGroup::Compose (
const std::vector< Derived > & instances
)
function FromIdentity¶
Create identity elements.
Parameters:
num_elementsNumber of identity elements.
Returns:
Instance with identity elements.
function FromRandom¶
Create random elements.
static inline Derived inertialsim::geometry::MatrixLieGroup::FromRandom (
int num_elements=1,
std::optional< Eigen::numext::uint64_t > seed=std::nullopt
)
Parameters:
num_elementsNumber of random elements.
Returns:
Instance with random elements.
Protected Functions Documentation¶
function AsAlgebra¶
Get the algebra elements.
Returns:
Array of algebra elements.
function AsGroup¶
Get the group elements.
Returns:
Array of group elements.
function CubicHermiteInterpolate¶
Cubic Hermite spline interpolation.
inline Derived inertialsim::geometry::MatrixLieGroup::CubicHermiteInterpolate (
const Timestamps & time
) const
Parameters:
timeTimes at which to interpolate.
Returns:
Interpolated instance.
function LinearInterpolate¶
Linear interpolation implementation.
inline Derived inertialsim::geometry::MatrixLieGroup::LinearInterpolate (
const Timestamps & time
) const
Parameters:
timeTimes at which to interpolate.
Returns:
Interpolated instance.
function MatrixLieGroup¶
Constructor.
inline explicit inertialsim::geometry::MatrixLieGroup::MatrixLieGroup (
const std::optional< Timestamps > & time=std::nullopt
)
Parameters:
timeOptional time array. If provided, will be validated.
function derived [½]¶
CRTP helper to access derived class.
function derived [2/2]¶
function num_times¶
Protected Static Functions Documentation¶
function Exp¶
Exponential map from algebra to group.
static inline GroupElement inertialsim::geometry::MatrixLieGroup::Exp (
const AlgebraElement & vector
)
Parameters:
vectorAlgebra element.
Returns:
Group element.
function FromAlgebra¶
Create instance from algebra elements.
static inline Derived inertialsim::geometry::MatrixLieGroup::FromAlgebra (
const AlgebraArray & elements,
const std::optional< Timestamps > & time
)
Parameters:
elementsArray of algebra elements.timeOptional time array.
Returns:
New instance.
function FromGroup¶
Create instance from group elements.
static inline Derived inertialsim::geometry::MatrixLieGroup::FromGroup (
const GroupArray & elements,
const std::optional< Timestamps > & time
)
Parameters:
elementsArray of group elements.timeOptional time array.
Returns:
New instance.
function Jacobian¶
Calculate the Jacobian given algebra elements.
static inline JacobianMatrixArray inertialsim::geometry::MatrixLieGroup::Jacobian (
const AlgebraArray & algebra,
const std::string & side="left",
bool inverse=false
)
Parameters:
algebraAlgebra elements.side"left" for world frame, "right" for body frame.inverseIf true, compute the inverse Jacobian.
Returns:
Jacobian matrix.
function Log¶
Logarithm map from group to algebra.
static inline AlgebraElement inertialsim::geometry::MatrixLieGroup::Log (
const GroupElement & element
)
Parameters:
elementGroup element.
Returns:
Algebra element.
The documentation for this class was generated from the following file cpp/include/inertialsim/geometry/lie_group.h