navlie.lib.states.MatrixLieGroupState¶
- class navlie.lib.states.MatrixLieGroupState(value: ndarray, group: MatrixLieGroup, stamp: float | None = None, state_id: Any | None = None, direction='right')¶
Bases:
State
The MatrixLieGroupState class. Although this class can technically be used directly, it is recommended to use one of the subclasses instead, such as
SE2State
orSO3State
.- Parameters:
value (np.ndarray) – Value of of the state. If the value has as many elements as the DOF of the group, then it is assumed to be a vector of exponential coordinates. Otherwise, the value must be a 2D numpy array representing a direct element of the group in matrix form.
group (MatrixLieGroup) – A pymlg.MatrixLieGroup class, such as pymlg.SE2 or pymlg.SO3.
stamp (float, optional) – timestamp, by default None
state_id (Any, optional) – optional state ID, by default None
direction (str, optional) –
either “left” or “right”, by default “right”. Defines the perturbation \(\delta \mathbf{x}\) as either
\[ \begin{align}\begin{aligned}\mathbf{X} = \mathbf{X} \exp(\delta \mathbf{x}^\wedge) ext{ (right)}\\\mathbf{X} = \exp(\delta \mathbf{x}^\wedge) \mathbf{X} ext{ (left)}\end{aligned}\end{align} \]
- direction¶
- group¶
- plus(dx: ndarray) → MatrixLieGroupState¶
A generic “addition” operation given a
dx
numpy array with as many elements as thedof
of this state.
- minus(x: MatrixLieGroupState) → ndarray¶
A generic “subtraction” operation given another State object of the same type, always returning a numpy array.
- copy() → MatrixLieGroupState¶
Returns a copy of this State instance.
- plus_jacobian(dx: ndarray) → ndarray¶
Jacobian of the
plus
operator. That is, using Lie derivative notation,\[\mathbf{J} = \frac{D (\mathcal{X} \oplus \delta \mathbf{x})}{D \delta \mathbf{x}}\]For Lie groups, this is known as the group Jacobian.
- minus_jacobian(x: MatrixLieGroupState) → ndarray¶
Jacobian of the
minus
operator with respect to self.\[\mathbf{J} = \frac{D (\mathcal{Y} \ominus \mathcal{X})}{D \mathcal{Y}}\]That is, if
dx = y.minus(x)
then this is the Jacobian ofdx
with respect toy
. For Lie groups, this is the inverse of the group Jacobian evaluated atdx = x1.minus(x2)
.
- dot(other: MatrixLieGroupState) → MatrixLieGroupState¶
- minus_jacobian_fd(x: State, step_size=1e-08) → ndarray¶
Calculates the minus jacobian with finite difference.
- plus_jacobian_fd(dx, step_size=1e-08) → ndarray¶
Calculates the plus jacobian with finite difference.
- state_id¶