Skip to content

Commit

Permalink
Add composite state tutorial
Browse files Browse the repository at this point in the history
  • Loading branch information
CharlesCossette committed Feb 5, 2024
1 parent 8cc2119 commit af23e4c
Show file tree
Hide file tree
Showing 5 changed files with 427 additions and 5 deletions.
1 change: 1 addition & 0 deletions docs/source/api.rst
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@ Below is a list of all the modules in the navlie package. Click on any of the l
:recursive:
:template: custom-module-template.rst

navlie.composite
navlie.datagen
navlie.filters
navlie.imm
Expand Down
3 changes: 2 additions & 1 deletion docs/source/tutorial.rst
Original file line number Diff line number Diff line change
Expand Up @@ -23,4 +23,5 @@ All the dependencies should get installed by this command and the package should
1. Getting Started <self>
2. Toy Problem - Traditional <./tutorial/traditional.ipynb>
3. Toy Problem - Lie groups <./tutorial/lie_groups.ipynb>
4. Specifying Jacobians <./tutorial/jacobians.ipynb>
4. Specifying Jacobians <./tutorial/jacobians.ipynb>
4. Composite States <./tutorial/composite.ipynb>
406 changes: 406 additions & 0 deletions docs/source/tutorial/composite.ipynb

Large diffs are not rendered by default.

4 changes: 2 additions & 2 deletions docs/source/tutorial/lie_groups.ipynb
Original file line number Diff line number Diff line change
Expand Up @@ -205,9 +205,9 @@
" self.Q = input_covariance_matrix\n",
"\n",
" def evaluate(self, x:SE2State, u:nav.lib.VectorInput, dt:float):\n",
" u = np.array([u.value[0], u.value[1], 0])\n",
" vel = np.array([u.value[0], u.value[1], 0])\n",
" x_next = x.copy()\n",
" x_next.value = x.value @ expm(wedge_se2(u * dt))\n",
" x_next.value = x.value @ expm(wedge_se2(vel * dt))\n",
" return x_next\n",
" \n",
" def input_covariance(self, x:SE2State, u:nav.lib.VectorInput, dt:float):\n",
Expand Down
18 changes: 16 additions & 2 deletions navlie/composite.py
Original file line number Diff line number Diff line change
Expand Up @@ -527,15 +527,29 @@ def covariance(
class CompositeMeasurementModel(MeasurementModel):
"""
Wrapper for a standard measurement model that assigns the model to a specific
substate (referenced by `state_id`) inside a CompositeState.
substate (referenced by `state_id`) inside a CompositeState. This class
will take care of extracting the relevant substate from the CompositeState,
and then applying the measurement model to it. It will also take care of
padding the Jacobian with zeros appropriately to match the degrees of freedom
of the larger CompositeState.
"""

def __init__(self, model: MeasurementModel, state_id):
"""
Parameters
----------
model : MeasurementModel
Standard measurement model, which is appropriate only for a single
substate in the CompositeState.
state_id : Any
The unique ID of the relevant substate in the CompositeState, to
assign the measurement model to.
"""
self.model = model
self.state_id = state_id

def __repr__(self):
return f"{self.model}(of substate {self.state_id})"
return f"{self.model} (of substate '{self.state_id}')"

def evaluate(self, x: CompositeState) -> np.ndarray:
return self.model.evaluate(x.get_state_by_id(self.state_id))
Expand Down

0 comments on commit af23e4c

Please sign in to comment.