navlie.lib.states.VectorState¶
- class navlie.lib.states.VectorState(value: ndarray, stamp: float | None = None, state_id=None)¶
Bases:
State
A standard vector-based state, with value represented by a 1D numpy array.
- plus(dx: ndarray) → VectorState¶
A generic “addition” operation given a
dx
numpy array with as many elements as thedof
of this state.
- minus(x: VectorState) → ndarray¶
A generic “subtraction” operation given another State object of the same type, always returning a numpy array.
- 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: State) → 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)
.
- copy() → VectorState¶
Returns a copy of this State instance.
- state_id¶