From af23e4cbdc389d2d67cc997da376b88ae61647fe Mon Sep 17 00:00:00 2001 From: Charles Cossette Date: Sun, 4 Feb 2024 16:06:22 -0800 Subject: [PATCH 1/2] Add composite state tutorial --- docs/source/api.rst | 1 + docs/source/tutorial.rst | 3 +- docs/source/tutorial/composite.ipynb | 406 ++++++++++++++++++++++++++ docs/source/tutorial/lie_groups.ipynb | 4 +- navlie/composite.py | 18 +- 5 files changed, 427 insertions(+), 5 deletions(-) create mode 100644 docs/source/tutorial/composite.ipynb diff --git a/docs/source/api.rst b/docs/source/api.rst index eb854f6c..4870a37d 100644 --- a/docs/source/api.rst +++ b/docs/source/api.rst @@ -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 diff --git a/docs/source/tutorial.rst b/docs/source/tutorial.rst index 41dce19e..bdcf0772 100644 --- a/docs/source/tutorial.rst +++ b/docs/source/tutorial.rst @@ -23,4 +23,5 @@ All the dependencies should get installed by this command and the package should 1. Getting Started 2. Toy Problem - Traditional <./tutorial/traditional.ipynb> 3. Toy Problem - Lie groups <./tutorial/lie_groups.ipynb> - 4. Specifying Jacobians <./tutorial/jacobians.ipynb> \ No newline at end of file + 4. Specifying Jacobians <./tutorial/jacobians.ipynb> + 4. Composite States <./tutorial/composite.ipynb> \ No newline at end of file diff --git a/docs/source/tutorial/composite.ipynb b/docs/source/tutorial/composite.ipynb new file mode 100644 index 00000000..8a00bfdb --- /dev/null +++ b/docs/source/tutorial/composite.ipynb @@ -0,0 +1,406 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Composite States\n", + "\n", + "The [CompositeState](../_autosummary/navlie.composite.CompositeState.rst) is a class that allows you to arbitarily combine multiple states, potentially of different types, into a new state that can be used with the navlie framework.\n", + "\n", + "Let's consider the previous example where we used the following $SE(2)$ pose transformation matrix to represent the state:\n", + "\n", + "$$ \n", + "\\mathbf{T} = \\begin{bmatrix} \\mathbf{C}_{ab} & \\mathbf{r}_a \\\\ \\mathbf{0} & 1 \\end{bmatrix} \\in SE(2).\n", + "$$\n", + "\n", + "Suppose we now also want to estimate a wheel odometry bias $\\mathbf{b} \\in \\mathbb{R}^2$ in addition to the robot's pose. Our state is now \n", + "\n", + "$$\n", + "\\mathbf{x} = (\\mathbf{T}, \\mathbf{b}) \\in SE(2) \\times \\mathbb{R}^2.\n", + "$$\n", + "\n", + "This can be implemented easily using the [CompositeState](../_autosummary/navlie.composite.CompositeState.rst) class in one of two ways: either directly or by inheritance. We'll show the former approach first." + ] + }, + { + "cell_type": "code", + "execution_count": 48, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "CompositeState(stamp=0.0, state_id=None) with substates:\n", + " SE2State(stamp=0.0, state_id=pose, direction=right)\n", + " [[ 0.99500417 -0.09983342 1.84679329]\n", + " [ 0.09983342 0.99500417 3.09491919]\n", + " [ 0. 0. 1. ]]\n", + " VectorState(stamp=0.0, dof=2, state_id=bias)\n", + " [0.1 2. ]\n" + ] + } + ], + "source": [ + "import navlie as nav \n", + "import numpy as np\n", + "\n", + "# Define the pose and bias as their own states\n", + "T = nav.lib.SE2State(value = [0.1, 2.0, 3.0], stamp = 0.0, state_id=\"pose\")\n", + "b = nav.lib.VectorState(value = [0.1, 2.0], stamp = 0.0, state_id=\"bias\")\n", + "\n", + "# Combine into a composite state, and its ready to use!\n", + "x = nav.CompositeState([T, b], stamp=0.0)\n", + "\n", + "print(x)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "The ``CompositeState`` class is a subclass of the ``State`` class, but who's ``value`` is a list of states, referred to as the *substates*. A convenience of this class is that the composite state's ``plus``, ``minus``, and ``copy`` methods have already been implemented for you based on the implementations in the substates. Note that the order in which the states are listed is important, and will correspond to the order of the components in the vectors involved in the ``plus`` and ``minus`` operations. This can be demonstrated with the following example." + ] + }, + { + "cell_type": "code", + "execution_count": 49, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "\n", + "Result after plus():\n", + "CompositeState(stamp=0.0, state_id=None) with substates:\n", + " SE2State(stamp=0.0, state_id=pose, direction=right)\n", + " [[ 0.45359612 -0.89120736 1.80531705]\n", + " [ 0.89120736 0.45359612 6.55185711]\n", + " [ 0. 0. 1. ]]\n", + " VectorState(stamp=0.0, dof=2, state_id=bias)\n", + " [4.1 7. ]\n", + "\n", + "Result after minus():\n", + "[[1.]\n", + " [2.]\n", + " [3.]\n", + " [4.]\n", + " [5.]]\n" + ] + } + ], + "source": [ + "# plus() and minus() have been defined for you. Here, the first three elements\n", + "# of the vector to be added correspond to the pose (since it has 3 DOF), and the\n", + "# last two to the bias.\n", + "x_temp = x.plus(np.array([1,2,3,4,5]))\n", + "print(\"\\nResult after plus():\")\n", + "print(x_temp)\n", + "\n", + "dx = x_temp.minus(x)\n", + "print(\"\\nResult after minus():\")\n", + "print(dx)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Next, we must write a process model that works with this state. We'll use the same process model as before, but now we'll also include the wheel odometry bias in the state. The bias process model will be modelled as a random walk of the form \n", + "\n", + "$$\n", + "\\mathbf{b}_{k+1} = \\mathbf{b}_k + \\Delta t \\mathbf{w}^\\mathrm{bias}_k,\n", + "$$\n", + "\n", + "where $\\mathbf{w}^{\\mathrm{bias}}_k \\sim \\mathcal{N}(0, \\mathbf{Q}^{\\mathrm{bias}})$ represents random error associated with this otherwise constant process model, which allows the bias to slowly vary. The process model for the composite state is then" + ] + }, + { + "cell_type": "code", + "execution_count": 50, + "metadata": {}, + "outputs": [], + "source": [ + "from scipy.linalg import expm\n", + "\n", + "def wedge_se2(x):\n", + " return np.array([[ 0, -x[0], x[1]],\n", + " [x[0], 0, x[2]], \n", + " [ 0, 0, 0]])\n", + "\n", + "class WheeledRobotWithBias(nav.ProcessModel):\n", + " def __init__(self, input_covariance_matrix):\n", + " self.Q = input_covariance_matrix\n", + "\n", + " def evaluate(self, x: nav.CompositeState, u: nav.lib.VectorInput, dt:float):\n", + " pose = x.value[0]\n", + " bias = x.value[1]\n", + " vel = np.array([u.value[0] - bias.value[0], u.value[1] - bias.value[1], 0])\n", + " x_next = x.copy()\n", + " x_next.value[0].value = pose.value @ expm(wedge_se2(vel * dt))\n", + "\n", + " # Largely data generation and jacobian purposes, we also update the bias\n", + " # state with an input, even if the input here is always zero in the\n", + " # nominal case.\n", + " x_next.value[1].value = bias.value + u.value[2:4]*dt\n", + " return x_next\n", + " \n", + " def input_covariance(self, x: nav.CompositeState, u: nav.lib.VectorInput, dt:float):\n", + " return self.Q\n", + "\n", + "Q = np.eye(4) * 0.1**2\n", + "process_model = WheeledRobotWithBias(Q)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "We'd like to use the same measurement model as before, which was just a series of range measurements to known landmarks:" + ] + }, + { + "cell_type": "code", + "execution_count": 51, + "metadata": {}, + "outputs": [], + "source": [ + "class RangeToLandmarkSE2(nav.MeasurementModel):\n", + " def __init__(\n", + " self,\n", + " landmark_position: np.ndarray,\n", + " measurement_covariance: float,\n", + " ):\n", + " self.landmark_position = landmark_position\n", + " self.R = measurement_covariance\n", + "\n", + " def evaluate(self, x: nav.lib.SE2State):\n", + " pos = x.value[0:2, 2]\n", + " return np.linalg.norm(pos - self.landmark_position)\n", + "\n", + " def covariance(self, x: nav.lib.SE2State):\n", + " return self.R\n", + " \n", + "R = 0.1**2\n", + "landmarks = np.array([[1, 1], [1, 2], [2, 2], [2, 1]])" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "The problem is that this was made for an ``SE2State`` instead of our new composite state, and specifically the line `pos = x.value[0:2, 2]` is going to throw an error when we feed in a composite state. This is easy to change, but then that means we have to make a similar change for all sorts of different state definitions. An alternative is to use the [CompositeMeasurementModel](../_autosummary/navlie.composite.CompositeMeasurementModel.rst), which is just a lightweight wrapper around one measurement model that \"assigns\" the model to a specific substate, referenced to by its `state_id` field. It is used as follows:" + ] + }, + { + "cell_type": "code", + "execution_count": 52, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "RangeToLandmarkSE2(of substate pose)\n", + "Jacobian:\n", + "[[0. 0.46544123 0.88507893 0. 0. ]]\n" + ] + } + ], + "source": [ + "meas_models = []\n", + "for lm in landmarks:\n", + " meas_models.append(\n", + " nav.CompositeMeasurementModel(RangeToLandmarkSE2(lm, R), \"pose\")\n", + " )\n", + "\n", + "print(meas_models[0])\n", + "print(\"Jacobian:\")\n", + "print(meas_models[0].jacobian(x))" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "This does mean that the `state_id` of each substate must be unique, but this is a good practice anyway. The `CompositeMeasurementModel` will then automatically handle the extraction of the relevant substate from the composite state and pass it to the measurement model, as well as handle the corresponding Jacobian accordingly. This is a good way to avoid having to write a lot of boilerplate code for different state definitions. Notice in the above example that the Jacobian has two extra zeros at the end, which correspond to the bias state that has no effect on the measurement. This is automatically handled by the `CompositeMeasurementModel`.\n", + "\n", + "With our problem now set up, we can run a filter on it with the same snippet as usual!" + ] + }, + { + "cell_type": "code", + "execution_count": 53, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + } + ], + "source": [ + "dg = nav.DataGenerator(\n", + " process_model=process_model, \n", + " input_func=lambda t, x: np.array([0.5, 0.3, 0.0, 0.0]), \n", + " input_covariance= Q, \n", + " input_freq=50, \n", + " meas_model_list=meas_models, \n", + " meas_freq_list=[10, 10, 10, 10] \n", + ")\n", + "\n", + "state_data, input_data, meas_data = dg.generate(x, start=0, stop=30, noise=True)\n", + "\n", + "# First, define the filter\n", + "kalman_filter = nav.ExtendedKalmanFilter(process_model)\n", + "P0 = np.diag([0.1**2, 1**2, 1**2, 0.1**2, 0.1**2]) # Initial covariance\n", + "x = nav.StateWithCovariance(x, P0) # Estimate and covariance in one container\n", + "\n", + "meas_idx = 0\n", + "y = meas_data[meas_idx]\n", + "estimates = []\n", + "for k in range(len(input_data) - 1):\n", + " u = input_data[k]\n", + "\n", + " # Fuse any measurements that have occurred.\n", + " while y.stamp < input_data[k + 1].stamp and meas_idx < len(meas_data):\n", + " x = kalman_filter.correct(x, y, u)\n", + "\n", + " # Load the next measurement\n", + " meas_idx += 1\n", + " if meas_idx < len(meas_data):\n", + " y = meas_data[meas_idx]\n", + "\n", + " # Predict until the next input is available\n", + " dt = input_data[k + 1].stamp - x.state.stamp\n", + " x = kalman_filter.predict(x, u, dt)\n", + "\n", + " estimates.append(x.copy())\n", + "\n", + "\n", + "results = nav.GaussianResultList.from_estimates(estimates, state_data)\n", + "\n", + "import matplotlib.pyplot as plt\n", + "fig, axs = nav.plot_error(results)\n", + "axs[0,0].set_title(\"Pose Estimation Errors\")\n", + "axs[0,0].set_ylabel(\"theta (rad)\")\n", + "axs[1,0].set_ylabel(\"x (m)\")\n", + "axs[2,0].set_ylabel(\"y (m)\")\n", + "axs[2,0].set_xlabel(\"Time (s)\")\n", + "axs[0, 1].set_title(\"Bias Estimation Errors\")\n", + "axs[0, 1].set_ylabel(\"ang. vel. (rad/s)\")\n", + "axs[1, 1].set_ylabel(\"forward vel. (m/s)\")\n", + "axs[1, 1].set_xlabel(\"Time (s)\")\n", + "\n", + "fig, ax = nav.plot_nees(results)\n", + "ax.set_title(\"NEES\")\n", + "ax.set_xlabel(\"Time (s)\")\n", + "plt.show()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Inheriting from `CompositeState`\n", + "\n", + "The previous example showed how to use the `CompositeState` class directly, but it's also possible to inherit from it. This is useful if you want to add some extra methods or attributes to the composite state, or if you are going to frequently be using the same composite state. Here's an example of how you would do it:" + ] + }, + { + "cell_type": "code", + "execution_count": 55, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "WheeledRobotState(stamp=0.1, state_id=None) with substates:\n", + " SE2State(stamp=0.1, state_id=pose, direction=right)\n", + " [[ 0.99500417 -0.09983342 1.84679329]\n", + " [ 0.09983342 0.99500417 3.09491919]\n", + " [ 0. 0. 1. ]]\n", + " VectorState(stamp=0.1, dof=2, state_id=bias)\n", + " [0.1 2. ]\n", + "SE2State(stamp=0.1, state_id=pose, direction=right)\n", + " [[ 0.99500417 -0.09983342 1.84679329]\n", + " [ 0.09983342 0.99500417 3.09491919]\n", + " [ 0. 0. 1. ]]\n" + ] + } + ], + "source": [ + "class WheeledRobotState(nav.CompositeState):\n", + " def __init__(self, pose_values: np.ndarray, bias_values: np.ndarray, stamp: float):\n", + " pose = nav.lib.SE2State(pose_values, stamp=stamp, state_id=\"pose\")\n", + " bias = nav.lib.VectorState(bias_values, stamp=stamp, state_id=\"bias\")\n", + " super().__init__([pose, bias], stamp=stamp)\n", + "\n", + " # Define any getter that you want for convenience! \n", + " @property\n", + " def pose(self):\n", + " return self.value[0]\n", + "\n", + " @property\n", + " def bias(self):\n", + " return self.value[1]\n", + "\n", + " def copy(self):\n", + " return WheeledRobotState(self.pose.copy(), self.bias.copy())\n", + " \n", + "x = WheeledRobotState([0.1, 2.0, 3.0], [0.1, 2.0], stamp = 0.1)\n", + "print(x)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "This can end up looking a lot cleaner, and is potentially more flexible to work with since you can add methods and attributes to the composite state. For example, because of the getters we defined above, we can access the pose and bias more ergonomically with `x.pose` and `x.bias`." + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.8.16" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/docs/source/tutorial/lie_groups.ipynb b/docs/source/tutorial/lie_groups.ipynb index f78c876b..fd96344d 100644 --- a/docs/source/tutorial/lie_groups.ipynb +++ b/docs/source/tutorial/lie_groups.ipynb @@ -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", diff --git a/navlie/composite.py b/navlie/composite.py index e96c4b47..76ea65dd 100644 --- a/navlie/composite.py +++ b/navlie/composite.py @@ -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)) From b02d6d106c2d7cd0419dd2831a78b922a4d324c3 Mon Sep 17 00:00:00 2001 From: Charles Cossette Date: Sun, 4 Feb 2024 16:08:52 -0800 Subject: [PATCH 2/2] More docs --- navlie/composite.py | 4 ++-- navlie/filters.py | 7 ++++--- 2 files changed, 6 insertions(+), 5 deletions(-) diff --git a/navlie/composite.py b/navlie/composite.py index 76ea65dd..5ee9d791 100644 --- a/navlie/composite.py +++ b/navlie/composite.py @@ -570,8 +570,8 @@ def covariance(self, x: CompositeState) -> np.ndarray: class CompositeMeasurement(Measurement): def __init__(self, y: Measurement, state_id: Any): """ - Converts a standard Measurement into a CompositeMeasurement, which - replaces the model with a CompositeMeasurementModel. + Converts a standard ``Measurement`` into a CompositeMeasurement, which + simply replaces the model with a CompositeMeasurementModel. Parameters ---------- diff --git a/navlie/filters.py b/navlie/filters.py index 4f72ee0c..756ebb94 100644 --- a/navlie/filters.py +++ b/navlie/filters.py @@ -449,8 +449,8 @@ def correct( def generate_sigmapoints( dof: int, method: str ) -> Tuple[np.ndarray, np.ndarray]: - """Generates unit sigma points from three available - methods. + """ + Generates unit sigma points from three available methods. Parameters ---------- @@ -466,7 +466,8 @@ def generate_sigmapoints( Returns ------- Tuple[np.ndarray, np.ndarray] - returns the unit sigma points and the weights + returns the unit sigma points and the weights, respectively. For the + sigmapoints, each *column* will represent a sigma point. """ if method == "unscented": kappa = 2