navlie.types.State¶
- class navlie.types.State(value: Any, dof: int, stamp: float | None = None, state_id=None)¶
Bases:
ABCAn abstract state \(\mathcal{X}\) is an object containing the following attributes:
a value of some sort;
a certain number of degrees of freedom (dof);
plusandminusmethods that generalize addition and subtracting to to this object.
Optionally, it is often useful to assign a timestamp (
stamp) and a label (state_id) to differentiate state instances from others.When implementing a new state type, you should inherit from this class as shown in the tutorial.
Note
The
plusandminusmust correspond to each other, in the sense that the following must hold:\[\delta \mathbf{x} = (\mathcal{X} \oplus \delta \mathbf{x}) \ominus \mathcal{X}\]for any state \(\mathcal{X}\) and any perturbation \(\delta \mathbf{x}\). In practice this can be tested with something along the lines of:
x = State(...) # some state object dx = np.random.randn(x.dof) dx_test = x.plus(dx).minus(x) assert np.allclose(dx, dx_test)
- value¶
State value
- Type:
Any
- state_id¶
- abstract plus(dx: ndarray) → State¶
A generic “addition” operation given a
dxnumpy array with as many elements as thedofof this state.
- abstract minus(x: State) → 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
plusoperator. 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.
- plus_jacobian_fd(dx, step_size=1e-08) → ndarray¶
Calculates the plus jacobian with finite difference.
- minus_jacobian(x: State) → ndarray¶
Jacobian of the
minusoperator 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 ofdxwith respect toy. For Lie groups, this is the inverse of the group Jacobian evaluated atdx = x1.minus(x2).