navlie.composite.CompositeState¶
- class navlie.composite.CompositeState(state_list: List[State], stamp: float | None = None, state_id=None)¶
Bases:
StateA “composite” state object intended to hold a list of State objects as a single conceptual “state”. The intended use is to hold a list of states as a single state at a specific time, of potentially different types, and this class will take care of defining the appropriate operations on the composite state such as the
plusandminusmethods, as well as theplus_jacobianandminus_jacobianmethods.Each state in the provided list has an index (the index in the list), as well as a state_id, which is found as an attribute in the corresponding State object.
It is possible to access sub-states in the composite states both by index and by ID.
- Parameters:
state_list (List[State]) – List of State that forms this composite state
stamp (float, optional) – Timestamp of the composite state. This can technically be different from the timestamps of the substates.
state_id (Any, optional) – State ID of the composite state. This can be different from the state IDs of the substates.
- state_id¶
- get_index_by_id(state_id)¶
Get index of a particular state_id in the list of states.
- add_state(state: State, stamp: float | None = None, state_id=None)¶
Adds a state and it’s corresponding slice to the composite state.
- remove_state_by_id(state_id)¶
Removes a given state by ID.
- get_slice_by_id(state_id, slices=None)¶
Get slice of a particular state_id in the list of states.
- get_matrix_block_by_ids(mat: ndarray, state_id_1: Any, state_id_2: Any | None = None) → ndarray¶
Gets the portion of a matrix corresponding to two states.
This function is useful when extract specific blocks of a covariance matrix, for example.
- Parameters:
mat (np.ndarray) – N x N matrix
state_id_1 (Any) – State ID of state 1.
state_id_2 (Any, optional) – State ID of state 2. If None, state_id_2 is set to state_id_1.
- Returns:
Subblock of mat corrsponding to slices of state_id_1 and state_id_2.
- Return type:
np.ndarray
- set_matrix_block_by_ids(new_mat_block: ndarray, mat: ndarray, state_id_1: Any, state_id_2: Any | None = None) → ndarray¶
Sets the portion of the covariance block corresponding to two states.
- Parameters:
new_mat_block (np.ndarray) – A subblock to be entered into mat.
mat (np.ndarray) – Full matrix.
state_id_1 (Any) – State ID of state 1.
state_id_2 (Any, optional) – State ID of state 2. If None, state_id_2 is set to state_id_1.
- Returns:
mat with updated subblock.
- Return type:
np.ndarray
- to_list()¶
Converts the CompositeState object back into a list of states.
- copy() → CompositeState¶
Returns a new composite state object where the state values have also been copied.
- plus(dx, new_stamp: float | None = None) → CompositeState¶
Updates the value of each sub-state given a dx. Interally parses the dx vector.
- minus(x: CompositeState) → ndarray¶
A generic “subtraction” operation given another State object of the same type, always returning a numpy array.
- plus_by_id(dx, state_id: int, new_stamp: float | None = None) → CompositeState¶
Updates a specific sub-state.
- jacobian_from_blocks(block_dict: dict)¶
Returns the jacobian of the entire composite state given jacobians associated with some of the substates. These are provided as a dictionary with the the keys being the substate IDs.
- 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.
- minus_jacobian(x: CompositeState) → 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).