Lie Groups

SO(2)

class inekf.SO2(*args, **kwargs)

Bases: inekf.lie_groups.LieGroup

2D rotational states, also known as the 2x2 special orthogonal group, SO(2).

See the C++ counterpart (InEKF::SO2) for documentation on constructing an object. Further, we have overloaded the [] operator to function as a python template. Example of this can be seen in Getting Started. Templates include:

Templates:

  • A Number of augmented Euclidean states. Can be -1 or “D” for dynamic. Defaults to 0.

SE(2)

class inekf.SE2(*args, **kwargs)

Bases: inekf.lie_groups.LieGroup

2D rigid body transformation, also known as the 3x3 special Euclidean group, SE(2).

See the C++ counterpart (InEKF::SE2) for documentation on constructing an object. Further, we have overloaded the [] operator to function as a python template. Example of this can be seen in Getting Started. Templates include:

Templates:

  • C Number of Euclideans columns to include. Can be -1 or “D” for dynamic. Defaults to 1.

  • A Number of augmented Euclidean states. Can be -1 or “D” for dynamic. Defaults to 0.

Methods:

__getitem__(idx)

Gets the ith positional column of the group.

addCol(x, sigma)

Adds a column to the matrix state.

__getitem__(idx)

Gets the ith positional column of the group.

Parameters

idx (float) – Index of column to get, from 0 to C-1.

Returns

np.ndarray

addCol(x, sigma)

Adds a column to the matrix state. Only usable if C = Eigen::Dynamic.

Parameters
  • x (np.ndarray) – Column to add in.

  • sigma (np.ndarray) – Covariance of element. Only used if state is uncertain.

SO(3)

class inekf.SO3(*args, **kwargs)

Bases: inekf.lie_groups.LieGroup

3D rotational states, also known as the 3x3 special orthogonal group, SO(3).

See the C++ counterpart (InEKF::SO3) for documentation on constructing an object. Further, we have overloaded the [] operator to function as a python template. Example of this can be seen in Getting Started. Templates include:

Templates:

  • A Number of augmented Euclidean states. Can be -1 or “D” for dynamic. Defaults to 0.

SE(3)

class inekf.SE3(*args, **kwargs)

Bases: inekf.lie_groups.LieGroup

3D rigid body transformation, also known as the 4x4 special Euclidean group, SE(3).

See the C++ counterpart (InEKF::SE3) for documentation on constructing an object. Further, we have overloaded the [] operator to function as a python template. Example of this can be seen in Getting Started. Templates include:

Templates:

  • C Number of Euclideans columns to include. Can be -1 or “D” for dynamic. Defaults to 1.

  • A Number of augmented Euclidean states. Can be -1 or “D” for dynamic. Defaults to 0.

Methods:

__getitem__(idx)

Gets the ith positional column of the group.

addCol(x, sigma)

Adds a column to the matrix state.

__getitem__(idx)

Gets the ith positional column of the group.

Parameters

idx (float) – Index of column to get, from 0 to C-1.

Returns

np.ndarray

addCol(x, sigma)

Adds a column to the matrix state. Only usable if C = Eigen::Dynamic.

Parameters
  • x (np.ndarray) – Column to add in.

  • sigma (np.ndarray) – Covariance of element. Only used if state is uncertain.

Lie Group Base

class inekf.LieGroup

Attributes:

Ad

Get adjoint of group element.

R

Gets rotational component of the state.

aug

Get additional Euclidean state of object.

cov

Get covariance of group element.

inverse

Invert group element.

log

Move this element from group -> algebra -> R^n

mat

Get actual group element.

uncertain

Returns whether object is uncertain, ie if it has a covariance.

Methods:

Ad_(g)

Compute the linear map Adjoint

__invert__()

Invert group element.

__matmul__(rhs)

Combine transformations.

addAug(a, sigma)

Adds an element to the augmented Euclidean state.

exp(xi)

Move an element from R^n -> algebra -> group

log_(g)

Move an element from group -> algebra -> R^n

wedge(xi)

Move element in R^n to the Lie algebra.

property Ad

Get adjoint of group element.

Returns

np.ndarray

static Ad_(g)

Compute the linear map Adjoint

Parameters

g (inekf.LieGroup) – Element of group

Returns

np.ndarray

property R

Gets rotational component of the state.

Returns

inekf.SO2

__invert__()

Invert group element. Drops augmented state and covariance.

Returns

inekf.LieGroup

__matmul__(rhs)

Combine transformations. Augmented states are summed.

Parameters

rhs (inekf.LieGroup) – Right hand element of multiplication.

Returns

inekf.LieGroup

addAug(a, sigma)

Adds an element to the augmented Euclidean state. Only usable if A = Eigen::Dynamic.

Parameters
  • x (float) – Variable to add.

  • sigma (float) – Covariance of element. Only used if state is uncertain.

property aug

Get additional Euclidean state of object.

Returns

np.ndarray

property cov

Get covariance of group element.

Returns

np.ndarray

static exp(xi)

Move an element from R^n -> algebra -> group

Parameters

xi (np.ndarray) – Tangent vector

Returns

inekf.LieGroup

property inverse

Invert group element. Augmented portion and covariance is dropped.

Returns

inekf.LieGroup

property log

Move this element from group -> algebra -> R^n

Returns

np.ndarray

static log_(g)

Move an element from group -> algebra -> R^n

Parameters

g (inekf.LieGroup) – Group element

Returns

np.ndarray

property mat

Get actual group element.

Returns

np.ndarray

property uncertain

Returns whether object is uncertain, ie if it has a covariance.

Returns

bool

static wedge(xi)

Move element in R^n to the Lie algebra.

Parameters

xi (np.ndarray) – Tangent vector

Returns

np.ndarray