Lie

MuJoCo does not currently offer a native Lie group interface for rigid body transforms, though it does have a collection of functions for manipulating quaternions and rotation matrices. The goal of this library is to provide this unified interface. Whenever possible, the underlying lie operation leverages the corresponding MuJoCo function. For example, from_matrix() uses mujoco.mju_mat2Quat under the hood.

This library is heavily ported from jaxlie, swapping out JAX for Numpy and adding a few additional features.

MatrixLieGroup

class mink.lie.base.MatrixLieGroup

Interface definition for matrix Lie groups.

matrix_dim

Dimension of square matrix output.

Type:

int

parameters_dim

Dimension of underlying parameters.

Type:

int

tangent_dim

Dimension of tangent space.

Type:

int

space_dim

Dimension of coordinates that can be transformed.

Type:

int

abstract classmethod identity() Self

Returns identity element.

Return type:

Self

abstract classmethod from_matrix(matrix: ndarray) Self

Get group member from matrix representation.

Parameters:

matrix (ndarray) –

Return type:

Self

abstract classmethod sample_uniform() Self

Draw a uniform sample from the group.

Return type:

Self

abstract as_matrix() ndarray

Get transformation as a matrix.

Return type:

ndarray

abstract parameters() ndarray

Get underlying representation.

Return type:

ndarray

abstract apply(target: ndarray) ndarray

Applies group action to a point.

Parameters:

target (ndarray) –

Return type:

ndarray

abstract multiply(other: Self) Self

Composes this transformation with another.

Parameters:

other (Self) –

Return type:

Self

abstract classmethod exp(tangent: ndarray) Self

Computes expm(wedge(tangent)).

Parameters:

tangent (ndarray) –

Return type:

Self

abstract log() ndarray

Computes vee(logm(transformation matrix)).

Return type:

ndarray

abstract adjoint() ndarray

Computes the adjoint.

Return type:

ndarray

abstract inverse() Self

Computes the inverse of the transform.

Return type:

Self

abstract normalize() Self

Normalize/projects values and returns.

Return type:

Self

plus(other: ndarray) Self

Alias for rplus.

Parameters:

other (ndarray) –

Return type:

Self

minus(other: Self) ndarray

Alias for rminus.

Parameters:

other (Self) –

Return type:

ndarray

SO3

class mink.lie.so3.SO3

Bases: MatrixLieGroup

Special orthogonal group for 3D rotations.

Internal parameterization is (qw, qx, qy, qz). Tangent parameterization is (omega_x, omega_y, omega_z).

parameters() ndarray

Get underlying representation.

Return type:

ndarray

classmethod from_matrix(matrix: ndarray) SO3

Get group member from matrix representation.

Parameters:

matrix (ndarray) –

Return type:

SO3

classmethod identity() SO3

Returns identity element.

Return type:

SO3

classmethod sample_uniform() SO3

Draw a uniform sample from the group.

Return type:

SO3

as_matrix() ndarray

Get transformation as a matrix.

Return type:

ndarray

inverse() SO3

Computes the inverse of the transform.

Return type:

SO3

normalize() SO3

Normalize/projects values and returns.

Return type:

SO3

apply(target: ndarray) ndarray

Applies group action to a point.

Parameters:

target (ndarray) –

Return type:

ndarray

multiply(other: SO3) SO3

Composes this transformation with another.

Parameters:

other (SO3) –

Return type:

SO3

classmethod exp(tangent: ndarray) SO3

Computes expm(wedge(tangent)).

Parameters:

tangent (ndarray) –

Return type:

SO3

log() ndarray

Computes vee(logm(transformation matrix)).

Return type:

ndarray

adjoint() ndarray

Computes the adjoint.

Return type:

ndarray

SE3

class mink.lie.se3.SE3

Bases: MatrixLieGroup

Special Euclidean group for proper rigid transforms in 3D.

Internal parameterization is (qw, qx, qy, qz, x, y, z). Tangent parameterization is (vx, vy, vz, omega_x, omega_y, omega_z).

parameters() ndarray

Get underlying representation.

Return type:

ndarray

classmethod identity() SE3

Returns identity element.

Return type:

SE3

classmethod from_matrix(matrix: ndarray) SE3

Get group member from matrix representation.

Parameters:

matrix (ndarray) –

Return type:

SE3

classmethod sample_uniform() SE3

Draw a uniform sample from the group.

Return type:

SE3

as_matrix() ndarray

Get transformation as a matrix.

Return type:

ndarray

classmethod exp(tangent: ndarray) SE3

Computes expm(wedge(tangent)).

Parameters:

tangent (ndarray) –

Return type:

SE3

inverse() SE3

Computes the inverse of the transform.

Return type:

SE3

normalize() SE3

Normalize/projects values and returns.

Return type:

SE3

apply(target: ndarray) ndarray

Applies group action to a point.

Parameters:

target (ndarray) –

Return type:

ndarray

multiply(other: SE3) SE3

Composes this transformation with another.

Parameters:

other (SE3) –

Return type:

SE3

log() ndarray

Computes vee(logm(transformation matrix)).

Return type:

ndarray

adjoint() ndarray

Computes the adjoint.

Return type:

ndarray