diff --git a/.gitignore b/.gitignore index 4a6aa3cc0..6a262f045 100644 --- a/.gitignore +++ b/.gitignore @@ -42,3 +42,6 @@ venv/ ENV/ env.bak/ venv.bak/ + +# Files for MacOS +.DS_Store diff --git a/control/freqplot.py b/control/freqplot.py index 1c7f794ba..798b6da58 100644 --- a/control/freqplot.py +++ b/control/freqplot.py @@ -147,6 +147,8 @@ def bode_plot( figure with the correct number and shape of axes, a new figure is created. The shape of the array must match the shape of the plotted data. + freq_label: str, optional + Frequency label (defaults to "rad/sec" or "Hertz") grid : bool, optional If True, plot grid lines on gain and phase plots. Default is set by `config.defaults['freqplot.grid']`. @@ -168,6 +170,8 @@ def bode_plot( legend_loc : int or str, optional Include a legend in the given location. Default is 'center right', with no legend for a single response. Use False to suppress legend. + magnitude_label : str, optional + Label to use for magnitude axis. Defaults to "Magnitude". margins_method : str, optional Method to use in computing margins (see :func:`stability_margins`). omega_limits : array_like of two values @@ -179,6 +183,8 @@ def bode_plot( Number of samples to use for the frequeny range. Defaults to config.defaults['freqplot.number_of_samples']. Ignored if data is not a list of systems. + phase_label : str, optional + Label to use for phase axis. Defaults to "Phase [rad]". plot : bool, optional (legacy) If given, `bode_plot` returns the legacy return values of magnitude, phase, and frequency. If False, just return the diff --git a/control/phaseplot.py b/control/phaseplot.py index b7a247c45..859c60c6a 100644 --- a/control/phaseplot.py +++ b/control/phaseplot.py @@ -309,7 +309,7 @@ def vectorfield( sys._update_params(params) for i, x in enumerate(points): vfdata[i, :2] = x - vfdata[i, 2:] = sys._rhs(0, x, 0) + vfdata[i, 2:] = sys._rhs(0, x, np.zeros(sys.ninputs)) with plt.rc_context(rcParams): out = ax.quiver( diff --git a/doc/examples.rst b/doc/examples.rst index 3f4a97fee..5c253e0a9 100644 --- a/doc/examples.rst +++ b/doc/examples.rst @@ -7,7 +7,7 @@ Examples The source code for the examples below are available in the `examples/` subdirectory of the source code distribution. They can also be accessed online -via the [python-control GitHub repository](https://github.com/python-control/python-control/tree/master/examples). +via the `python-control GitHub repository `_. Python scripts @@ -62,3 +62,19 @@ online sources. simulating_discrete_nonlinear steering stochresp + +Google Colab Notebooks +====================== + +A collection of Jupyter notebooks are available on `Google Colab +`_, where they can be executed +through a web browser: + +* `Caltech CDS 110 Google Colab notebooks + `_: + Jupyter notebooks created by Richard Murray for CDS 110 (Analysis + and Design of Feedback Systems) at Caltech. + +Note: in order to execute the Jupyter notebooks in this collection, +you will need a Google account that has access to the Google +Colaboratory application. diff --git a/examples/.gitignore b/examples/.gitignore new file mode 100644 index 000000000..ad3049346 --- /dev/null +++ b/examples/.gitignore @@ -0,0 +1 @@ +.ipynb-clean diff --git a/examples/Makefile b/examples/Makefile new file mode 100644 index 000000000..554e078ff --- /dev/null +++ b/examples/Makefile @@ -0,0 +1,29 @@ +# Makefile for python-control examples +# RMM, 6 Jul 2024 +# +# This makefile allows cleanup and posting of Jupyter notebooks into +# Google Colab. +# +# Files are copied to Google Colab using rclone. In order to copy files to +# Google Colab, you should edit the GDRIVE variable to use the name of the +# drive you have configured in rclone and the path where you want to place +# the files. The default location is set up for the fbsbook.org@gmail.com +# Google Drive account, currently maintained by Richard Murray. + +NOTEBOOKS = cds110-L*_*.ipynb cds112-L*_*.ipynb +GDRIVE= fbsbook-gdrive:python-control/public/notebooks + +# Clean up notebooks to remove output +clean: .ipynb-clean +.ipynb-clean: $(NOTEBOOKS) + @for i in $?; do \ + echo jupyter nbconvert --clear-output clear-metadata $$i; \ + jupyter nbconvert \ + --ClearMetadataPreprocessor.enabled=True \ + --clear-output $$i; \ + done + touch $@ + +# Post Jupyter notebooks on course website +post: .ipynb-clean + rclone copy . $(GDRIVE) --include /cds110-L\*_\*.ipynb diff --git a/examples/cds110-L1_servomech-python.ipynb b/examples/cds110-L1_servomech-python.ipynb new file mode 100644 index 000000000..a4e479492 --- /dev/null +++ b/examples/cds110-L1_servomech-python.ipynb @@ -0,0 +1,571 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "hairy-humidity", + "metadata": { + "id": "hairy-humidity" + }, + "source": [ + "
\n", + "

CDS 110, Lecture 1

\n", + "

Dynamics and Control of a Servomechanism System using Python-Control

\n", + "

Richard M. Murray, Winter 2024

\n", + "
\n", + "\n", + "[Open in Google Colab](https://colab.research.google.com/drive/1GKRYwtbHWSWc21EIYYIZUnbJqUorhY8w)\n", + "\n", + "In this lecture we show how to model an input/output system and design a controller for the system (using eigenvalue placement). This main intent of this lecture is to introduce the Python Control Systems Toolbox ([python-control](https://python-control.org)) and how it can be used to design a control system.\n", + "\n", + "We consider a class of control systems know as *servomechanisms*. Servermechanisms are mechanical systems that use feedback to provide high precision control of position and velocity. Some examples of servomechanisms are shown below:\n", + "\n", + "| | | |\n", + "| -- | -- | -- |\n", + "| Satellite Dish | Disk Drive | Robotics |\n", + "| \"Satellite | \"Disk | \"Disk\n", + "| [YouTube video](https://www.youtube.com/watch?v=HSGfE_sC2hw) | [YouTube video](https://www.youtube.com/watch?v=oQh8KDea6SI) | [YouTube video](https://www.youtube.com/watch?v=hg3TIFIxWCo)\n", + "| | |" + ] + }, + { + "cell_type": "markdown", + "id": "2c284896-bcff-4c06-b80d-d9d6fbc0690f", + "metadata": {}, + "source": [ + "The python-control toolbox can be installed using `pip` over from conda-forge. The code below will import the control toolbox either from your local installation or via pip. We use the prefix `ct` to access control toolbox commands:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "invalid-carnival", + "metadata": {}, + "outputs": [], + "source": [ + "# Import standard packages needed for this exercise\n", + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "try:\n", + " import control as ct\n", + " print(\"python-control\", ct.__version__)\n", + "except ImportError:\n", + " !pip install control\n", + " import control as ct" + ] + }, + { + "cell_type": "markdown", + "id": "P7t3Nm4Tre2Z", + "metadata": { + "id": "P7t3Nm4Tre2Z" + }, + "source": [ + "## System dynamics\n", + "\n", + "Consider a simple mechanism consisting of a spring loaded arm that is driven by a motor, as shown below:\n", + "\n", + "
\"servomech-diagram\"
\n", + "\n", + "The motor applies a torque that twists the arm against a linear spring and moves the end of the arm across a rotating platter. The input to the system is the motor torque $\\tau_\\text{m}$. The force exerted by the spring is a nonlinear function of the head position due to the way it is attached.\n", + "\n", + "The equations of motion for the system are given by\n", + "\n", + "$$\n", + "J \\ddot \\theta = -b \\dot\\theta - k r\\sin\\theta + \\tau_\\text{m},\n", + "$$\n", + "\n", + "which can be written in state space form as\n", + "\n", + "$$\n", + "\\frac{d}{dt} \\begin{bmatrix} \\theta \\\\ \\theta \\end{bmatrix} =\n", + " \\begin{bmatrix} \\dot\\theta \\\\ -k r \\sin\\theta / J - b\\dot\\theta / J \\end{bmatrix}\n", + " + \\begin{bmatrix} 0 \\\\ 1/J \\end{bmatrix} \\tau_\\text{m}.\n", + "$$\n", + "\n", + "The system parameters are given by\n", + "\n", + "$$\n", + "k = 1,\\quad J = 100,\\quad b = 10,\n", + "\\quad r = 1,\\quad l = 2,\\quad \\epsilon = 0.01.\n", + "$$\n", + "\n", + "and we assume that time is measured in milliseconds (ms) and distance in centimeters (cm). (The constants here are made up and don't necessarily reflect a real disk drive, though the units and time constants are motivated by computer disk drives.)" + ] + }, + { + "cell_type": "markdown", + "id": "3e476db9", + "metadata": { + "id": "3e476db9" + }, + "source": [ + "The system dynamics can be modeled in python-control using a `NonlinearIOSystem` object, which we create with the `nlsys` function:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "27bb3c38", + "metadata": {}, + "outputs": [], + "source": [ + "# Parameter values\n", + "servomech_params = {\n", + " 'J': 100, # Moment of inertia of the motor\n", + " 'b': 10, # Angular damping of the arm\n", + " 'k': 1, # Spring constant\n", + " 'r': 1, # Location of spring contact on arm\n", + " 'l': 2, # Distance to the read head\n", + " 'eps': 0.01, # Magnitude of velocity-dependent perturbation\n", + "}\n", + "\n", + "# State derivative\n", + "def servomech_update(t, x, u, params):\n", + " # Extract the configuration and velocity variables from the state vector\n", + " theta = x[0] # Angular position of the disk drive arm\n", + " thetadot = x[1] # Angular velocity of the disk drive arm\n", + " tau = u[0] # Torque applied at the base of the arm\n", + "\n", + " # Get the parameter values\n", + " J, b, k, r = map(params.get, ['J', 'b', 'k', 'r'])\n", + "\n", + " # Compute the angular acceleration\n", + " dthetadot = 1/J * (\n", + " -b * thetadot - k * r * np.sin(theta) + tau)\n", + "\n", + " # Return the state update law\n", + " return np.array([thetadot, dthetadot])\n", + "\n", + "# System output (tip radial position + angular velocity)\n", + "def servomech_output(t, x, u, params):\n", + " l = params['l']\n", + " return np.array([l * x[0], x[1]])\n", + "\n", + "# System dynamics\n", + "servomech = ct.nlsys(\n", + " servomech_update, servomech_output, name='servomech',\n", + " params=servomech_params, states=['theta_', 'thdot_'],\n", + " outputs=['y', 'thdot'], inputs=['tau'])\n", + "\n", + "print(servomech)\n", + "print(\"\\nParams:\", servomech.params)" + ] + }, + { + "cell_type": "markdown", + "id": "competitive-terrain", + "metadata": { + "id": "competitive-terrain" + }, + "source": [ + "### Linearization\n", + "\n", + "To study the open loop dynamics of the system, we compute the linearization of the dynamics about the equilibrium point corresponding to $\\theta_\\text{e} = 15^\\circ$." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "senior-carpet", + "metadata": {}, + "outputs": [], + "source": [ + "# Convert the equilibrium angle to radians\n", + "theta_e = (15 / 180) * np.pi\n", + "\n", + "# Compute the input required to hold this position\n", + "u_e = servomech.params['k'] * servomech.params['r'] * np.sin(theta_e)\n", + "print(\"Equilibrium torque = %g\" % u_e)\n", + "\n", + "# Linearize the system about the equilibrium point\n", + "P = servomech.linearize([theta_e, 0], u_e)[0, 0]\n", + "# P.update_names(name='linservo')\n", + "print(\"Linearized dynamics:\\n\", P)" + ] + }, + { + "cell_type": "markdown", + "id": "qGtb17lO4PvM", + "metadata": { + "id": "qGtb17lO4PvM" + }, + "source": [ + "We can check the roots of the characteristic equation for this second order system using the `poles` method (we will learn how this works later in the term):" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "Vkji0Y8FT7oq", + "metadata": {}, + "outputs": [], + "source": [ + "# Check the stability of the equilibrium point\n", + "P.poles()" + ] + }, + { + "cell_type": "markdown", + "id": "naH-Nl7V4c2R", + "metadata": { + "id": "naH-Nl7V4c2R" + }, + "source": [ + "Alternatively, we can look at the eigenvalues of the \"dynamics matrix\" for the linearized system (we will learn about this formulation in [Lecture 3](cds110-L3_lti-systems.ipynb)):" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "aKxayyiK4NLj", + "metadata": {}, + "outputs": [], + "source": [ + "evals, evecs = np.linalg.eig(P.A)\n", + "print(evals)" + ] + }, + { + "cell_type": "markdown", + "id": "AYQlD5v9GcK4", + "metadata": { + "id": "AYQlD5v9GcK4" + }, + "source": [ + "Both approaches give the same result and we see that the system is stable (negative real part) with an imaginary component (so we can expect some oscillation in the response)." + ] + }, + { + "cell_type": "markdown", + "id": "instant-lancaster", + "metadata": { + "id": "instant-lancaster" + }, + "source": [ + "### Open loop step response\n", + "\n", + "A standard method for understanding the dynamics is to plot output of the system in response to an input that is set to 1 at time $t = 0$ (called the \"step response\").\n", + "\n", + "We use the `step_response` function to plot the step response of the linearized, open-loop system and compute the \"rise time\" and \"settling time\" (we will define these more formally next week)." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "african-mauritius", + "metadata": {}, + "outputs": [], + "source": [ + "# Compute the step response\n", + "lin_response = ct.step_response(P)\n", + "timepts, output = lin_response.time, lin_response.outputs\n", + "\n", + "# Plot step response (input 0 to output 0)\n", + "plt.plot(timepts, output)\n", + "plt.xlabel(\"Time $t$ [ms]\")\n", + "plt.ylabel(\"Position $y$ [cm]\")\n", + "plt.title(\"Step response for the linearized, open-loop system\")\n", + "\n", + "# Compute and print properties of the step response\n", + "results = ct.step_info(P)\n", + "print(\"Rise time:\", results['RiseTime']) # 10-90% rise time\n", + "print(\"Settling time:\", results['SettlingTime']) # 2% error\n", + "\n", + "# Calculate the rise time start time by hand\n", + "rise_time_start = timepts[np.where(output > 0.1 * output[-1])[0][0]]\n", + "rise_time_stop = rise_time_start + results['RiseTime']\n", + "\n", + "# Add lines for the step response features\n", + "plt.plot([timepts[0], timepts[-1]], [output[-1], output[-1]], 'k--')\n", + "\n", + "plt.plot([rise_time_start, rise_time_start], [0, 2.5], 'k:')\n", + "plt.plot([rise_time_stop, rise_time_stop], [0, 2.5], 'k:')\n", + "plt.arrow(rise_time_start, 0.5, rise_time_stop - rise_time_start, 0)\n", + "plt.text((rise_time_start + rise_time_stop)/2, 0.6, '$T_r$')\n", + "\n", + "plt.plot([0, 0], [0, 2.5], 'k:')\n", + "plt.plot([results['SettlingTime'], results['SettlingTime']], [0, 2.5], 'k:')\n", + "plt.arrow(0, 1.5, results['SettlingTime'], 0)\n", + "plt.text(results['SettlingTime']/2, 1.6, '$T_s$');\n" + ] + }, + { + "cell_type": "markdown", + "id": "DoCK6MWlHaUO", + "metadata": { + "id": "DoCK6MWlHaUO" + }, + "source": [ + "We see that the open loop step response (for the linearized system) is stable, and that the final value is larger than 1 (this value just depends on the parameters in the system)." + ] + }, + { + "cell_type": "markdown", + "id": "nviDlWek9dge", + "metadata": { + "id": "nviDlWek9dge" + }, + "source": [ + "We can also compare the response of the linearized system to the full nonlinear system:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "qwrPhD499jbl", + "metadata": {}, + "outputs": [], + "source": [ + "nl_response = ct.input_output_response(servomech, timepts, U=1)\n", + "\n", + "# Plot step response (input 0 to output 0)\n", + "plt.plot(timepts, output, label=\"linearized\")\n", + "plt.plot(timepts, nl_response.outputs[0], label=\"nonlinear\")\n", + "\n", + "plt.xlabel(\"Time $t$ [ms]\")\n", + "plt.ylabel(\"Position $y$ [cm]\")\n", + "plt.title(\"Step response for the open-loop system\")\n", + "plt.legend();" + ] + }, + { + "cell_type": "markdown", + "id": "7YNmgE2XHmL3", + "metadata": { + "id": "7YNmgE2XHmL3" + }, + "source": [ + "We see that the nonlinear system responds differently. This is because the force exerted by the spring is nonlinear due to the kinematics of the mechanism design." + ] + }, + { + "cell_type": "markdown", + "id": "stuffed-premiere", + "metadata": { + "id": "stuffed-premiere" + }, + "source": [ + "## Feedback control design\n", + "\n", + "We next design a feedback controller for the system that allows the system to track a desired position $y_\\text{d}$ and sets the closed loop eigenvalues of the linearized system to $\\lambda_{1,2} = −10 \\pm 10 i$. We will learn how to do this more formally in later lectures, so if you aren't familiar with these techniques, that's OK.\n", + "\n", + "We make use of full state feedback of the form $u = -K(x - x_\\text{d})$ where $x_\\text{d}$ is the desired state of the system. The python-control `place` command can be used to compute the state feedback gains $K$ that set the closed loop poles at a desired location:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "8NK8O6XT7B_a", + "metadata": {}, + "outputs": [], + "source": [ + "# Place the closed loop poles using feedback\n", + "# u = -K (x - xd)\n", + "\n", + "# Find the gains required to place the gains at the desired location\n", + "K = ct.place(P.A, P.B, [-10 + 10*1j, -10 - 10*1j])\n", + "print(f\"{K=}\\n\")\n", + "\n", + "# Implement an I/O system implementing this control law\n", + "def statefbk_output(t, x, u, params):\n", + " l = params.get('l', 2)\n", + " # Create the current and desired state\n", + " x = np.array([u[0] / l, u[1]])\n", + " xd = np.array([u[2] / l, u[3]])\n", + " return -K @ (x - xd)\n", + "\n", + "statefbk = ct.nlsys(\n", + " None, statefbk_output, name='statefbk',\n", + " inputs=['y', 'thdot', 'y_d', 'thdot_d'],\n", + " outputs=['tau']\n", + ")\n", + "print(statefbk)" + ] + }, + { + "cell_type": "markdown", + "id": "v1fb1pJ_zRLk", + "metadata": { + "id": "v1fb1pJ_zRLk" + }, + "source": [ + "Note that this controller has no internal state, but rather is a static input/output function." + ] + }, + { + "cell_type": "markdown", + "id": "ZR8EKtn-H9V7", + "metadata": { + "id": "ZR8EKtn-H9V7" + }, + "source": [ + "We can now connect the controller to the process using the `interconnect` command. Because we have named the signals in a careful way, the `interconnect` command can automatically connect everything together:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "associate-assistant", + "metadata": {}, + "outputs": [], + "source": [ + "clsys = ct.interconnect(\n", + " [servomech, statefbk],\n", + " inputs=['y_d', 'thdot_d'],\n", + " outputs=['y', 'tau']\n", + ")\n", + "print(clsys)" + ] + }, + { + "cell_type": "markdown", + "id": "4o5oy_6N51yf", + "metadata": { + "id": "4o5oy_6N51yf" + }, + "source": [ + "To examine the dynamics of the closed loop system, we plot the step response for the closed loop system and compute the rise time, settling time, and steady state error." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "qIEH3Trn53d4", + "metadata": {}, + "outputs": [], + "source": [ + "# Compute the step response of the closed loop system\n", + "timepts = np.linspace(0, 1)\n", + "clsys_resp = ct.input_output_response(clsys, timepts, [1, 0])\n", + "\n", + "plt.plot(clsys_resp.time, clsys_resp.outputs[0])\n", + "plt.xlabel(\"Time $t$ [ms]\")\n", + "plt.ylabel(\"Position $y$ [cm]\")\n", + "plt.title(\"Step response for closed loop, state space controller\")\n", + "\n", + "# Compute and print properties of the step response\n", + "results = ct.step_info(clsys_resp.outputs[0], timepts)\n", + "print(\"\")\n", + "print(f\"Rise time: {results['RiseTime']:.2g} ms\")\n", + "print(f\"Settling time: {results['SettlingTime']:.2g} ms\")\n", + "print(f\"Steady state error: {abs(results['SteadyStateValue'] - 1) * 100:.2g}%\")" + ] + }, + { + "cell_type": "markdown", + "id": "K-ZX_SDmN4rF", + "metadata": { + "id": "K-ZX_SDmN4rF" + }, + "source": [ + "Note the change in timescale (100 ms to 1 ms) and also the fact that the system now goes to the reference value ($y = 1$)." + ] + }, + { + "cell_type": "markdown", + "id": "e0176710", + "metadata": { + "id": "e0176710" + }, + "source": [ + "## Frequency response\n", + "\n", + "Another way to measure the performance of the system is to compute its frequency response.\n", + "\n", + "Roughly speaking, we set the input of the system to be of the form $u(t) = \\sin(\\omega t)$ and then look at the output signal $y(t)$. For a *linear* system, we can show that the output signal will have the form\n", + "\n", + "$$\n", + "y(t) = M \\sin(\\omega t + \\phi)\n", + "$$\n", + "\n", + "where the magnitude $M$ and phase $\\phi$ depend on the input frequency.\n", + "\n", + "We can plot the magnitude (also called the \"gain\") and the phase of the system as a function of the frequency $\\omega$ and plot these values on a log-log and log-linear scale (called a *Bode* plot):" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "a8684cc1", + "metadata": {}, + "outputs": [], + "source": [ + "# Compute the linearization of the closed loop system\n", + "G = clsys.linearize([theta_e, 0], [0, 0], name=\"G\")\n", + "\n", + "# Plot the Bode plot (input[0] = yd, outut[0] = y)\n", + "response = ct.frequency_response(G[0, 0])\n", + "cplt = response.plot(title=\"Bode plot for G\", freq_label=\"Frequency [rad/ms]\")" + ] + }, + { + "cell_type": "markdown", + "id": "W_kzSIKGsSka", + "metadata": { + "id": "W_kzSIKGsSka" + }, + "source": [ + "Examination of the frequency response allows us to identify the range of input frequencies over which the control system can accurately track the input ($M(\\omega) \\approx 1$). For this system, we have good tracking up to approximately 10 rad/ms, which corresponds to about 1.6 kHz." + ] + }, + { + "cell_type": "markdown", + "id": "rocky-hobby", + "metadata": { + "id": "rocky-hobby" + }, + "source": [ + "## Trajectory tracking\n", + "\n", + "Another type of analysis we might do is to see how well the system can track a more complicated reference trajectory. For the disk drive example, we might move the system from one point on the disk to a second and then to a third (as we read different portions of the disk).\n", + "\n", + "To explore this, we can create simulations of the full nonlinear system with the linear controllers designed above and plot the response of the system. We do that here for a reference trajectory that has an initial value of 0 cm at $t = 0$, to 1 cm at $t = 0.5$, to 3 cm at $t = 1$, back to 2 cm at $t = 1.5$ ms:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "utility-community", + "metadata": {}, + "outputs": [], + "source": [ + "# Create a reference trajectory to track\n", + "timepts = np.linspace(0, 2.5, 250)\n", + "ref = [\n", + " np.concatenate((\n", + " np.ones(50) * 0,\n", + " np.ones(50) * 1,\n", + " np.ones(50) * 3,\n", + " np.ones(100) * 2,\n", + " )), 0]\n", + "\n", + "# Create the system response and plot the results\n", + "response = ct.input_output_response(clsys, timepts, ref)\n", + "plt.plot(response.time, response.outputs[0])\n", + "\n", + "# Plot the reference trajectory\n", + "plt.plot(timepts, ref[0], 'k--');\n", + "\n", + "# Label the plot\n", + "plt.xlabel(\"Time $t$ [ms]\")\n", + "plt.ylabel(\"Position $y$ [cm]\")\n", + "plt.title(\"Trajectory tracking with full nonlinear dynamics\");" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "074427a3", + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/examples/cds110-L2_invpend-dynamics.ipynb b/examples/cds110-L2_invpend-dynamics.ipynb new file mode 100644 index 000000000..5b1bfc099 --- /dev/null +++ b/examples/cds110-L2_invpend-dynamics.ipynb @@ -0,0 +1,433 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": { + "id": "t0JD8EbaVWg-" + }, + "source": [ + "
\n", + "

CDS 110, Lecture 2

\n", + "

Nonlinear Dynamics (and Control) of an Inverted Pendulum System

\n", + "

Richard M. Murray, Winter 2024

\n", + "
\n", + "\n", + "[Open in Google Colab](https://colab.research.google.com/drive/1is083NiFdHcHX8Hq56oh_AO35nQGO4bh)\n", + "\n", + "In this lecture we investigate the nonlinear dynamics of an inverted pendulum system. More information on this example can be found in [FBS2e](https://fbswiki.org/wiki/index.php?title=FBS), Examples 3.3 and 5.4. This lecture demonstrates how to use [python-control](https://python-control.org) to analyze nonlinear systems, including creating phase plane plots.\n" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Import the packages needed for the examples included in this notebook\n", + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "from math import pi\n", + "try:\n", + " import control as ct\n", + " print(\"python-control\", ct.__version__)\n", + "except ImportError:\n", + " !pip install control\n", + " import control as ct" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "P_ZMCccjvHY1" + }, + "source": [ + "## System model" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "Msad1ficHjtc" + }, + "source": [ + "We consider an invereted pendulum, which is a simplified version of a balance system:\n", + "\n", + "
\"invpend.diagram\"
\n", + "\n", + "The dynamics for an inverted pendulum system can be written as:\n", + "\n", + "$$\n", + " \\dfrac{d}{dt} \\begin{bmatrix} \\theta \\\\ \\dot\\theta\\end{bmatrix} =\n", + " \\begin{bmatrix}\n", + " \\dot\\theta \\\\\n", + " \\dfrac{m g l}{J_\\text{t}} \\sin \\theta\n", + " - \\dfrac{b}{J_\\text{t}} \\dot\\theta\n", + " + \\dfrac{l}{J_\\text{t}} u \\cos\\theta\n", + " \\end{bmatrix}, \\qquad\n", + " y = \\theta,\n", + "$$\n", + "\n", + "where $m$ and $J_t = J + m l^2$ are the mass and (total) moment of inertia of the system to be balanced, $l$ is the distance from the base to the center of mass of the balanced body, $b$ is the coefficient of rotational friction, and $g$ is the acceleration due to gravity.\n", + "\n", + "We begin by creating a nonlinear model of the system:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "invpend_params = {'m': 1, 'l': 1, 'b': 0.5, 'g': 1}\n", + "def invpend_update(t, x, u, params):\n", + " m, l, b, g = params['m'], params['l'], params['b'], params['g']\n", + " umax = params.get('umax', 1)\n", + " usat = np.clip(u[0], -umax, umax)\n", + " return [x[1], -b/m * x[1] + (g * l / m) * np.sin(x[0] + usat/m)]\n", + "invpend = ct.nlsys(\n", + " invpend_update, states=['theta', 'thdot'],\n", + " inputs=['tau'], outputs=['theta', 'thdot'],\n", + " params=invpend_params, name='invpend')\n", + "print(invpend)" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "IAoQAORFvLj1" + }, + "source": [ + "## Open loop dynamics" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "vOALp_IwjVxC" + }, + "source": [ + "The open loop dynamics of the system can be visualized using the `phase_plane_plot` command in python-control:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "ct.phase_plane_plot(\n", + " invpend, [-2*pi - 1, 2*pi + 1, -2, 2], 8),\n", + "\n", + "# Draw lines at the downward equilibrium angles\n", + "plt.plot([-pi, -pi], [-2, 2], 'k--')\n", + "plt.plot([pi, pi], [-2, 2], 'k--')" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "WZuvqNzeJinm" + }, + "source": [ + "We see that the vertical ($\\theta = 0$) equilibrium point is unstable, but the downward equlibrium points ($\\theta = \\pm \\pi$) are stable.\n", + "\n", + "Note also the *separatrices* for the equilibrium point, which gives insights into the regions of attraction (the red dashed line separates the two regions of attraction)." + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "2JibDTJBKHIF" + }, + "source": [ + "## Proportional feedback\n", + "\n", + "We now stabilize the system using a simple proportional feedback controller:\n", + "\n", + "$$u = -k_\\text{p} \\theta.$$\n", + "\n", + "This controller can be designed as an input/output system that has no state dynamics, just a mapping from the inputs to the outputs:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Set up the controller\n", + "def propctrl_output(t, x, u, params):\n", + " kp = params.get('kp', 1)\n", + " return -kp * (u[0] - u[1])\n", + "propctrl = ct.nlsys(\n", + " None, propctrl_output, name=\"p_ctrl\",\n", + " inputs=['theta', 'r'], outputs='tau'\n", + ")\n", + "print(propctrl)" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "AvU35WoBMFjt" + }, + "source": [ + "Note that the input to the controller is the reference value $r$ (which we will always take to be zero), the measured output $y$, which is the angle $\\theta$ for our system. The output of the controller is the system input $u$, corresponding to the force applied to the wheels.\n", + "\n", + "To connect the controller to the system, we use the [`interconnect`](https://python-control.readthedocs.io/en/latest/generated/control.interconnect.html) function, which will connect all signals that have the same names:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Create the closed loop system\n", + "clsys = ct.interconnect(\n", + " [invpend, propctrl], name='invpend w/ proportional feedback',\n", + " inputs=['r'], outputs=['theta', 'tau'], params={'kp': 1})\n", + "print(clsys)" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "IIiSaHNuM1u_" + }, + "source": [ + "Note: you will see a warning when you run this command, because the output $\\dot\\theta$ (`thdot`) is not connected to anything. You can ignore this here, but as you get to more complicated examples, you should pay attention to warnings of this sort and make sure they are OK." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "We can now linearize the closed loop system at different gains and compute the eigenvalues to check for stability:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Solution\n", + "for kp in [0, 1, 10]:\n", + " print(\"kp = \", kp, \"; poles = \", clsys.linearize([0, 0], [0], params={'kp': kp}).poles())" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "iV4u31DsNWP9" + }, + "source": [ + "We see that at $k_\\text{p} = 10$ the eigenvalues (poles) of the closed loop system both have negative real part, and so the system is stabilized." + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "Jg87a3iZP-Qd" + }, + "source": [ + "### Phase portrait\n", + "\n", + "To study the resulting dynamics, we try plotting a phase plot using the same commands as before, but now for the closed loop system (with appropriate proportional gain):" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "ct.phase_plane_plot(\n", + " clsys, [-2*pi, 2*pi, -2, 2], 8, params={'kp': 10});" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "jhU2gidqi-ri" + }, + "source": [ + "This plot is not very useful and has several errors. It shows the limitations of the default parameter values for the `phase_plane_plot` command.\n", + "\n", + "Some things to notice in this plot:\n", + "* Not all of the equilibrium points are showing up (there are two unstable equilibrium points that are missing)\n", + "* There is no detail about what is happening near the origin." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "### Improved phase portrait\n", + "\n", + "To fix these issues, we can do a couple of things:\n", + "* Restrict the range of the plot from $-3\\pi/2$ to $3\\pi/2$, which means that grid used to calculate the equilibrium point is a bit finer.\n", + "* Reset the grid spacing, so that we have more initial conditions around the edge of the plot and a finer search for equilibrium points.\n", + "\n", + "Here's some improved code:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "kp_params = {'kp': 10}\n", + "ct.phase_plane_plot(\n", + " clsys, [-1.5 * pi, 1.5 * pi, -2, 2], 8,\n", + " gridspec=[13, 7], params=kp_params,\n", + " plot_separatrices={'timedata': 5})\n", + "plt.plot([-pi, -pi], [-2, 2], 'k--', [ pi, pi], [-2, 2], 'k--')\n", + "plt.plot([-pi/2, -pi/2], [-2, 2], 'k:', [ pi/2, pi/2], [-2, 2], 'k:');" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Play around with some paramters to see what happens\n", + "fig, axs = plt.subplots(2, 2)\n", + "for i, kp in enumerate([3, 10]):\n", + " for j, umax in enumerate([0.2, 1]):\n", + " ct.phase_plane_plot(\n", + " clsys, [-1.5 * pi, 1.5 * pi, -2, 2], 8,\n", + " gridspec=[13, 7], plot_separatrices={'timedata': 5},\n", + " params={'kp': kp, 'umax': umax}, ax=axs[i, j])\n", + " axs[i, j].set_title(f\"{kp=}, {umax=}\")\n", + "plt.tight_layout()" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "dYeVbfG4kU-9" + }, + "source": [ + "## State space controller\n", + "\n", + "For the proportional controller, we have limited control over the dynamics of the closed loop system. For example, we see that the solutions near the origin are highly oscillatory in both the $k_\\text{p} = 3$ and $k_\\text{p} = 10$ cases.\n", + "\n", + "An alternative is to use \"full state feedback\", in which we set\n", + "\n", + "$$\n", + "u = -K (x - x_\\text{d}) = -k_1 (\\theta - \\theta_d) - k_2 (\\dot\\theta - \\dot\\theta_d).\n", + "$$\n", + "\n", + "We will learn more about how to design these controllers later, so if you aren't familiar with the idea of eigenvalue placement, just take this as a bit of \"control theory magic\" for now.\n", + "\n", + "To compute the gains, we make use of the `place` command, applied to the linearized system:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Linearize the system\n", + "P = invpend.linearize([0, 0], [0])\n", + "\n", + "# Place the closed loop eigenvalues (poles) at desired locations\n", + "K = ct.place(P.A, P.B, [-1 + 0.1j, -1 - 0.1j])\n", + "print(f\"{K=}\")" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "def statefbk_output(t, x, u, params):\n", + " K = params.get('K', np.array([0, 0]))\n", + " return -K @ (u[0:2] - u[2:])\n", + "statefbk = ct.nlsys(\n", + " None, statefbk_output, name=\"k_ctrl\",\n", + " inputs=['theta', 'thdot', 'theta_d', 'thdot_d'], outputs='tau'\n", + ")\n", + "print(statefbk)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "clsys_sf = ct.interconnect(\n", + " [invpend, statefbk], name='invpend w/ state feedback',\n", + " inputs=['theta_d', 'thdot_d'], outputs=['theta', 'tau'], params={'kp': 1})\n", + "print(clsys_sf)" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "aGm3usQIvmqN" + }, + "source": [ + "### Phase portrait" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "ct.phase_plane_plot(\n", + " clsys_sf, [-1.5 * pi, 1.5 * pi, -2, 2], 8,\n", + " gridspec=[13, 7], params={'K': K})\n", + "plt.plot([-pi, -pi], [-2, 2], 'k--', [ pi, pi], [-2, 2], 'k--')\n", + "plt.plot([-pi/2, -pi/2], [-2, 2], 'k:', [ pi/2, pi/2], [-2, 2], 'k:')" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "A7UNUtfJwLWQ" + }, + "source": [ + "Note that the closed loop response around the upright equilibrium point is much less oscillatory (consistent with where we placed the closed loop eigenvalues of the system dynamics)." + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "eVSa1Mvqycov" + }, + "source": [ + "## Things to try\n", + "\n", + "Here are some things to try with the above code:\n", + "* Try changing the locations of the closed loop eigenvalues in the `place` command\n", + "* Try resetting the limits of the control action (`umax`)\n", + "* Try leaving the state space controller fixed but changing the parameters of the system dynamics ($m$, $l$, $b$). Does the controller still stabilize the system?\n", + "* Plot the initial condition response of the system and see how to map time traces to phase plot traces." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 4 +} diff --git a/examples/cds110-L3_lti-systems.ipynb b/examples/cds110-L3_lti-systems.ipynb new file mode 100644 index 000000000..652bb1216 --- /dev/null +++ b/examples/cds110-L3_lti-systems.ipynb @@ -0,0 +1,515 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": { + "id": "gQZtf4ZqM8HL" + }, + "source": [ + "
\n", + "

CDS 110, Lecture 3

\n", + "

Python Tools for Analyzing Linear Systems

\n", + "

Richard M. Murray, Winter 2024

\n", + "
\n", + "\n", + "[Open in Google Colab](https://colab.research.google.com/drive/164yYvB86c2EvEcIHpUPNXCroiN9nnTAa)\n", + "\n", + "In this lecture we describe tools in the Python Control Systems Toolbox ([python-control](https://python-control.org)) that can be used to analyze linear systems, including some of the options available to present the information in different ways.\n" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "try:\n", + " import control as ct\n", + " print(\"python-control\", ct.__version__)\n", + "except ImportError:\n", + " !pip install control\n", + " import control as ct" + ] + }, + { + "attachments": {}, + "cell_type": "markdown", + "metadata": { + "id": "qMVGK15gNQw2" + }, + "source": [ + "## Coupled mass spring system\n", + "\n", + "Consider the spring mass system below:\n", + "\n", + "
\n", + "\n", + "We wish to analyze the time and frequency response of this system using a variety of python-control functions for linear systems analysis.\n", + "\n", + "### System dynamics\n", + "\n", + "The dynamics of the system can be written as\n", + "\n", + "$$\n", + "\\begin{aligned}\n", + " m \\ddot{q}_1 &= -2 k q_1 - c \\dot{q}_1 + k q_2, \\\\\n", + " m \\ddot{q}_2 &= k q_1 - 2 k q_2 - c \\dot{q}_2 + ku\n", + "\\end{aligned}\n", + "$$\n", + "\n", + "or in state space form:\n", + "\n", + "$$\n", + "\\begin{aligned}\n", + " \\dfrac{dx}{dt} &= \\begin{bmatrix}\n", + " 0 & 0 & 1 & 0 \\\\\n", + " 0 & 0 & 0 & 1 \\\\[0.5ex]\n", + " -\\dfrac{2k}{m} & \\dfrac{k}{m} & -\\dfrac{c}{m} & 0 \\\\[0.5ex]\n", + " \\dfrac{k}{m} & -\\dfrac{2k}{m} & 0 & -\\dfrac{c}{m}\n", + " \\end{bmatrix} x\n", + " + \\begin{bmatrix}\n", + " 0 \\\\ 0 \\\\[0.5ex] 0 \\\\[1ex] \\dfrac{k}{m}\n", + " \\end{bmatrix} u.\n", + "\\end{aligned}\n", + "$$\n", + "\n" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Define the parameters for the system\n", + "m, c, k = 1, 0.1, 2\n", + "# Create a linear system\n", + "A = np.array([\n", + " [0, 0, 1, 0],\n", + " [0, 0, 0, 1],\n", + " [-2*k/m, k/m, -c/m, 0],\n", + " [k/m, -2*k/m, 0, -c/m]\n", + "])\n", + "B = np.array([[0], [0], [0], [k/m]])\n", + "C = np.array([[1, 0, 0, 0], [0, 1, 0, 0]])\n", + "D = 0\n", + "\n", + "sys = ct.ss(A, B, C, D, outputs=['q1', 'q2'], name=\"coupled spring mass\")\n", + "print(sys)" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "kobxJ1yG4v_1" + }, + "source": [ + "Another way to get these same dynamics is to define an input/output system:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "coupled_params = {'m': 1, 'c': 0.1, 'k': 2}\n", + "def coupled_update(t, x, u, params):\n", + " m, c, k = params['m'], params['c'], params['k']\n", + " return np.array([\n", + " x[2], x[3],\n", + " -2*k/m * x[0] + k/m * x[1] - c/m * x[2],\n", + " k/m * x[0] -2*k/m * x[1] - c/m * x[3] + k/m * u[0]\n", + " ])\n", + "def coupled_output(t, x, u, params):\n", + " return x[0:2]\n", + "coupled = ct.nlsys(\n", + " coupled_update, coupled_output, inputs=1, outputs=['q1', 'q2'],\n", + " states=['q1', 'q2', 'q1dot', 'q2dot'], name='coupled (nl)',\n", + " params=coupled_params\n", + ")\n", + "print(coupled.linearize([0, 0, 0, 0], [0]))" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "YmH87LEXWo1U" + }, + "source": [ + "### Initial response\n", + "\n", + "The `initial_response` function can be used to compute the response of the system with no input, but starting from a given initial condition. This function returns a response object, which can be used for plotting." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "response = ct.initial_response(sys, X0=[1, 0, 0, 0])\n", + "cplt = response.plot()" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "Y4aAxYvZRBnD" + }, + "source": [ + "If you want to play around with the way the data are plotted, you can also use the response object to get direct access to the states and outputs." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Plot the outputs of the system on the same graph, in different colors\n", + "t = response.time\n", + "x = response.states\n", + "plt.plot(t, x[0], 'b', t, x[1], 'r')\n", + "plt.legend(['$x_1$', '$x_2$'])\n", + "plt.xlim(0, 50)\n", + "plt.ylabel('States')\n", + "plt.xlabel('Time [s]')\n", + "plt.title(\"Initial response from $x_1 = 1$, $x_2 = 0$\");" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "Cou0QVnkTou9" + }, + "source": [ + "There are also lots of options available in `initial_response` and `.plot()` for tuning the plots that you get." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "for X0 in [[1, 0, 0, 0], [0, 2, 0, 0], [1, 2, 0, 0], [0, 0, 1, 0], [0, 0, 2, 0]]:\n", + " response = ct.initial_response(sys, T=20, X0=X0)\n", + " response.plot(label=f\"{X0=}\")" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "b3VFPUBKT4bh" + }, + "source": [ + "### Step response\n", + "\n", + "Similar to `initial_response`, you can also generate a step response for a linear system using the `step_response` function, which returns a time response object:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "cplt = ct.step_response(sys).plot()" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "iHZR1Q3IcrFT" + }, + "source": [ + "We can analyze the properties of the step response using the `stepinfo` command:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "step_info = ct.step_info(sys)\n", + "print(\"Input 0, output 0 rise time = \",\n", + " step_info[0][0]['RiseTime'], \"seconds\\n\")\n", + "step_info" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "F8KxXwqHWFab" + }, + "source": [ + "Note that by default the inputs are not included in the step response plot (since they are a bit boring), but you can change that:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "stepresp = ct.step_response(sys)\n", + "cplt = stepresp.plot(plot_inputs=True)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Plot the inputs on top of the outputs\n", + "cplt = stepresp.plot(plot_inputs='overlay')" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Look at the \"shape\" of the step response\n", + "print(f\"{stepresp.time.shape=}\")\n", + "print(f\"{stepresp.inputs.shape=}\")\n", + "print(f\"{stepresp.states.shape=}\")\n", + "print(f\"{stepresp.outputs.shape=}\")" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "FDfZkyk1ly0T" + }, + "source": [ + "## Forced response\n", + "\n", + "To compute the response to an input, using the convolution equation, we can use the `forced_response` function:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "T = np.linspace(0, 50, 500)\n", + "U1 = np.cos(T)\n", + "U2 = np.sin(3 * T)\n", + "\n", + "resp1 = ct.forced_response(sys, T, U1)\n", + "resp2 = ct.forced_response(sys, T, U2)\n", + "resp3 = ct.forced_response(sys, T, U1 + U2)\n", + "\n", + "# Plot the individual responses\n", + "resp1.sysname = 'U1'; resp1.plot(color='b')\n", + "resp2.sysname = 'U2'; resp2.plot(color='g')\n", + "resp3.sysname = 'U1 + U2'; resp3.plot(color='r');" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Show that the system response is linear\n", + "cplt = resp3.plot()\n", + "cplt.axes[0, 0].plot(resp1.time, resp1.outputs[0] + resp2.outputs[0], 'k--')\n", + "cplt.axes[1, 0].plot(resp1.time, resp1.outputs[1] + resp2.outputs[1], 'k--')\n", + "cplt.axes[2, 0].plot(resp1.time, resp1.inputs[0] + resp2.inputs[0], 'k--');" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Show that the forced response from non-zero initial condition is not linear\n", + "X0 = [1, 0, 0, 0]\n", + "resp1 = ct.forced_response(sys, T, U1, X0=X0)\n", + "resp2 = ct.forced_response(sys, T, U2, X0=X0)\n", + "resp3 = ct.forced_response(sys, T, U1 + U2, X0=X0)\n", + "\n", + "cplt = resp3.plot()\n", + "cplt.axes[0, 0].plot(resp1.time, resp1.outputs[0] + resp2.outputs[0], 'k--')\n", + "cplt.axes[1, 0].plot(resp1.time, resp1.outputs[1] + resp2.outputs[1], 'k--')\n", + "cplt.axes[2, 0].plot(resp1.time, resp1.inputs[0] + resp2.inputs[0], 'k--');" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "mo7hpvPQkKke" + }, + "source": [ + "### Frequency response" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Manual computation of the frequency response\n", + "resp = ct.input_output_response(sys, T, np.sin(1.35 * T))\n", + "\n", + "cplt = resp.plot(\n", + " plot_inputs='overlay', \n", + " legend_map=np.array([['lower left'], ['lower left']]),\n", + " label=[['q1', 'u[0]'], ['q2', None]])" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "muqeLlJJ6s8F" + }, + "source": [ + "The magnitude and phase of the frequency response is controlled by the transfer function,\n", + "\n", + "$$\n", + "G(s) = C (sI - A)^{-1} B + D\n", + "$$\n", + "\n", + "which can be computed using the `ss2tf` function:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "try:\n", + " G = ct.ss2tf(sys, name='u to q1, q2')\n", + "except ct.ControlMIMONotImplemented:\n", + " # Create SISO transfer functions, in case we don't have slycot\n", + " G = ct.ss2tf(sys[0, 0], name='u to q1')\n", + "print(G)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Gain and phase for the simulation above\n", + "from math import pi\n", + "val = G(1.35j)\n", + "print(f\"{G(1.35j)=}\")\n", + "print(f\"Gain: {np.absolute(val)}\")\n", + "print(f\"Phase: {np.angle(val)}\", \" (\", np.angle(val) * 180/pi, \"deg)\")" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Gain and phase at s = 0 (= steady state step response)\n", + "print(f\"{G(0)=}\")\n", + "print(\"Final value of step response:\", stepresp.outputs[0, 0, -1])" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "I9eFoXm92Jgj" + }, + "source": [ + "The frequency response across all frequencies can be computed using the `frequency_response` function:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "freqresp = ct.frequency_response(sys)\n", + "cplt = freqresp.plot()" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "pylQb07G2cqe" + }, + "source": [ + "By default, frequency responses are plotted using a \"Bode plot\", which plots the log of the magnitude and the (linear) phase against the log of the forcing frequency.\n", + "\n", + "You can also call the Bode plot command directly, and change the way the data are presented:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "cplt = ct.bode_plot(sys, overlay_outputs=True)" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "I_LTjP2J6gqx" + }, + "source": [ + "Note the \"dip\" in the frequency response for y[1] at frequency 2 rad/sec, which corresponds to a \"zero\" of the transfer function.\n", + "\n", + "This dip becomes even more pronounced in the case of low damping coefficient $c$:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "cplt = ct.frequency_response(\n", + " coupled.linearize([0, 0, 0, 0], [0], params={'c': 0.01})\n", + ").plot(overlay_outputs=True)" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "c7eWm8LCGh01" + }, + "source": [ + "## Additional resources\n", + "* [Code for FBS2e figures](https://fbswiki.org/wiki/index.php/Category:Figures): Python code used to generate figures in FBS2e\n", + "* [Python-control documentation for plotting time responses](https://python-control.readthedocs.io/en/0.10.0/plotting.html#time-response-data)\n", + "* [Python-control documentation for plotting frequency responses](https://python-control.readthedocs.io/en/0.10.0/plotting.html#frequency-response-data)\n", + "* [Python-control examples](https://python-control.readthedocs.io/en/0.10.0/examples.html): lots of Python and Jupyter examples of control system analysis and design\n" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 4 +} diff --git a/examples/cds110-L4a_predprey-statefbk.ipynb b/examples/cds110-L4a_predprey-statefbk.ipynb new file mode 100644 index 000000000..487a4e40b --- /dev/null +++ b/examples/cds110-L4a_predprey-statefbk.ipynb @@ -0,0 +1,411 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": { + "id": "gQZtf4ZqM8HL" + }, + "source": [ + "
\n", + "

CDS 110, Lecture 4a

\n", + "

Dynamics and State Feedback Control of a Predator-Prey Model

\n", + "

Richard M. Murray, Winter 2024

\n", + "
\n", + "\n", + "[Open in Google Colab](https://colab.research.google.com/drive/1yMOSRNDDNtm-TJGMXX3NS7F4XybOuch-)\n", + "\n", + "In this lecture we describe the use of state space control concepts to analyze and stabilize the dynamics of a nonlinear model of a predator-prey system.\n" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "try:\n", + " import control as ct\n", + " print(\"python-control\", ct.__version__)\n", + "except ImportError:\n", + " !pip install control\n", + " import control as ct" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "qMVGK15gNQw2" + }, + "source": [ + "## Predator-Prey System Model\n", + "\n", + "We consider a predator-prey system, in which a predator species (lynxes) interacts with a prey species (hares):\n", + "\n", + "
\n", + " \"predprey-photo\"\n", + "   \n", + " \"predprey-photo\"\n", + "
\n", + "\n", + "The graph on the right shows the populations of hares and lynxes between 1845 and 1935 in a section of the Canadian Rockies (MacLulich, 1937)." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Define the dynamics for the predator-prey system (no input)\n", + "predprey_params = {'r': 1.6, 'd': 0.56, 'b': 0.6, 'k': 125, 'a': 3.2, 'c': 50}\n", + "def predprey_update(t, x, u, params):\n", + " \"\"\"Predator prey dynamics\"\"\"\n", + " r, d, b, k, a, c = map(params.get, ['r', 'd', 'b', 'k', 'a', 'c'])\n", + " u = np.clip(u, -r, r)\n", + "\n", + " # Dynamics for the system\n", + " dx0 = (r + u[0]) * x[0] * (1 - x[0]/k) - a * x[1] * x[0]/(c + x[0])\n", + " dx1 = b * a * x[1] * x[0] / (c + x[0]) - d * x[1]\n", + "\n", + " return np.array([dx0, dx1])\n", + "\n", + "# Create a nonlinear I/O system\n", + "predprey = ct.nlsys(\n", + " predprey_update, name='predprey', params=predprey_params,\n", + " states=['H', 'L'], inputs='u', outputs=['H', 'L'])" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "YmH87LEXWo1U" + }, + "source": [ + "### Open loop dynamics\n", + "\n", + "The open loop dynamics of the system are oscillatory, with a period similar to the data shown above:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "T = np.linspace(0, 100, 500)\n", + "response = ct.input_output_response(\n", + " predprey, T, 0, [35, 35]\n", + ")\n", + "ct.time_response_plot(response, plot_inputs=False, overlay_signals=True);" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "We can also visualize the data using a phase plane plot:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Generate a simple phase portrait\n", + "ct.phase_plane_plot(predprey, [0, 120, 0, 100], 1, gridtype='meshgrid');" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "We see that the default parameters give a lot of warning messages and the phase portrait does not convey all of the details in some regions of the state space.\n", + "\n", + "We can make sure of some of the functions in the `phaseplot` module to get a better view of the dynamics:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Generate a phase portrait\n", + "ct.phaseplot.equilpoints(predprey, [-5, 126, -5, 100])\n", + "ct.phaseplot.streamlines(\n", + " predprey, np.array([\n", + " [0, 100], [1, 0],\n", + " ]), 10, color='b')\n", + "ct.phaseplot.streamlines(\n", + " predprey, np.array([[124, 1]]), np.linspace(0, 10, 500), color='b')\n", + "ct.phaseplot.streamlines(\n", + " predprey, np.array([[125, 25], [125, 50], [125, 75]]), 3, color='b')\n", + "ct.phaseplot.streamlines(predprey, np.array([2, 8]), 6, color='b')\n", + "ct.phaseplot.streamlines(\n", + " predprey, np.array([[20, 30]]), np.linspace(0, 65, 500),\n", + " gridtype='circlegrid', gridspec=[2, 1], arrows=10, color='r')\n", + "ct.phaseplot.vectorfield(predprey, [5, 125, 5, 100], gridspec=[20, 20])\n", + "\n", + "# Add the limit cycle\n", + "resp1 = ct.initial_response(predprey, np.linspace(0, 100), [20, 75])\n", + "resp2 = ct.initial_response(\n", + " predprey, np.linspace(0, 20, 500), resp1.states[:, -1])\n", + "plt.plot(resp2.states[0], resp2.states[1], color='k');" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "KhjlC1258qff" + }, + "source": [ + "### Find the equilibrium points and check stability\n", + "\n", + "We see that there are three equilibrium points in the system. We can test the stability of the center equilibrium point, which from the phase portrait appears to be unstable." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "xe, ue = ct.find_eqpt(predprey, [20, 30], 0)\n", + "print(f\"{xe=}\")\n", + "print(f\"{ue=}\")" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "sys = predprey.linearize(xe, ue)\n", + "print(sys)\n", + "print(\"Poles: \", sys.poles())" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "sUECx0cz9QpK" + }, + "source": [ + "## Stabilization\n", + "\n", + "Suppose now that we have the ability to modulate the food supply for the hares. We do this by modifying the parameter $r$ in the model (this is the term `u` in the model at the top of the notebook). We can use the `place` command to find a set of gains that stabilize the dynamics around the unstable equilibrium point." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "K = ct.place(sys.A, sys.B, [-0.1, -0.2])\n", + "print(f\"{K=}\")" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Design an eigenvalue placement (EP) controller to stabilize the equilibrium point\n", + "epctrl = ct.nlsys(\n", + " None, lambda t, x, u, params: -K @ (u[0:2] - xe),\n", + " inputs=['H', 'L', 'r'], outputs=['u'],\n", + ")\n", + "predprey_ep = ct.interconnect(\n", + " [predprey, epctrl], inputs=['r'], outputs=['H', 'L', 'u'],\n", + " name='predprey w/ eval placement'\n", + ")\n", + "print(predprey_ep)\n", + "\n", + "# Show the connection table, useful for debugging what is connected to what\n", + "predprey_ep.connection_table()" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "xe_ep, ue_ep = ct.find_eqpt(predprey_ep, [20, 30], [0])\n", + "print(f\"{xe_ep=}\")\n", + "print(f\"{ue_ep=}\")\n", + "print(\"Poles: \", predprey_ep.linearize(xe_ep, ue_ep).poles())" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Generate a simple phase portrait\n", + "ct.phase_plane_plot(\n", + " predprey_ep, [0, 120, 0, 100], 1,\n", + " plot_separatrices=False,\n", + " gridtype='meshgrid', gridspec=[8, 5]\n", + " );\n", + "ct.phaseplot.streamlines(\n", + " predprey_ep, np.array([xe_ep]), 20, dir='reverse',\n", + " gridtype='circlegrid', gridspec=[4, 11]);" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Simulation from someplace nearby\n", + "T = np.linspace(0, 40)\n", + "response = ct.input_output_response(predprey_ep, T, 0, [35, 35])\n", + "ct.time_response_plot(\n", + " response, plot_inputs=False, overlay_signals=True,\n", + " title=\"I/O response with eval placement, \" +\n", + " f\"r = {predprey.params['r']}\",\n", + " legend_loc='upper right')\n", + "plt.plot([T[0], T[-1]], [0, 0], 'k--')\n", + "plt.plot([T[0], T[-1]], [xe_ep[0], xe_ep[0]], 'k--')\n", + "plt.plot([T[0], T[-1]], [xe_ep[1], xe_ep[1]], 'k--')" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "zZTBWhlTgSNk" + }, + "source": [ + "## Integral feedback\n", + "\n", + "Another technique that we will learn about later in the class is integral feedback, which can be used to compensate for modeling uncertainty and constant disturbances.\n", + "\n", + "We start by asking what happens if we change the value for the parameter $r$ from its original value of 1.6 to a new value of 1.65 (a change of less than 4%):" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Simulate with a change in food for the hares\n", + "T = np.linspace(0, 40)\n", + "response = ct.input_output_response(\n", + " predprey_ep, T, 0, [35, 35], params={'r': 1.65}\n", + ")\n", + "ct.time_response_plot(\n", + " response, plot_inputs=False, overlay_signals=True,\n", + " title=\"I/O response w/ eval placement, \" +\n", + " f\"r = {response.params['r']}\")\n", + "plt.plot([T[0], T[-1]], [0, 0], 'k--')\n", + "plt.plot([T[0], T[-1]], [xe_ep[0], xe_ep[0]], 'k--')\n", + "plt.plot([T[0], T[-1]], [xe_ep[1], xe_ep[1]], 'k--')\n", + "response.sysname" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "We see that the controller no longer stabilizes the equilibrium point (shown with the dashed lines). In particular, the steady state value of the lynx population does to almost twice the original value.\n", + "\n", + "This effect is even worse if we increase $r$ just a bit more (from 1.65 to 1.7)." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "T = np.linspace(0, 40)\n", + "response = ct.input_output_response(\n", + " predprey_ep, T, 0, xe, params={'r': 1.7}\n", + ")\n", + "ct.time_response_plot(\n", + " response, plot_inputs=False, overlay_signals=True,\n", + " title=\"I/O response for predprey w/ eval placement, \" +\n", + " f\"r = {response.params['r']}\")\n", + "plt.plot([T[0], T[-1]], [0, 0], 'k--')\n", + "plt.plot([T[0], T[-1]], [xe_ep[0], xe_ep[0]], 'k--')\n", + "plt.plot([T[0], T[-1]], [xe_ep[1], xe_ep[1]], 'k--')\n", + "response.sysname" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "The system dynamics are now oscillatory, indicating that we are no longer stabilizing the desired equilibrium point. This indicates a lack of robustness in our feedback control system.\n", + "\n", + "We can compensate for the change in the parameter $r$ by making use of integral feedback in our controller. We will learn more about integral feedback in later lectures, but for now we demonstrate its ability to compensate for errors in our system model." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Integral feedback\n", + "# Design an eigenvalue placement (EP) controller to stabilize the equilibrium point\n", + "Ki = 0.0001\n", + "pictrl = ct.nlsys(\n", + " lambda t, x, u, params: u[1] - u[2],\n", + " lambda t, x, u, params: -K @ (u[0:2] - xe) - Ki * x[0],\n", + " inputs=['H', 'L', 'r'], outputs=['u'], states=1,\n", + ")\n", + "predprey_pi = ct.interconnect(\n", + " [predprey, pictrl], inputs=['r'], outputs=['H', 'L', 'u'],\n", + " name='predprey_pi'\n", + ")\n", + "print(predprey_pi)\n", + "\n", + "# Simulate with a change in food for the hares\n", + "T = np.linspace(0, 100, 500)\n", + "response = ct.input_output_response(\n", + " predprey_pi, T, xe[1], [25, 25, 0], params={'r': 1.65})\n", + "ct.time_response_plot(\n", + " response, plot_inputs=False, overlay_signals=True,\n", + " title=\"I/O response w/ integral action, \" +\n", + " f\"r = {response.params['r']}\",\n", + " legend_loc='upper right')\n", + "\n", + "plt.plot([T[0], T[-1]], [0, 0], 'k--')\n", + "plt.plot([T[0], T[-1]], [xe_ep[0], xe_ep[0]], 'k--')\n", + "plt.plot([T[0], T[-1]], [xe_ep[1], xe_ep[1]], 'k--')" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "We see that the system is once again stable at the desired equilibrium point!" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 4 +} diff --git a/examples/cds110-L4b_lqr-tracking.ipynb b/examples/cds110-L4b_lqr-tracking.ipynb new file mode 100644 index 000000000..a4b1a0711 --- /dev/null +++ b/examples/cds110-L4b_lqr-tracking.ipynb @@ -0,0 +1,916 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": { + "id": "EHq8UWSjXSyz" + }, + "source": [ + "
\n", + "

CDS 110, Lecture 4b

\n", + "

LQR Tracking

\n", + "

Richard M. Murray and Natalie Bernat, Winter 2024

\n", + "
\n", + "\n", + "[Open in Google Colab](https://colab.research.google.com/drive/1Q6hXokOO_e3-wl6_ghigpxGJRUrGcHp3)\n", + "\n", + "This example uses a linear system to show how to implement LQR based tracking and some of the tradeoffs between feedfoward and feedback. Integral action is also implemented." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "try:\n", + " import control as ct\n", + " print(\"python-control\", ct.__version__)\n", + "except ImportError:\n", + " !pip install control\n", + " import control as ct" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "a23d6f89" + }, + "source": [ + "# Part I: Second order linear system\n", + "\n", + "We'll use a simple linear system to illustrate the concepts:\n", + "$$\n", + "\\frac{dx}{dt} =\n", + "\\begin{bmatrix}\n", + "0 & 10 \\\\\n", + "-1 & 0\n", + "\\end{bmatrix}\n", + "x +\n", + "\\begin{bmatrix}\n", + "0 \\\\\n", + "1\n", + "\\end{bmatrix}\n", + "u,\n", + "\\qquad\n", + "y = \\begin{bmatrix} 1 & 1 \\end{bmatrix} x.\n", + "$$\n", + "\n", + "" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Define a simple linear system that we want to control\n", + "A = np.array([[0, 10], [-1, 0]])\n", + "B = np.array([[0], [1]])\n", + "C = np.array([[1, 1]])\n", + "sys = ct.ss(A, B, C, 0, name='sys')\n", + "print(sys)" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "ja1g1MlbieJy" + }, + "source": [ + "## Linear quadratic regulator (LQR) design\n", + "\n", + "We'll design a controller of the form\n", + "\n", + "$$\n", + "u=-Kx+k_rr\n", + "$$\n", + "\n", + "- For the feedback control gain $K$, we'll use linear quadratic regulator theory. We seek to find the control law that minimizes the cost function:\n", + "\n", + " $$\n", + " J(x(\\cdot), u(\\cdot)) = \\int_0^\\infty x^T(\\tau) Q x(\\tau) + u^T(\\tau) R u(\\tau)\\, d\\tau\n", + " $$\n", + "\n", + " The weighting matrices $Q\\succeq 0 \\in \\mathbb{R}^{n \\times n}$ and $R \\succ 0\\in \\mathbb{R}^{m \\times m}$ should be chosen based on the desired performance of the system (tradeoffs in state errors and input magnitudes). See Example 3.5 in [Optimization Based Control (OBC)](https://fbswiki.org/wiki/index.php/Supplement:_Optimization-Based_Control) for a discussion of how to choose these weights. For now, we just choose identity weights for all states and inputs.\n", + "\n", + "- For the feedforward control gain $k_r$, we derive the feedforward gain from an equilibrium point analysis:\n", + " $$\n", + " y_e = C(A-BK)^{-1}Bk_rr\n", + " \\qquad\\implies\\qquad k_r = \\frac{-1}{C(A-BK)^{-1}B}\n", + " $$" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Construct an LQR controller for the system\n", + "Q = np.eye(sys.nstates)\n", + "R = np.eye(sys.ninputs)\n", + "K, _, _ = ct.lqr(sys, Q, R)\n", + "print('K: '+str(K))\n", + "\n", + "# Set the feedforward gain to track the reference\n", + "kr = (-1 / (C @ np.linalg.inv(A - B @ K) @ B))\n", + "print('k_r: '+str(kr))" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "99f036ea" + }, + "source": [ + "Now that we have our gains designed, we can simulate the closed loop system:\n", + "$$\n", + "\\frac{dx}{dt} = A_{cl}x + B_{cl} r,\n", + "\\quad A_{cl} = A-BK,\n", + "\\quad B_{cl} = Bk_r\n", + "$$\n", + "Notice that, with a state feedback controller, the new (closed loop) dynamics matrix absorbs the old (open loop) \"input\" $u$, and the new (closed loop) input is our reference signal $r$." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Create a closed loop system\n", + "A_cl = A - B @ K\n", + "B_cl = B * kr\n", + "clsys = ct.ss(A_cl, B_cl, C, 0)\n", + "print(clsys)" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "84422c3f" + }, + "source": [ + "## System simulations\n", + "\n", + "### Baseline controller\n", + "\n", + "To see how the baseline controller performs, we ask it to track a constant reference $r = 2$:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Plot the step response with respect to the reference input\n", + "r = 2\n", + "Tf = 8\n", + "tvec = np.linspace(0, Tf, 100)\n", + "\n", + "U = r * np.ones_like(tvec)\n", + "time, output = ct.input_output_response(clsys, tvec, U)\n", + "plt.plot(time, output)\n", + "plt.plot([time[0], time[-1]], [r, r], '--');\n", + "plt.legend(['y', 'r']);\n", + "plt.ylabel(\"Output\")\n", + "plt.xlabel(\"Time $t$ [sec]\")\n", + "plt.title(\"Baseline controller step response\")" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "ea2d1c59" + }, + "source": [ + "Things to try:\n", + "- set $k_r=0$\n", + "- set $k_r \\neq \\frac{-1}{C(A-BK)^{-1}B}$\n", + "- try different LQR weightings" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "84ee7635" + }, + "source": [ + "### Disturbance rejection\n", + "\n", + "To add an input disturbance to the system, we include a second open loop input:\n", + "$$\n", + "\\frac{dx}{dt} =\n", + "\\begin{bmatrix}\n", + "0 & 10 \\\\\n", + "-1 & 0\n", + "\\end{bmatrix}\n", + "x +\n", + "\\begin{bmatrix}\n", + "0 & 0\\\\\n", + "1 & 1\n", + "\\end{bmatrix}\n", + "\\begin{bmatrix}\n", + "u\\\\\n", + "d\n", + "\\end{bmatrix},\n", + "\\qquad\n", + "y = \\begin{bmatrix} 1 & 1 \\end{bmatrix} x.\n", + "$$\n", + "\n", + "Our closed loop system becomes:\n", + "$$\n", + "\\frac{dx}{dt} =\n", + "\\begin{bmatrix}\n", + "0 & 10 \\\\\n", + "-1-K_{1} & 0-K_{2}\n", + "\\end{bmatrix}\n", + "x +\n", + "\\begin{bmatrix}\n", + "0 & 0\\\\\n", + "k_r & 1\n", + "\\end{bmatrix}\n", + "\\begin{bmatrix}\n", + "r\\\\\n", + "d\n", + "\\end{bmatrix},\n", + "\\qquad\n", + "y = \\begin{bmatrix} 1 & 1 \\end{bmatrix} x.\n", + "$$" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Resimulate with a disturbance input\n", + "B_ext = np.hstack([B * kr, B])\n", + "clsys = ct.ss(A - B @ K, B_ext, C, 0)\n", + "\n", + "# Construct the inputs for the augmented system\n", + "delta = 0.5\n", + "U = np.vstack([r * np.ones_like(tvec), delta * np.ones_like(tvec)])\n", + "\n", + "time, output = ct.input_output_response(clsys, tvec, U)\n", + "\n", + "plt.plot(time, output[0])\n", + "plt.plot([time[0], time[-1]], [r, r], '--')\n", + "plt.legend(['y', 'r']);\n", + "plt.ylabel(\"Output\")\n", + "plt.xlabel(\"Time $t$ [sec]\")\n", + "plt.title(\"Baseline controller step response with disturbance\");" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "Qis2PP3nd7ua" + }, + "source": [ + "We see that this leads to steady state error, since the feedforward signal didn't include an offset for the disturbance." + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "84a9e61c" + }, + "source": [ + "#### Integral feedback\n", + "\n", + "A standard approach to compensate for constant disturbances is to use integral feedback. To do this, we have to keep track of the integral of the error\n", + "\n", + "$$z = \\int_0^\\tau (y - r)\\, d\\tau= \\int_0^\\tau (Cx - r)\\, d\\tau.$$\n", + "\n", + "We do this by creating an augmented system that includes the dynamics of the process ($dx/dt$) along with the dynamics of the integrator state ($dz/dt$):\n", + "\n", + "$$\n", + "\\frac{d}{dt}\\begin{bmatrix}\n", + "x \\\\\n", + "z\n", + "\\end{bmatrix} =\n", + "\\begin{bmatrix}\n", + "A & 0 \\\\\n", + "C & 0\n", + "\\end{bmatrix}\n", + "\\begin{bmatrix}\n", + "x \\\\\n", + "z\n", + "\\end{bmatrix} +\n", + "\\begin{bmatrix}\n", + "B\\\\\n", + "0 \\\\\n", + "\\end{bmatrix}\n", + "u+\n", + "\\begin{bmatrix}\n", + "0\\\\\n", + "-I \\\\\n", + "\\end{bmatrix}\n", + "r,\n", + "\\qquad\n", + "y = \\begin{bmatrix} C \\\\ 0 \\end{bmatrix} \\begin{bmatrix}\n", + "x \\\\\n", + "z\n", + "\\end{bmatrix}.\n", + "$$\n" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Define an augmented state space for use with LQR\n", + "A_aug = np.block([[sys.A, np.zeros((sys.nstates, 1))], [C, 0] ])\n", + "B_aug = np.vstack([sys.B, 0])\n", + "print(\"A =\", A_aug, \"\\nB =\", B_aug)" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "463d9b85" + }, + "source": [ + "\n", + "Our controller then takes the form:\n", + "\n", + "$$\n", + "\\begin{aligned}\n", + "u &= - Kx - k_\\text{i} \\int_0^\\tau (y - r)\\, d\\tau+k_rr \\\\\n", + " &= - (Kx + k_\\text{i}z)+k_rr .\n", + "\\end{aligned}\n", + "$$\n", + "\n", + "This results in the closed loop system:\n", + "$$\n", + "\\frac{dx}{dt} =\n", + "\\begin{bmatrix}\n", + "A-BK & -Bk_i \\\\\n", + "C & 0\n", + "\\end{bmatrix}\n", + "\\begin{bmatrix}\n", + "x \\\\\n", + "z\n", + "\\end{bmatrix} +\n", + "\\begin{bmatrix}\n", + "Bk_r\\\\\n", + "-I \\\\\n", + "\\end{bmatrix}\n", + "r,\n", + "\\qquad\n", + "y = \\begin{bmatrix} C \\\\ 0 \\end{bmatrix} \\begin{bmatrix}\n", + "x \\\\\n", + "z\n", + "\\end{bmatrix}.\n", + "$$\n", + "\n", + "Since z is part of the augmented state space, we can generate an LQR controller for the augmented system to find both the usual gain $K$ and the integral gain $k_i$:\n", + "$$\n", + "\\bar{K} = \\begin{bmatrix} K& k_i\\end{bmatrix}\n", + "$$" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Create an LQR controller for the augmented system\n", + "K_aug, _, _ = ct.lqr(A_aug, B_aug, np.diag([1, 1, 1]), np.eye(sys.ninputs))\n", + "print('K_aug: '+str(K_aug))\n", + "\n", + "K = K_aug[:, 0:2]\n", + "ki = K_aug[:, 2]\n", + "kr = -1 / (C @ np.linalg.inv(A - B * K) @ B)" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "19bb6592" + }, + "source": [ + "\n", + "\n", + "\n", + "Notice that the value of $K$ changed, so we needed to recompute $k_r$ too." + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "zHlf8zoHoqvF" + }, + "source": [ + "To run simulations, we return to our system augmented with a disturbance, but we expand the outputs available to the controller:\n", + "\n", + "$$\n", + "\\frac{dx}{dt} =\n", + "\\begin{bmatrix}\n", + "0 & 10 \\\\\n", + "-1 & 0\n", + "\\end{bmatrix}\n", + "x +\n", + "\\begin{bmatrix}\n", + "0 & 0\\\\\n", + "1 & 1\n", + "\\end{bmatrix}\n", + "\\begin{bmatrix}\n", + "u\\\\\n", + "d\n", + "\\end{bmatrix},\n", + "$$\n", + "\n", + "$$\n", + "\\bar{y} = \\begin{bmatrix} 1 & 0 & 1 \\\\ 0 & 1 & 1 \\end{bmatrix}^T x = \\begin{bmatrix} x_1 & x_2 & y \\end{bmatrix} .\n", + "$$\n", + "\n", + "The controller then constructs its internal state $z$ out of $x$ and $r$.\n", + "\n", + "" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Construct a system with disturbance inputs, and full outputs (for the controller)\n", + "A_integral = sys.A\n", + "B_integral = np.hstack([sys.B, sys.B])\n", + "C_integral = [[1, 0], [0, 1], [1, 1]] # outputs for the controller: x1, x2, y\n", + "sys_integral = ct.ss(\n", + " A_integral, B_integral, C_integral, 0,\n", + " inputs=['u', 'd'],\n", + " outputs=['x1', 'x2', 'y']\n", + ")\n", + "print(sys_integral)\n", + "\n", + "# Construct an LQR+integral controller for the system with an internal state z\n", + "A_ctrl = [[0]]\n", + "B_ctrl = [[1, 1, -1]] # z_dot=Cx-r\n", + "C_ctrl = -ki #-ki*z\n", + "D_ctrl = np.hstack([-K, kr]) #-K*x + kr*r\n", + "ctrl_integral=ct.ss(\n", + " A_ctrl, B_ctrl, C_ctrl, D_ctrl, # u = -ki*z - K*x + kr*r\n", + " inputs=['x1', 'x2', 'r'], # system outputs + reference\n", + " outputs=['u'], # controller action\n", + ")\n", + "print(ctrl_integral)\n", + "\n", + "# Create the closed loop system\n", + "clsys_integral = ct.interconnect([sys_integral, ctrl_integral], inputs=['r', 'd'], outputs=['y'])\n", + "print(clsys_integral)\n", + "\n", + "# Resimulate with a disturbance input\n", + "delta = 0.5\n", + "U = np.vstack([r * np.ones_like(tvec), delta * np.ones_like(tvec)])\n", + "time, output, states = ct.input_output_response(clsys_integral, tvec, U, return_x=True)\n", + "plt.plot(time, output[0])\n", + "plt.plot([time[0], time[-1]], [r, r], '--')\n", + "plt.plot(time, states[2])\n", + "plt.legend(['y', 'r', 'z']);\n", + "plt.ylabel(\"Output\")\n", + "plt.xlabel(\"Time $t$ [sec]\")\n", + "plt.title(\"LQR+integral controller step response with disturbance\")" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "M9nXbITrhYg7" + }, + "source": [ + "Notice that the steady state value of $z=\\int(y-r)$ is not zero, but rather settles to whatever value makes $y-r$ zero!\n", + "" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "f8bfc15c" + }, + "source": [ + "# Part II: PVTOL Linear Quadratic Regulator Example\n", + "\n", + "Natalie Bernat, 26 Apr 2024
\n", + "Richard M. Murray, 25 Jan 2022\n", + "\n", + "This notebook contains an example of LQR control applied to the PVTOL system. It demonstrates how to construct an LQR controller by linearizing the system, and provides an alternate view of the feedforward component of the controller." + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "77e2ed47" + }, + "source": [ + "## System description\n", + "\n", + "We use the PVTOL dynamics from [Feedback Systems (FBS2e)](https://fbswiki.org/wiki/index.php/Feedback_Systems:_An_Introduction_for_Scientists_and_Engineers), which can be found in Example 3.12}\n", + "\n", + "\n", + "\n", + " \n", + " \n", + " \n", + "\n", + "
\n", + "$$\n", + "\\begin{aligned}\n", + " m \\ddot x &= F_1 \\cos\\theta - F_2 \\sin\\theta - c \\dot x, \\\\\n", + " m \\ddot y &= F_1 \\sin\\theta + F_2 \\cos\\theta - m g - c \\dot y, \\\\\n", + " J \\ddot \\theta &= r F_1.\n", + "\\end{aligned}\n", + "$$\n", + " \n", + "$$\n", + "\\frac{dz}{dt} =\n", + "\\begin{bmatrix}\n", + "z_4 \\\\\n", + "z_5 \\\\\n", + "z_6 \\\\\n", + "-\\frac{c}{m}z_4 \\\\\n", + "-g-\\frac{c}{m}z_5 \\\\\n", + "0\n", + "\\end{bmatrix} +\n", + "\\begin{bmatrix}\n", + "0 \\\\\n", + "0 \\\\\n", + "0 \\\\\n", + "\\frac{F_1}{m}cos\\theta -\\frac{F_2}{m}sin\\theta \\\\\n", + "\\frac{F_1}{m}sin\\theta +\\frac{F_2}{m}cos\\theta \\\\\n", + "-\\frac{r}{J}F_1\n", + "\\end{bmatrix}\n", + "$$\n", + "
\n", + "\n", + "The state space variables for this system are:\n", + "\n", + "$z=(x,y,\\theta, \\dot x,\\dot y,\\dot \\theta), \\quad u=(F_1,F_2)$\n", + "\n", + "Notice that the x and y positions ($z_1$ and $z_2$) do not actually appear in the dynamics-- this makes sense, since the aircraft should hypothetically fly the same way no matter where in the air it is (neglecting effects near the ground)." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# PVTOL dynamics\n", + "def pvtol_update(t, x, u, params):\n", + " from math import cos, sin\n", + " \n", + " # Get the parameter values\n", + " m, J, r, g, c = map(params.get, ['m', 'J', 'r', 'g', 'c'])\n", + "\n", + " # Get the inputs and states\n", + " x, y, theta, xdot, ydot, thetadot = x\n", + " F1, F2 = u\n", + "\n", + " # Constrain the inputs\n", + " F2 = np.clip(F2, 0, 1.5 * m * g)\n", + " F1 = np.clip(F1, -0.1 * F2, 0.1 * F2)\n", + "\n", + " # Dynamics\n", + " xddot = (F1 * cos(theta) - F2 * sin(theta) - c * xdot) / m\n", + " yddot = (F1 * sin(theta) + F2 * cos(theta) - m * g - c * ydot) / m\n", + " thddot = (r * F1) / J\n", + "\n", + " return np.array([xdot, ydot, thetadot, xddot, yddot, thddot])\n", + "\n", + "def pvtol_output(t, x, u, params):\n", + " return x\n", + "\n", + "pvtol = ct.nlsys(\n", + " pvtol_update, pvtol_output, name='pvtol',\n", + " states = [f'x{i}' for i in range(6)],\n", + " inputs = ['F1', 'F2'],\n", + " outputs=[f'x{i}' for i in range(6)],\n", + " # outputs = ['x', 'y', 'theta', 'xdot', 'ydot', 'thdot'],\n", + " params = {\n", + " 'm': 4., # mass of aircraft\n", + " 'J': 0.0475, # inertia around pitch axis\n", + " 'r': 0.25, # distance to center of force\n", + " 'g': 9.8, # gravitational constant\n", + " 'c': 0.05, # damping factor (estimated)\n", + " }\n", + ")\n", + "\n", + "print(pvtol)\n", + "print(pvtol.params)" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "YZiISLS-qMS_" + }, + "source": [ + "Next, we'll linearize the system around the equilibrium points. As discussed in FBS2e (example 7.9), the linearization around this equilibrium point has the form:\n", + "$$\n", + "A =\n", + "\\begin{bmatrix}\n", + "0 & 0 & 0 & 1 & 0 & 0\\\\\n", + "0 & 0 & 0 & 0 & 1 & 0 \\\\\n", + "0 & 0 & 0 & 0 & 0 & 1 \\\\\n", + "0 & 0 & -g & -c/m & 0 & 0 \\\\\n", + "0 & 0 & 0 & 0 & -c/m & 0 \\\\\n", + "0 & 0 & 0 & 0 & 0 & 0\n", + "\\end{bmatrix}\n", + ", \\quad B=\n", + "\\begin{bmatrix}\n", + "0 & 0 \\\\\n", + "0 & 0 \\\\\n", + "0 & 0 \\\\\n", + "1/m & 0 \\\\\n", + "0 & 1/m \\\\\n", + "r/J & 0\n", + "\\end{bmatrix}\n", + ".\n", + "$$\n", + "(note that here $r$ is a system parameter, not the same as the reference $r$ we've been using elsewhere in this notebook)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "To compute this linearization in python-control, we start by computing the equilibrium point. We do this using the `find_eqpt` function, which can be used to find equilibrium points satisfying varioius conditions. For this system, we wish to find the state $x_\\text{e}$ and input $u_\\text{e}$ that holds the $x, y$ position of the aircraft at the point $(0, 0)$. The `find_eqpt` function performs a numerical optimization to find the values of $x_\\text{e}$ and $u_\\text{e}$ corresponding to an equilibrium point with the desired values for the outputs. We pass the function initial guesses for the state and input as well the values of the output and the indices of the output that we wish to constrain:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Find the equilibrium point corresponding to hover\n", + "xeq, ueq = ct.find_eqpt(pvtol, np.zeros(6), np.zeros(2), y0=np.zeros(6), iy=[0, 1])\n", + "print(f\"{xeq=}, {ueq=}\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Using these values, we compute the linearization:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "linsys = pvtol.linearize(xeq, ueq)\n", + "print(linsys)" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "7cb8840b" + }, + "source": [ + "## Linear quadratic regulator (LQR) design\n", + "\n", + "Now that we have a linearized model of the system, we can compute a controller using linear quadratic regulator theory. We wish to minimize the following cost function\n", + "\n", + "$$\n", + "J(\\phi(\\cdot), \\nu(\\cdot)) = \\int_0^\\infty \\phi^T(\\tau) Q \\phi(\\tau) + \\nu^T(\\tau) R \\nu(\\tau)\\, d\\tau,\n", + "$$\n", + "\n", + "where we have changed to our linearized coordinates:\n", + "\n", + "$$\\phi=z-z_e, \\quad \\nu = u-u_e$$\n", + "\n", + "Using the standard approach for finding K, we obtain a feedback controller for the system:\n", + "$$\\nu=-K\\phi$$" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Start with a diagonal weighting\n", + "Q1 = np.diag([1, 1, 1, 1, 1, 1])\n", + "R1 = np.diag([1, 1])\n", + "K, X, E = ct.lqr(linsys, Q1, R1)" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "863d07de" + }, + "source": [ + "To create a controller for the system, we have to apply a control signal $u$, so we change back from the relative coordinates to the absolute coordinates:\n", + "\n", + "$$u=u_e - K(z - z_e)$$\n", + "\n", + "Notice that, since $(Kz_e+u_e)$ is completely determined by (user-defined) inputs to the system, this term is a type of feedforward control signal.\n", + "\n", + "To create a controller for the system, we can use the function [`create_statefbk_iosystem()`](https://python-control.readthedocs.io/en/latest/generated/control.create_statefbk_iosystem.html), which creates an I/O system that takes in a desired trajectory $(x_\\text{d}, u_\\text{d})$ and the current state $x$ and generates a control law of the form:\n", + "\n", + "$$\n", + "u = u_\\text{d} - K (x - x_\\text{d})\n", + "$$\n", + "\n", + "Note that this is slightly different than the first equation: here we are using $x_\\text{d}$ instead of $x_\\text{e}$ and $u_\\text{d}$ instead of $u_\\text{e}$. This is because we want our controller to track a desired trajectory $(x_\\text{d}(t), u_\\text{d}(t))$ rather than just stabilize the equilibrium point $(x_\\text{e}, u_\\text{e})$." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "control, pvtol_closed = ct.create_statefbk_iosystem(pvtol, K)\n", + "print(control, \"\\n\")\n", + "print(pvtol_closed)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "This command will usually generate a warning saying that python control \"cannot verify system output is system state\". This happens because we specified an output function `pvtol_output` when we created the system model, and python-control does not have a way of checking that the output function returns the entire state (which is needed if we are going to do full-state feedback).\n", + "\n", + "This warning could be avoided by passing the argument `None` for the system output function, in which case python-control returns the full state as the output (and it knows that the full state is being returned as the output)." + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "bedcb0c0" + }, + "source": [ + "## Closed loop system simulation\n", + "\n", + "For this simple example, we set the target for the system to be a \"step\" input that moves the system 1 meter to the right.\n", + "\n", + "We start by defining a short function to visualize the output using a collection of plots:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Utility function to plot the results in a useful way\n", + "def plot_results(t, x, u, fig=None):\n", + " # Set the size of the figure\n", + " if fig is None:\n", + " fig = plt.figure(figsize=(10, 6))\n", + "\n", + " # Top plot: xy trajectory\n", + " plt.subplot(2, 1, 1)\n", + " lines = plt.plot(x[0], x[1])\n", + " plt.xlabel('x [m]')\n", + " plt.ylabel('y [m]')\n", + " plt.axis('equal')\n", + "\n", + " # Mark starting and ending points\n", + " color = lines[0].get_color()\n", + " plt.plot(x[0, 0], x[1, 0], 'o', color=color, fillstyle='none')\n", + " plt.plot(x[0, -1], x[1, -1], 'o', color=color, fillstyle='full')\n", + "\n", + "\n", + " # Time traces of the state and input\n", + " plt.subplot(2, 4, 5)\n", + " plt.plot(t, x[1])\n", + " plt.xlabel('Time t [sec]')\n", + " plt.ylabel('y [m]')\n", + "\n", + " plt.subplot(2, 4, 6)\n", + " plt.plot(t, x[2])\n", + " plt.xlabel('Time t [sec]')\n", + " plt.ylabel('theta [rad]')\n", + "\n", + " plt.subplot(2, 4, 7)\n", + " plt.plot(t, u[0])\n", + " plt.xlabel('Time t [sec]')\n", + " plt.ylabel('$F_1$ [N]')\n", + "\n", + " plt.subplot(2, 4, 8)\n", + " plt.plot(t, u[1])\n", + " plt.xlabel('Time t [sec]')\n", + " plt.ylabel('$F_2$ [N]')\n", + " plt.tight_layout()\n", + "\n", + " return fig" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Next we generate a step response and plot the results. Because our closed loop system takes as inputs $x_\\text{d}$ and $u_\\text{d}$, we need to set those variable to values that would correspond to our step input. In this case, we are taking a step in the $x$ coordinate, so we set $x_\\text{d}$ to be $1$ in that coordinate starting at $t = 0$ and continuing for some sufficiently long period of time ($15$ seconds):" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Generate a step response by setting xd, ud\n", + "Tf = 15\n", + "T = np.linspace(0, Tf, 100)\n", + "xd = np.outer(np.array([1, 0, 0, 0, 0, 0]), np.ones_like(T))\n", + "ud = np.outer(ueq, np.ones_like(T))\n", + "ref = np.vstack([xd, ud])\n", + "\n", + "response = ct.input_output_response(pvtol_closed, T, ref, xeq)\n", + "fig = plot_results(response.time, response.states, response.outputs[6:])" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "f014e660" + }, + "source": [ + "This controller does a pretty good job. We see in the top plot the $x$, $y$ projection of the trajectory, with the open circle indicating the starting point and the closed circle indicating the final point. The bottom set of plots show the altitude and pitch as functions of time, as well as the input forces. All of the signals look reasonable.\n", + "\n", + "The limitations of the linear controller can be seen if we take a larger step, say 10 meters." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "xd = np.outer(np.array([10, 0, 0, 0, 0, 0]), np.ones_like(T))\n", + "ref = np.vstack([xd, ud])\n", + "response = ct.input_output_response(pvtol_closed, T, ref, xeq)\n", + "fig = plot_results(response.time, response.states, response.outputs[6:])" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "4luxppVpm6Xo" + }, + "source": [ + "We now see that the trajectory looses significant altitude ($> 2.5$ meters). This is because the linear controller sees a large initial error and so it applies very large input forces to correct for the error ($F_1 \\approx -10$ N at $t = 0$. This causes the aircraft to pitch over to a large angle (almost $-60$ degrees) and this causes a large loss in altitude.\n", + "\n", + "We will see in the [Lecture 6](cds110-L6a_kincar-trajgen) how to remedy this problem by making use of feasible trajectory generation." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 4 +} diff --git a/examples/cds110-L5_kincar-estimation.ipynb b/examples/cds110-L5_kincar-estimation.ipynb new file mode 100644 index 000000000..6eea0a1f0 --- /dev/null +++ b/examples/cds110-L5_kincar-estimation.ipynb @@ -0,0 +1,815 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": { + "id": "-cop8q3CTs-G" + }, + "source": [ + "
\n", + "

CDS 110, Lecture 5

\n", + "

State Estimation for a Kinematic Car Model

\n", + "

Richard M. Murray, Winter 2024

\n", + "
\n", + "\n", + "[Open in Google Colab](https://colab.research.google.com/drive/1TESB0NzWS3XBxJa_hdOXMifICbBEDRz8)\n", + "\n", + "In this lecture, we will show how to construct an observer for a system in the presence of noise and disturbances.\n", + "\n", + "Recall that an observer is a system that takes as input the (noisy) measured output of a system along with the applied input to the system, and produces as estimate $\\hat x$ of the current state:\n", + "\n", + "
\n", + "\n", + "
\n", + "\n" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Import the various Python packages that we require\n", + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "from math import pi, sin, cos, tan\n", + "try:\n", + " import control as ct\n", + " print(\"python-control\", ct.__version__)\n", + "except ImportError:\n", + " !pip install control\n", + " import control as ct\n", + "import control.flatsys as fs" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "c5UGnS73sH4c" + }, + "source": [ + "## White noise\n", + "\n", + "A white noise process $W(t)$ is a signal that has the property that the mean of the signal is 0 and the value of the signal at any point in time $t$ is uncorrelated to the value of the signal at a point in time $s$, but that has a fixed amount of variance. Mathematically, a white noise process $W\n", + "(t) \\in \\mathbb{R}^k$ satisfies\n", + "\n", + "$$\n", + "\\begin{aligned}\n", + "\\mathbb{E}\\{W(t)\\} &= 0, &&\\text{for all $t$} \\\\\n", + "\\mathbb{E}\\{W^\\mathtt{T}(t) W(s)\\} &= Q\\, \\delta(t-s) && \\text{for all $s, t$},\n", + "\\end{aligned}\n", + "$$\n", + "\n", + "where $Q \\in \\mathbb{R}^{k \\times k}$ is the \"intensity\" of the white noise process.\n", + "\n", + "The python-control function `white_noise` can be used to create an instantiation of a white noise process:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Create the time vector that we want to use\n", + "Tf = 5\n", + "T = np.linspace(0, Tf, 1000)\n", + "dt = T[1] - T[0]\n", + "\n", + "# Create a white noise signal\n", + "?ct.white_noise\n", + "Q = np.array([[0.1]])\n", + "W = ct.white_noise(T, Q)\n", + "\n", + "plt.figure(figsize=[5, 3])\n", + "plt.plot(T, W[0])\n", + "plt.xlabel('Time [s]')\n", + "plt.ylabel('$V$');" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "MtAPkkCd14_g" + }, + "source": [ + "To confirm this is a white noise signal, we can compute the correlation function\n", + "\n", + "$$\n", + "\\rho(\\tau) = \\mathbb{E}\\{V^\\mathtt{T}(t) V(t + \\tau)\\} = Q\\, \\delta(\\tau),\n", + "$$\n", + "\n", + "where $\\delta(\\tau)$ is the unit impulse function:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Correlation function for the input\n", + "tau, r_W = ct.correlation(T, W)\n", + "\n", + "plt.plot(tau, r_W, 'r-')\n", + "plt.xlabel(r'$\\tau$')\n", + "plt.ylabel(r'$r_W(\\tau)$')\n", + "\n", + "# Compute out the area under the peak\n", + "print(\"Signal covariance: \", Q.item())\n", + "print(\"Area under impulse: \", np.max(W) * dt)" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "1eN_MZ94tQ9v" + }, + "source": [ + "## System definition: kinematic car\n", + "\n", + "We make use of a simple model for a vehicle navigating in the plane, known as the \"bicycle model\". The kinematics of this vehicle can be written in terms of the contact point $(x, y)$ and the angle $\\theta$ of the vehicle with respect to the horizontal axis:\n", + "\n", + "\n", + "\n", + " \n", + " \n", + "\n", + "
\n", + "$$\n", + "\\large\\begin{aligned}\n", + " \\dot x &= \\cos\\theta\\, v \\\\\n", + " \\dot y &= \\sin\\theta\\, v \\\\\n", + " \\dot\\theta &= \\frac{v}{l} \\tan \\delta\n", + "\\end{aligned}\n", + "$$\n", + "
\n", + "\n", + "The input $v$ represents the velocity of the vehicle and the input $\\delta$ represents the turning rate. The parameter $l$ is the wheelbase." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# System definition\n", + "# Function to compute the RHS of the system dynamics\n", + "def kincar_update(t, x, u, params):\n", + " # Get the parameters for the model\n", + " l = params['wheelbase'] # vehicle wheelbase\n", + " deltamax = params['maxsteer'] # max steering angle (rad)\n", + "\n", + " # Saturate the steering input\n", + " delta = np.clip(u[1], -deltamax, deltamax)\n", + "\n", + " # Return the derivative of the state\n", + " return np.array([\n", + " np.cos(x[2]) * u[0], # xdot = cos(theta) v\n", + " np.sin(x[2]) * u[0], # ydot = sin(theta) v\n", + " (u[0] / l) * np.tan(delta) # thdot = v/l tan(delta)\n", + " ])\n", + "\n", + "kincar_params={'wheelbase': 3, 'maxsteer': 0.5}\n", + "\n", + "# Create nonlinear input/output system\n", + "kincar = ct.nlsys(\n", + " kincar_update, None, name=\"kincar\", params=kincar_params,\n", + " inputs=('v', 'delta'), outputs=('x', 'y', 'theta'),\n", + " states=('x', 'y', 'theta'))" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Utility function to plot lane change manuever\n", + "def plot_lanechange(t, y, u, figure=None, yf=None, label=None):\n", + " # Plot the xy trajectory\n", + " plt.subplot(3, 1, 1, label='xy')\n", + " plt.plot(y[0], y[1], label=label)\n", + " plt.xlabel(\"x [m]\")\n", + " plt.ylabel(\"y [m]\")\n", + " if yf is not None:\n", + " plt.plot(yf[0], yf[1], 'ro')\n", + "\n", + " # Plot x and y as functions of time\n", + " plt.subplot(3, 2, 3, label='x')\n", + " plt.plot(t, y[0])\n", + " plt.ylabel(\"$x$ [m]\")\n", + "\n", + " plt.subplot(3, 2, 4, label='y')\n", + " plt.plot(t, y[1])\n", + " plt.ylabel(\"$y$ [m]\")\n", + "\n", + " # Plot the inputs as a function of time\n", + " plt.subplot(3, 2, 5, label='v')\n", + " plt.plot(t, u[0])\n", + " plt.xlabel(\"Time $t$ [sec]\")\n", + " plt.ylabel(\"$v$ [m/s]\")\n", + "\n", + " plt.subplot(3, 2, 6, label='delta')\n", + " plt.plot(t, u[1])\n", + " plt.xlabel(\"Time $t$ [sec]\")\n", + " plt.ylabel(\"$\\\\delta$ [rad]\")\n", + "\n", + " plt.subplot(3, 1, 1)\n", + " plt.title(\"Lane change manuever\")\n", + " if label:\n", + " plt.legend()\n", + " plt.tight_layout()" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "5F-40uInyvQr" + }, + "source": [ + "We next define a desired trajectory for the vehicle. For simplicity, we use a piecewise linear trajectory and then stabilize the system around that trajectory. We will learn in a later lecture how to do this is in more rigorous way. For now, it is enough to know that this generates a feasible trajectory for the vehicle." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Generate a trajectory for the vehicle\n", + "# Define the endpoints of the trajectory\n", + "x0 = np.array([0., -4., 0.]); u0 = np.array([10., 0.])\n", + "xf = np.array([40., 4., 0.]); uf = np.array([10., 0.])\n", + "Tf = 4\n", + "Ts = Tf / 100\n", + "\n", + "# First 0.6 seconds: drive straight\n", + "T1 = np.linspace(0, 0.6, 15, endpoint=False)\n", + "x1 = np.array([6, -4, 0])\n", + "xd1 = np.array([x0 + (x1 - x0) * (t - T1[0]) / (T1[-1] - T1[0]) for t in T1]).transpose()\n", + "\n", + "# Next 2.8 seconds: change to the other lane\n", + "T2 = np.linspace(0.6, 3.4, 70, endpoint=False)\n", + "x2 = np.array([35, 4, 0])\n", + "xd2 = np.array([x1 + (x2 - x1) * (t - T2[0]) / (T2[-1] - T2[0]) for t in T2]).transpose()\n", + "\n", + "# Final 0.6 seconds: drive straight\n", + "T3 = np.linspace(3.4, Tf, 15, endpoint=False)\n", + "xd3 = np.array([x2 + (xf - x2) * (t - T3[0]) / (T3[-1] - T3[0]) for t in T3]).transpose()\n", + "\n", + "T = np.hstack([T1, T2, T3])\n", + "xr = np.hstack([xd1, xd2, xd3])\n", + "ur = np.array([u0 for t in T]).transpose()\n", + "\n", + "# Now create a simple controller to stabilize the trajectory\n", + "P = kincar.linearize(x0, u0)\n", + "K, _, _ = ct.lqr(\n", + " kincar.linearize(x0, u0),\n", + " np.diag([10, 100, 1]), np.diag([10, 10])\n", + ")\n", + "\n", + "# Construct a closed loop controller for the system\n", + "ctrl, clsys = ct.create_statefbk_iosystem(kincar, K)\n", + "resp = ct.input_output_response(clsys, T, [xr, ur], x0)\n", + "\n", + "xd = resp.states\n", + "ud = resp.outputs[kincar.nstates:]\n", + "\n", + "plot_lanechange(T, xd, ud, label='feasible')\n", + "plot_lanechange(T, xr, ur, label='reference')" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Simulation of the open loop trajectory\n", + "sys_resp = ct.input_output_response(kincar, T, ud, xd[:, 0])\n", + "plt.plot(sys_resp.states[0], sys_resp.states[1])\n", + "plt.axis([0, 40, -5, 5])\n", + "plt.xlabel(\"$x$ [m]\")\n", + "plt.ylabel(\"$y$ [m]\")\n", + "plt.gca().set_aspect('equal')" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "7V81jzfZtiRe" + }, + "source": [ + "## State estimation\n", + "\n", + "To illustrate how we can estimate the state of the trajectory, we construct an observer that takes the measured inputs and outputs to the system and computes an estimate of the state, using a estimator with dynamics\n", + "\n", + "$$\n", + "\\dot{\\hat x} = f(\\hat x, u) - L(C \\hat x - y)\n", + "$$\n", + "\n", + "Note that we go ahead and use the nonlinear dynamics for the prediction term, but the linearization for the correction term.\n", + "\n", + "We can determine the estimator gain $L$ via multiple methods:\n", + "* Eigenvalue placement\n", + "* Optimal estimation (Kalman filter)" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "Jt_5SUTBuN7-" + }, + "source": [ + "### Eigenvalue placement" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Define the outputs to use for measurements\n", + "C = np.eye(2, 3)\n", + "\n", + "# Compute the linearization of the nonlinear dynamics\n", + "P = kincar.linearize([0, 0, 0], [10, 0])\n", + "\n", + "# Compute the gains via eigenvalue placement\n", + "L = ct.place(P.A.T, C.T, [-1, -2, -3]).T\n", + "\n", + "# Estimator update law\n", + "def estimator_update(t, xhat, u, params):\n", + " # Extract the inputs to the estimator\n", + " y = u[0:2] # first two system outputs\n", + " u = u[2:4] # inputs that were applied\n", + "\n", + " # Update the state estimate\n", + " xhatdot = kincar.updfcn(t, xhat, u, kincar_params) \\\n", + " - params['L'] @ (C @ xhat - y)\n", + "\n", + " # Return the derivative\n", + " return xhatdot\n", + "\n", + "estimator = ct.nlsys(\n", + " estimator_update, None, name='estimator',\n", + " states=kincar.nstates, params={'L': L},\n", + " inputs= kincar.state_labels[0:2] + kincar.input_labels,\n", + " outputs=[f'xh{i}' for i in range(kincar.nstates)],\n", + ")\n", + "print(estimator)\n", + "print(estimator.params)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Run the estimator from a different initial condition\n", + "estresp = ct.input_output_response(\n", + " estimator, T, [xd[0:2], ud], [0, -3, 0])\n", + "\n", + "fig, axs = plt.subplots(3, 1, figsize=[5, 4])\n", + "\n", + "axs[0].plot(estresp.time, estresp.outputs[0], 'b-', T, xd[0], 'r--')\n", + "axs[0].set_ylabel(\"$x$\")\n", + "axs[0].legend([r\"$\\hat x$\", \"$x$\"])\n", + "\n", + "axs[1].plot(estresp.time, estresp.outputs[1], 'b-', T, xd[1], 'r--')\n", + "axs[1].set_ylabel(\"$y$\")\n", + "\n", + "axs[2].plot(estresp.time, estresp.outputs[2], 'b-', T, xd[2], 'r--')\n", + "axs[2].set_ylabel(r\"$\\theta$\")\n", + "axs[2].set_xlabel(\"Time $t$ [s]\")\n", + "\n", + "plt.tight_layout()" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "KPkD-wSXt8d0" + }, + "source": [ + "### Kalman filter\n", + "\n", + "An alternative mechanism for creating an estimator is through the use of optimal estimation (Kalman filtering).\n", + "\n", + "Suppose that we have (very) noisy measurements of the system position, and also have disturbances taht are applied to our control signal." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Disturbance and noise covariances\n", + "Qv = np.diag([0.1**2, 0.01**2])\n", + "Qw = np.eye(2) * 0.1**2\n", + "\n", + "u_noisy = ud + ct.white_noise(T, Qv)\n", + "sys_resp = ct.input_output_response(kincar, T, u_noisy, xd[:, 0])\n", + "\n", + "# Create noisy version of the measurements\n", + "y_noisy = sys_resp.outputs[0:2] + ct.white_noise(T, Qw)\n", + "\n", + "plt.plot(y_noisy[0], y_noisy[1], 'k-')\n", + "plt.plot(sys_resp.outputs[0], sys_resp.outputs[1], 'b-')\n", + "plt.axis([0, 40, -5, 5])\n", + "plt.xlabel(\"$x$ [m]\")\n", + "plt.ylabel(\"$y$ [m]\")\n", + "plt.legend(['measured', 'actual'])\n", + "plt.gca().set_aspect('equal')" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "A Kalman filter allows us to estimate the optimal state given measurements of the inputs and outputs, as well as knowledge of the covariance of the signals." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Compute the Kalman gains (linear quadratic estimator)\n", + "L_kf, _, _ = ct.lqe(P.A, P.B, C, Qv, Qw)\n", + "\n", + "kfresp = ct.input_output_response(\n", + " estimator, T, [y_noisy, ud], [0, -3, 0],\n", + " params={'L': L_kf})\n", + "\n", + "fig, axs = plt.subplots(3, 1, figsize=[5, 4])\n", + "\n", + "axs[0].plot(T, y_noisy[0], 'k-')\n", + "axs[0].plot(kfresp.time, kfresp.outputs[0], 'b-', T, sys_resp.outputs[0], 'r--')\n", + "axs[0].set_ylabel(\"$x$\")\n", + "axs[0].legend([r\"$\\hat x$\", \"$x$\"])\n", + "\n", + "axs[1].plot(T, y_noisy[1], 'k-')\n", + "axs[1].plot(kfresp.time, kfresp.outputs[1], 'b-', T, sys_resp.outputs[1], 'r--')\n", + "axs[1].set_ylabel(\"$y$\")\n", + "\n", + "axs[2].plot(kfresp.time, kfresp.outputs[2], 'b-', T, sys_resp.outputs[2], 'r--')\n", + "axs[2].set_ylabel(r\"$\\theta$\")\n", + "axs[2].set_xlabel(\"Time $t$ [s]\")\n", + "\n", + "plt.tight_layout()" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "pMfHmzsW0Dqh" + }, + "source": [ + "We can get a better view of the convergence by plotting the errors:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "fig, axs = plt.subplots(3, 1, figsize=[5, 4])\n", + "\n", + "axs[0].plot(kfresp.time, kfresp.outputs[0] - sys_resp.outputs[0])\n", + "axs[0].plot([T[0], T[-1]], [0, 0], 'k--')\n", + "axs[0].set_ylabel(\"$x$ error\")\n", + "axs[0].set_ylim([-1, 1])\n", + "\n", + "axs[1].plot(kfresp.time, kfresp.outputs[1] - sys_resp.outputs[1])\n", + "axs[1].plot([T[0], T[-1]], [0, 0], 'k--')\n", + "axs[1].set_ylabel(\"$y$ error\")\n", + "axs[1].set_ylim([-1, 1])\n", + "\n", + "axs[2].plot(kfresp.time, kfresp.outputs[2] - sys_resp.outputs[2])\n", + "axs[2].plot([T[0], T[-1]], [0, 0], 'k--')\n", + "axs[2].set_ylabel(r\"$\\theta$ error\")\n", + "axs[2].set_xlabel(\"Time $t$ [s]\")\n", + "axs[2].set_ylim([-0.2, 0.2])\n", + "\n", + "plt.tight_layout()" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "nccW48C5tns9" + }, + "source": [ + "## Output feedback control\n", + "\n", + "We next construct a controller that makes use of the estimated state. We will attempt to control the longitudinal position using the steering angle as an input, with the velocity set to the desired velocity (no tracking of the longitudinal position)." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Compute the linearization of the nonlinear dynamics\n", + "P = kincar.linearize([0, 0, 0], [10, 0])\n", + "\n", + "# Extract out the linearized dynamics from delta to y\n", + "Alat = P.A[1:3, 1:3]\n", + "Blat = P.B[1:3, 1:2]\n", + "Clat = P.C[1:2, 1:3]\n", + "\n", + "sys = ct.ss(Alat, Blat, Clat, 0)\n", + "print(sys)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Construct a state space controller, using LQR\n", + "Qx = np.diag([1, 10])\n", + "Qu = np.diag([1])\n", + "\n", + "K, _, _ = ct.lqr(Alat, Blat, Qx, Qu)\n", + "print(f\"{K=}\")\n", + "\n", + "kf = -1 / (Clat @ np.linalg.inv(Alat - Blat @ K) @ Blat)\n", + "print(f\"{kf=}\")" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "v5oHK9-XMrEv" + }, + "source": [ + "### Direct state space feedback\n", + "\n", + "We start by checking the response of the system assuming that we measure the state directly.\n", + "\n" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Construct a controller for the full system\n", + "def ctrl_output(t, x, u, params):\n", + " r_v, r_y = u[0:2]\n", + " x = u[3:5] # y, theta\n", + " return np.vstack([r_v, -K @ x + kf * r_y])\n", + "ctrl = ct.nlsys(\n", + " None, ctrl_output, name='ctrl',\n", + " inputs=['r_v', 'r_y', 'x', 'y', 'theta'],\n", + " outputs=['v', 'delta']\n", + ")\n", + "print(ctrl)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Direct state feedback\n", + "clsys_direct = ct.interconnect(\n", + " [kincar, ctrl],\n", + " inputs=['r_v', 'r_y'],\n", + " outputs=['x', 'y', 'theta', 'v', 'delta'],\n", + ")\n", + "print(clsys_direct)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Run a simulation\n", + "clresp_direct = ct.input_output_response(\n", + " clsys_direct, T, [10, xd[1]], X0=[0, -3, 0])\n", + "\n", + "plt.plot(clresp_direct.outputs[0], clresp_direct.outputs[1])\n", + "plt.plot(xd[0], xd[1], 'r--')\n", + "# plt.plot(clresp.time, clresp.outputs[1])\n", + "plt.xlabel(\"$x$ [m]\")\n", + "plt.ylabel(\"$y$ [m]\")\n", + "plt.gca().set_aspect('equal')" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "J0iS9V8YT4Ox" + }, + "source": [ + "Note the \"lag\" in the $x$ coordinate. This comes from the fact that we did not use feedback to maintain the longitudinal position as a function of time, compared with the desired trajectory. To see this, we can look at the commanded speed ($v$) versus the desired speed:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "plot_lanechange(T, xd, ud, label=\"desired\")\n", + "plot_lanechange(T, clresp_direct.outputs[0:2], clresp_direct.outputs[-2:], label=\"actual\")" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "SDrkfC_LUPDu" + }, + "source": [ + "From this plot we can also see that there is a very large input $\\delta$ applied at $t=0$. This is something we would have to fix if we were to implement this on a physical system (-1 rad $\\approx -60^\\circ$!)." + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "KS0E2g6aMgC0" + }, + "source": [ + "### Estimator-based control\n", + "\n", + "We now consider the case were we cannot directly measure the state, but instead have to estimate the state from the commanded input and measured output. We can insert the estimator into the system model by reconnecting the inputs and outputs. The `ct.interconnect` function provides the needed flexibility:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "?ct.interconnect" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "rgI9QjBMAy7b" + }, + "source": [ + "We now create the system model that includes the estimator (observer). Here is the system we are trying to construct:\n", + "\n", + "\n", + "\n", + "\n", + "(Be careful with the notation: in the diagram above $y$ is the measured outputs, which for our system are the $x$ and $y$ position of the vehicle, so overusing the symbol $y$.)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Connect the system, estimator, and controller\n", + "clsys_estim = ct.interconnect(\n", + " [kincar, estimator, ctrl],\n", + " inplist=['ctrl.r_v', 'ctrl.r_y', 'estimator.x', 'estimator.y'],\n", + " inputs=['r_v', 'r_y', 'noise_x', 'noise_y'],\n", + " outlist=[\n", + " 'kincar.x', 'kincar.y', 'kincar.theta',\n", + " 'estimator.xh0', 'estimator.xh1', 'estimator.xh2',\n", + " 'ctrl.v', 'ctrl.delta'\n", + " ],\n", + " outputs=['x', 'y', 'theta', 'xhat', 'yhat', 'thhat', 'v', 'delta'],\n", + " connections=[\n", + " ['kincar.v', 'ctrl.v'],\n", + " ['kincar.delta', 'ctrl.delta'],\n", + " ['estimator.x', 'kincar.x'],\n", + " ['estimator.y', 'kincar.y'],\n", + " ['estimator.delta', 'ctrl.delta'],\n", + " ['estimator.v', 'ctrl.v'],\n", + " ['ctrl.x', 'estimator.xh0'],\n", + " ['ctrl.y', 'estimator.xh1'],\n", + " ['ctrl.theta', 'estimator.xh2'],\n", + " ],\n", + ")\n", + "print(clsys_estim)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Run a simulation with no noise first\n", + "clresp_nonoise = ct.input_output_response(\n", + " clsys_estim, T, [10, xd[1], 0, 0], X0=[0, -3, 0, 0, -5, 0])\n", + "\n", + "plt.plot(clresp_nonoise.outputs[0], clresp_nonoise.outputs[1])\n", + "plt.plot(xd[0], xd[1], 'r--')\n", + "\n", + "plt.xlabel(\"$x$ [m]\")\n", + "plt.ylabel(\"$y$ [m]\")\n", + "plt.gca().set_aspect('equal')" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Add some noise\n", + "Qv = np.diag([0.1**2, 0.01**2])\n", + "Qw = np.eye(2) * 0.1**2\n", + "\n", + "u_noise = ct.white_noise(T, Qv)\n", + "y_noise = ct.white_noise(T, Qw)\n", + "\n", + "# Run a simulation\n", + "clresp_noisy = ct.input_output_response(\n", + " clsys_estim, T, [10, xd[1], y_noise], X0=[0, -3, 0, 0, -5, 0])\n", + "\n", + "plt.plot(clresp_direct.outputs[0], clresp_direct.outputs[1], label='direct')\n", + "plt.plot(clresp_nonoise.outputs[0], clresp_nonoise.outputs[1], label='nonoise')\n", + "plt.plot(clresp_noisy.outputs[0], clresp_noisy.outputs[1], label='noisy')\n", + "plt.legend()\n", + "plt.plot(xd[0], xd[1], 'r--')\n", + "\n", + "plt.xlabel(\"$x$ [m]\")\n", + "plt.ylabel(\"$y$ [m]\")\n", + "plt.gca().set_aspect('equal')" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Plot the differences in y to make differences more clear\n", + "plt.plot(\n", + " clresp_nonoise.time, clresp_nonoise.outputs[1] - clresp_direct.outputs[1],\n", + " label='nonoise')\n", + "plt.plot(\n", + " clresp_noisy.time, clresp_noisy.outputs[1] - clresp_direct.outputs[1],\n", + " label='noisy')\n", + "plt.legend()\n", + "plt.plot([clresp_nonoise.time[0], clresp_nonoise.time[-1]], [0, 0], 'r--')\n", + "\n", + "plt.xlabel(\"Time [s]\")\n", + "plt.ylabel(\"$y$ [m]\");" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Show the control inputs as well as the final trajectory\n", + "plot_lanechange(T, xd, ud, label=\"desired\")\n", + "plot_lanechange(T, clresp_noisy.outputs[0:2], clresp_noisy.outputs[-2:], label=\"actual\")" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "ZfxhaU9p_W4w" + }, + "source": [ + "### Things to try\n", + "\n", + "* Wrap a controller around the velocity (or $x$ position) in addition to the lateral ($y$) position\n", + "* Change the amounts of noise in the sensor signal\n", + "* Add disturbances to the dynamics (corresponding to wind, hills, etc)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 4 +} diff --git a/examples/cds110-L6a_kincar-trajgen.ipynb b/examples/cds110-L6a_kincar-trajgen.ipynb new file mode 100644 index 000000000..e139272bd --- /dev/null +++ b/examples/cds110-L6a_kincar-trajgen.ipynb @@ -0,0 +1,533 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "edb7e2c6", + "metadata": { + "id": "edb7e2c6" + }, + "source": [ + "
\n", + "

CDS 110, Lecture 6a

\n", + "

Trajectory Generation for a Kinematic Car Model

\n", + "

Richard M. Murray, Winter 2024

\n", + "
\n", + "\n", + "[Open in Google Colab](https://colab.research.google.com/drive/1vBFjCU2W6fSavy8loL0JfgZyO6UC46m3)\n", + "\n", + "This notebook contains an example of using (optimal) trajectory generation for a vehicle steering system. It illustrates different methods of setting up optimal control problems and solving them using python-control." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "7066eb69", + "metadata": {}, + "outputs": [], + "source": [ + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "import time\n", + "try:\n", + " import control as ct\n", + " print(\"python-control\", ct.__version__)\n", + "except ImportError:\n", + " !pip install control\n", + " import control as ct\n", + "import control.optimal as opt" + ] + }, + { + "cell_type": "markdown", + "id": "4afb09dd", + "metadata": { + "id": "4afb09dd" + }, + "source": [ + "## Vehicle steering dynamics\n", + "\n", + "\n", + "\n", + " \n", + " \n", + "\n", + "
\n", + "$$\n", + "\\large\\begin{aligned}\n", + " \\dot x &= \\cos\\theta\\, v \\\\\n", + " \\dot y &= \\sin\\theta\\, v \\\\\n", + " \\dot\\theta &= \\frac{v}{l} \\tan \\delta\n", + "\\end{aligned}\n", + "$$\n", + "
\n", + "\n", + "The vehicle dynamics are given by a simple bicycle model. We take the state of the system as $(x, y, \\theta)$ where $(x, y)$ is the position of the vehicle in the plane and $\\theta$ is the angle of the vehicle with respect to horizontal. The vehicle input is given by $(v, \\delta)$ where $v$ is the forward velocity of the vehicle and $\\delta$ is the angle of the steering wheel. The model includes saturation of the vehicle steering angle." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "a6143a8a", + "metadata": {}, + "outputs": [], + "source": [ + "# Code to model vehicle steering dynamics\n", + "\n", + "# Function to compute the RHS of the system dynamics\n", + "def kincar_update(t, x, u, params):\n", + " # Get the parameters for the model\n", + " l = params['wheelbase'] # vehicle wheelbase\n", + " deltamax = params['maxsteer'] # max steering angle (rad)\n", + "\n", + " # Saturate the steering input\n", + " delta = np.clip(u[1], -deltamax, deltamax)\n", + "\n", + " # Return the derivative of the state\n", + " return np.array([\n", + " np.cos(x[2]) * u[0], # xdot = cos(theta) v\n", + " np.sin(x[2]) * u[0], # ydot = sin(theta) v\n", + " (u[0] / l) * np.tan(delta) # thdot = v/l tan(delta)\n", + " ])\n", + "\n", + "kincar_params={'wheelbase': 3, 'maxsteer': 0.5}\n", + "\n", + "# Create nonlinear input/output system\n", + "kincar = ct.nlsys(\n", + " kincar_update, None, name=\"kincar\", params=kincar_params,\n", + " inputs=('v', 'delta'), outputs=('x', 'y', 'theta'),\n", + " states=('x', 'y', 'theta'))" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "4c2bf8d6-7580-4712-affc-928a8b046d8a", + "metadata": {}, + "outputs": [], + "source": [ + "# Utility function to plot lane change manuever\n", + "def plot_lanechange(t, y, u, figure=None, yf=None, label=None):\n", + " # Plot the xy trajectory\n", + " plt.subplot(3, 1, 1, label='xy')\n", + " plt.plot(y[0], y[1], label=label)\n", + " plt.xlabel(\"x [m]\")\n", + " plt.ylabel(\"y [m]\")\n", + " if yf is not None:\n", + " plt.plot(yf[0], yf[1], 'ro')\n", + "\n", + " # Plot x and y as functions of time\n", + " plt.subplot(3, 2, 3, label='x')\n", + " plt.plot(t, y[0])\n", + " plt.ylabel(\"$x$ [m]\")\n", + "\n", + " plt.subplot(3, 2, 4, label='y')\n", + " plt.plot(t, y[1])\n", + " plt.ylabel(\"$y$ [m]\")\n", + "\n", + " # Plot the inputs as a function of time\n", + " plt.subplot(3, 2, 5, label='v')\n", + " plt.plot(t, u[0])\n", + " plt.xlabel(\"Time $t$ [sec]\")\n", + " plt.ylabel(\"$v$ [m/s]\")\n", + "\n", + " plt.subplot(3, 2, 6, label='delta')\n", + " plt.plot(t, u[1])\n", + " plt.xlabel(\"Time $t$ [sec]\")\n", + " plt.ylabel(\"$\\\\delta$ [rad]\")\n", + "\n", + " plt.subplot(3, 1, 1)\n", + " plt.title(\"Lane change manuever\")\n", + " if label:\n", + " plt.legend()\n", + " plt.tight_layout()" + ] + }, + { + "cell_type": "markdown", + "id": "64bd3c3b", + "metadata": { + "id": "64bd3c3b" + }, + "source": [ + "## Optimal trajectory generation\n", + "\n", + "The general problem we are solving is of the form:\n", + "\n", + "$$\n", + "\\min_{u(\\cdot)}\n", + " \\int_0^T L(x,u)\\, dt + V \\bigl( x(T) \\bigr)\n", + "$$\n", + "subject to\n", + "$$\n", + " \\dot x = f(x, u), \\qquad x\\in \\mathcal{X} \\subset \\mathbb{R}^n,\\, u\\in \\mathcal{U} \\subset \\mathbb{R}^m\n", + "$$\n", + "\n", + "We consider the problem of changing from one lane to another over a perod of 10 seconds while driving at a forward speed of 10 m/s." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "42dcbd79", + "metadata": {}, + "outputs": [], + "source": [ + "# Initial and final conditions\n", + "x0 = np.array([ 0., -2., 0.]); u0 = np.array([10., 0.])\n", + "xf = np.array([100., 2., 0.]); uf = np.array([10., 0.])\n", + "Tf = 10" + ] + }, + { + "cell_type": "markdown", + "id": "5ff2e044", + "metadata": { + "id": "5ff2e044" + }, + "source": [ + "An important part of the optimization procedure is to give a good initial guess. Here are some possibilities:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "650d321a", + "metadata": {}, + "outputs": [], + "source": [ + "# Define the time horizon (and spacing) for the optimization\n", + "# timepts = np.linspace(0, Tf, 5, endpoint=True) # Try using this and see what happens\n", + "# timepts = np.linspace(0, Tf, 10, endpoint=True) # Try using this and see what happens\n", + "timepts = np.linspace(0, Tf, 20, endpoint=True)\n", + "\n", + "# Compute some initial guesses to use\n", + "bend_left = [10, 0.01] # slight left veer (will extend over all timepts)\n", + "straight_line = ( # straight line from start to end with nominal input\n", + " np.array([x0 + (xf - x0) * t/Tf for t in timepts]).transpose(),\n", + " u0\n", + ")" + ] + }, + { + "cell_type": "markdown", + "id": "4e75a2c4", + "metadata": { + "id": "4e75a2c4" + }, + "source": [ + "### Approach 1: standard quadratic cost\n", + "\n", + "We can set up the optimal control problem as trying to minimize the distance from the desired final point while at the same time as not exerting too much control effort to achieve our goal.\n", + "\n", + "$$\n", + "\\min_{u(\\cdot)}\n", + " \\int_0^T \\left[(x(\\tau) - x_\\text{f})^T Q_x (x(\\tau) - x_\\text{f}) + (u(\\tau) - u_\\text{f})^T Q_u (u(\\tau) - u_\\text{f})\\right] \\, d\\tau\n", + "$$\n", + "subject to\n", + "$$\n", + " \\dot x = f(x, u), \\qquad x \\in \\mathbb{R}^n,\\, u \\in \\mathbb{R}^m\n", + "$$\n", + "\n", + "The optimization module solves optimal control problems by choosing the values of the input at each point in the time horizon to try to minimize the cost:\n", + "\n", + "$$\n", + "u_i(t_j) = \\alpha_{i, j}, \\qquad\n", + "u_i(t) = \\frac{t_{i+1} - t}{t_{i+1} - t_i} \\alpha_{i, j} + \\frac{t - t_i}{t_{i+1} - t_i} \\alpha_{{i+1},j}\n", + "$$\n", + "\n", + "This means that each input generates a parameter value at each point in the time horizon, so the more refined your time horizon, the more parameters the optimizer has to search over." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "984c2f0b", + "metadata": {}, + "outputs": [], + "source": [ + "# Set up the cost functions\n", + "Qx = np.diag([.1, 10, .1]) # keep lateral error low\n", + "Qu = np.diag([.1, 1]) # minimize applied inputs\n", + "quad_cost = opt.quadratic_cost(kincar, Qx, Qu, x0=xf, u0=uf)\n", + "\n", + "# Compute the optimal control, setting step size for gradient calculation (eps)\n", + "start_time = time.process_time()\n", + "result1 = opt.solve_ocp(\n", + " kincar, timepts, x0, quad_cost,\n", + " initial_guess=straight_line,\n", + " # initial_guess= bend_left,\n", + " # initial_guess=u0,\n", + " # minimize_method='trust-constr',\n", + " # minimize_options={'finite_diff_rel_step': 0.01},\n", + " # trajectory_method='shooting'\n", + " # solve_ivp_method='LSODA'\n", + ")\n", + "print(\"* Total time = %5g seconds\\n\" % (time.process_time() - start_time))\n", + "\n", + "# Plot the results from the optimization\n", + "plot_lanechange(timepts, result1.states, result1.inputs, xf)\n", + "print(\"Final computed state: \", result1.states[:,-1])\n", + "\n", + "# Simulate the system and see what happens\n", + "t1, u1 = result1.time, result1.inputs\n", + "t1, y1 = ct.input_output_response(kincar, timepts, u1, x0)\n", + "plot_lanechange(t1, y1, u1, yf=xf[0:2])\n", + "print(\"Final simulated state:\", y1[:,-1])\n", + "\n", + "# Label the different lines\n", + "plt.subplot(3, 1, 1)\n", + "plt.legend(['desired', 'simulated', 'endpoint'])\n", + "plt.tight_layout()" + ] + }, + { + "cell_type": "markdown", + "id": "b7cade52", + "metadata": { + "id": "b7cade52" + }, + "source": [ + "Note the amount of time required to solve the problem and also any warning messages about to being able to solve the optimization (mainly in earlier versions of python-control). You can try to adjust a number of factors to try to get a better solution:\n", + "* Try changing the number of points in the time horizon\n", + "* Try using a different initial guess\n", + "* Try changing the optimization method (see commented out code)" + ] + }, + { + "cell_type": "markdown", + "id": "6a9f9d9b", + "metadata": { + "id": "6a9f9d9b" + }, + "source": [ + "### Approach 2: input cost, input constraints, terminal cost\n", + "\n", + "The previous solution integrates the position error for the entire horizon, and so the car changes lanes very quickly (at the cost of larger inputs). Instead, we can penalize the final state and impose a higher cost on the inputs, resulting in a more gradual lane change.\n", + "\n", + "$$\n", + "\\min_{u(\\cdot)}\n", + " \\int_0^T \\underbrace{\\left[x(\\tau)^T Q_x x(\\tau) + (u(\\tau) - u_\\text{f})^T Q_u (u(\\tau) - u_\\text{f})\\right]}_{L(x, u)} \\, d\\tau + \\underbrace{(x(T) - x_\\text{f})^T Q_\\text{f} (x(T) - x_\\text{f})}_{V\\left(x(T)\\right)}\n", + "$$\n", + "subject to\n", + "$$\n", + " \\dot x = f(x, u), \\qquad x \\in \\mathbb{R}^n,\\, u \\in \\mathbb{R}^m\n", + "$$\n", + "\n", + "We can also try using a different solver for this example. You can pass the solver using the `minimize_method` keyword and send options to the solver using the `minimize_options` keyword (which should be set to a dictionary of options)." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "a201e33c", + "metadata": {}, + "outputs": [], + "source": [ + "# Add input constraint, input cost, terminal cost\n", + "constraints = [ opt.input_range_constraint(kincar, [8, -0.1], [12, 0.1]) ]\n", + "traj_cost = opt.quadratic_cost(kincar, None, np.diag([0.1, 1]), u0=uf)\n", + "term_cost = opt.quadratic_cost(kincar, np.diag([1, 10, 100]), None, x0=xf)\n", + "\n", + "# Compute the optimal control\n", + "start_time = time.process_time()\n", + "result2 = opt.solve_ocp(\n", + " kincar, timepts, x0, traj_cost, constraints, terminal_cost=term_cost,\n", + " initial_guess=straight_line,\n", + " # minimize_method='trust-constr',\n", + " # minimize_options={'finite_diff_rel_step': 0.01},\n", + " # minimize_method='SLSQP', minimize_options={'eps': 0.01},\n", + " # log=True,\n", + ")\n", + "print(\"* Total time = %5g seconds\\n\" % (time.process_time() - start_time))\n", + "\n", + "# Plot the results from the optimization\n", + "plot_lanechange(timepts, result2.states, result2.inputs, xf)\n", + "print(\"Final computed state: \", result2.states[:,-1])\n", + "\n", + "# Simulate the system and see what happens\n", + "t2, u2 = result2.time, result2.inputs\n", + "t2, y2 = ct.input_output_response(kincar, timepts, u2, x0)\n", + "plot_lanechange(t2, y2, u2, yf=xf[0:2])\n", + "print(\"Final simulated state:\", y2[:,-1])\n", + "\n", + "# Label the different lines\n", + "plt.subplot(3, 1, 1)\n", + "plt.legend(['desired', 'simulated', 'endpoint'], loc='upper left')\n", + "plt.tight_layout()" + ] + }, + { + "cell_type": "markdown", + "id": "3d2ccf97", + "metadata": { + "id": "3d2ccf97" + }, + "source": [ + "### Approach 3: terminal constraints\n", + "\n", + "We can also remove the cost function on the state and replace it with a terminal *constraint* on the state as well as bounds on the inputs. If a solution is found, it guarantees we get to exactly the final state:\n", + "\n", + "$$\n", + "\\min_{u(\\cdot)}\n", + " \\int_0^T \\underbrace{(u(\\tau) - u_\\text{f})^T Q_u (u(\\tau) - u_\\text{f})}_{L(x, u)} \\, d\\tau\n", + "$$\n", + "subject to\n", + "$$\n", + " \\begin{aligned}\n", + " \\dot x &= f(x, u), & \\qquad &x \\in \\mathbb{R}^n,\\, u \\in \\mathbb{R}^m \\\\\n", + " x(T) &= x_\\text{f} & &u_\\text{lb} \\leq u(t) \\leq u_\\text{ub},\\, \\text{for all $t$}\n", + " \\end{aligned}\n", + "$$\n", + "\n", + "Note that trajectory and terminal constraints can be very difficult to satisfy for a general optimization." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "dc77a856", + "metadata": {}, + "outputs": [], + "source": [ + "# Input cost and terminal constraints\n", + "R = np.diag([1, 1]) # minimize applied inputs\n", + "cost3 = opt.quadratic_cost(kincar, np.zeros((3,3)), R, u0=uf)\n", + "constraints = [\n", + " opt.input_range_constraint(kincar, [8, -0.1], [12, 0.1]) ]\n", + "terminal = [ opt.state_range_constraint(kincar, xf, xf) ]\n", + "\n", + "# Compute the optimal control\n", + "start_time = time.process_time()\n", + "result3 = opt.solve_ocp(\n", + " kincar, timepts, x0, cost3, constraints,\n", + " terminal_constraints=terminal, initial_guess=straight_line,\n", + "# solve_ivp_kwargs={'atol': 1e-3, 'rtol': 1e-2},\n", + "# minimize_method='trust-constr',\n", + "# minimize_options={'finite_diff_rel_step': 0.01},\n", + ")\n", + "print(\"* Total time = %5g seconds\\n\" % (time.process_time() - start_time))\n", + "\n", + "# Plot the results from the optimization\n", + "plot_lanechange(timepts, result3.states, result3.inputs, xf)\n", + "print(\"Final computed state: \", result3.states[:,-1])\n", + "\n", + "# Simulate the system and see what happens\n", + "t3, u3 = result3.time, result3.inputs\n", + "t3, y3 = ct.input_output_response(kincar, timepts, u3, x0)\n", + "plot_lanechange(t3, y3, u3, yf=xf[0:2])\n", + "print(\"Final state: \", y3[:,-1])\n", + "\n", + "# Label the different lines\n", + "plt.subplot(3, 1, 1)\n", + "plt.legend(['desired', 'simulated', 'endpoint'], loc='upper left')\n", + "plt.tight_layout()" + ] + }, + { + "cell_type": "markdown", + "id": "9e744463", + "metadata": { + "id": "9e744463" + }, + "source": [ + "### Approach 4: terminal constraints w/ basis functions (if time)\n", + "\n", + "As a final example, we can use a basis function to reduce the size of the problem and get faster answers with more temporal resolution:\n", + "\n", + "$$\n", + "\\min_{u(\\cdot)}\n", + " \\int_0^T L(x, u) \\, d\\tau + V\\left(x(T)\\right)\n", + "$$\n", + "subject to\n", + "$$\n", + " \\begin{aligned}\n", + " \\dot x &= f(x, u), \\qquad x \\in \\mathcal{X} \\subset \\mathbb{R}^n,\\, u \\in \\mathcal{U} \\subset \\mathbb{R}^m \\\\\n", + " u(t) &= \\sum_i \\alpha_i \\phi^i(t),\n", + " \\end{aligned}\n", + "$$\n", + "where $\\phi^i(t)$ are a set of basis functions.\n", + "\n", + "Here we parameterize the input by a set of 4 Bezier curves but solve for a much more time resolved set of inputs. Note that while we are using the `control.flatsys` module to define the basis functions, we are not exploiting the fact that the system is differentially flat." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "ee82aa25", + "metadata": {}, + "outputs": [], + "source": [ + "# Get basis functions for flat systems module\n", + "import control.flatsys as flat\n", + "\n", + "# Compute the optimal control\n", + "start_time = time.process_time()\n", + "result4 = opt.solve_ocp(\n", + " kincar, timepts, x0, quad_cost, constraints,\n", + " terminal_constraints=terminal,\n", + " initial_guess=straight_line,\n", + " basis=flat.PolyFamily(4, T=Tf),\n", + " # solve_ivp_kwargs={'method': 'RK45', 'atol': 1e-2, 'rtol': 1e-2},\n", + " # solve_ivp_kwargs={'atol': 1e-3, 'rtol': 1e-2},\n", + " # minimize_method='trust-constr', minimize_options={'disp': True},\n", + " log=False\n", + ")\n", + "print(\"* Total time = %5g seconds\\n\" % (time.process_time() - start_time))\n", + "\n", + "# Plot the results from the optimization\n", + "plot_lanechange(timepts, result4.states, result4.inputs, xf)\n", + "print(\"Final computed state: \", result3.states[:,-1])\n", + "\n", + "# Simulate the system and see what happens\n", + "t4, u4 = result4.time, result4.inputs\n", + "t4, y4 = ct.input_output_response(kincar, timepts, u4, x0)\n", + "plot_lanechange(t4, y4, u4, yf=xf[0:2])\n", + "print(\"Final simulated state: \", y4[:,-1])\n", + "\n", + "# Label the different lines\n", + "plt.subplot(3, 1, 1)\n", + "plt.legend(['desired', 'simulated', 'endpoint'], loc='upper left')\n", + "plt.tight_layout()" + ] + }, + { + "cell_type": "markdown", + "id": "2a74388e", + "metadata": { + "id": "2a74388e" + }, + "source": [ + "Note how much smoother the inputs look, although the solver can still have a hard time satisfying the final constraints, resulting in longer computation times." + ] + }, + { + "cell_type": "markdown", + "id": "1465d149", + "metadata": { + "id": "1465d149" + }, + "source": [ + "### Additional things to try\n", + "\n", + "* Compare the results here with what we go last week exploiting the property of differential flatness (computation time, in particular)\n", + "* Try using different weights, solvers, initial guess and other properties and see how things change.\n", + "* Try using different values for `initial_guess` to get faster convergence and/or different classes of solutions." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "02bad3d5", + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/examples/cds110-L6b_kincar-tracking.ipynb b/examples/cds110-L6b_kincar-tracking.ipynb new file mode 100644 index 000000000..9f4cbb475 --- /dev/null +++ b/examples/cds110-L6b_kincar-tracking.ipynb @@ -0,0 +1,509 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "exempt-legislation", + "metadata": { + "id": "exempt-legislation" + }, + "source": [ + "
\n", + "

CDS 110, Lecture 6b

\n", + "

Trajectory Tracking for a Kinematic Car

\n", + "

Richard M. Murray, Winter 2024

\n", + "
\n", + "\n", + "[Open in Google Colab](https://colab.research.google.com/drive/12VSFMqM6HVyj8TY_3zb0AnsJrG6UeLKF)\n", + "\n", + "This notebook contains an example of using trajectory tracking for a (nonlinear) state space system. The controller is of the form\n", + "\n", + "$$\n", + " u = u_\\text{d} − K (x − x_\\text{d}),\n", + "$$\n", + "\n", + "where $x_\\text{d}, u_\\text{d}$ is a feasible trajectory, and $K$ is a feedback gain first computed around a nominal condition and then computed using gain scheduling." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "corresponding-convenience", + "metadata": {}, + "outputs": [], + "source": [ + "# Import the packages needed for the examples included in this notebook\n", + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "import itertools\n", + "from cmath import sqrt\n", + "from math import pi\n", + "try:\n", + " import control as ct\n", + " print(\"python-control\", ct.__version__)\n", + "except ImportError:\n", + " !pip install control\n", + " import control as ct\n", + "import control.optimal as opt\n", + "import control.flatsys as fs" + ] + }, + { + "cell_type": "markdown", + "id": "corporate-sense", + "metadata": { + "id": "corporate-sense" + }, + "source": [ + "## Vehicle Steering Dynamics\n", + "\n", + "The vehicle dynamics are given by a simple bicycle model:\n", + "\n", + "\n", + "\n", + " \n", + " \n", + "\n", + "
\n", + "$$\\large\n", + "\\begin{aligned}\n", + " \\dot x &= \\cos\\theta\\, v \\\\\n", + " \\dot y &= \\sin\\theta\\, v \\\\\n", + " \\dot\\theta &= \\frac{v}{l} \\tan \\delta\n", + "\\end{aligned}\n", + "$$\n", + "
\n", + "\n", + "We take the state of the system as $(x, y, \\theta)$ where $(x, y)$ is the position of the vehicle in the plane and $\\theta$ is the angle of the vehicle with respect to horizontal. The vehicle input is given by $(v, \\delta)$ where $v$ is the forward velocity of the vehicle and $\\delta$ is the angle of the steering wheel. The model includes saturation of the vehicle steering angle." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "naval-pizza", + "metadata": {}, + "outputs": [], + "source": [ + "# Code to model vehicle steering dynamics\n", + "\n", + "# Function to compute the RHS of the system dynamics\n", + "def kincar_update(t, x, u, params):\n", + " # Get the parameters for the model\n", + " l = params['wheelbase'] # vehicle wheelbase\n", + " deltamax = params['maxsteer'] # max steering angle (rad)\n", + "\n", + " # Saturate the steering input\n", + " delta = np.clip(u[1], -deltamax, deltamax)\n", + "\n", + " # Return the derivative of the state\n", + " return np.array([\n", + " np.cos(x[2]) * u[0], # xdot = cos(theta) v\n", + " np.sin(x[2]) * u[0], # ydot = sin(theta) v\n", + " (u[0] / l) * np.tan(delta) # thdot = v/l tan(delta)\n", + " ])\n", + "\n", + "kincar_params={'wheelbase': 3, 'maxsteer': 0.5}\n", + "\n", + "# Create nonlinear input/output system\n", + "kincar = ct.nlsys(\n", + " kincar_update, None, name=\"kincar\", params=kincar_params,\n", + " inputs=('v', 'delta'), outputs=('x', 'y', 'theta'),\n", + " states=('x', 'y', 'theta'))" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "6340dbd4-7867-47ad-aefb-1bea7f6ad566", + "metadata": {}, + "outputs": [], + "source": [ + "# Utility function to plot lane change manuever\n", + "def plot_lanechange(t, y, u, figure=None, yf=None, label=None):\n", + " # Plot the xy trajectory\n", + " plt.subplot(3, 1, 1, label='xy')\n", + " plt.plot(y[0], y[1], label=label)\n", + " plt.xlabel(\"x [m]\")\n", + " plt.ylabel(\"y [m]\")\n", + " if yf is not None:\n", + " plt.plot(yf[0], yf[1], 'ro')\n", + "\n", + " # Plot x and y as functions of time\n", + " plt.subplot(3, 2, 3, label='x')\n", + " plt.plot(t, y[0])\n", + " plt.ylabel(\"$x$ [m]\")\n", + "\n", + " plt.subplot(3, 2, 4, label='y')\n", + " plt.plot(t, y[1])\n", + " plt.ylabel(\"$y$ [m]\")\n", + "\n", + " # Plot the inputs as a function of time\n", + " plt.subplot(3, 2, 5, label='v')\n", + " plt.plot(t, u[0])\n", + " plt.xlabel(\"Time $t$ [sec]\")\n", + " plt.ylabel(\"$v$ [m/s]\")\n", + "\n", + " plt.subplot(3, 2, 6, label='delta')\n", + " plt.plot(t, u[1])\n", + " plt.xlabel(\"Time $t$ [sec]\")\n", + " plt.ylabel(\"$\\\\delta$ [rad]\")\n", + "\n", + " plt.subplot(3, 1, 1)\n", + " plt.title(\"Lane change manuever\")\n", + " if label:\n", + " plt.legend()\n", + " plt.tight_layout()" + ] + }, + { + "cell_type": "markdown", + "id": "BAsKLMWWK3W2", + "metadata": { + "id": "BAsKLMWWK3W2" + }, + "source": [ + "## State feedback controller\n", + "\n", + "We start by designing a state feedback controller that can be used to stabilize the system. We design the controller around a nominal forward speed of 10 m/s and then apply this to the vehicle at different speeds." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "g7DztIjmK2K_", + "metadata": {}, + "outputs": [], + "source": [ + "# Compute the linearization of the dynamics at a nominal point\n", + "x_nom = np.array([0, 0, 0])\n", + "u_nom = np.array([5, 0])\n", + "P = ct.linearize(kincar, x_nom, u_nom) # Linearized systems\n", + "print(P)\n", + "\n", + "Qx = np.diag([1, 10, 0.1])\n", + "Qu = np.diag([1, 1])\n", + "K, _, _ = ct.lqr(P.A, P.B, Qx, Qu)\n", + "print(K)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "szvKKh6rLgkt", + "metadata": {}, + "outputs": [], + "source": [ + "# Create the closed loop system using create_statefbk_iosystem\n", + "?ct.create_statefbk_iosystem\n", + "ctrl, clsys = ct.create_statefbk_iosystem(\n", + " kincar, K, xd_labels=['xd', 'yd', 'thetad'], ud_labels=['vd', 'deltad'])\n", + "print(clsys)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "gow-ZEerMCw7", + "metadata": {}, + "outputs": [], + "source": [ + "# Create a trajectory corresponding to a slow lane change\n", + "x0 = np.array([0, -2, 0]); u0 = [10, 0]\n", + "xf = np.array([100, 2, 0])\n", + "Tf = 10\n", + "timepts = np.linspace(0, Tf, 20)\n", + "\n", + "straight_line = ( # straight line from start to end with nominal input\n", + " np.array([x0 + (xf - x0) * t/Tf for t in timepts]).transpose(),\n", + " u0\n", + ")\n", + "\n", + "desired = opt.solve_ocp(\n", + " kincar, timepts, x0,\n", + " cost=opt.quadratic_cost(kincar, None, Qu, u0=u0),\n", + " terminal_constraints=opt.state_range_constraint(kincar, xf, xf),\n", + " initial_guess=straight_line)\n", + "\n", + "plot_lanechange(desired.time, desired.states, desired.inputs, yf=xf)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "NLa4dbI8PWhY", + "metadata": {}, + "outputs": [], + "source": [ + "# Simulate the system with an initial condition error\n", + "# Use t_eval to evaluate at points between inputs\n", + "actual = ct.input_output_response(\n", + " clsys, timepts, [desired.states, desired.inputs],\n", + " X0=[-3, -5, 0], t_eval=np.linspace(0, Tf, 500))\n", + "\n", + "plot_lanechange(actual.time, actual.states, actual.outputs[3:])\n", + "plot_lanechange(desired.time, desired.states, desired.inputs, yf=xf)" + ] + }, + { + "cell_type": "markdown", + "id": "TKyc2jOiWJBe", + "metadata": { + "id": "TKyc2jOiWJBe" + }, + "source": [ + "Note that the value of $\\delta$ is very large at the start. This is truncated in the model so that it does not exceed $\\pm 0.5$ rad." + ] + }, + { + "cell_type": "markdown", + "id": "6c6c4b9b", + "metadata": { + "id": "6c6c4b9b" + }, + "source": [ + "## Reference trajectory subsystem\n", + "\n", + "In addition to generating a trajectory for the system, we can also create $x_\\text{d}$ and $u_\\text{d}$ corresponding to reference inputs $r_y$ and $r_v$.\n", + "\n", + "The reference trajectory block below generates a simple trajectory for the system given the desired speed (vref) and lateral position (yref). The trajectory consists of a straight line of the form (vref * t, yref, 0) with nominal\n", + "input (vref, 0)." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "significant-november", + "metadata": {}, + "outputs": [], + "source": [ + "# System state: none\n", + "# System input: vref, yref\n", + "# System output: xd, yd, thetad, vd, deltad\n", + "# System parameters: none\n", + "#\n", + "def trajgen_output(t, x, u, params):\n", + " vref, yref = u\n", + " return np.array([vref * t, yref, 0, vref, 0])\n", + "\n", + "# Define the trajectory generator as an input/output system\n", + "trajgen = ct.nlsys(\n", + " None, trajgen_output, name='trajgen',\n", + " inputs=('vref', 'yref'),\n", + " outputs=('xd', 'yd', 'thetad', 'vd', 'deltad'))\n", + "\n", + "print(trajgen)" + ] + }, + { + "cell_type": "markdown", + "id": "0w5s56uUWw-v", + "metadata": { + "id": "0w5s56uUWw-v" + }, + "source": [ + "## Step responses\n", + "\n", + "To explore the dynamics of the system, we create a set of lane changes at different forward speeds. Since the linearization depends on the speed, this means that the closed loop performance of the system will vary." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "mtGLwMQkXEzw", + "metadata": {}, + "outputs": [], + "source": [ + "steering_fixed = ct.interconnect(\n", + " [kincar, ctrl, trajgen],\n", + " inputs=['vref', 'yref'],\n", + " outputs=kincar.output_labels + kincar.input_labels\n", + ")\n", + "print(steering_fixed)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "sz7NaJTGXua1", + "metadata": {}, + "outputs": [], + "source": [ + "# Set up the simulation conditions\n", + "yref = 1\n", + "T = np.linspace(0, 5, 100)\n", + "\n", + "# Do an iteration through different speeds\n", + "for vref in [2, 5, 20]:\n", + " # Simulate the closed loop controller response\n", + " tout, yout = ct.input_output_response(\n", + " steering_fixed, T, [vref * np.ones(len(T)), yref * np.ones(len(T))],\n", + " params={'maxsteer': 1})\n", + "\n", + " # Plot the results\n", + " plot_lanechange(tout, yout, yout[3:])\n", + "\n", + "# Label the different curves\n", + "plt.subplot(3, 1, 1)\n", + "plt.legend([\"$v_d$ = \" + f\"{vref}\" for vref in [2, 10, 20]])\n", + "plt.tight_layout()" + ] + }, + { + "cell_type": "markdown", + "id": "3cc26675", + "metadata": { + "id": "3cc26675" + }, + "source": [ + "## Gain scheduled controller\n", + "\n", + "For this system we use a simple schedule on the forward vehicle velocity and\n", + "place the poles of the system at fixed values. The controller takes the\n", + "current and desired vehicle position and orientation plus the velocity\n", + "velocity as inputs, and returns the velocity and steering commands.\n", + "\n", + "Linearizing the system about the desired trajectory, we obtain\n", + "\n", + "$$\n", + " \\begin{aligned}\n", + " A(x_\\text{d}) &= \\left. \\frac{\\partial f}{\\partial x} \\right|_{(x_\\text{d}, u_\\text{d})}\n", + " = \\left.\n", + " \\begin{bmatrix}\n", + " 0 & 0 & -\\sin\\theta_\\text{d}\\, v_\\text{d} \\\\ 0 & 0 & \\cos\\theta_\\text{d}\\, v_\\text{d} \\\\ 0 & 0 & 0\n", + " \\end{bmatrix}\n", + " \\right|_{(x_\\text{d}, u_\\text{d})}\n", + " = \\begin{bmatrix}\n", + " 0 & 0 & 0 \\\\ 0 & 0 & v_\\text{d} \\\\ 0 & 0 & 0\n", + " \\end{bmatrix}, \\\\\n", + " B(x_\\text{d}) &= \\left. \\frac{\\partial f}{\\partial u} \\right|_{(x_\\text{d}, u_\\text{d})}\n", + " = \\begin{bmatrix}\n", + " 1 & 0 \\\\ 0 & 0 \\\\ 0 & v_\\text{d}/l\n", + " \\end{bmatrix}.\n", + " \\end{aligned}\n", + "$$\n", + "\n", + "We see that these matrices depend only on $\\theta_\\text{d}$ and $v_\\text{d}$, so we choose these as the scheduling variables and design a controller of the form\n", + "\n", + "$$\n", + "u = u_\\text{d} - K(\\mu) (x - x_\\text{d})\n", + "$$\n", + "\n", + "where $\\mu = (\\theta_\\text{d}, v_\\text{d})$ and we interpolate the gains based on LQR controllers computed at a fixed set of points $\\mu_i$." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "another-milwaukee", + "metadata": {}, + "outputs": [], + "source": [ + "# Define the points for the scheduling variables\n", + "gs_speeds = [2, 10, 20]\n", + "gs_angles = np.linspace(-pi, pi, 4)\n", + "\n", + "# Create controllers at each scheduling point (\n", + "points = [np.array([speed, angle])\n", + " for speed in gs_speeds for angle in gs_angles]\n", + "gains = [np.array(ct.lqr(kincar.linearize(\n", + " [0, 0, angle], [speed, 0]), Qx, Qu)[0])\n", + " for speed in gs_speeds for angle in gs_angles]\n", + "print(f\"{points=}\")\n", + "print(f\"{gains=}\")\n", + "\n", + "# Create the gain scheduled system\n", + "ctrl_gs, _ = ct.create_statefbk_iosystem(\n", + " kincar, (gains, points), name='controller',\n", + " xd_labels=['xd', 'yd', 'thetad'], ud_labels=['vd', 'deltad'],\n", + " gainsched_indices=['vd', 'theta'], gainsched_method='linear')\n", + "print(ctrl_gs)" + ] + }, + { + "cell_type": "markdown", + "id": "4ca5ab53", + "metadata": { + "id": "4ca5ab53" + }, + "source": [ + "## System construction\n", + "\n", + "The input to the full closed loop system is the desired lateral position and the desired forward velocity. The output for the system is taken as the full vehicle state plus the velocity of the vehicle.\n", + "\n", + "We construct the system using the `ct.interconnect` function and use signal labels to keep track of everything. " + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "editorial-satisfaction", + "metadata": {}, + "outputs": [], + "source": [ + "steering_gainsched = ct.interconnect(\n", + " [trajgen, ctrl_gs, kincar], name='steering',\n", + " inputs=['vref', 'yref'],\n", + " outputs=kincar.output_labels + kincar.input_labels\n", + ")\n", + "print(steering_gainsched)" + ] + }, + { + "cell_type": "markdown", + "id": "47f5d528", + "metadata": { + "id": "47f5d528" + }, + "source": [ + "## System simulation\n", + "\n", + "We now simulate the gain scheduled controller for a step input in the $y$ position, using a range of vehicle speeds $v_\\text{d}$:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "smoking-trail", + "metadata": {}, + "outputs": [], + "source": [ + "# Plot the reference trajectory for the y position\n", + "# plt.plot([0, 5], [yref, yref], 'k-', linewidth=0.6)\n", + "\n", + "# Find the signals we want to plot\n", + "y_index = steering_gainsched.find_output('y')\n", + "v_index = steering_gainsched.find_output('v')\n", + "\n", + "# Do an iteration through different speeds\n", + "for vref in [2, 5, 20]:\n", + " # Simulate the closed loop controller response\n", + " tout, yout = ct.input_output_response(\n", + " steering_gainsched, T, [vref * np.ones(len(T)), yref * np.ones(len(T))],\n", + " X0=[0, 0, 0], params={'maxsteer': 0.5}\n", + " )\n", + "\n", + " # Plot the results\n", + " plot_lanechange(tout, yout, yout[3:])\n", + "\n", + "# Label the different curves\n", + "plt.subplot(3, 1, 1)\n", + "plt.legend([\"$v_d$ = \" + f\"{vref}\" for vref in [2, 10, 20]])\n", + "plt.tight_layout()" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "6f571b2b", + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/examples/cds110-L6c_doubleint-rhc.ipynb b/examples/cds110-L6c_doubleint-rhc.ipynb new file mode 100644 index 000000000..d9a693a27 --- /dev/null +++ b/examples/cds110-L6c_doubleint-rhc.ipynb @@ -0,0 +1,651 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "9d41c333", + "metadata": { + "id": "9d41c333" + }, + "source": [ + "
\n", + "

CDS 110, Lecture 6c

\n", + "

Receding Horizon Control of a Double Integrator with Bounded Input

\n", + "

Richard M. Murray, Winter 2024

\n", + "
\n", + "\n", + "[Open in Google Colab](https://colab.research.google.com/drive/1AufRjpbdKcOEoWO5NEiczF3C8Rc4JuTL)\n", + "\n", + "To illustrate the implementation of a receding horizon controller, we consider a linear system corresponding to a double integrator with bounded input:\n", + "\n", + "$$\n", + " \\dot x = \\begin{bmatrix} 0 & 1 \\\\ 0 & 0 \\end{bmatrix} x + \\begin{bmatrix} 0 \\\\ 1 \\end{bmatrix} \\text{clip}(u)\n", + " \\qquad\\text{where}\\qquad\n", + " \\text{clip}(u) = \\begin{cases}\n", + " -1 & u < -1, \\\\\n", + " u & -1 \\leq u \\leq 1, \\\\\n", + " 1 & u > 1.\n", + " \\end{cases}\n", + "$$\n", + "\n", + "We implement a model predictive controller by choosing\n", + "\n", + "$$\n", + " Q_x = \\begin{bmatrix} 1 & 0 \\\\ 0 & 0 \\end{bmatrix}, \\qquad\n", + " Q_u = \\begin{bmatrix} 1 \\end{bmatrix}, \\qquad\n", + " P_1 = \\begin{bmatrix} 0.1 & 0 \\\\ 0 & 0.1 \\end{bmatrix}.\n", + "$$" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "4fe0af7f", + "metadata": {}, + "outputs": [], + "source": [ + "import numpy as np\n", + "import scipy as sp\n", + "import matplotlib.pyplot as plt\n", + "import time\n", + "try:\n", + " import control as ct\n", + " print(\"python-control\", ct.__version__)\n", + "except ImportError:\n", + " !pip install control\n", + " import control as ct\n", + "import control.optimal as opt\n", + "import control.flatsys as fs" + ] + }, + { + "cell_type": "markdown", + "id": "4c695f81", + "metadata": { + "id": "4c695f81" + }, + "source": [ + "## System definition\n", + "\n", + "The system is defined as a double integrator with bounded input." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "5c01f571", + "metadata": {}, + "outputs": [], + "source": [ + "def doubleint_update(t, x, u, params):\n", + " # Get the parameters\n", + " lb = params.get('lb', -1)\n", + " ub = params.get('ub', 1)\n", + " assert lb < ub\n", + "\n", + " # bound the input\n", + " u_clip = np.clip(u, lb, ub)\n", + "\n", + " return np.array([x[1], u_clip[0]])\n", + "\n", + "proc = ct.nlsys(\n", + " doubleint_update, None, name=\"double integrator\",\n", + " inputs = ['u'], outputs=['x[0]', 'x[1]'], states=2)" + ] + }, + { + "cell_type": "markdown", + "id": "6c2f0d00", + "metadata": { + "id": "6c2f0d00" + }, + "source": [ + "## Receding horizon controller\n", + "\n", + "To define a receding horizon controller, we create an optimal control problem (using the `OptimalControlProblem` class) and then use the `compute_trajectory` method to solve for the trajectory from the current state.\n", + "\n", + "We start by defining the cost functions, which consists of a trajectory cost and a terminal cost:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "a501efef", + "metadata": {}, + "outputs": [], + "source": [ + "Qx = np.diag([1, 0]) # state cost\n", + "Qu = np.diag([1]) # input cost\n", + "traj_cost=opt.quadratic_cost(proc, Qx, Qu)\n", + "\n", + "P1 = np.diag([0.1, 0.1]) # terminal cost\n", + "term_cost = opt.quadratic_cost(proc, P1, None)" + ] + }, + { + "cell_type": "markdown", + "id": "c5470629", + "metadata": { + "id": "c5470629" + }, + "source": [ + "We also set up a set of constraints the correspond to the fact that the input should have magnitude 1. This can be done using either the [`input_range_constraint`](https://python-control.readthedocs.io/en/0.9.3.post2/generated/control.optimal.input_range_constraint.html) function or the [`input_poly_constraint`](https://python-control.readthedocs.io/en/0.9.3.post2/generated/control.optimal.input_poly_constraint.html) function." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "cb4c511a", + "metadata": {}, + "outputs": [], + "source": [ + "traj_constraints = opt.input_range_constraint(proc, -1, 1)\n", + "# traj_constraints = opt.input_poly_constraint(\n", + "# proc, np.array([[1], [-1]]), np.array([1, 1]))" + ] + }, + { + "cell_type": "markdown", + "id": "a5568374", + "metadata": { + "id": "a5568374" + }, + "source": [ + "We define the horizon for evaluating finite-time, optimal control by setting up a set of time points across the designed horizon. The input will be computed at each time point." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "9edec673", + "metadata": {}, + "outputs": [], + "source": [ + "Th = 5\n", + "timepts = np.linspace(0, Th, 11, endpoint=True)\n", + "print(timepts)" + ] + }, + { + "cell_type": "markdown", + "id": "cb8fcecc", + "metadata": { + "id": "cb8fcecc" + }, + "source": [ + "Finally, we define the optimal control problem that we want to solve (without actually solving it)." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "e9f31be6", + "metadata": {}, + "outputs": [], + "source": [ + "# Set up the optimal control problem\n", + "ocp = opt.OptimalControlProblem(\n", + " proc, timepts, traj_cost,\n", + " terminal_cost=term_cost,\n", + " trajectory_constraints=traj_constraints,\n", + " # terminal_constraints=term_constraints,\n", + ")" + ] + }, + { + "cell_type": "markdown", + "id": "ee9a39dd", + "metadata": { + "id": "ee9a39dd" + }, + "source": [ + "To make sure that the problem is properly defined, we solve the problem for a specific initial condition. We also compare the amount of time required to solve the problem from a \"cold start\" (no initial guess) versus a \"warm start\" (use the previous solution, shifted forward on point in time)." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "887295eb", + "metadata": {}, + "outputs": [], + "source": [ + "X0 = np.array([1, 1])\n", + "\n", + "start_time = time.process_time()\n", + "res = ocp.compute_trajectory(X0, initial_guess=0, return_states=True)\n", + "stop_time = time.process_time()\n", + "print(f'* Cold start: {stop_time-start_time:.3} sec')\n", + "\n", + "# Resolve using previous solution (shifted forward) as initial guess to compare timing\n", + "start_time = time.process_time()\n", + "u = res.inputs\n", + "u_shift = np.hstack([u[:, 1:], u[:, -1:]])\n", + "ocp.compute_trajectory(X0, initial_guess=u_shift, print_summary=False)\n", + "stop_time = time.process_time()\n", + "print(f'* Warm start: {stop_time-start_time:.3} sec')" + ] + }, + { + "cell_type": "markdown", + "id": "115dec26", + "metadata": { + "id": "115dec26" + }, + "source": [ + "(In this case the timing is not that different since the system is very simple.)\n", + "\n", + "Plotting the result, we see that the solution is properly computed." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "4b98e773", + "metadata": {}, + "outputs": [], + "source": [ + "plt.plot(res.time, res.states[0], 'k-', label='$x_1$')\n", + "plt.plot(res.time, res.inputs[0], 'b-', label='u')\n", + "plt.xlabel('Time [s]')\n", + "plt.ylabel('$x_1$, $u$')\n", + "plt.legend();" + ] + }, + { + "cell_type": "markdown", + "id": "0e85981a", + "metadata": { + "id": "0e85981a" + }, + "source": [ + "We implement the receding horizon controller using a function that we can use with different versions of the problem." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "eb2e8126", + "metadata": {}, + "outputs": [], + "source": [ + "# Create a figure to use for plotting\n", + "def run_rhc_and_plot(\n", + " proc, ocp, X0, Tf, print_summary=False, verbose=False, ax=None, plot=True):\n", + " # Start at the initial point\n", + " x = X0\n", + "\n", + " # Initialize the axes\n", + " if plot and ax is None:\n", + " ax = plt.axes()\n", + "\n", + " # Initialize arrays to store the final trajectory\n", + " time_, inputs_, outputs_, states_ = [], [], [], []\n", + "\n", + " # Generate the individual traces for the receding horizon control\n", + " for t in ocp.timepts:\n", + " # Compute the optimal trajectory over the horizon\n", + " start_time = time.process_time()\n", + " res = ocp.compute_trajectory(x, print_summary=print_summary)\n", + " if verbose:\n", + " print(f\"{t=}: comp time = {time.process_time() - start_time:0.3}\")\n", + "\n", + " # Simulate the system for the update time, with higher res for plotting\n", + " tvec = np.linspace(0, res.time[1], 20)\n", + " inputs = res.inputs[:, 0] + np.outer(\n", + " (res.inputs[:, 1] - res.inputs[:, 0]) / (tvec[-1] - tvec[0]), tvec)\n", + " soln = ct.input_output_response(proc, tvec, inputs, x)\n", + "\n", + " # Save this segment for later use (final point will appear in next segment)\n", + " time_.append(t + soln.time[:-1])\n", + " inputs_.append(soln.inputs[:, :-1])\n", + " outputs_.append(soln.outputs[:, :-1])\n", + " states_.append(soln.states[:, :-1])\n", + "\n", + " if plot:\n", + " # Plot the results over the full horizon\n", + " h3, = ax.plot(t + res.time, res.states[0], 'k--', linewidth=0.5)\n", + " ax.plot(t + res.time, res.inputs[0], 'b--', linewidth=0.5)\n", + "\n", + " # Plot the results for this time segment\n", + " h1, = ax.plot(t + soln.time, soln.states[0], 'k-')\n", + " h2, = ax.plot(t + soln.time, soln.inputs[0], 'b-')\n", + "\n", + " # Update the state to use for the next time point\n", + " x = soln.states[:, -1]\n", + "\n", + " # Append the final point to the response\n", + " time_.append(t + soln.time[-1:])\n", + " inputs_.append(soln.inputs[:, -1:])\n", + " outputs_.append(soln.outputs[:, -1:])\n", + " states_.append(soln.states[:, -1:])\n", + "\n", + " # Label the plot\n", + " if plot:\n", + " # Adjust the limits for consistency\n", + " ax.set_ylim([-4, 3.5])\n", + "\n", + " # Add reference line for input lower bound\n", + " ax.plot([0, 7], [-1, -1], 'k--', linewidth=0.666)\n", + "\n", + " # Label the results\n", + " ax.set_xlabel(\"Time $t$ [sec]\")\n", + " ax.set_ylabel(\"State $x_1$, input $u$\")\n", + " ax.legend(\n", + " [h1, h2, h3], ['$x_1$', '$u$', 'prediction'],\n", + " loc='lower right', labelspacing=0)\n", + " plt.tight_layout()\n", + "\n", + " # Append\n", + " return ct.TimeResponseData(\n", + " np.hstack(time_), np.hstack(outputs_), np.hstack(states_), np.hstack(inputs_))" + ] + }, + { + "cell_type": "markdown", + "id": "be13e00a", + "metadata": { + "id": "be13e00a" + }, + "source": [ + "Finally, we call the controller and plot the response. The solid lines show the portions of the trajectory that we follow. The dashed lines are the trajectory over the full horizon, but which are not followed since we update the computation at each time step. (To get rid of the statistics of each optimization call, use `print_summary=False`.)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "305a1127", + "metadata": {}, + "outputs": [], + "source": [ + "Tf = 10\n", + "rhc_resp = run_rhc_and_plot(proc, ocp, X0, Tf, verbose=True, print_summary=False)\n", + "print(f\"xf = {rhc_resp.states[:, -1]}\")" + ] + }, + { + "cell_type": "markdown", + "id": "6005bfb3", + "metadata": { + "id": "6005bfb3" + }, + "source": [ + "## RHC vs LQR vs LQR terminal cost\n", + "\n", + "In the example above, we used a receding horizon controller with the terminal cost as $P_1 = \\text{diag}(0.1, 0.1)$. An alternative is to set the terminal cost to be the LQR terminal cost that goes along with the trajectory cost, which then provides a \"cost to go\" that matches the LQR \"cost to go\" (but keeping in mind that the LQR controller does not necessarily respect the constraints).\n", + "\n", + "The following code compares the original RHC formulation with a receding horizon controller using an LQR terminal cost versus an LQR controller." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "ea2de1f3", + "metadata": {}, + "outputs": [], + "source": [ + "# Get the LQR solution\n", + "K, P_lqr, E = ct.lqr(proc.linearize(0, 0), Qx, Qu)\n", + "print(f\"P_lqr = \\n{P_lqr}\")\n", + "\n", + "# Create an LQR controller (and run it)\n", + "lqr_ctrl, lqr_clsys = ct.create_statefbk_iosystem(proc, K)\n", + "lqr_resp = ct.input_output_response(lqr_clsys, rhc_resp.time, 0, X0)\n", + "\n", + "# Create a new optimal control problem using the LQR terminal cost\n", + "# (need use more refined time grid as well, to approximate LQR rate)\n", + "lqr_timepts = np.linspace(0, Th, 25, endpoint=True)\n", + "lqr_term_cost=opt.quadratic_cost(proc, P_lqr, None)\n", + "ocp_lqr = opt.OptimalControlProblem(\n", + " proc, lqr_timepts, traj_cost, terminal_cost=lqr_term_cost,\n", + " trajectory_constraints=traj_constraints,\n", + ")\n", + "\n", + "# Create the response for the new controller\n", + "rhc_lqr_resp = run_rhc_and_plot(\n", + " proc, ocp_lqr, X0, 10, plot=False, print_summary=False)\n", + "\n", + "# Plot the different responses to compare them\n", + "fig, ax = plt.subplots(2, 1)\n", + "ax[0].plot(rhc_resp.time, rhc_resp.states[0], label='RHC + P_1')\n", + "ax[0].plot(rhc_lqr_resp.time, rhc_lqr_resp.states[0], '--', label='RHC + P_lqr')\n", + "ax[0].plot(lqr_resp.time, lqr_resp.outputs[0], ':', label='LQR')\n", + "ax[0].legend()\n", + "\n", + "ax[1].plot(rhc_resp.time, rhc_resp.inputs[0], label='RHC + P_1')\n", + "ax[1].plot(rhc_lqr_resp.time, rhc_lqr_resp.inputs[0], '--', label='RHC + P_lqr')\n", + "ax[1].plot(lqr_resp.time, lqr_resp.outputs[2], ':', label='LQR')" + ] + }, + { + "cell_type": "markdown", + "id": "9497530b", + "metadata": { + "id": "9497530b" + }, + "source": [ + "## Discrete time RHC\n", + "\n", + "Many receding horizon control problems are solved based on a discrete time model. We show here how to implement this for a \"double integrator\" system, which in discrete time has the form\n", + "\n", + "$$\n", + " x[k+1] = \\begin{bmatrix} 1 & 1 \\\\ 0 & 1 \\end{bmatrix} x[k] + \\begin{bmatrix} 0 \\\\ 1 \\end{bmatrix} \\text{clip}(u[k])\n", + "$$\n" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "ae7cefa5", + "metadata": {}, + "outputs": [], + "source": [ + "#\n", + "# System definition\n", + "#\n", + "\n", + "def doubleint_update(t, x, u, params):\n", + " # Get the parameters\n", + " lb = params.get('lb', -1)\n", + " ub = params.get('ub', 1)\n", + " assert lb < ub\n", + "\n", + " # Get the sampling time\n", + " dt = params.get('dt', 1)\n", + "\n", + " # bound the input\n", + " u_clip = np.clip(u, lb, ub)\n", + "\n", + " return np.array([x[0] + dt * x[1], x[1] + dt * u_clip[0]])\n", + "\n", + "proc = ct.nlsys(\n", + " doubleint_update, None, name=\"double integrator\",\n", + " inputs = ['u'], outputs=['x[0]', 'x[1]'], states=2,\n", + " params={'dt': 1}, dt=1)\n", + "\n", + "#\n", + "# Linear quadratic regulator\n", + "#\n", + "\n", + "# Define the cost functions to use\n", + "Qx = np.diag([1, 0]) # state cost\n", + "Qu = np.diag([1]) # input cost\n", + "P1 = np.diag([0.1, 0.1]) # terminal cost\n", + "\n", + "# Get the LQR solution\n", + "K, P, E = ct.dlqr(proc.linearize(0, 0), Qx, Qu)\n", + "\n", + "# Test out the LQR controller, with no constraints\n", + "linsys = proc.linearize(0, 0)\n", + "clsys_lin = ct.ss(linsys.A - linsys.B @ K, linsys.B, linsys.C, 0, dt=proc.dt)\n", + "\n", + "X0 = np.array([2, 1]) # initial conditions\n", + "Tf = 10 # simulation time\n", + "res = ct.initial_response(clsys_lin, Tf, X0=X0)\n", + "\n", + "# Plot the results\n", + "plt.figure(1); plt.clf(); ax = plt.axes()\n", + "ax.plot(res.time, res.states[0], 'k-', label='$x_1$')\n", + "ax.plot(res.time, (-K @ res.states)[0], 'b-', label='$u$')\n", + "\n", + "# Test out the LQR controller with constraints\n", + "clsys_lqr = ct.feedback(proc, -K, 1)\n", + "tvec = np.arange(0, Tf, proc.dt)\n", + "res_lqr_const = ct.input_output_response(clsys_lqr, tvec, 0, X0)\n", + "\n", + "# Plot the results\n", + "ax.plot(res_lqr_const.time, res_lqr_const.states[0], 'k--', label='constrained')\n", + "ax.plot(res_lqr_const.time, (-K @ res_lqr_const.states)[0], 'b--')\n", + "ax.plot([0, 7], [-1, -1], 'k--', linewidth=0.75)\n", + "\n", + "# Adjust the limits for consistency\n", + "ax.set_ylim([-4, 3.5])\n", + "\n", + "# Label the results\n", + "ax.set_xlabel(\"Time $t$ [sec]\")\n", + "ax.set_ylabel(\"State $x_1$, input $u$\")\n", + "ax.legend(loc='lower right', labelspacing=0)\n", + "plt.title(\"Linearized LQR response from x0\")" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "13cfc5d8", + "metadata": {}, + "outputs": [], + "source": [ + "#\n", + "# Receding horizon controller\n", + "#\n", + "\n", + "# Create the constraints\n", + "traj_constraints = opt.input_range_constraint(proc, -1, 1)\n", + "term_constraints = opt.state_range_constraint(proc, [0, 0], [0, 0])\n", + "\n", + "# Define the optimal control problem we want to solve\n", + "T = 5\n", + "timepts = np.arange(0, T * proc.dt, proc.dt)\n", + "\n", + "# Set up the optimal control problems\n", + "ocp_orig = opt.OptimalControlProblem(\n", + " proc, timepts,\n", + " opt.quadratic_cost(proc, Qx, Qu),\n", + " trajectory_constraints=traj_constraints,\n", + " terminal_cost=opt.quadratic_cost(proc, P1, None),\n", + ")\n", + "\n", + "ocp_lqr = opt.OptimalControlProblem(\n", + " proc, timepts,\n", + " opt.quadratic_cost(proc, Qx, Qu),\n", + " trajectory_constraints=traj_constraints,\n", + " terminal_cost=opt.quadratic_cost(proc, P, None),\n", + ")\n", + "\n", + "ocp_low = opt.OptimalControlProblem(\n", + " proc, timepts,\n", + " opt.quadratic_cost(proc, Qx, Qu),\n", + " trajectory_constraints=traj_constraints,\n", + " terminal_cost=opt.quadratic_cost(proc, P/10, None),\n", + ")\n", + "\n", + "ocp_high = opt.OptimalControlProblem(\n", + " proc, timepts,\n", + " opt.quadratic_cost(proc, Qx, Qu),\n", + " trajectory_constraints=traj_constraints,\n", + " terminal_cost=opt.quadratic_cost(proc, P*10, None),\n", + ")\n", + "weight_list = [P1, P, P/10, P*10]\n", + "ocp_list = [ocp_orig, ocp_lqr, ocp_low, ocp_high]\n", + "\n", + "# Do a test run to figure out how long computation takes\n", + "start_time = time.process_time()\n", + "ocp_lqr.compute_trajectory(X0)\n", + "stop_time = time.process_time()\n", + "print(\"* Process time: %0.2g s\\n\" % (stop_time - start_time))\n", + "\n", + "# Create a figure to use for plotting\n", + "fig, [[ax_orig, ax_lqr], [ax_low, ax_high]] = plt.subplots(2, 2)\n", + "ax_list = [ax_orig, ax_lqr, ax_low, ax_high]\n", + "ax_name = ['orig', 'lqr', 'low', 'high']\n", + "\n", + "# Generate the individual traces for the receding horizon control\n", + "for ocp, ax, name, Pf in zip(ocp_list, ax_list, ax_name, weight_list):\n", + " x, t = X0, 0\n", + " for i in np.arange(0, Tf, proc.dt):\n", + " # Calculate the optimal trajectory\n", + " res = ocp.compute_trajectory(x, print_summary=False)\n", + " soln = ct.input_output_response(proc, res.time, res.inputs, x)\n", + "\n", + " # Plot the results for this time instant\n", + " ax.plot(res.time[:2] + t, res.inputs[0, :2], 'b-', linewidth=1)\n", + " ax.plot(res.time[:2] + t, soln.outputs[0, :2], 'k-', linewidth=1)\n", + "\n", + " # Plot the results projected forward\n", + " ax.plot(res.time[1:] + t, res.inputs[0, 1:], 'b--', linewidth=0.75)\n", + " ax.plot(res.time[1:] + t, soln.outputs[0, 1:], 'k--', linewidth=0.75)\n", + "\n", + " # Update the state to use for the next time point\n", + " x = soln.states[:, 1]\n", + " t += proc.dt\n", + "\n", + " # Adjust the limits for consistency\n", + " ax.set_ylim([-1.5, 3.5])\n", + "\n", + " # Label the results\n", + " ax.set_xlabel(\"Time $t$ [sec]\")\n", + " ax.set_ylabel(\"State $x_1$, input $u$\")\n", + " ax.set_title(f\"MPC response for {name}\")\n", + " plt.tight_layout()" + ] + }, + { + "cell_type": "markdown", + "id": "015dc953", + "metadata": { + "id": "015dc953" + }, + "source": [ + "We can also implement a receding horizon controller for a discrete time system using `opt.create_mpc_iosystem`. This creates a controller that accepts the current state as the input and generates the control to apply from that state." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "4f8bb594", + "metadata": {}, + "outputs": [], + "source": [ + "# Construct using create_mpc_iosystem\n", + "clsys = opt.create_mpc_iosystem(\n", + " proc, timepts, opt.quadratic_cost(proc, Qx, Qu), traj_constraints,\n", + " terminal_cost=opt.quadratic_cost(proc, P1, None),\n", + ")\n", + "print(clsys)" + ] + }, + { + "cell_type": "markdown", + "id": "f1b08fb4", + "metadata": { + "id": "f1b08fb4" + }, + "source": [ + "(This function needs some work to be more user-friendly, e.g. renaming of the inputs and outputs.)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "d2afd287", + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/examples/cds110-L7_bode-nyquist.ipynb b/examples/cds110-L7_bode-nyquist.ipynb new file mode 100644 index 000000000..6e9f63337 --- /dev/null +++ b/examples/cds110-L7_bode-nyquist.ipynb @@ -0,0 +1,856 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "8c577d78-3e4a-4f08-93ed-5c60867b9a3b", + "metadata": { + "id": "hairy-humidity" + }, + "source": [ + "
\n", + "

CDS 110, Lecture 7

\n", + "

Frequency Domain Analysis using Bode/Nyquist plots

\n", + "

Richard M. Murray, Winter 2024

\n", + "
\n", + "\n", + "[Open in Google Colab](https://colab.research.google.com/drive/1-BIaln1nF41fGqavzliuWT74nBkAnM3x)\n", + "\n", + "The purpose of this lecture is to introduce tools that can be used for frequency domain modeling and analysis of linear systems. It illustrates the use of a variety of frequency domain analysis and plotting tools." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "invalid-carnival", + "metadata": {}, + "outputs": [], + "source": [ + "# Import standard packages needed for this exercise\n", + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "import math\n", + "try:\n", + " import control as ct\n", + " print(\"python-control\", ct.__version__)\n", + "except ImportError:\n", + " !pip install control\n", + " import control as ct\n", + "\n", + "# Use ctrlplot defaults for matplotlib\n", + "plt.rcParams.update(ct.rcParams)" + ] + }, + { + "cell_type": "markdown", + "id": "P7t3Nm4Tre2Z", + "metadata": { + "id": "P7t3Nm4Tre2Z" + }, + "source": [ + "## Stable system: servomechanism\n", + "\n", + "We start with a simple example a stable system for which we wish to design a simple controller and analyze its performance, demonstrating along the way the basic frequency domain analysis functions in the Python control toolbox (python-control).\n", + "\n", + "Consider a simple mechanism for positioning a mechanical arm whose equations of motion are given by\n", + "\n", + "$$\n", + "J \\ddot \\theta = -b \\dot\\theta - k r\\sin\\theta + \\tau_\\text{m},\n", + "$$\n", + "\n", + "which can be written in state space form as\n", + "\n", + "$$\n", + "\\frac{d}{dt} \\begin{bmatrix} \\theta \\\\ \\theta \\end{bmatrix} =\n", + " \\begin{bmatrix} \\dot\\theta \\\\ -k r \\sin\\theta / J - b\\dot\\theta / J \\end{bmatrix}\n", + " + \\begin{bmatrix} 0 \\\\ 1/J \\end{bmatrix} \\tau_\\text{m}.\n", + "$$\n", + "\n", + "The system consists of a spring loaded arm that is driven by a motor, as shown below.\n", + "\n", + "
\"servomech-diagram\"
\n", + "\n", + "The motor applies a torque that twists the arm against a linear spring and moves the end of the arm across a rotating platter. The input to the system is the motor torque $\\tau_\\text{m}$. The force exerted by the spring is a nonlinear function of the head position due to the way it is attached.\n", + "\n", + "The system parameters are given by\n", + "\n", + "$$\n", + "k = 1,\\quad J = 100,\\quad b = 10,\n", + "\\quad r = 1,\\quad l = 2,\\quad \\epsilon = 0.01,\n", + "$$\n", + "\n", + "and we assume that time is measured in msec and distance in cm. (The constants here are made up and don't necessarily reflect a real disk drive, though the units and time constants are motivated by computer disk drives.)" + ] + }, + { + "cell_type": "markdown", + "id": "3e476db9", + "metadata": { + "id": "3e476db9" + }, + "source": [ + "The system dynamics can be modeled in python-control using a `NonlinearIOSystem` object, which we create with the `nlsys` function:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "27bb3c38", + "metadata": {}, + "outputs": [], + "source": [ + "# Parameter values\n", + "servomech_params = {\n", + " 'J': 100, # Moment of inertia of the motor\n", + " 'b': 10, # Angular damping of the arm\n", + " 'k': 1, # Spring constant\n", + " 'r': 1, # Location of spring contact on arm\n", + " 'l': 2, # Distance to the read head\n", + " 'eps': 0.01, # Magnitude of velocity-dependent perturbation\n", + "}\n", + "\n", + "# State derivative\n", + "def servomech_update(t, x, u, params):\n", + " # Extract the configuration and velocity variables from the state vector\n", + " theta = x[0] # Angular position of the disk drive arm\n", + " thetadot = x[1] # Angular velocity of the disk drive arm\n", + " tau = u[0] # Torque applied at the base of the arm\n", + "\n", + " # Get the parameter values\n", + " J, b, k, r = map(params.get, ['J', 'b', 'k', 'r'])\n", + "\n", + " # Compute the angular acceleration\n", + " dthetadot = 1/J * (\n", + " -b * thetadot - k * r * np.sin(theta) + tau)\n", + "\n", + " # Return the state update law\n", + " return np.array([thetadot, dthetadot])\n", + "\n", + "# System output (end of arm)\n", + "def servomech_output(t, x, u, params):\n", + " l = params['l']\n", + " return np.array([l * x[0]])\n", + "\n", + "# System dynamics\n", + "servomech = ct.nlsys(\n", + " servomech_update, servomech_output, name='servomech',\n", + " params=servomech_params,\n", + " states=['theta_', 'thdot_'],\n", + " outputs=['y'], inputs=['tau'])\n", + "\n", + "print(servomech)\n", + "print(\"\\nParams:\", servomech.params)" + ] + }, + { + "cell_type": "markdown", + "id": "competitive-terrain", + "metadata": { + "id": "competitive-terrain" + }, + "source": [ + "### Linearization\n", + "\n", + "To study the open loop dynamics of the system, we compute the linearization of the dynamics about the equilibrium point corresponding to $\\theta_\\text{e} = 15^\\circ$." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "senior-carpet", + "metadata": {}, + "outputs": [], + "source": [ + "# Convert the equilibrium angle to radians\n", + "theta_e = (15 / 180) * np.pi\n", + "\n", + "# Compute the input required to hold this position\n", + "u_e = servomech.params['k'] * servomech.params['r'] * np.sin(theta_e)\n", + "print(\"Equilibrium torque = %g\" % u_e)\n", + "\n", + "# Linearize the system about the equilibrium point\n", + "P = servomech.linearize([theta_e, 0], u_e, name='P_ss')\n", + "P.name = 'P_ss' # TODO: fix in nlsys_improvements\n", + "print(\"Linearized dynamics:\", P)\n", + "print(\"Zeros: \", P.zeros())\n", + "print(\"Poles: \", P.poles())\n", + "print(\"\")\n", + "\n", + "# Transfer function representation\n", + "P_tf = ct.tf(P, name='P_tf')\n", + "print(P_tf)" + ] + }, + { + "cell_type": "markdown", + "id": "instant-lancaster", + "metadata": { + "id": "instant-lancaster" + }, + "source": [ + "### Open loop frequency response\n", + "\n", + "A standard method for understanding the dynamics is to plot the output of the system in response to sinusoids with unit magnitude at different frequencies.\n", + "\n", + "We use the `frequency_response` function to plot the step response of the linearized, open-loop system." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "RxXFTpwO5bGI", + "metadata": {}, + "outputs": [], + "source": [ + "# Reset the frequency response label to correspond to a time unit of ms\n", + "ct.set_defaults('freqplot', freq_label=\"Frequency [rad/ms]\")\n", + "\n", + "# Frequency response\n", + "freqresp = ct.frequency_response(P, np.logspace(-2, 0))\n", + "freqresp.plot()\n", + "\n", + "# Equivalent command\n", + "ct.bode_plot(P_tf, np.logspace(-2, 0), '--')" + ] + }, + { + "cell_type": "markdown", + "id": "stuffed-premiere", + "metadata": { + "id": "stuffed-premiere" + }, + "source": [ + "### Feedback control design\n", + "\n", + "We next design a feedback controller for the system using a proportional integral controller, which has transfer function\n", + "\n", + "$$\n", + "C(s) = \\frac{k_\\text{p} s + k_\\text{i}}{s}\n", + "$$\n", + "\n", + "We will learn how to choose $k_\\text{p}$ and $k_\\text{i}$ more formally in W9. For now we just pick different values to see how the dynamics are impacted." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "8NK8O6XT7B_a", + "metadata": {}, + "outputs": [], + "source": [ + "kp = 1\n", + "ki = 1\n", + "\n", + "# Create tf from numerator/denominator coefficients\n", + "C = ct.tf([kp, ki], [1, 0], name='C')\n", + "print(C)\n", + "\n", + "# Alternative method: define \"s\" and use algebra\n", + "s = ct.tf('s')\n", + "C = ct.tf(kp + ki/s, name='C')\n", + "print(C)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "074427a3", + "metadata": {}, + "outputs": [], + "source": [ + "# Loop transfer function\n", + "L = P * C\n", + "cplt = ct.bode_plot([P, C, L], label=['P', 'C', 'L'])\n", + "cplt.set_plot_title(\"PI controller for servomechanism\")" + ] + }, + { + "cell_type": "markdown", + "id": "Bg5ga11VuRtI", + "metadata": { + "id": "Bg5ga11VuRtI" + }, + "source": [ + "Note that L = P * C corresponds to addition in both the magnitude and the phase." + ] + }, + { + "cell_type": "markdown", + "id": "UmYmSzx2rTfg", + "metadata": { + "id": "UmYmSzx2rTfg" + }, + "source": [ + "### Nyquist analysis\n", + "\n", + "To check stability (and eventually robustness), we use the Nyquist criterion." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "Qmp59pmS9GLj", + "metadata": {}, + "outputs": [], + "source": [ + "fig = plt.figure(figsize=[7, 4])\n", + "ax1 = plt.subplot(2, 2, 1)\n", + "ax2 = plt.subplot(2, 2, 3)\n", + "ct.bode_plot(L, ax=[ax1, ax2])\n", + "\n", + "# Tidy up the figure a bit\n", + "fig.align_labels()\n", + "ax1.set_title(\"Bode plot for L\")\n", + "\n", + "ax2 = plt.subplot(1, 2, 2)\n", + "ct.nyquist_plot(L, ax=ax2, title=\"\")\n", + "plt.title(\"Nyquist plot for L\")\n", + "\n", + "plt.suptitle(\"Loop analysis for (unstable) servomechanism\")\n", + "plt.tight_layout()" + ] + }, + { + "cell_type": "markdown", + "id": "s4dDf4PrZqU3", + "metadata": { + "id": "s4dDf4PrZqU3" + }, + "source": [ + "We see from this plot that the loop transfer function encircles the -1 point => closed loop system should be unstable. We can check this by making use of additional features of Nyquist analysis." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "K7ifUBL0Z3xN", + "metadata": {}, + "outputs": [], + "source": [ + "# Get the Nyquist *response*, so that we can get back encirclements\n", + "nyqresp = ct.nyquist_response(L)\n", + "print(\"N = encirclements: \", nyqresp.count)\n", + "print(\"P = RHP poles of L: \", np.sum(np.real(L.poles()) > 0))\n", + "print(\"Z = N + P = RHP zeros of 1 + L:\", np.sum(np.real((1 + L).zeros()) > 0))\n", + "print(\"Zeros of (1 + L) = \", (1 + L).zeros())\n", + "print(\"\")\n", + "\n", + "T = ct.feedback(L)\n", + "ct.step_response(T).plot(\n", + " title=\"Step response for (unstable) servomechanism\",\n", + " time_label=\"Time [ms]\");" + ] + }, + { + "cell_type": "markdown", + "id": "p3JxLilMxdOE", + "metadata": { + "id": "p3JxLilMxdOE" + }, + "source": [ + "### Poles on the $j\\omega$ axis\n", + "\n", + "Note that we have a pole at 0 (due to the integrator in the controller). How is this handled?\n", + "\n", + "A: use a small loop to the right around poles on the $j\\omega$ axis => not inside the contour.\n", + "\n", + "To see this, we use the `nyquist_response` function, which returns the contour used to compute the Nyquist curve. If we zoom in on the contour near the origin, we see how the outer edge of the Nyquist curve is computed." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "R5IBk3Ai9Slk", + "metadata": {}, + "outputs": [], + "source": [ + "fig = plt.figure(figsize=[7, 5.8])\n", + "\n", + "# Plot the D contour\n", + "ax1 = plt.subplot(2, 2, 1)\n", + "plt.plot(np.real(nyqresp.contour), np.imag(nyqresp.contour))\n", + "plt.axis([-1e-4, 4e-4, 0, 4e-4])\n", + "plt.xlabel('Real axis')\n", + "plt.ylabel('Imaginary axis')\n", + "plt.title(\"Zoom on D-contour\")\n", + "\n", + "# Clean up the display of the units\n", + "from matplotlib import ticker\n", + "ax1.xaxis.set_major_formatter(ticker.StrMethodFormatter(\"{x:.0e}\"))\n", + "ax1.yaxis.set_major_formatter(ticker.StrMethodFormatter(\"{x:.0e}\"))\n", + "\n", + "ax2 = plt.subplot(2, 2, 2)\n", + "ct.nyquist_plot(L, ax=ax2)\n", + "plt.title(\"Nyquist curve\")\n", + "\n", + "plt.suptitle(\"Nyquist contour for pole at the origin\")\n", + "plt.tight_layout()" + ] + }, + { + "cell_type": "markdown", + "id": "h20JRZ_r4fGy", + "metadata": { + "id": "h20JRZ_r4fGy" + }, + "source": [ + "### Second iteration feedback control design\n", + "\n", + "We now redesign the control system to give something that is stable. We can do this by moving the zero for the controller to a lower frequency, so that the phase lag from the integrator does not overlap with the phase lag from the system dynamics." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "YsM8SnXz_Kaj", + "metadata": {}, + "outputs": [], + "source": [ + "# Change the frequency response to avoid crossing over -180 with large gain\n", + "Cnew = ct.tf(kp + (ki/200)/s, name='C_new')\n", + "Lnew = ct.tf(P * Cnew, name='L_new')\n", + "\n", + "plt.figure(figsize=[7, 4])\n", + "ax1 = plt.subplot(2, 2, 1)\n", + "ax2 = plt.subplot(2, 2, 3)\n", + "ct.bode_plot([Lnew, L], ax=[ax1, ax2], label=['L_new', 'L_old'])\n", + "\n", + "# Clean up the figure a bit\n", + "ax1.loglog([1e-3, 1e1], [1, 1], 'k', linewidth=0.5)\n", + "ax1.set_title(\"Bode plot for L_new, L_old\", size='medium')\n", + "\n", + "ax3=plt.subplot(1, 2, 2)\n", + "ct.nyquist_plot(Lnew, max_curve_magnitude=5, ax=ax3)\n", + "ax3.set_title(\"Nyquist plot for Lnew\", size='medium')\n", + "\n", + "plt.suptitle(\"Loop analysis for (stable) servomechanism\")\n", + "plt.tight_layout()" + ] + }, + { + "cell_type": "markdown", + "id": "kFjeGXzDvucx", + "metadata": { + "id": "kFjeGXzDvucx" + }, + "source": [ + "We see now that we have no encirclements, and so the system should be stable.\n", + "\n", + "Note however that the Nyquist curve is close to the -1 point => not *that* stable." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "GGfJwG716jU2", + "metadata": {}, + "outputs": [], + "source": [ + "# Compute the transfer function from r to y\n", + "Tnew = ct.feedback(Lnew)\n", + "cplt = ct.step_response(Tnew).plot(time_label=\"Time [ms]\")\n", + "cplt.set_plot_title(\"Step response for (stable) spring-mass system\")" + ] + }, + { + "cell_type": "markdown", + "id": "b5114fa7-6924-47d7-8dd2-f12060152edd", + "metadata": {}, + "source": [ + "### Third iteration feedback control design (via loop shaping)\n", + "\n", + "To get a better design, we use a PID controller to shape the frequency response so that we get high gain at low frequency and low phase at crossover." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "e6da93a4-5202-45d7-9e5a-697848f4ba71", + "metadata": {}, + "outputs": [], + "source": [ + "# Design parameters\n", + "Td = 1 # Set to gain crossover frequency\n", + "Ti = Td * 10 # Set to low frequency region\n", + "kp = 500 # Tune to get desired bandwith\n", + "\n", + "# Updated gains\n", + "kp = 150\n", + "Ti = Td * 5; kp = 150\n", + "\n", + "# Compute controller parmeters\n", + "ki = kp/Ti\n", + "kd = kp * Td\n", + "\n", + "# Controller transfer function\n", + "ctrl_shape = kp + ki / s + kd * s\n", + "\n", + "# Frequency response (open loop) - use this to help tune your design\n", + "ltf_shape = ct.tf(P_tf * ctrl_shape, name='L_shape')\n", + "\n", + "cplt = ct.frequency_response([P, ctrl_shape]).plot(label=['P', 'C_shape'])\n", + "cplt = ct.frequency_response(ltf_shape).plot(margins=True)\n", + "\n", + "cplt.set_plot_title(\"Loop shaping design for servomechanism controller\")" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "d731f372-4992-464c-9ca5-49cc1d554799", + "metadata": {}, + "outputs": [], + "source": [ + "# Compute the transfer function from r to y\n", + "T_shape = ct.feedback(ltf_shape)\n", + "cplt = ct.step_response(T_shape).plot(\n", + " time_label=\"Time [ms]\",\n", + " title = \"Step response for servomechanism with PID controller\")" + ] + }, + { + "cell_type": "markdown", + "id": "JL99vo4trep5", + "metadata": { + "id": "JL99vo4trep5" + }, + "source": [ + "### Closed loop frequency response\n", + "\n", + "We can also look at the closed loop frequency response to understand how different inputs affect different outputs. The `gangof4` function computes the standard transfer functions:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "ceqcg3oM619g", + "metadata": {}, + "outputs": [], + "source": [ + "cplt = ct.gangof4(P_tf, ctrl_shape)" + ] + }, + { + "cell_type": "markdown", + "id": "gel18-iqwYYs", + "metadata": { + "id": "gel18-iqwYYs" + }, + "source": [ + "### Stability margins\n", + "\n", + "Another standard set of analysis tools is to identify the gain, phase, and stability margins for the system:\n", + "\n", + "* **Gain margin:** the maximimum amount of additional gain that we can put into the loop and still maintain stability.\n", + "* **Phase margin:** the maximum amount of additional phase (lag) that we can put into the loop and still maintain stability.\n", + "* **Stability margin:** the maximum amount of combined gain and phase at the critical frequency that can be put into the loop and still maintain stability.\n", + "\n", + "The first two of the items can be computed either by looking at the frequency response or by using the `margin` command.\n", + "\n", + "The stabilty margin is the minimum distance between -1 and $L(jw)$, which is just the minimum value of $|1 - L(j\\omega)|$.\n", + "\n" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "m-8ItbHwxLrv", + "metadata": {}, + "outputs": [], + "source": [ + "plt.figure(figsize=[7, 4])\n", + "\n", + "# Gain and phase margin on Bode plot\n", + "ax1 = plt.subplot(2, 2, 1)\n", + "plt.title(\"Bode plot for Lnew, with margins\")\n", + "ax2 = plt.subplot(2, 2, 3)\n", + "ct.bode_plot(Lnew, ax=[ax1, ax2], margins=True)\n", + "\n", + "# Compute gain and phase margin\n", + "gm, pm, wpc, wgc = ct.margin(Lnew)\n", + "print(f\"Gm = {gm:2.2g} (at {wpc:.2g} rad/ms)\")\n", + "print(f\"Pm = {pm:3.2g} deg (at {wgc:.2g} rad/ms)\")\n", + "\n", + "# Compute the stability margin\n", + "resp = ct.frequency_response(1 + Lnew)\n", + "sm = np.min(resp.magnitude)\n", + "wsm = resp.omega[np.argmin(resp.magnitude)]\n", + "print(f\"Sm = {sm:2.2g} (at {wsm:.2g} rad/ms)\")\n", + "\n", + "# Plot the Nyquist curve\n", + "ax3 = plt.subplot(1, 2, 2)\n", + "ct.nyquist_plot(Lnew, ax=ax3)\n", + "plt.title(\"Nyquist plot for Lnew [zoomed]\")\n", + "plt.axis([-2, 3, -2.6, 2.6])\n", + "\n", + "#\n", + "# Annotate it to see the margins\n", + "#\n", + "\n", + "# Gain margin (special case here, since infinite)\n", + "Lgm = 0\n", + "plt.plot([-1, Lgm], [0, 0], 'k-', linewidth=0.5)\n", + "plt.text(-0.9, 0.1, \"1/gm\")\n", + "\n", + "# Phase margin\n", + "theta = np.linspace(0, 2 * math.pi)\n", + "plt.plot(np.cos(theta), np.sin(theta), 'k--', linewidth=0.5)\n", + "plt.text(-1.3, -0.8, \"pm\")\n", + "\n", + "# Stability margin\n", + "Lsm = Lnew(wsm * 1j)\n", + "plt.plot([-1, Lsm.real], [0, Lsm.imag], 'k-', linewidth=0.5)\n", + "plt.text(-0.4, -0.5, \"sm\")\n", + "\n", + "plt.suptitle(\"\")\n", + "plt.tight_layout()" + ] + }, + { + "cell_type": "markdown", + "id": "WsOzQST9rFC-", + "metadata": { + "id": "WsOzQST9rFC-" + }, + "source": [ + "## Unstable system: inverted pendulum\n", + "\n", + "When we have a system that is open loop unstable, the Nyquist curve will need to have encirclements to be stable. In this case, the interpretation of the various characteristics can be more complicated.\n", + "\n", + "To explore this, we consider a simple model for an inverted pendulum, which has (normalized) dynamics:\n", + "\n", + "$$\n", + "\\dot x = \\begin{bmatrix} 0 & 1 & \\\\ -1 & 0.1 \\end{bmatrix} x + \\begin{bmatrix} 0 \\\\ 1 \\end{bmatrix} u, \\qquad\n", + "y = \\begin{bmatrix} 1 & 0 \\end{bmatrix} x\n", + "$$\n", + "\n", + "Transfer function for the system can be shown to be\n", + "\n", + "$$\n", + "P(s) = \\frac{1}{s^2 + 0.1 s - 1}.\n", + "$$\n", + "\n", + "This system is unstable, with poles $\\sim\\pm 1$." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "ZbPzrlPIrHnp", + "metadata": {}, + "outputs": [], + "source": [ + "P = ct.tf([1], [1, 0.1, -1])\n", + "P.poles()" + ] + }, + { + "cell_type": "markdown", + "id": "W-sBWxKi6SPx", + "metadata": { + "id": "W-sBWxKi6SPx" + }, + "source": [ + "### PD controller\n", + "\n", + "We construct a proportional-derivative (PD) controller for the system,\n", + "\n", + "$$\n", + "u = k_\\text{p} e + k_\\text{d} \\dot{e}\n", + "$$\n", + "\n", + "which is roughly the equivalent of using state feedback (since the system states are $\\theta$ and $\\dot\\theta$)." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "hjQS_dED7yJE", + "metadata": {}, + "outputs": [], + "source": [ + "# Transfer function for a PD controller\n", + "kp = 10\n", + "kd = 2\n", + "C = ct.tf([kd, kp], [1])\n", + "\n", + "# Loop transfer function\n", + "L = P * C\n", + "L.name = 'L'\n", + "print(L)\n", + "print(\"Zeros: \", L.zeros())\n", + "print(\"Poles: \", L.poles())" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "YI_KJo0E9pFd", + "metadata": {}, + "outputs": [], + "source": [ + "# Bode and Nyquist plots\n", + "plt.figure(figsize=[7, 4])\n", + "ax1 = plt.subplot(2, 2, 1)\n", + "plt.title(\"Bode plot for L\", size='medium')\n", + "ax2 = plt.subplot(2, 2, 3)\n", + "ct.bode_plot(L, ax=[ax1, ax2])\n", + "\n", + "ax3 = plt.subplot(1, 2, 2)\n", + "ct.nyquist_plot(L, ax=ax3)\n", + "plt.title(\"Nyquist plot for L\", size='medium')\n", + "\n", + "plt.suptitle(\"Loop analysis for inverted pendulum\")\n", + "plt.tight_layout()" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "8dH03kv9-Da8", + "metadata": {}, + "outputs": [], + "source": [ + "# Check the Nyquist criterion\n", + "nyqresp = ct.nyquist_response(L)\n", + "print(\"N = encirclements: \", nyqresp.count)\n", + "print(\"P = RHP poles of L: \", np.sum(np.real(L.poles()) > 0))\n", + "print(\"Z = N + P = RHP zeros of 1 + L:\", np.sum(np.real((1 + L).zeros()) >= 0))\n", + "print(\"Poles of L = \", L.poles())\n", + "print(\"Zeros of 1 + L = \", (1 + L).zeros())\n", + "print(\"\")\n", + "\n", + "T = ct.feedback(L)\n", + "ct.initial_response(T, X0=[0.1, 0]).plot();" + ] + }, + { + "cell_type": "markdown", + "id": "7bb03f68-0c99-40e9-86cd-a9f2816b4096", + "metadata": {}, + "source": [ + "Note that we get a warning when we set the initial condition. This is because `T` is a transfer function and so it doesn't have a unique state space realization. If the initial state is zero this doesn't matter, but if the initial state is nonzero then the assignment of states is not well defined." + ] + }, + { + "cell_type": "markdown", + "id": "VXlYhs8X7DuN", + "metadata": { + "id": "VXlYhs8X7DuN" + }, + "source": [ + "### Gang of 4\n", + "\n", + "Another useful thing to look at is the transfer functions from noise and disturbances to the system outputs and inputs:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "oTmOun41_opt", + "metadata": {}, + "outputs": [], + "source": [ + "ct.gangof4(P, C);" + ] + }, + { + "cell_type": "markdown", + "id": "U41ve1zh7XPh", + "metadata": { + "id": "U41ve1zh7XPh" + }, + "source": [ + "We see that the response from the input $r$ (or equivalently noise $n$) to the process input is very large for large frequencies. This means that we are amplifying high frequency noise (and comes from the fact that we used derivative feedback)." + ] + }, + { + "cell_type": "markdown", + "id": "YROqmZTd8WYs", + "metadata": { + "id": "YROqmZTd8WYs" + }, + "source": [ + "### High frequency rolloff\n", + "\n", + "We can attempt to resolve this by \"rolling off\" the derivative action at high frequencies:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "vhKi_L-F_6Ws", + "metadata": {}, + "outputs": [], + "source": [ + "Cnew = (kp + kd * s) / (s/20 + 1)**2\n", + "Cnew.name = 'Cnew'\n", + "print(Cnew)\n", + "\n", + "Lnew = P * Cnew\n", + "Lnew.name = 'Lnew'\n", + "\n", + "plt.figure(figsize=[7, 4])\n", + "ax1 = plt.subplot(2, 2, 1)\n", + "ax2 = plt.subplot(2, 2, 3)\n", + "ct.bode_plot([Lnew, L], ax=[ax1, ax2])\n", + "ax1.loglog([1e-1, 1e2], [1, 1], 'k', linewidth=0.5)\n", + "ax1.set_title(\"Bode plot for L, Lnew\", size='medium')\n", + "\n", + "ax3 = plt.subplot(1, 2, 2)\n", + "ct.nyquist_plot(Lnew, ax=ax3)\n", + "ax3.set_title(\"Nyquist plot for Lnew\", size='medium')\n", + "\n", + "plt.suptitle(\"Stability analysis for inverted pendulum\")\n", + "plt.tight_layout()" + ] + }, + { + "cell_type": "markdown", + "id": "WgrAE9XE7_nJ", + "metadata": { + "id": "WgrAE9XE7_nJ" + }, + "source": [ + "While not (yet) a very high performing controller, this change does get rid of the issues with the high frequency noise:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "FknwW6GkBLLU", + "metadata": {}, + "outputs": [], + "source": [ + "# Check the gang of 4\n", + "ct.gangof4(P, Cnew);" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "wJHJLjXwCNz-", + "metadata": {}, + "outputs": [], + "source": [ + "# See what the step response looks like\n", + "Tnew = ct.feedback(Lnew)\n", + "ct.step_response(Tnew, 10).plot()" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "WUhz529a-w3q", + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/examples/cds110-L8a_maglev-limits.ipynb b/examples/cds110-L8a_maglev-limits.ipynb new file mode 100644 index 000000000..5a7473ade --- /dev/null +++ b/examples/cds110-L8a_maglev-limits.ipynb @@ -0,0 +1,278 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "gToHma1nvZxz", + "metadata": { + "id": "gToHma1nvZxz" + }, + "source": [ + "
\n", + "

CDS 110, Lecture 8a

\n", + "

Fundamental Limits for Control of a Magnetic Levitation System

\n", + "

Richard M. Murray, Winter 2024

\n", + "
\n", + "\n", + "[Open in Google Colab](https://colab.research.google.com/drive/1MuDZfw72UkI4_Ji_AsEDTPi7IaSURsYP)\n", + "\n", + "This notebook contains the code used to create the magnetic levitation example in Lecture 8-1 of CDS 110, Winter 2024." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "dc288b3e-60cc-4a75-8af5-81f9d1eede41", + "metadata": {}, + "outputs": [], + "source": [ + "import numpy as np\n", + "import scipy as sp\n", + "import matplotlib.pyplot as plt\n", + "from math import pi\n", + "try:\n", + " import control as ct\n", + " print(\"python-control\", ct.__version__)\n", + "except ImportError:\n", + " !pip install control\n", + " import control as ct\n", + "import control.optimal as opt\n", + "import control.flatsys as fs" + ] + }, + { + "cell_type": "markdown", + "id": "RFi9litmZKT2", + "metadata": { + "id": "RFi9litmZKT2" + }, + "source": [ + "The magnetic leviation system consists of a metal ball, an electromagnet, and an IR sensor:\n", + "\n", + "
\"maglev-diagram\"
\n", + "\n", + "It is governed by following equation:\n", + "\n", + "$$ \\ddot{z} = g - \\frac{k_mk_A^2}{m}\\frac{u^2}{z^2} - \\frac{c}{m}\\dot{z},$$\n", + "\n", + "where $z$ is the vertical height of the ball and $u$ is the input current applied to the electromagnet. The output is given by $v_{ir}$, which is the voltage measured at the IR sensor:\n", + "\n", + "$$v_{ir} = k_T z + v_0 $$" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "80da9750-1a34-4a54-ab3a-ff37ea7be0f6", + "metadata": {}, + "outputs": [], + "source": [ + "# System dynamics\n", + "maglev_params = {\n", + " 'kT': 613.65, # gain between position and voltage\n", + " 'v0': -16.18,\t # voltage offset at zero position\n", + " 'm': 0.2,\t # mass of ball, kg\n", + " 'g': 9.81, # gravitational constant\n", + " 'kA': 1,\t # electromagnet conductance\n", + " 'c': 1 # damping (added to improve visualization)\n", + "}\n", + "# gain on magnetic attractive force\n", + "maglev_params['km'] = 3.13e-3 * (maglev_params['m']/2) / maglev_params['kA']**2\n", + "\n", + "def maglev_update(t, x, u, params):\n", + " m, g, kA, km, c = map(params.get, ['m', 'g', 'kA', 'km', 'c'])\n", + " return np.array([\n", + " x[1],\n", + " g - km/m * (kA * u[0])**2 / x[0]**2 - c * x[1]\n", + " ])\n", + "\n", + "def maglev_output(t, x, u, params):\n", + " kT, v0 = map(params.get, ['kT', 'v0'])\n", + " return np.array([kT * x[0] + v0])\n", + "\n", + "maglev = ct.nlsys(\n", + " maglev_update, maglev_output, params=maglev_params, name='maglev',\n", + " inputs='Vu', outputs='Vy', states=['pos', 'vel']\n", + ")" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "b5c56e04-03b7-4c18-be3c-3f4308aedb98", + "metadata": {}, + "outputs": [], + "source": [ + "# Compute the equilibrium point that holds the ball at the origin\n", + "xeq, ueq = ct.find_eqpt(maglev, [0.02, 0], 0.2, y0=0)\n", + "print(f\"{xeq=}, {ueq=}\", end='\\n----\\n')\n", + "\n", + "# Compute the linearization at that point\n", + "magP = ct.linearize(maglev, xeq, ueq, name='sys')\n", + "print(magP, end='\\n----\\n')\n", + "\n", + "print(\"Poles:\", magP.poles())\n", + "print(\"Zeros:\", magP.zeros())" + ] + }, + { + "cell_type": "markdown", + "id": "22a2766f-217a-4213-ba19-c11485cc42cc", + "metadata": {}, + "source": [ + "The controller for this system is implemented via an electrical circuit consisting of resistors and capacitors. We don't show the circuit here, but just write down the model for the transfer function:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "b4741e88-bedd-4ef0-b8b9-9deb5fa93d5d", + "metadata": {}, + "outputs": [], + "source": [ + "# Controller (analog circuit)\n", + "k1 = 0.5\t\t\t\t# gain set by gain pot\n", + "R1 = 22000\t\t\t\t# Internal resistor\n", + "R2 = 22000\t\t\t\t# Resistor plug-in\n", + "R = 2000; C = 1e-6\t\t# RC plug-in\n", + "\n", + "# Controller based on analog circuit\n", + "magC1 = -ct.tf([(R1 + R) * C, 1], [R * C, 1]) * k1 * R2/R1\n", + "magL1 = magP * magC1" + ] + }, + { + "cell_type": "markdown", + "id": "641c0df2-90f6-4573-af7f-41a305337e77", + "metadata": {}, + "source": [ + "We can now use a Nyquist plot to see if the controller is stabilizing:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "378b14b8-f8e4-4ed6-b09d-cdf577ea47d1", + "metadata": {}, + "outputs": [], + "source": [ + "# Nyquist plot\n", + "cplt = ct.nyquist_plot([magP, magL1], label=[\"sys\", \"sys * ctrl\"])" + ] + }, + { + "cell_type": "markdown", + "id": "HKGSdW5f91mZ", + "metadata": { + "id": "HKGSdW5f91mZ" + }, + "source": [ + "We see that the controller causes the system to have clockwise net encircelement of the origin. Since the open loop system has one unstable pole, this gives $Z = N + P = 0$ and so the closed loop system is stable." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "7850f14d-79ab-4250-a0c7-8ddc10ebb977", + "metadata": {}, + "outputs": [], + "source": [ + "# Bode plots\n", + "magC1.name = \"ctrl\"\n", + "cplt = ct.bode_plot(\n", + " [magP, magC1, magL1], np.logspace(0, 4), initial_phase=0,\n", + " label=['P', 'C', 'L'])\n", + "cplt.axes[0, 0].set_ylim(0.06, 1.5e1)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "d83c5d5c-238a-45a1-9a81-a3779e7f7bc3", + "metadata": {}, + "outputs": [], + "source": [ + "# Sensitivity function for closed loop system/.\n", + "magS1 = ct.feedback(1, magL1, name=\"S1\")" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "3bdcb116-02fd-46d9-ab4d-5b25511d0b21", + "metadata": {}, + "outputs": [], + "source": [ + "# Step response\n", + "magT1 = ct.feedback(magL1, name=\"T1\")\n", + "ct.step_response(magT1).plot(title=\"Step response for closed loop system\")" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "e2ddb53c-023b-466b-ac15-221c22befd6d", + "metadata": {}, + "outputs": [], + "source": [ + "# Try to improve performance by increasing DC gain\n", + "# System with gain increased\n", + "magC2 = magC1*5 \t\t\t # increased gain\n", + "magL2 = magP * magC2 \t\t\t # loop transfer function\n", + "magS2 = ct.feedback(1, magP * magC2, name=\"S2\") \t# sensitivity function\n", + "magT2 = ct.feedback(magP * magC2, 1, name=\"T2\") \t# closed loop response\n", + "\n", + "# System with gain increased even more\n", + "magC3 = magC1*20\t\t\t # increased gain\n", + "magL3 = magP*magC3\t\t\t # loop transfer function\n", + "magS3 = ct.feedback(1, magP * magC3, name=\"S3\")\t # sensitivity function\n", + "magT3 = ct.feedback(magP * magC3, 1, name=\"T3\")\t # closed loop response\n", + "\n", + "# Plot step responses for different systems\n", + "colors = ['b', 'g', '#FF7F50']\n", + "for sys in [magT1, magT2, magT3]:\n", + " ct.step_response(sys).plot(color=colors.pop())\n", + "\n", + "# Bode plot for sensitivity function\n", + "plt.figure()\n", + "cplt = ct.bode_plot([magS1, magS2, magS3], plot_phase=False)\n", + "\n", + "# Add magnitude of 1\n", + "xdata = cplt.lines[0][0][0].get_xdata()\n", + "ydata = np.ones_like(xdata)\n", + "plt.plot(xdata, ydata, color='k', linestyle='--');" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "4df561a2-16aa-41b0-9971-f8c151467730", + "metadata": {}, + "outputs": [], + "source": [ + "# Bode integral calculation\n", + "omega = np.linspace(0, 1e6, 100000)\n", + "for name, sys in zip(['C1', 'C2', 'C3'], [magS1, magS2, magS3]):\n", + " freqresp = ct.frequency_response(sys, omega)\n", + " bodeint = np.trapz(np.log(freqresp.magnitude), omega)\n", + " print(\"Bode integral for\", name, \"=\", bodeint)\n", + "\n", + "print(\"pi * sum[ Re(pk) ]\", pi * np.sum(magP.poles()[magP.poles().real > 0]))" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "M2EvTYHq8yRb", + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/examples/cds110-L8b_pvtol-complete-limits.ipynb b/examples/cds110-L8b_pvtol-complete-limits.ipynb new file mode 100644 index 000000000..0b482c865 --- /dev/null +++ b/examples/cds110-L8b_pvtol-complete-limits.ipynb @@ -0,0 +1,1032 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "659a189e-33c9-426f-b318-7cb2f433ae4a", + "metadata": { + "id": "659a189e-33c9-426f-b318-7cb2f433ae4a" + }, + "source": [ + "
\n", + "

CDS 110, Lecture 8b

\n", + "

Full Controller Stack for a Planar Vertical Take-Off and Landing (PVTOL) System

\n", + "

Richard M. Murray, Winter 2024

\n", + "
\n", + "\n", + "[Open in Google Colab](https://colab.research.google.com/drive/1XulsQqbthMkr3g58OTctIYKYpqirOgns)\n", + "\n", + "The purpose of this lecture is to introduce tools that can be used for frequency domain modeling and analysis of linear systems." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "1be7545a", + "metadata": {}, + "outputs": [], + "source": [ + "import numpy as np\n", + "import scipy as sp\n", + "import matplotlib.pyplot as plt\n", + "from math import sin, cos, pi\n", + "from scipy.optimize import NonlinearConstraint\n", + "import time\n", + "try:\n", + " import control as ct\n", + " print(\"python-control\", ct.__version__)\n", + "except ImportError:\n", + " !pip install control\n", + " import control as ct\n", + "import control.optimal as opt\n", + "import control.flatsys as fs\n", + "\n", + "# Use control parameters for plotting\n", + "plt.rcParams.update(ct.rcParams)" + ] + }, + { + "cell_type": "markdown", + "id": "c5a1858a", + "metadata": { + "id": "c5a1858a" + }, + "source": [ + "## System definition\n", + "\n", + "Consider the PVTOL system `pvtol_noisy`, defined in `pvtol.py`:\n", + "\n", + "$$\n", + " \\begin{aligned}\n", + " m \\ddot x &= F_1 \\cos\\theta - F_2 \\sin\\theta - c \\dot x + D_x, \\\\\n", + " m \\ddot y &= F_1 \\sin\\theta + F_2 \\cos\\theta - c \\dot y - m g + D_y, \\\\\n", + " J \\ddot \\theta &= r F_1,\n", + " \\end{aligned} \\qquad\n", + " \\vec Y =\n", + " \\begin{bmatrix} x \\\\ y \\\\ \\theta \\end{bmatrix} +\n", + " \\begin{bmatrix} N_x \\\\ N_y \\\\ N_z \\end{bmatrix}.\n", + "$$\n", + "\n", + "Assume that the input disturbances are modeled by independent, first\n", + "order Markov (Ornstein-Uhlenbeck) processes with\n", + "$Q_D = \\text{diag}(0.01, 0.01)$ and $\\omega_0 = 1$ and that the noise\n", + "is modeled as white noise with covariance matrix\n", + "\n", + "$$\n", + " Q_N = \\begin{bmatrix}\n", + " 2 \\times 10^{-4} & 0 & 1 \\times 10^{-5} \\\\\n", + " 0 & 2 \\times 10^{-4} & 1 \\times 10^{-5} \\\\\n", + " 1 \\times 10^{-5} & 1 \\times 10^{-5} & 1 \\times 10^{-4}\n", + " \\end{bmatrix}.\n", + "$$\n", + "\n", + "We will design a controller consisting of a trajectory generation module, a\n", + "gain-scheduled, trajectory tracking module, and a state estimation\n", + "module the moves the system from the origin to the equilibrum point\n", + "point $x_\\text{f}$, $y_\\text{f}$ = 10, 0 while satisfying the\n", + "constraint $0.5 \\sin(\\pi x / 10) - 0.1 \\leq y \\leq 1$." + ] + }, + { + "cell_type": "markdown", + "id": "D1aFeNuglL4a", + "metadata": { + "id": "D1aFeNuglL4a" + }, + "source": [ + "We start by creating the PVTOL system without noise or disturbances." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "c32ec3f8", + "metadata": {}, + "outputs": [], + "source": [ + "# STANDARD PVTOL DYNAMICS\n", + "def _pvtol_update(t, x, u, params):\n", + "\n", + " # Get the parameter values\n", + " m = params.get('m', 4.) # mass of aircraft\n", + " J = params.get('J', 0.0475) # inertia around pitch axis\n", + " r = params.get('r', 0.25) # distance to center of force\n", + " g = params.get('g', 9.8) # gravitational constant\n", + " c = params.get('c', 0.05) # damping factor (estimated)\n", + "\n", + " # Get the inputs and states\n", + " x, y, theta, xdot, ydot, thetadot = x\n", + " F1, F2 = u\n", + "\n", + " # Constrain the inputs\n", + " F2 = np.clip(F2, 0, 1.5 * m * g)\n", + " F1 = np.clip(F1, -0.1 * F2, 0.1 * F2)\n", + "\n", + " # Dynamics\n", + " xddot = (F1 * cos(theta) - F2 * sin(theta) - c * xdot) / m\n", + " yddot = (F1 * sin(theta) + F2 * cos(theta) - m * g - c * ydot) / m\n", + " thddot = (r * F1) / J\n", + "\n", + " return np.array([xdot, ydot, thetadot, xddot, yddot, thddot])\n", + "\n", + "# Define pvtol output function to only be x, y, and theta\n", + "def _pvtol_output(t, x, u, params):\n", + " return x[0:3]\n", + "\n", + "# Create nonlinear input-output system of nominal pvtol system\n", + "pvtol_nominal = ct.nlsys(\n", + " _pvtol_update, _pvtol_output, name=\"pvtol_nominal\",\n", + " states = [f'x{i}' for i in range(6)],\n", + " inputs = ['F1', 'F2'],\n", + " outputs = [f'x{i}' for i in range(3)]\n", + ")\n", + "\n", + "print(pvtol_nominal)" + ] + }, + { + "cell_type": "markdown", + "id": "TTMQAAhFldW7", + "metadata": { + "id": "TTMQAAhFldW7" + }, + "source": [ + "Next, we create a PVTOL system with noise and disturbances. This system will use the nominal PVTOL system and add disturbances as inputs to the state dynamics and noise to the system output." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "tqSvuzvOkps1", + "metadata": {}, + "outputs": [], + "source": [ + "# Add wind and noise to system dynamics\n", + "def _noisy_update(t, x, u, params):\n", + " # Get the inputs\n", + " F1, F2, Dx, Dy = u[:4]\n", + " if u.shape[0] > 4:\n", + " Nx, Ny, Nth = u[4:]\n", + " else:\n", + " Nx, Ny, Nth = 0, 0, 0\n", + "\n", + " # Get the system response from the original dynamics\n", + " xdot, ydot, thetadot, xddot, yddot, thddot = \\\n", + " _pvtol_update(t, x, [F1, F2], params)\n", + "\n", + " # Get the parameter values we need\n", + " m = params.get('m', 4.) # mass of aircraft\n", + " J = params.get('J', 0.0475) # inertia around pitch axis\n", + "\n", + " # Now add the disturbances\n", + " xddot += Dx / m\n", + " yddot += Dy / m\n", + "\n", + " return np.array([xdot, ydot, thetadot, xddot, yddot, thddot])\n", + "\n", + "# Define pvtol_noisy output function to only be x, y, and theta\n", + "def _noisy_output(t, x, u, params):\n", + " F1, F2, Dx, Dy, Nx, Ny, Nth = u\n", + " return x[0:3] + np.array([Nx, Ny, Nth])\n", + "\n", + "# CREATE NONLINEAR INPUT-OUTPUT SYSTEM\n", + "pvtol_noisy = ct.nlsys(\n", + " _noisy_update, _noisy_output, name=\"pvtol_noisy\",\n", + " states = [f'x{i}' for i in range(6)],\n", + " inputs = ['F1', 'F2'] + ['Dx', 'Dy'] + ['Nx', 'Ny', 'Nth'],\n", + " outputs = ['x', 'y', 'theta'],\n", + " params = {\n", + " 'm': 4., # mass of aircraft\n", + " 'J': 0.0475, # inertia around pitch axis\n", + " 'r': 0.25, # distance to center of force\n", + " 'g': 9.8, # gravitational constant\n", + " 'c': 0.05, # damping factor (estimated)\n", + " }\n", + ")\n", + "\n", + "print(pvtol_noisy)" + ] + }, + { + "cell_type": "markdown", + "id": "057cba8f-79bd-4a45-a184-2424c569785d", + "metadata": { + "id": "057cba8f-79bd-4a45-a184-2424c569785d" + }, + "source": [ + "Note that the outputs of `pvtol_noisy` are not the full set of states, but rather the states we can measure: $x$, $y$, and $\\theta$." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "7ce469b3-faa0-4bac-b9d4-02e4dae7a2da", + "metadata": {}, + "outputs": [], + "source": [ + "# Utility function tlot the trajectory in xy coordinates\n", + "def plot_results(t, x, u, fig=None):\n", + " # Set the size of the figure\n", + " if fig is None:\n", + " fig = plt.figure(figsize=(10, 6))\n", + "\n", + " # Top plot: xy trajectory\n", + " plt.subplot(2, 1, 1)\n", + " plt.plot(x[0], x[1])\n", + " plt.xlabel('x [m]')\n", + " plt.ylabel('y [m]')\n", + " plt.axis('equal')\n", + "\n", + " # Time traces of the state and input\n", + " plt.subplot(2, 4, 5)\n", + " plt.plot(t, x[1])\n", + " plt.xlabel('Time t [sec]')\n", + " plt.ylabel('y [m]')\n", + "\n", + " plt.subplot(2, 4, 6)\n", + " plt.plot(t, x[2])\n", + " plt.xlabel('Time t [sec]')\n", + " plt.ylabel('theta [rad]')\n", + "\n", + " plt.subplot(2, 4, 7)\n", + " plt.plot(t, u[0])\n", + " plt.xlabel('Time t [sec]')\n", + " plt.ylabel('$F_1$ [N]')\n", + "\n", + " plt.subplot(2, 4, 8)\n", + " plt.plot(t, u[1])\n", + " plt.xlabel('Time t [sec]')\n", + " plt.ylabel('$F_2$ [N]')\n", + " plt.tight_layout()\n", + "\n", + " return fig\n" + ] + }, + { + "cell_type": "markdown", + "id": "081764e0", + "metadata": { + "id": "081764e0" + }, + "source": [ + "## Estimator\n", + "\n", + "We start by designing an optimal estimator for the system. We choose the noise intensities\n", + "based on knowledge of the modeling errors, disturbances, and sensor characteristics:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "778fb908", + "metadata": {}, + "outputs": [], + "source": [ + "# Disturbance and noise intensities\n", + "Qv = np.diag([1e-2, 1e-2])\n", + "Qw = np.array([[2e-4, 0, 1e-5], [0, 2e-4, 1e-5], [1e-5, 1e-5, 1e-4]])\n", + "Qwinv = np.linalg.inv(Qw)\n", + "\n", + "# Initial state covariance\n", + "P0 = np.eye(pvtol_noisy.nstates)" + ] + }, + { + "cell_type": "markdown", + "id": "1Q55PHN1omJs", + "metadata": { + "id": "1Q55PHN1omJs" + }, + "source": [ + "We will use a linear quadratic estimator (Kalman filter) to design an optimal estimator for the system. Recall that the `ct.lqe` function takes in a linear system as input, so we first linear our `pvtol_noisy` system around its equilibrium point." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "WADb1-VcuR5t", + "metadata": {}, + "outputs": [], + "source": [ + "# Find the equilibrium point corresponding to the origin\n", + "xe, ue = ct.find_eqpt(\n", + " sys = pvtol_noisy,\n", + " x0 = np.zeros(pvtol_noisy.nstates),\n", + " u0 = np.zeros(pvtol_noisy.ninputs),\n", + " y0 = [0, 0, 0],\n", + " iu=range(2, pvtol_noisy.ninputs),\n", + " iy=[0, 1]\n", + ")\n", + "print(f\"{xe=}\")\n", + "print(f\"{ue=}\")\n", + "\n", + "# Linearize system for Kalman filter\n", + "pvtol_noisy_lin = pvtol_noisy.linearize(xe, ue)\n", + "\n", + "# Extract the linearization for use in LQR design\n", + "A, B, C = pvtol_noisy_lin.A, pvtol_noisy_lin.B, pvtol_noisy_lin.C" + ] + }, + { + "cell_type": "markdown", + "id": "6E9s147Cpppr", + "metadata": { + "id": "6E9s147Cpppr" + }, + "source": [ + "We want to define an estimator that takes in the measured states $x$, $y$, and $\\theta$, as well as applied inputs $F_1$ and $F_2$. As the estimator doesn't have any measurement of the noise/disturbances applied to the system, we will design our controller with only these inputs." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "nvZHm0Ooqkj_", + "metadata": {}, + "outputs": [], + "source": [ + "# use ct.lqe to create an L matrix, using only measured inputs F1 and F2\n", + "L, Pf, _ = ct.lqe(A, B[:,:2], C, Qv, Qw)" + ] + }, + { + "cell_type": "markdown", + "id": "KXVetnCUrHvs", + "metadata": { + "id": "KXVetnCUrHvs" + }, + "source": [ + "We now create our estimator." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "M77vo5PgrIEv", + "metadata": {}, + "outputs": [], + "source": [ + "# Create standard (optimal) estimator update function\n", + "def estimator_update(t, xhat, u, params):\n", + "\n", + " # Extract the inputs to the estimator\n", + " y = u[0:3] # just grab the first three outputs\n", + " u_cmd = u[3:5] # get the inputs that were applied as well\n", + "\n", + " # Update the state estimate using PVTOL (non-noisy) dynamics\n", + " return _pvtol_update(t, xhat, u_cmd, params) - L @ (C @ xhat - y)\n", + "\n", + "# Create estimator\n", + "estimator = ct.nlsys(\n", + " estimator_update, None,\n", + " name = 'Estimator',\n", + " states=pvtol_noisy.nstates,\n", + " inputs= pvtol_noisy.output_labels \\\n", + " + pvtol_noisy.input_labels[0:2],\n", + " outputs=[f'xh{i}' for i in range(pvtol_noisy.nstates)],\n", + ")" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "1JOPx1TXrnr-", + "metadata": {}, + "outputs": [], + "source": [ + "print(estimator)" + ] + }, + { + "cell_type": "markdown", + "id": "46d8463d", + "metadata": { + "id": "46d8463d" + }, + "source": [ + "## Gain scheduled controller\n", + "\n", + "We next design our (gain scheduled) controller for the system. Here, as in the case of the estimator, we will create the controller using the nominal PVTOL system, so that the applied inputs to the system are only $F_1$ and $F_2$. If we were to make a controller using the noisy PVTOL system, then the inputs applied via control action would include noise and disturbances, which is incorrect." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "2e5fbef3", + "metadata": {}, + "outputs": [], + "source": [ + "# Define the weights for the LQR problem\n", + "Qx = np.diag([100, 10, (180/np.pi) / 5, 0, 0, 0])\n", + "# Qx = np.diag([10, 100, (180/np.pi) / 5, 0, 0, 0]) # Try this out to see what changes\n", + "Qu = np.diag([10, 1])" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "e5cc3cc0", + "metadata": {}, + "outputs": [], + "source": [ + "# Construct the array of gains and the gain scheduled controller\n", + "import itertools\n", + "import math\n", + "\n", + "# Set up points around which to linearize (control-0.9.3: must be 2D or greater)\n", + "angles = np.linspace(-math.pi/3, math.pi/3, 10)\n", + "speeds = np.linspace(-10, 10, 3)\n", + "points = list(itertools.product(angles, speeds))\n", + "\n", + "# Compute the gains at each design point of angles and speeds\n", + "gains = []\n", + "\n", + "# Iterate through points\n", + "for point in points:\n", + "\n", + " # Compute the state that we want to linearize about\n", + " xgs = xe.copy()\n", + " xgs[2], xgs[4] = point[0], point[1]\n", + "\n", + " # Linearize the system and compute the LQR gains\n", + " linsys = pvtol_noisy.linearize(xgs, ue)\n", + " A = linsys.A\n", + " B = linsys.B[:,:2]\n", + " K, X, E = ct.lqr(A, B, Qx, Qu)\n", + " gains.append(K)\n", + "\n", + "# Construct the controller\n", + "gs_ctrl, gs_clsys = ct.create_statefbk_iosystem(\n", + " sys = pvtol_nominal,\n", + " gain = (gains, points),\n", + " gainsched_indices=['xh2', 'xh4'],\n", + " estimator=estimator\n", + ")\n", + "\n", + "print(gs_ctrl)" + ] + }, + { + "cell_type": "markdown", + "id": "ecd28a73", + "metadata": { + "id": "ecd28a73" + }, + "source": [ + "## Trajectory generation\n", + "\n", + "Finally, we need to design the trajectory that we want to follow. We consider a situation with state constraints that represent the specific experimental conditions for this system (at Caltech):\n", + "* `ceiling`: The system has limited vertical travel, so we constrain the vertical position to lie between $-0.5$ and $2$ meters.\n", + "* `nicolas`: When testing, we placed a person in between the initial and final position, and we need to avoid hitting him as we move from start to finish.\n", + "\n", + "The code below defines the initial conditions, final conditions, and constraints." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "5eb12bfa", + "metadata": {}, + "outputs": [], + "source": [ + "# Define the initial and final conditions\n", + "x_delta = np.array([10, 0, 0, 0, 0, 0])\n", + "x0, u0 = ct.find_eqpt(\n", + " sys = pvtol_nominal,\n", + " x0 = np.zeros(6),\n", + " u0 = np.zeros(2),\n", + " y0 = np.zeros(3),\n", + " iy=[0, 1]\n", + ")\n", + "xf, uf = ct.find_eqpt(\n", + " sys = pvtol_nominal,\n", + " x0 = x0 + x_delta,\n", + " u0 = u0,\n", + " y0 = (x0 + x_delta)[:3],\n", + " iy=[0, 1]\n", + ")\n", + "\n", + "# Define the time horizon for the manuever\n", + "Tf = 5\n", + "timepts = np.linspace(0, Tf, 100, endpoint=False)\n", + "\n", + "# Create a constraint corresponding to the obstacle\n", + "ceiling = (NonlinearConstraint, lambda x, u: x[1], [-0.5], [2])\n", + "nicolas = (NonlinearConstraint,\n", + " lambda x, u: x[1] - (0.5 * sin(pi * x[0] / 10) - 0.1), [0], [1])\n", + "\n", + "# # Reset the nonlinear constraint to give some extra room\n", + "# nicolas = (NonlinearConstraint,\n", + "# lambda x, u: x[1] - (0.8 * sin(pi * x[0] / 10) - 0.1), [0], [1])" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "610aa247", + "metadata": {}, + "outputs": [], + "source": [ + "# Re-define the time horizon for the manuever\n", + "Tf = 5\n", + "timepts = np.linspace(0, Tf, 20, endpoint=False)\n", + "\n", + "# We provide a tent shape as an intial guess\n", + "xm = (x0 + xf) / 2 + np.array([0, 0.5, 0, 0, 0, 0])\n", + "tm = int(len(timepts)/2)\n", + "# straight line from start to midpoint to end with nominal input\n", + "tent = (\n", + " np.hstack([\n", + " np.array([x0 + (xm - x0) * t/(Tf/2) for t in timepts[0:tm]]).transpose(),\n", + " np.array([xm + (xf - xm) * t/(Tf/2) for t in timepts[0:tm]]).transpose()\n", + " ]),\n", + " u0\n", + ")\n", + "\n", + "# terminal constraint\n", + "term_constraints = opt.state_range_constraint(pvtol_nominal, xf, xf)\n", + "\n", + "# trajectory cost\n", + "traj_cost = opt.quadratic_cost(pvtol_nominal, None, Qu, x0=xf, u0=uf)\n", + "\n", + "# find optimal trajectory\n", + "start_time = time.process_time()\n", + "traj = opt.solve_ocp(\n", + " sys = pvtol_nominal,\n", + " timepts = timepts,\n", + " initial_guess=tent,\n", + " X0=x0,\n", + " cost = traj_cost,\n", + " trajectory_constraints=[ceiling, nicolas],\n", + " terminal_constraints=term_constraints,\n", + ")\n", + "print(\"* Total time = %5g seconds\\n\" % (time.process_time() - start_time))\n", + "\n", + "# Create the desired trajectory\n", + "xd, ud = traj.states, traj.inputs" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "e59ddc29", + "metadata": {}, + "outputs": [], + "source": [ + "# Extend the trajectory to hold the final position for Tf seconds\n", + "holdpts = np.arange(Tf, Tf + Tf, timepts[1]-timepts[0])\n", + "xd = np.hstack([xd, np.outer(xf, np.ones_like(holdpts))])\n", + "ud = np.hstack([ud, np.outer(uf, np.ones_like(holdpts))])\n", + "timepts = np.hstack([timepts, holdpts])\n", + "\n", + "# Plot the desired trajectory\n", + "plot_results(timepts, xd, ud)\n", + "plt.suptitle('Desired Trajectory')\n", + "\n", + "# Add the constraints to the plot\n", + "plt.subplot(2, 1, 1)\n", + "\n", + "plt.plot([0, 10], [2, 2], 'r--')\n", + "plt.text(5, 1.8, 'Ceiling', ha='center')\n", + "\n", + "x_nic = np.linspace(0, 10, 50)\n", + "y_nic = 0.5 * np.sin(pi * x_nic / 10) - 0.1\n", + "plt.plot(x_nic, y_nic, 'r--')\n", + "plt.text(5, 0, 'Nicolas Petit', ha='center')\n", + "plt.tight_layout()" + ] + }, + { + "cell_type": "markdown", + "id": "affe55fa", + "metadata": { + "id": "affe55fa" + }, + "source": [ + "## Final Control System Implementation\n", + "\n", + "We now put together the final control system and simulate it. If you have named your inputs and outputs to each of the subsystems properly, the code below should connect everything up correctly. If you get errors about inputs or outputs that are not connected to anything, check the names of your inputs and outputs in the various\n", + "systems above and make sure everything lines up as it should." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "50dff557", + "metadata": {}, + "outputs": [], + "source": [ + "# Create the interconnected system\n", + "clsys = ct.interconnect(\n", + " [pvtol_noisy, gs_ctrl, estimator],\n", + " inputs=gs_clsys.input_labels[:8] + pvtol_noisy.input_labels[2:],\n", + " outputs=pvtol_noisy.output_labels + pvtol_noisy.input_labels[:2]\n", + ")\n", + "print(clsys)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "0f24e6f5", + "metadata": {}, + "outputs": [], + "source": [ + "# Generate disturbance and noise vectors\n", + "V = ct.white_noise(timepts, Qv)\n", + "W = ct.white_noise(timepts, Qw)\n", + "for i in range(V.shape[0]):\n", + " plt.subplot(2, 3, i+1)\n", + " plt.plot(timepts, V[i])\n", + " plt.ylabel(f'V[{i}]')\n", + "\n", + "for i in range(W.shape[0]):\n", + " plt.subplot(2, 3, i+4)\n", + " plt.plot(timepts, W[i])\n", + " plt.ylabel(f'W[{i}]')\n", + " plt.xlabel('Time $t$ [s]')\n", + "\n", + "plt.tight_layout()" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "f63091cf", + "metadata": {}, + "outputs": [], + "source": [ + "# Simulate the open loop system and plot the results (+ state trajectory)\n", + "resp = ct.input_output_response(\n", + " sys = clsys,\n", + " T = timepts,\n", + " U = [xd, ud, V, W],\n", + " X0 = np.zeros(12))\n", + "\n", + "plot_results(resp.time, resp.outputs[0:3], resp.outputs[3:5])\n", + "\n", + "# Add the constraints to the plot\n", + "plt.subplot(2, 1, 1)\n", + "plt.plot([0, 10], [1, 1], 'r--')\n", + "x_nic = np.linspace(0, 10, 50)\n", + "y_nic = 0.5 * np.sin(pi * x_nic / 10) - 0.1\n", + "plt.plot(x_nic, y_nic, 'r--')\n", + "plt.text(5, 0, 'Nicolas Petit', ha='center')\n", + "plt.suptitle(\"Measured Trajectory\")\n", + "plt.tight_layout()" + ] + }, + { + "cell_type": "markdown", + "id": "89221230", + "metadata": { + "id": "89221230" + }, + "source": [ + "We see that with the addition of disturbances and noise, we sometimes violate the constraint 'nicolas' (if your plot doesn't show an intersection with the bottom dashed curve, try regenerating the noise and running the simulation again). This can be fixed by establishing a more conservative constraint (see commented out constraint in code block above)." + ] + }, + { + "cell_type": "markdown", + "id": "3f2e9776-0ba9-4295-9473-a17cb4854836", + "metadata": { + "id": "3f2e9776-0ba9-4295-9473-a17cb4854836" + }, + "source": [ + "## Small signal analysis\n", + "\n", + "We next look at the properties of the system using the small signal (linearized) dynamics. This analysis is useful to check the robustness and performance of the controller around trajectories and equilibrium points.\n", + "\n", + "We will carry out the analysis around the initial condition." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "JgZyPyMkcoOl", + "metadata": {}, + "outputs": [], + "source": [ + "## Small signal analysis\n", + "X0 = np.hstack([x0, x0]) # system state, estim state\n", + "U0 = np.hstack([x0, u0, np.zeros(5)]) # xd, ud, dist, noise\n", + "G = clsys.linearize(X0, U0)\n", + "print(clsys)\n", + "\n", + "# Get input/output dictionaries: inp['sig'] = index for 'sig'\n", + "inp = clsys.input_index\n", + "out = clsys.output_index\n", + "\n", + "fig, axs = plt.subplots(2, 3, figsize=[9, 6])\n", + "omega = np.logspace(-2, 2)\n", + "\n", + "# Complementary sensitivity\n", + "G_x_xd = ct.tf(G[out['x'], inp['xd[0]']])\n", + "G_y_yd = ct.tf(G[out['y'], inp['xd[1]']])\n", + "ct.bode_plot(\n", + " [G_x_xd, G_y_yd], omega,\n", + " plot_phase=False, ax=np.array([[axs[0, 0]]]))\n", + "axs[0, 0].legend(['F T_x', 'F T_y'])\n", + "axs[0, 0].loglog([omega[0], omega[-1]], [1, 1], 'k', linewidth=0.5)\n", + "axs[0, 0].set_title(\"From xd, yd\", fontsize=9)\n", + "axs[0, 0].set_ylabel(\"To x, y\")\n", + "axs[0, 0].set_xlabel(\"\")\n", + "\n", + "# Load (or input) sensitivity\n", + "G_x_dx = ct.tf(G[out['x'], inp['Dx']])\n", + "G_y_dy = ct.tf(G[out['y'], inp['Dy']])\n", + "ct.bode_plot(\n", + " [G_x_dx, G_y_dy], omega,\n", + " plot_phase=False, ax=np.array([[axs[0, 1]]]))\n", + "axs[0, 1].legend(['PS_x', 'PS_y'])\n", + "axs[0, 1].loglog([omega[0], omega[-1]], [1, 1], 'k', linewidth=0.5)\n", + "axs[0, 1].set_title(\"From Dx, Dy\", fontsize=9)\n", + "axs[0, 1].set_xlabel(\"\")\n", + "axs[0, 1].set_ylabel(\"\")\n", + "\n", + "# Sensitivity\n", + "G_x_Nx = ct.tf(G[out['x'], inp['Nx']])\n", + "G_y_Ny = ct.tf(G[out['y'], inp['Ny']])\n", + "ct.bode_plot(\n", + " [G_x_Nx, G_y_Ny], omega,\n", + " plot_phase=False, ax=np.array([[axs[0, 2]]]))\n", + "axs[0, 2].legend(['S_x', 'S_y'])\n", + "axs[0, 2].set_title(\"From Nx, Ny\", fontsize=9)\n", + "axs[0, 2].loglog([omega[0], omega[-1]], [1, 1], 'k', linewidth=0.5)\n", + "axs[0, 2].set_xlabel(\"\")\n", + "axs[0, 2].set_ylabel(\"\")\n", + "\n", + "# Noise (or output) sensitivity\n", + "G_F1_xd = ct.tf(G[out['F1'], inp['xd[0]']])\n", + "G_F2_yd = ct.tf(G[out['F2'], inp['xd[1]']])\n", + "ct.bode_plot(\n", + " [G_F1_xd, G_F2_yd], omega,\n", + " plot_phase=False, ax=np.array([[axs[1, 0]]]))\n", + "axs[1, 0].legend(['FCS_x', 'FCS_y'])\n", + "axs[1, 0].loglog([omega[0], omega[-1]], [1, 1], 'k', linewidth=0.5)\n", + "axs[1, 0].set_ylabel(\"To F1, F2\")\n", + "\n", + "G_F1_dx = ct.tf(G[out['F1'], inp['Dx']])\n", + "G_F2_dy = ct.tf(G[out['F2'], inp['Dy']])\n", + "ct.bode_plot(\n", + " [G_F1_dx, G_F2_dy], omega,\n", + " plot_phase=False, ax=np.array([[axs[1, 1]]]))\n", + "axs[1, 1].legend(['~T_x', '~T_y'])\n", + "axs[1, 1].loglog([omega[0], omega[-1]], [1, 1], 'k', linewidth=0.5)\n", + "axs[1, 1].set_ylabel(\"\")\n", + "\n", + "# Sensitivity\n", + "G_F1_Nx = ct.tf(G[out['F1'], inp['Nx']])\n", + "G_F1_Ny = ct.tf(G[out['F1'], inp['Ny']])\n", + "ct.bode_plot(\n", + " [G_F1_Nx, G_F1_Ny], omega,\n", + " plot_phase=False, ax=np.array([[axs[1, 2]]]))\n", + "axs[1, 2].legend(['C S_x', 'C S_y'])\n", + "axs[1, 2].loglog([omega[0], omega[-1]], [1, 1], 'k', linewidth=0.5)\n", + "axs[1, 2].set_ylabel(\"\")\n", + "\n", + "plt.suptitle(\"Gang of Six for PVTOL\")\n", + "plt.tight_layout()" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "xfi1mXJTe3Gm", + "metadata": {}, + "outputs": [], + "source": [ + "# Solve for the loop transfer function horizontal direction\n", + "# S = 1 / (1 + L) => S + SL = 1 => L = (1 - S)/S\n", + "Lx = (1 - G_x_Nx) / G_x_Nx; Lx.name = 'Lx'\n", + "Ly = (1 - G_y_Ny) / G_y_Ny; Ly.name = 'Ly'\n", + "\n", + "# Create Nyquist plot\n", + "ct.nyquist_plot([Lx, Ly], max_curve_magnitude=5, max_curve_offset=0.2);" + ] + }, + { + "cell_type": "markdown", + "id": "L7L6UZTn_Qtn", + "metadata": { + "id": "L7L6UZTn_Qtn" + }, + "source": [ + "### Gain Margins of $L_x$, $L_y$\n", + "\n", + "We can zoom in on the plot to see the gain, phase, and stability margins:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "3FX7YXrR2cuQ", + "metadata": {}, + "outputs": [], + "source": [ + "cplt = ct.nyquist_plot([Lx, Ly])\n", + "lower_upper_bound = 1.1\n", + "cplt.axes[0, 0].set_xlim([-lower_upper_bound, lower_upper_bound])\n", + "cplt.axes[0, 0].set_ylim([-lower_upper_bound, lower_upper_bound])\n", + "cplt.axes[0, 0].set_aspect('equal')\n", + "\n", + "# Gain margin for Lx\n", + "neg1overgm_x = -0.67 # vary this manually to find intersection with curve\n", + "color = cplt.lines[0][0].get_color()\n", + "plt.plot(neg1overgm_x, 0, color=color, marker='o', fillstyle='none')\n", + "gm_x = -1/neg1overgm_x\n", + "\n", + "# Gain margin for Ly\n", + "neg1overgm_y = -0.32 # vary this manually to find intersection with curve\n", + "color = cplt.lines[1][0].get_color()\n", + "plt.plot(neg1overgm_y, 0, color=color, marker='o', fillstyle='none')\n", + "gm_y = -1/neg1overgm_y\n", + "\n", + "print('Margins obtained visually:')\n", + "print('Gain margin of Lx: '+str(gm_x))\n", + "print('Gain margin of Ly: '+str(gm_y))\n", + "print('\\n')\n", + "\n", + "# get gain margin computationally\n", + "gm_xc, pm_xc, wpc_xc, wgc_xc = ct.margin(Lx)\n", + "gm_yc, pm_yc, wpc_yc, wgc_yc = ct.margin(Ly)\n", + "\n", + "print('Margins obtained computationally:')\n", + "print('Gain margin of Lx: '+str(gm_xc))\n", + "print('Gain margin of Ly: '+str(gm_yc))\n", + "\n", + "print('\\n')" + ] + }, + { + "cell_type": "markdown", + "id": "VnrVNvhz_Zi2", + "metadata": { + "id": "VnrVNvhz_Zi2" + }, + "source": [ + "### Phase Margins of $L_x$, $L_y$" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "zKb_o9ZN_ffF", + "metadata": {}, + "outputs": [], + "source": [ + "# add customizations to Nyquist plot\n", + "cplt = ct.nyquist_plot(\n", + " [Lx, Ly], max_curve_magnitude=5, max_curve_offset=0.2,\n", + " unit_circle=True)\n", + "lower_upper_bound = 2\n", + "cplt.axes[0, 0].set_xlim([-lower_upper_bound, lower_upper_bound])\n", + "cplt.axes[0, 0].set_ylim([-lower_upper_bound, lower_upper_bound])\n", + "cplt.axes[0, 0].set_aspect('equal')\n", + "\n", + "# Phase margin of Lx:\n", + "th_pm_x = 0.14*np.pi\n", + "th_plt_x = np.pi + th_pm_x\n", + "color = cplt.lines[0][0].get_color()\n", + "plt.plot(np.cos(th_plt_x), np.sin(th_plt_x), color=color, marker='o')\n", + "\n", + "# Phase margin of Ly\n", + "th_pm_y = 0.19*np.pi\n", + "th_plt_y = np.pi + th_pm_y\n", + "color = cplt.lines[1][0].get_color()\n", + "plt.plot(np.cos(th_plt_y), np.sin(th_plt_y), color=color, marker='o')\n", + "\n", + "print('Margins obtained visually:')\n", + "print('Phase margin: '+str(float(th_pm_x)))\n", + "print('Phase margin: '+str(float(th_pm_y)))\n", + "print('\\n')\n", + "\n", + "# get margin computationally\n", + "gm_xc, pm_xc, wpc_xc, wgc_xc = ct.margin(Lx)\n", + "gm_yc, pm_yc, wpc_yc, wgc_yc = ct.margin(Ly)\n", + "\n", + "print('Margins obtained computationally:')\n", + "print('Phase margin of Lx: '+str(np.deg2rad(pm_xc)))\n", + "print('Phase margin of Ly: '+str(np.deg2rad(pm_yc)))\n", + "\n", + "print('\\n')" + ] + }, + { + "cell_type": "markdown", + "id": "dF0BIq5BDXII", + "metadata": { + "id": "dF0BIq5BDXII" + }, + "source": [ + "### Stability Margins of $L_x$, $L_y$\n" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "XQPB_h6Y1cAW", + "metadata": {}, + "outputs": [], + "source": [ + "# add customizations to Nyquist plot\n", + "cplt = ct.nyquist_plot([Lx, Ly], max_curve_magnitude=5, max_curve_offset=0.2)\n", + "lower_upper_bound = 2\n", + "cplt.axes[0, 0].set_xlim([-lower_upper_bound, lower_upper_bound])\n", + "cplt.axes[0, 0].set_ylim([-lower_upper_bound, lower_upper_bound])\n", + "cplt.axes[0, 0].set_aspect('equal')\n", + "\n", + "# Stability margin:\n", + "sm_x = 0.3 # vary this manually to find min which intersects\n", + "color = cplt.lines[0][0].get_color()\n", + "sm_circle = plt.Circle((-1, 0), sm_x, color=color, fill=False, ls=':')\n", + "cplt.axes[0, 0].add_patch(sm_circle)\n", + "\n", + "sm_y = 0.5 # vary this manually to find min which intersects\n", + "color = cplt.lines[1][0].get_color()\n", + "sm_circle = plt.Circle((-1, 0), sm_y, color=color, fill=False, ls=':')\n", + "cplt.axes[0, 0].add_patch(sm_circle)\n", + "\n", + "print('Margins obtained visually:')\n", + "print('* Stability margin of Lx: '+str(sm_x))\n", + "print('* Stability margin of Ly: '+str(sm_y))\n", + "\n", + "# Compute the stability margin computationally\n", + "print('') # blank line\n", + "print('Margins obtained computationally:')\n", + "resp = ct.frequency_response(1 + Lx)\n", + "sm = np.min(resp.magnitude)\n", + "wsm = resp.omega[np.argmin(resp.magnitude)]\n", + "\n", + "print(f\"* Stability margin of Lx = {sm:2.2g} (at {wsm:.2g} rad/s)\")\n", + "resp = ct.frequency_response(1 + Ly)\n", + "sm = np.min(resp.magnitude)\n", + "wsm = resp.omega[np.argmin(resp.magnitude)]\n", + "print(f\"* Stability margin of Ly = {sm:2.2g} (at {wsm:.2g} rad/s)\")\n", + "print('')" + ] + }, + { + "cell_type": "markdown", + "id": "boAjWk56GXYZ", + "metadata": { + "id": "boAjWk56GXYZ" + }, + "source": [ + "We see that the frequencies at which the stability margins are found corresponds to the peak of the magnitude of the sensitivity functions for $L_x$ and $L_y$." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "JkbMn8pif7Ub", + "metadata": {}, + "outputs": [], + "source": [ + "# Confirm stability using Nyquist criterion\n", + "nyqresp_x = ct.nyquist_response(Lx)\n", + "nyqresp_y = ct.nyquist_response(Ly)\n", + "\n", + "print(\"Nx =\", nyqresp_x.count, \"; Px =\", np.sum(np.real(Lx.poles()) > 0))\n", + "print(\"Ny =\", nyqresp_y.count, \"; Py =\", np.sum(np.real(Ly.poles()) > 0))" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "4d038db9-f671-4f0f-82db-51096e8272b7", + "metadata": {}, + "outputs": [], + "source": [ + "# Take a look at the locations of the poles\n", + "np.real(Ly.poles())" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "9dd57510-4b03-4c0a-90ae-35011f90c41b", + "metadata": {}, + "outputs": [], + "source": [ + "# See what happened in the contour\n", + "plt.plot(np.real(nyqresp_y.contour), np.imag(nyqresp_y.contour))\n", + "plt.axis([-1e-4, 4e-4, 0, 4e-4])\n", + "plt.title(\"Zoom on D-contour\");" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "e7b9a2f9-f40f-4090-ae69-6bf53fea54a9", + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/examples/cds110-L9_servomech-pid.ipynb b/examples/cds110-L9_servomech-pid.ipynb new file mode 100644 index 000000000..3c8f5df5a --- /dev/null +++ b/examples/cds110-L9_servomech-pid.ipynb @@ -0,0 +1,635 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": { + "id": "FAZsjB3IN9JN" + }, + "source": [ + "
\n", + "

CDS 110, Lecture 9

\n", + "

PID Control of a Servomechanism

\n", + "

Richard M. Murray, Winter 2024

\n", + "
\n", + "\n", + "[Open in Google Colab](https://colab.research.google.com/drive/1BP0DFHh94tSxAyQetvOEbBEHKrSoVGQW)\n", + "\n", + "In this lecture we will use a variety of methods to design proportional (P), proportional-integral (PI), and proportional-integral-derivative (PID) controllers for a cart pendulum system." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "from math import pi\n", + "try:\n", + " import control as ct\n", + " print(\"python-control\", ct.__version__)\n", + "except ImportError:\n", + " !pip install control\n", + " import control as ct" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "T0rjwp1mONm1" + }, + "source": [ + "## System dynamics\n", + "\n", + "Consider a simple mechanism consisting of a spring loaded arm that is driven by a motor, as shown below:\n", + "\n", + "
\"servomech-diagram\"
\n", + "\n", + "The motor applies a torque that twists the arm against a linear spring and moves the end of the arm across a rotating platter. The input to the system is the motor torque $\\tau_\\text{m}$. The force exerted by the spring is a nonlinear function of the head position due to the way it is attached.\n", + "\n", + "The equations of motion for the system are given by\n", + "\n", + "$$\n", + "J \\ddot \\theta = -b \\dot\\theta - k r\\sin\\theta + \\tau_\\text{m},\n", + "$$\n", + "\n", + "which can be written in state space form as\n", + "\n", + "$$\n", + "\\frac{d}{dt} \\begin{bmatrix} \\theta \\\\ \\theta \\end{bmatrix} =\n", + " \\begin{bmatrix} \\dot\\theta \\\\ -k r \\sin\\theta / J - b\\dot\\theta / J \\end{bmatrix}\n", + " + \\begin{bmatrix} 0 \\\\ 1/J \\end{bmatrix} \\tau_\\text{m}.\n", + "$$\n", + "\n", + "The system parameters are given by\n", + "\n", + "$$\n", + "k = 1,\\quad J = 100,\\quad b = 10,\n", + "\\quad r = 1,\\quad l = 2,\\quad \\epsilon = 0.01.\n", + "$$\n", + "\n", + "and we assume that time is measured in milliseconds (ms) and distance in centimeters (cm). (The constants here are made up and don't necessarily reflect a real disk drive, though the units and time constants are motivated by computer disk drives.)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Parameter values\n", + "servomech_params = {\n", + " 'J': 100, # Moment of inertia of the motor\n", + " 'b': 10, # Angular damping of the arm\n", + " 'k': 1, # Spring constant\n", + " 'r': 1, # Location of spring contact on arm\n", + " 'l': 2, # Distance to the read head\n", + " 'eps': 0.01, # Magnitude of velocity-dependent perturbation\n", + "}\n", + "\n", + "# State derivative\n", + "def servomech_update(t, x, u, params):\n", + " # Extract the configuration and velocity variables from the state vector\n", + " theta = x[0] # Angular position of the disk drive arm\n", + " thetadot = x[1] # Angular velocity of the disk drive arm\n", + " tau = u[0] # Torque applied at the base of the arm\n", + "\n", + " # Get the parameter values\n", + " J, b, k, r = map(params.get, ['J', 'b', 'k', 'r'])\n", + "\n", + " # Compute the angular acceleration\n", + " dthetadot = 1/J * (\n", + " -b * thetadot - k * r * np.sin(theta) + tau)\n", + "\n", + " # Return the state update law\n", + " return np.array([thetadot, dthetadot])\n", + "\n", + "# System output (full state)\n", + "def servomech_output(t, x, u, params):\n", + " l = params['l']\n", + " return l * x[0]\n", + "\n", + "# System dynamics\n", + "servomech = ct.nlsys(\n", + " servomech_update, servomech_output, name='servomech',\n", + " params=servomech_params,\n", + " states=['theta_', 'thdot_'],\n", + " outputs=['y'], inputs=['tau'])" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "n4bQu0e2_aBT" + }, + "source": [ + "In addition to the system dynamics, we assume there are actuator dynamics that limit the performance of the system. We take these as first order dynamics with saturation:\n", + "\n", + "$$\n", + "\\tau = \\text{sat} \\left(\\frac{\\alpha}{s + \\alpha} u\\right)\n", + "$$" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "actuator_params = {\n", + " 'umax': 5, # Saturation limits\n", + " 'alpha': 10, # Actuator time constant\n", + "}\n", + "\n", + "def actuator_update(t, x, u, params):\n", + " # Get parameter values\n", + " alpha = params['alpha']\n", + " umax = params['umax']\n", + "\n", + " # Clip the input\n", + " u_clip = np.clip(u, -umax, umax)\n", + "\n", + " # Actuator dynamics\n", + " return -alpha * x + alpha * u_clip\n", + "\n", + "actuator = ct.nlsys(\n", + " actuator_update, None, params=actuator_params,\n", + " inputs='u', outputs='tau', states=1, name='actuator')\n", + "\n", + "system = ct.series(actuator, servomech)\n", + "system.name = 'system' # missing feature\n", + "print(system)" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "8HYyndF_saE0" + }, + "source": [ + "### Linearization\n", + "\n", + "To study the open loop dynamics of the system, we compute the linearization of the dynamics about the equilibrium point corresponding to $\\theta_\\text{e} = 15^\\circ$." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Convert the equilibrium angle to radians\n", + "theta_e = (15 / 180) * np.pi\n", + "\n", + "# Compute the input required to hold this position\n", + "u_e = servomech.params['k'] * servomech.params['r'] * np.sin(theta_e)\n", + "print(\"Equilibrium torque = %g\" % u_e)\n", + "\n", + "# Linearize the system dynamics about the equilibrium point\n", + "P = ct.tf(\n", + " system.linearize([0, theta_e, 0], u_e, copy_names=True)[0, 0])\n", + "P.name = 'P' # bug\n", + "print(P, end=\"\\n\\n\")\n", + "\n", + "ct.bode_plot(P)" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "J1dwXObJSKp-" + }, + "source": [ + "## Ziegler-Nichols tuning\n", + "\n", + "Ziegler-Nichols tuning provides a method for choosing the gains of a PID controller that give reasonable closed loop response. More information can be found in [Feedback Systems](https://fbswiki.org/wiki/index.php/Feedback_Systems:_An_Introduction_for_Scientists_and_Engineers) (FBS2e), Section 11.3.\n", + "\n", + "We show here the figures and tables that we will use (from FBS2e):\n", + "\n", + "
\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "To use the Ziegler-Nichols turning rules, we plot the step response, compute the parameters (shown in the figure), and then apply the formulas in the table:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Plot the step response\n", + "resp = ct.step_response(P)\n", + "resp.plot()\n", + "\n", + "# Find the point of the steepest slope\n", + "slope = np.diff(resp.outputs) / np.diff(resp.time)\n", + "mxi = np.argmax(slope)\n", + "mx_time = resp.time[mxi]\n", + "mx_out= resp.outputs[mxi]\n", + "plt.plot(resp.time[mxi], resp.outputs[mxi], 'ro')\n", + "\n", + "# Draw a line going through the point of max slope\n", + "mx_slope = slope[mxi]\n", + "timepts = np.linspace(0, mx_time*2)\n", + "plt.plot(timepts, mx_out + mx_slope * (timepts - mx_time), 'r-')\n", + "\n", + "# Solve for the Ziegler-Nichols parameters\n", + "a = -(mx_out - mx_slope * mx_time) # Find the value of the line at t = 0\n", + "tau = a / mx_slope # Solve a + mx_slope * tau = 0\n", + "print(f\"{a=}, {tau=}\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "We can then construct a controller using the parameters:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "s = ct.tf('s')\n", + "\n", + "# Proportional controller\n", + "kp = 1/a\n", + "ctrl_zn_P = kp\n", + "\n", + "# PI controller\n", + "kp = 0.9/a\n", + "Ti = tau/0.3; ki = kp/Ti\n", + "ctrl_zn_PI = kp + ki / s\n", + "\n", + "# PID controller\n", + "kp = 1.2/a\n", + "Ti = tau/0.5; ki = kp/Ti\n", + "Td = 0.5 * tau; kd = kp * Td\n", + "ctrl_zn_PID = kp + ki / s + kd * s\n", + "\n", + "print(ctrl_zn_PID)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Compute the closed loop systems and plots the step and\n", + "# frequency responses.\n", + "\n", + "clsys_zn_P = ct.feedback(P * ctrl_zn_P)\n", + "clsys_zn_P.name = 'P'\n", + "\n", + "clsys_zn_PI = ct.feedback(P * ctrl_zn_PI)\n", + "clsys_zn_PI.name = 'PI'\n", + "\n", + "clsys_zn_PID = ct.feedback(P * ctrl_zn_PID)\n", + "clsys_zn_PID.name = 'PID'\n", + "\n", + "# Plot the step responses\n", + "resp.sysname = 'open_loop'\n", + "resp.plot(color='k')\n", + "\n", + "stepresp_zn_P = ct.step_response(clsys_zn_P)\n", + "stepresp_zn_P.plot(color='b')\n", + "\n", + "stepresp_zn_PI = ct.step_response(clsys_zn_PI)\n", + "stepresp_zn_PI.plot(color='r')\n", + "\n", + "stepresp_zn_PID = ct.step_response(clsys_zn_PID)\n", + "stepresp_zn_PID.plot(color='g')\n", + "plt.legend()\n", + "\n", + "plt.figure()\n", + "ct.bode_plot([clsys_zn_P, clsys_zn_PI, clsys_zn_PID]);" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "6iZwB2WEeg8S" + }, + "source": [ + "## Loop shaping\n", + "\n", + "A better design can be obtained by looking at the loop transfer function and adjusting the controller parameters to give a loop shape that will give closed loop properties. We show the steps for such a design here:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Design parameters\n", + "Td = 1 # Set to gain crossover frequency\n", + "Ti = Td * 10 # Set to low frequency region\n", + "kp = 500 # Tune to get desired bandwith\n", + "\n", + "# Updated gains\n", + "kp = 150\n", + "Ti = Td * 5; kp = 150\n", + "\n", + "# Compute controller parmeters\n", + "ki = kp/Ti\n", + "kd = kp * Td\n", + "\n", + "# Controller transfer function\n", + "ctrl_shape = kp + ki / s + kd * s\n", + "ctrl_shape.name = 'C'\n", + "\n", + "# Frequency response (open loop) - use this to help tune your design\n", + "ltf_shape = P * ctrl_shape\n", + "ltf_shape.name = 'L'\n", + "\n", + "ct.frequency_response([P, ctrl_shape]).plot()\n", + "ct.frequency_response(ltf_shape).plot(margins=True);" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Compute the closed loop systemsand plot the step response\n", + "# and Nyquist plot (to make sure margins look OK)\n", + "\n", + "# Create the closed loop systems\n", + "clsys_shape = ct.feedback(P * ctrl_shape)\n", + "clsys_shape.name = 'loopshape'\n", + "\n", + "# Step response\n", + "plt.subplot(2, 1, 1)\n", + "stepresp_shape = ct.step_response(clsys_shape)\n", + "stepresp_shape.plot(color='b')\n", + "plt.plot([0, stepresp_shape.time[-1]], [1, 1], 'k--')\n", + "\n", + "# Compare to the ZN controller\n", + "ax = plt.subplot(2, 1, 2)\n", + "ct.step_response(clsys_shape, stepresp_zn_PID.time).plot(\n", + " color='b', ax=np.array([[ax]]))\n", + "stepresp_zn_PID.plot(color='g', ax=np.array([[ax]]))\n", + "ax.plot([0, stepresp_shape.time[-1]], [1, 1], 'k--')\n", + "\n", + "# Nyquist plot\n", + "plt.figure()\n", + "ct.nyquist([ltf_shape])" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "We see that the loop shaping controller has better step response (faster rise and settling time, less overshoot)." + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "GyXQXykafzWs" + }, + "source": [ + "### Gang of Four\n", + "\n", + "When designing a controller, it is important to look at all of the input/output responses, not just the response from reference to output (which is what the step response above focuses on). \n", + "\n", + "In the frequency domain, the Gang of 4 plots provide useful information on all (important) input/output pairs:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "ct.gangof4(P, ctrl_shape)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "These all look pretty resonable, except that the transfer function from the reference $r$ to the system input $u$ is getting large at high frequency. This occurs because we did not filter the derivative on the PID controller, so high frequency components of the reference signal (or the measurement noise!) get amplified. We will fix this in the more advanced controller below." + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "uFO3wiWXhBAK" + }, + "source": [ + "## Anti-windup + derivative filtering\n", + "\n", + "In addition to the amplification of high frequency signals due to the derivative term, another practical consideration in the use of PID controllers is integrator windup. Integrator windup occurs when there are limits on the control inputs so that the error signal may not descrease quickly. This causes the integral term in the PID controller to see an error for a long period of time, and the resulting integration of the error must be offset by making the error have opposite sign for some period of time. This is often undesireable.\n", + "\n", + "To see how to address both amplification of noise due to the derivative term and integrator windup effects in the presence of input constraints, we now implement PID controller with anti-windup and derivative filtering, as shown in the following figure (see also Figure 11.11 in [FBS2e](https://fbswiki.org/wiki/index.php/Feedback_Systems:_An_Introduction_for_Scientists_and_Engineers)):\n", + "\n", + "
\n", + "\n", + "
\n", + "\n", + "### Low pass filter\n", + "\n", + "The low pass filtered derivative has transfer function\n", + "\n", + "$$\n", + "G(s) = \\frac{a\\, s}{s + a}.\n", + "$$\n", + "\n", + "This can be implemented using the differential equation\n", + "\n", + "$$\n", + "\\dot \\xi = -a \\xi + a y, \\qquad\n", + "\\eta = -a \\xi + a y.\n", + "$$" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "ctrl_params = {'kaw': 5 * ki, 'a': 10/Td}\n", + "\n", + "def ctrl_update(t, x, u, params):\n", + " # Get the parameter values\n", + " kaw = params['kaw']\n", + " a = params['a']\n", + " umax_ctrl = params.get('umax_ctrl', actuator.params['umax'])\n", + "\n", + " # Extract the signals into more familiar variable names\n", + " r, y = u[0], u[1]\n", + " z = x[0] # integral error\n", + " xi = x[1] # filtered derivative\n", + "\n", + " # Compute the controller components\n", + " u_prop = kp * (r - y)\n", + " u_int = z\n", + " ydt_f = -a * xi + a * (-y)\n", + " u_der = kd * ydt_f\n", + "\n", + " # Compute the commanded and saturated outputs\n", + " u_cmd = u_prop + u_int + u_der\n", + " u_sat = np.clip(u_cmd, -umax_ctrl, umax_ctrl)\n", + "\n", + " dz = ki * (r - y) + kaw * (u_sat - u_cmd)\n", + " dxi = -a * xi + a * (-y)\n", + " return np.array([dz, dxi])\n", + "\n", + "def ctrl_output(t, x, u, params):\n", + " # Get the parameter values\n", + " kaw = params['kaw']\n", + " a = params['a']\n", + " umax_ctrl = params.get('umax_ctrl', params['umax'])\n", + "\n", + " # Extract the signals into more familiar variable names\n", + " r, y = u[0], u[1]\n", + " z = x[0] # integral error\n", + " xi = x[1] # filtered derivative\n", + "\n", + " # Compute the controller components\n", + " u_prop = kp * (r - y)\n", + " u_int = z\n", + " ydt_f = -a * xi + a * (-y)\n", + " u_der = kd * ydt_f\n", + "\n", + " # Compute the commanded and saturated outputs\n", + " u_cmd = u_prop + u_int + u_der\n", + " u_sat = np.clip(u_cmd, -umax_ctrl, umax_ctrl)\n", + "\n", + " return u_cmd\n", + "\n", + "ctrl = ct.nlsys(\n", + " ctrl_update, ctrl_output, name='ctrl', params=ctrl_params,\n", + " inputs=['r', 'y'], outputs=['u'], states=2)\n", + "\n", + "clsys = ct.interconnect(\n", + " [servomech, actuator, ctrl], name='clsys',\n", + " inputs=['r'], outputs=['y', 'tau'])\n", + "print(clsys)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Plot the step responses for the following cases:\n", + "#\n", + "# 'linear': the original linear step response (no actuation limits)\n", + "# 'clipped': PID controller with input limits, but not anti-windup\n", + "# 'anti-windup': PID controller with anti-windup compensation\n", + "\n", + "# Use more time points to get smoother response curves\n", + "timepts = np.linspace(0, 2*stepresp_shape.time[-1], 500)\n", + "\n", + "# Compute the response for the individual cases\n", + "stepsize = theta_e / 2\n", + "resp_ln = ct.input_output_response(\n", + " clsys, timepts, stepsize, params={'umax': np.inf, 'kaw': 0, 'a': 1e3})\n", + "resp_cl = ct.input_output_response(\n", + " clsys, timepts, stepsize, params={'umax': 5, 'kaw': 0, 'a': 100})\n", + "resp_aw = ct.input_output_response(\n", + " clsys, timepts, stepsize, params={'umax': 5, 'kaw': 2*ki, 'a': 100})\n", + "\n", + "# Plot the time responses in a single plot\n", + "ct.time_response_plot(resp_ln, color='b', plot_inputs=False, label=\"linear\")\n", + "ct.time_response_plot(resp_cl, color='r', plot_inputs=False, label=\"clipped\")\n", + "ct.time_response_plot(resp_aw, color='g', plot_inputs=False, label=\"anti-windup\");" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "DZS7v0EmdK3H" + }, + "source": [ + "The response of the anti-windup compensator is very sluggish, indicating that we may be setting $k_\\text{aw}$ too high." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "resp_aw = ct.input_output_response(\n", + " clsys, timepts, stepsize, params={'umax': 5, 'kaw': 0.05 * ki, 'a': 100})\n", + "\n", + "# Plot the time responses in a single plot\n", + "ct.time_response_plot(resp_ln, color='b', plot_inputs=False, label=\"linear\")\n", + "ct.time_response_plot(resp_cl, color='r', plot_inputs=False, label=\"clipped\")\n", + "ct.time_response_plot(resp_aw, color='g', plot_inputs=False, label=\"anti-windup\");" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "pCp_pu0Kh62b" + }, + "source": [ + "This gives a much better response, though the value of $k_\\text{aw}$ falls well outside the range of [2, 10]. One reason for this is that $k_\\text{aw}$ acts on the inputs, $\\tau$, which are roughly 100 larger than the size of the outputs, $y$, as seen in the above plots." + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "1FVGh3k0Y7vB" + }, + "source": [ + "We can now see if this affects the Gang of Four in the expected way:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "C = ctrl.linearize([0, 0], 0, params=resp_aw.params)[0, 1]\n", + "ct.gangof4(P, C);" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "vT1WfhRHb2ZU" + }, + "source": [ + "Note that in the transfer function from $r$ to $u$ (which is the same as the transfer function from $e$ to $u$, the high frequency gain is now bounded. (We could make it go back down by using a second order filter.)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 4 +} diff --git a/examples/cds110_bode-nyquist.ipynb b/examples/cds110_bode-nyquist.ipynb deleted file mode 100644 index eb0988e1c..000000000 --- a/examples/cds110_bode-nyquist.ipynb +++ /dev/null @@ -1,1254 +0,0 @@ -{ - "cells": [ - { - "cell_type": "markdown", - "id": "8c577d78-3e4a-4f08-93ed-5c60867b9a3b", - "metadata": { - "id": "hairy-humidity" - }, - "source": [ - "# Frequency domain analysis using Bode/Nyquist plots\n", - "\n", - "**CDS 110, Winter 2024**
\n", - "Richard M. Murray\n", - "\n", - "\n", - "The purpose of this lecture is to introduce tools that can be used for frequency domain modeling and analysis of linear systems. It illustrates the use of a variety of frequency domain analysis and plotting tools." - ] - }, - { - "cell_type": "code", - "execution_count": 1, - "id": "invalid-carnival", - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "python-control 0.10.1.dev32+gdbc998de\n" - ] - } - ], - "source": [ - "# Import standard packages needed for this exercise\n", - "import numpy as np\n", - "import matplotlib.pyplot as plt\n", - "import math\n", - "\n", - "from math import pi, sin, cos\n", - "\n", - "import control as ct\n", - "print(\"python-control\", ct.__version__)" - ] - }, - { - "cell_type": "markdown", - "id": "P7t3Nm4Tre2Z", - "metadata": { - "id": "P7t3Nm4Tre2Z" - }, - "source": [ - "## Stable system: servomechanism\n", - "\n", - "We start with a simple example a stable system for which we wish to design a simple controller and analyze its performance, demonstrating along the way the basic frequency domain analysis functions in the Python control toolbox (python-control).\n", - "\n", - "Consider a simple mechanism for positioning a mechanical arm whose equations of motion are given by\n", - "\n", - "$$\n", - "J \\ddot \\theta = -b \\dot\\theta - k r\\sin\\theta + \\tau_\\text{m},\n", - "$$\n", - "\n", - "which can be written in state space form as\n", - "\n", - "$$\n", - "\\frac{d}{dt} \\begin{bmatrix} \\theta \\\\ \\theta \\end{bmatrix} =\n", - " \\begin{bmatrix} \\dot\\theta \\\\ -k r \\sin\\theta / J - b\\dot\\theta / J \\end{bmatrix}\n", - " + \\begin{bmatrix} 0 \\\\ 1/J \\end{bmatrix} \\tau_\\text{m}.\n", - "$$\n", - "\n", - "The system consists of a spring loaded arm that is driven by a motor, as shown below.\n", - "\n", - "
\"servomech-diagram\"
\n", - "\n", - "The motor applies a torque that twists the arm against a linear spring and moves the end of the arm across a rotating platter. The input to the system is the motor torque $\\tau_\\text{m}$. The force exerted by the spring is a nonlinear function of the head position due to the way it is attached.\n", - "\n", - "The system parameters are given by\n", - "\n", - "$$\n", - "k = 1,\\quad J = 100,\\quad b = 10,\n", - "\\quad r = 1,\\quad l = 2,\\quad \\epsilon = 0.01,\n", - "$$\n", - "\n", - "and we assume that time is measured in msec and distance in cm. (The constants here are made up and don't necessarily reflect a real disk drive, though the units and time constants are motivated by computer disk drives.)" - ] - }, - { - "cell_type": "markdown", - "id": "3e476db9", - "metadata": { - "id": "3e476db9" - }, - "source": [ - "The system dynamics can be modeled in python-control using a `NonlinearIOSystem` object, which we create with the `nlsys` function:" - ] - }, - { - "cell_type": "code", - "execution_count": 2, - "id": "27bb3c38", - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - ": servomech\n", - "Inputs (1): ['tau']\n", - "Outputs (1): ['y']\n", - "States (2): ['theta_', 'thdot_']\n", - "\n", - "Update: \n", - "Output: \n", - "\n", - "Params: {'J': 100, 'b': 10, 'k': 1, 'r': 1, 'l': 2, 'eps': 0.01}\n" - ] - } - ], - "source": [ - "# Parameter values\n", - "servomech_params = {\n", - " 'J': 100, # Moment of inertial of the motor\n", - " 'b': 10, # Angular damping of the arm\n", - " 'k': 1, # Spring constant\n", - " 'r': 1, # Location of spring contact on arm\n", - " 'l': 2, # Distance to the read head\n", - " 'eps': 0.01, # Magnitude of velocity-dependent perturbation\n", - "}\n", - "\n", - "# State derivative\n", - "def servomech_update(t, x, u, params):\n", - " # Extract the configuration and velocity variables from the state vector\n", - " theta = x[0] # Angular position of the disk drive arm\n", - " thetadot = x[1] # Angular velocity of the disk drive arm\n", - " tau = u[0] # Torque applied at the base of the arm\n", - "\n", - " # Get the parameter values\n", - " J, b, k, r = map(params.get, ['J', 'b', 'k', 'r'])\n", - "\n", - " # Compute the angular acceleration\n", - " dthetadot = 1/J * (\n", - " -b * thetadot - k * r * np.sin(theta) + tau)\n", - "\n", - " # Return the state update law\n", - " return np.array([thetadot, dthetadot])\n", - "\n", - "# System output (end of arm)\n", - "def servomech_output(t, x, u, params):\n", - " l = params['l']\n", - " return np.array([l * x[0]])\n", - "\n", - "# System dynamics\n", - "servomech = ct.nlsys(\n", - " servomech_update, servomech_output, name='servomech',\n", - " params=servomech_params,\n", - " states=['theta_', 'thdot_'],\n", - " outputs=['y'], inputs=['tau'])\n", - "\n", - "print(servomech)\n", - "print(\"\\nParams:\", servomech.params)" - ] - }, - { - "cell_type": "markdown", - "id": "competitive-terrain", - "metadata": { - "id": "competitive-terrain" - }, - "source": [ - "### Linearization\n", - "\n", - "To study the open loop dynamics of the system, we compute the linearization of the dynamics about the equilibrium point corresponding to $\\theta_\\text{e} = 15^\\circ$." - ] - }, - { - "cell_type": "code", - "execution_count": 3, - "id": "senior-carpet", - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "Equilibrium torque = 0.258819\n", - "Linearized dynamics: : P_ss\n", - "Inputs (1): ['u[0]']\n", - "Outputs (1): ['y[0]']\n", - "States (2): ['x[0]', 'x[1]']\n", - "\n", - "A = [[ 0. 1. ]\n", - " [-0.00965926 -0.1 ]]\n", - "\n", - "B = [[0. ]\n", - " [0.01]]\n", - "\n", - "C = [[2. 0.]]\n", - "\n", - "D = [[0.]]\n", - "\n", - "Zeros: []\n", - "Poles: [-0.05+0.08461239j -0.05-0.08461239j]\n", - "\n", - ": P_tf\n", - "Inputs (1): ['u[0]']\n", - "Outputs (1): ['y[0]']\n", - "\n", - "\n", - " 0.02\n", - "----------------------\n", - "s^2 + 0.1 s + 0.009659\n", - "\n" - ] - } - ], - "source": [ - "# Convert the equilibrium angle to radians\n", - "theta_e = (15 / 180) * np.pi\n", - "\n", - "# Compute the input required to hold this position\n", - "u_e = servomech.params['k'] * servomech.params['r'] * np.sin(theta_e)\n", - "print(\"Equilibrium torque = %g\" % u_e)\n", - "\n", - "# Linearize the system about the equilibrium point\n", - "P = servomech.linearize([theta_e, 0], u_e, name='P_ss')\n", - "P.name = 'P_ss' # TODO: fix in nlsys_improvements\n", - "print(\"Linearized dynamics:\", P)\n", - "print(\"Zeros: \", P.zeros())\n", - "print(\"Poles: \", P.poles())\n", - "print(\"\")\n", - "\n", - "# Transfer function representation\n", - "P_tf = ct.tf(P, name='P_tf')\n", - "print(P_tf)" - ] - }, - { - "cell_type": "markdown", - "id": "instant-lancaster", - "metadata": { - "id": "instant-lancaster" - }, - "source": [ - "### Open loop frequency response\n", - "\n", - "A standard method for understanding the dynamics is to plot the output of the system in response to sinusoids with unit magnitude at different frequencies.\n", - "\n", - "We use the `frequency_response` function to plot the step response of the linearized, open-loop system." - ] - }, - { - "cell_type": "code", - "execution_count": 4, - "id": "RxXFTpwO5bGI", - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "array([[list([])],\n", - " [list([])]],\n", - " dtype=object)" - ] - }, - "execution_count": 4, - "metadata": {}, - "output_type": "execute_result" - }, - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "# Reset the frequency response label to correspond to a time unit of ms\n", - "ct.set_defaults('freqplot', freq_label=\"Frequency [rad/ms]\")\n", - "\n", - "# Frequency response\n", - "freqresp = ct.frequency_response(P, np.logspace(-2, 0))\n", - "freqresp.plot()\n", - "\n", - "# Equivalent command\n", - "ct.bode_plot(P_tf, np.logspace(-2, 0), '--')" - ] - }, - { - "cell_type": "markdown", - "id": "stuffed-premiere", - "metadata": { - "id": "stuffed-premiere" - }, - "source": [ - "### Feedback control design\n", - "\n", - "We next design a feedback controller for the system using a proportional integral controller, which has transfer function\n", - "\n", - "$$\n", - "C(s) = \\frac{k_\\text{p} s + k_\\text{i}}{s}\n", - "$$\n", - "\n", - "We will learn how to choose $k_\\text{p}$ and $k_\\text{i}$ more formally in W9. For now we just pick different values to see how the dynamics are impacted." - ] - }, - { - "cell_type": "code", - "execution_count": 5, - "id": "8NK8O6XT7B_a", - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - ": C\n", - "Inputs (1): ['u[0]']\n", - "Outputs (1): ['y[0]']\n", - "\n", - "\n", - "s + 1\n", - "-----\n", - " s\n", - "\n", - ": C\n", - "Inputs (1): ['u[0]']\n", - "Outputs (1): ['y[0]']\n", - "\n", - "\n", - "s + 1\n", - "-----\n", - " s\n", - "\n" - ] - } - ], - "source": [ - "kp = 1\n", - "ki = 1\n", - "\n", - "# Create tf from numerator/denominator coefficients\n", - "C = ct.tf([kp, ki], [1, 0], name='C')\n", - "print(C)\n", - "\n", - "# Alternative method: define \"s\" and use algebra\n", - "s = ct.tf('s')\n", - "C = ct.tf(kp + ki/s, name='C')\n", - "print(C)" - ] - }, - { - "cell_type": "code", - "execution_count": 6, - "id": "074427a3", - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "# Loop transfer function\n", - "L = P * C\n", - "ct.bode_plot([P, C, L], label=['P', 'C', 'L'])\n", - "ct.suptitle(\"PI controller for servomechanism\")" - ] - }, - { - "cell_type": "markdown", - "id": "Bg5ga11VuRtI", - "metadata": { - "id": "Bg5ga11VuRtI" - }, - "source": [ - "Note that L = P * C corresponds to addition in both the magnitude and the phase." - ] - }, - { - "cell_type": "markdown", - "id": "UmYmSzx2rTfg", - "metadata": { - "id": "UmYmSzx2rTfg" - }, - "source": [ - "### Nyquist analysis\n", - "\n", - "To check stability (and eventually robustness), we use the Nyquist criterion." - ] - }, - { - "cell_type": "code", - "execution_count": 7, - "id": "Qmp59pmS9GLj", - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "fig = plt.figure(figsize=[7, 4])\n", - "ax1 = plt.subplot(2, 2, 1)\n", - "ax2 = plt.subplot(2, 2, 3)\n", - "ct.bode_plot(L, ax=[ax1, ax2])\n", - "\n", - "# Tidy up the figure a bit\n", - "fig.align_labels()\n", - "ax1.set_title(\"Bode plot for L\", fontsize='medium')\n", - "\n", - "ax2 = plt.subplot(1, 2, 2)\n", - "ct.nyquist_plot(L, ax=ax2, title=\"\")\n", - "plt.title(\"Nyquist plot for L\", fontsize='medium')\n", - "\n", - "ct.suptitle(\"Loop analysis for (unstable) servomechanism\")" - ] - }, - { - "cell_type": "markdown", - "id": "s4dDf4PrZqU3", - "metadata": { - "id": "s4dDf4PrZqU3" - }, - "source": [ - "We see from this plot that the loop transfer function encircles the -1 point => closed loop system should be unstable. We can check this by making use of additional features of Nyquist analysis." - ] - }, - { - "cell_type": "code", - "execution_count": 8, - "id": "K7ifUBL0Z3xN", - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "N = encirclements: 2\n", - "P = RHP poles of L: 0\n", - "Z = N + P = RHP zeros of 1 + L: 2\n", - "Zeros of (1 + L) = [-0.26792107+0.j 0.08396054+0.259999j 0.08396054-0.259999j]\n", - "\n" - ] - }, - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "# Get the Nyquist *response*, so that we can get back encirclements\n", - "nyqresp = ct.nyquist_response(L)\n", - "print(\"N = encirclements: \", nyqresp.count)\n", - "print(\"P = RHP poles of L: \", np.sum(np.real(L.poles()) > 0))\n", - "print(\"Z = N + P = RHP zeros of 1 + L:\", np.sum(np.real((1 + L).zeros()) > 0))\n", - "print(\"Zeros of (1 + L) = \", (1 + L).zeros())\n", - "print(\"\")\n", - "\n", - "T = ct.feedback(L)\n", - "ct.step_response(T).plot(\n", - " title=\"Step response for (unstable) servomechanism\",\n", - " time_label=\"Time [ms]\");" - ] - }, - { - "cell_type": "markdown", - "id": "p3JxLilMxdOE", - "metadata": { - "id": "p3JxLilMxdOE" - }, - "source": [ - "### Poles on the $j\\omega$ axis\n", - "\n", - "Note that we have a pole at 0 (due to the integrator in the controller). How is this handled?\n", - "\n", - "A: use a small loop to the right around poles on the $j\\omega$ axis => not inside the contour.\n", - "\n", - "To see this, we use the `nyquist_response` function, which returns the contour used to compute the Nyquist curve. If we zoom in on the contour near the origin, we see how the outer edge of the Nyquist curve is computed." - ] - }, - { - "cell_type": "code", - "execution_count": 9, - "id": "R5IBk3Ai9Slk", - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "fig = plt.figure(figsize=[7, 5.8])\n", - "\n", - "# Plot the D contour\n", - "ax1 = plt.subplot(2, 2, 1)\n", - "plt.plot(np.real(nyqresp.contour), np.imag(nyqresp.contour))\n", - "plt.axis([-1e-4, 4e-4, 0, 4e-4])\n", - "plt.xlabel('Real axis')\n", - "plt.ylabel('Imaginary axis')\n", - "plt.title(\"Zoom on D-contour\", size='medium')\n", - "\n", - "# Clean up the display of the units\n", - "from matplotlib import ticker\n", - "ax1.xaxis.set_major_formatter(ticker.StrMethodFormatter(\"{x:.0e}\"))\n", - "ax1.yaxis.set_major_formatter(ticker.StrMethodFormatter(\"{x:.0e}\"))\n", - "\n", - "ax2 = plt.subplot(2, 2, 2)\n", - "ct.nyquist_plot(L, ax=ax2)\n", - "plt.title(\"Nyquist curve\", size='medium')\n", - "\n", - "ct.suptitle(\"Nyquist contour for pole at the origin\")" - ] - }, - { - "cell_type": "markdown", - "id": "h20JRZ_r4fGy", - "metadata": { - "id": "h20JRZ_r4fGy" - }, - "source": [ - "### Second iteration feedback control design\n", - "\n", - "We now redesign the control system to give something that is stable. We can do this by moving the zero for the controller to a lower frequency, so that the phase lag from the integrator does not overlap with the phase lag from the system dynamics." - ] - }, - { - "cell_type": "code", - "execution_count": 10, - "id": "YsM8SnXz_Kaj", - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "# Change the frequency response to avoid crossing over -180 with large gain\n", - "Cnew = ct.tf(kp + (ki/200)/s, name='C_new')\n", - "Lnew = ct.tf(P * Cnew, name='L_new')\n", - "\n", - "plt.figure(figsize=[7, 4])\n", - "ax1 = plt.subplot(2, 2, 1)\n", - "ax2 = plt.subplot(2, 2, 3)\n", - "ct.bode_plot([Lnew, L], ax=[ax1, ax2], label=['L_new', 'L_old'])\n", - "\n", - "# Clean up the figure a bit\n", - "ax1.loglog([1e-3, 1e1], [1, 1], 'k', linewidth=0.5)\n", - "ax1.set_title(\"Bode plot for L_new, L_old\", size='medium')\n", - "\n", - "ax3=plt.subplot(1, 2, 2)\n", - "ct.nyquist_plot(Lnew, max_curve_magnitude=5, ax=ax3)\n", - "ax3.set_title(\"Nyquist plot for Lnew\", size='medium')\n", - "\n", - "plt.suptitle(\"Loop analysis for (stable) servomechanism\")\n", - "plt.tight_layout()" - ] - }, - { - "cell_type": "markdown", - "id": "kFjeGXzDvucx", - "metadata": { - "id": "kFjeGXzDvucx" - }, - "source": [ - "We see now that we have no encirclements, and so the system should be stable.\n", - "\n", - "Note however that the Nyquist curve is close to the -1 point => not *that* stable." - ] - }, - { - "cell_type": "code", - "execution_count": 11, - "id": "GGfJwG716jU2", - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "Text(0.5, 0.98, 'Step response for (stable) spring-mass system')" - ] - }, - "execution_count": 11, - "metadata": {}, - "output_type": "execute_result" - }, - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "# Compute the transfer function from r to y\n", - "Tnew = ct.feedback(Lnew)\n", - "ct.step_response(Tnew).plot(time_label=\"Time [ms]\")\n", - "plt.suptitle(\"Step response for (stable) spring-mass system\")" - ] - }, - { - "cell_type": "markdown", - "id": "b5114fa7-6924-47d7-8dd2-f12060152edd", - "metadata": {}, - "source": [ - "### Third iteration feedback control design (via loop shaping)\n", - "\n", - "To get a better design, we use a PID controller to shape the frequency response so that we get high gain at low frequency and low phase at crossover." - ] - }, - { - "cell_type": "code", - "execution_count": 12, - "id": "e6da93a4-5202-45d7-9e5a-697848f4ba71", - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "# Design parameters\n", - "Td = 1 # Set to gain crossover frequency\n", - "Ti = Td * 10 # Set to low frequency region\n", - "kp = 500 # Tune to get desired bandwith\n", - "\n", - "# Updated gains\n", - "kp = 150\n", - "Ti = Td * 5; kp = 150\n", - "\n", - "# Compute controller parmeters\n", - "ki = kp/Ti\n", - "kd = kp * Td\n", - "\n", - "# Controller transfer function\n", - "ctrl_shape = kp + ki / s + kd * s\n", - "\n", - "# Frequency response (open loop) - use this to help tune your design\n", - "ltf_shape = ct.tf(P_tf * ctrl_shape, name='L_shape')\n", - "\n", - "ct.frequency_response([P, ctrl_shape]).plot(label=['P', 'C_shape'])\n", - "ct.frequency_response(ltf_shape).plot(margins=True)\n", - "\n", - "ct.suptitle(\"Loop shaping design for servomechanism controller\")\n", - "plt.tight_layout()" - ] - }, - { - "cell_type": "code", - "execution_count": 13, - "id": "d731f372-4992-464c-9ca5-49cc1d554799", - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "Text(0.5, 0.98, 'Step response for servomechanism with PID controller')" - ] - }, - "execution_count": 13, - "metadata": {}, - "output_type": "execute_result" - }, - { - "data": { - "image/png": "iVBORw0KGgoAAAANSUhEUgAAAnYAAAHbCAYAAABGPtdUAAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjguNCwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy8fJSN1AAAACXBIWXMAAA9hAAAPYQGoP6dpAABMyUlEQVR4nO3deXxU1cH/8e8kmUyWSYYQAiSEgEAAgYAKouKCCIiA0NSKGyiU6mMVfX5CcaGLUVyoVKm0T1GrFVwoi1jZBAQBl1pQrMrmAipLAANhywbZz++PZIYMWUhgZm4YPu/Xa14mN2fOPXNn7vD1nHvOtRljjAAAAHDWC7G6AQAAAPANgh0AAECQINgBAAAECYIdAABAkCDYAQAABAmCHQAAQJAg2AEAAAQJgh0AAECQINgBAAAECYJdgHz66af6+c9/rpSUFDkcDrVo0UKXXXaZfvOb33iVmzFjhmbNmmVNI+EzO3fu1NChQ9W0aVPZbDY98MADVjcJp/DYY4/JZrPp4MGDAd/3zp07ZbPZzupz3338qqrt++yDDz6QzWbTggULTmtfs2bNks1m8zzCwsKUnJysX/7yl9q7d2+d+zn5uREREWrZsqX69eunKVOm6MCBA6fVpkBZtmyZHnvsMb/U7T5eH3zwgWdbTe8rGjeCXQC8++676tOnj3JzczV16lStXLlS06dP1+WXX6558+Z5lSXYBYfx48fr008/1auvvqp169Zp/PjxVjcJjVhiYqLWrVunoUOHWt2U03bnnXdq3bp1Xtv8/X02c+ZMrVu3TqtWrdJdd92lOXPm6Morr1RBQUGDnvu3v/1NF1xwgZ555hmdf/75ev/99/3W5jO1bNkyPf7441Y3A41YmNUNOBdMnTpV5513nt577z2FhZ045LfccoumTp1qYcvqp6ysTKWlpXI4HFY35ayxZcsW9e7dW+np6T6pz8r3wBijwsJCRUZGBnzf5wqHw6FLL73U6mackeTkZCUnJwd0n926dVOvXr0kSf369VNZWZmeeOIJLVy4UCNHjqz3cyXpF7/4hcaPH68rrrhCN9xwg7Zv364WLVr4tf3+1hjP3WPHjikqKsrqZgQ1euwC4NChQ2rWrJlXqHMLCTnxFrRt21Zbt27Vhx9+6BkmaNu2refvubm5mjhxos477zyFh4erVatWeuCBB6r936nNZtN9992nl156SR07dpTD4VCXLl00d+7cU7bVPSQ0depUPfnkkzrvvPPkcDi0du1aSdLnn3+u4cOHq2nTpoqIiNCFF16o+fPne9Vx7NgxTzsjIiLUtGlT9erVS3PmzPGUGTNmjJxOp7Zu3ar+/fsrOjpaCQkJuu+++3Ts2DGv+goLCzVp0iSv1z1u3DgdPXrUq1zbtm11/fXXa8WKFbrooosUGRmpzp0769VXX21w++r7Wk/mHsr4/vvvtXz5cs/7uHPnTknS7t27NWrUKDVv3lwOh0Pnn3++nnvuOZWXl9f7PajJW2+9pUsuuUQul0tRUVFq166dxo4d61WmoZ+fF198Ueeff74cDodeeeUVNW/eXLfffnu1fR89elSRkZGaMGGCZ1tDXuef/vQnPfPMM2rbtq0iIyN19dVXa9u2bSopKdEjjzyipKQkuVwu/fznP69xmGzevHm67LLLFB0dLafTqUGDBunLL7+sVu7TTz/VsGHDFB8fr4iICLVv377GIfL9+/fr1ltvlcvlUosWLTR27Fjl5OR4lfnb3/6mq666Ss2bN1d0dLTS0tI0depUlZSUeJW7+uqr1a1bN23YsEFXXnml57354x//WOOxqNq7lZ2drf/5n/9R69at5XA4lJCQoMsvv9yrN8ld/7p169SnTx9FRkaqbdu2mjlzpqSK0YKLLrpIUVFRSktL04oVK6q93qqMMWrRooXGjRvn2VZWVqa4uDiFhIRo//79nu3Tpk1TWFiY5zw8ecjuVN9nklRSUqLf/e53SkpKUmxsrAYMGKDvvvuuzjbWxR2Od+3adVrPT0lJ0XPPPae8vDy99NJLpyy/d+9ez3sUHh6upKQk3XjjjV7HqSHnwrPPPqtp06bpvPPOk9Pp1GWXXab169d7yo0ZM0Z/+9vfJMlrONn9/VLTufvaa69Jkv7973+rf//+iomJUVRUlPr06aN33333tI6TVL/zzv09v3nzZl177bWKiYlR//79T3ufqCcDv7vzzjuNJHP//feb9evXm+Li4hrLffHFF6Zdu3bmwgsvNOvWrTPr1q0zX3zxhTHGmIKCAnPBBReYZs2amWnTppn333/fTJ8+3bhcLnPNNdeY8vJyTz2STOvWrU2XLl3MnDlzzOLFi811111nJJm33nqrzrbu2LHDSDKtWrUy/fr1MwsWLDArV640O3bsMGvWrDHh4eHmyiuvNPPmzTMrVqwwY8aMMZLMzJkzPXXcfffdJioqykybNs2sXbvWLF261Pzxj380f/3rXz1lRo8ebcLDw01KSop56qmnzMqVK81jjz1mwsLCzPXXX+8pV15ebgYNGmTCwsLMH/7wB7Ny5Urz7LPPmujoaHPhhReawsJCT9k2bdqY5ORk06VLF/P666+b9957z4wYMcJIMh9++GGD2lff13qynJwcs27dOtOyZUtz+eWXe97HwsJCc+DAAdOqVSuTkJBgXnzxRbNixQpz3333GUnmnnvuqdd7UJP//Oc/xmazmVtuucUsW7bMrFmzxsycOdPcfvvtnjIN/fy0atXKdO/e3fzzn/80a9asMVu2bDHjx483kZGRJicnx2v/M2bMMJLMpk2bjDGmwa+zTZs2ZtiwYWbp0qXmzTffNC1atDAdO3Y0t99+uxk7dqxZvny5efHFF43T6TTDhg3z2vdTTz1lbDabGTt2rFm6dKn517/+ZS677DITHR1ttm7d6im3YsUKY7fbTffu3c2sWbPMmjVrzKuvvmpuueUWT5mMjAwjyXTq1Mk8+uijZtWqVWbatGnG4XCYX/7yl177HT9+vHnhhRfMihUrzJo1a8yf//xn06xZs2rl+vbta+Lj401qaqp58cUXzapVq8y9995rJJnXXnut2rGo+tkaNGiQSUhIMH//+9/NBx98YBYuXGgeffRRM3fu3Gr1d+rUyfzjH/8w7733nrn++uuNJPP444+btLQ0M2fOHLNs2TJz6aWXGofDYfbu3Vvj58jtlltuMR07dvT8vn79eiPJREZGmtmzZ3u2Dx482PTu3bva8XOr6/ts7dq1RpJp27atGTlypHn33XfNnDlzTEpKiklNTTWlpaV1tnHmzJlGktmwYYPX9unTpxtJ5u9//7vXfqp+79X2XLf8/HwTGhpq+vfvX2cb9uzZYxITE73OqXnz5pmxY8eab775xhjT8HOhbdu25rrrrjMLFy40CxcuNGlpaSYuLs4cPXrUGGPM999/b2688UYjyXNM3d8vxtR+7n7wwQfGbrebnj17mnnz5pmFCxeaa6+91thsNq/Pk/t4rV271rPt5PfVmPqfd6NHjzZ2u920bdvWTJkyxaxevdq89957dR5XnDmCXQAcPHjQXHHFFUaSkWTsdrvp06ePmTJlisnLy/Mq27VrV9O3b99qdUyZMsWEhIRU+zJasGCBkWSWLVvm2eb+Es7KyvJsKy0tNZ07dzYdOnSos63uL5j27dtXC6CdO3c2F154oSkpKfHafv3115vExERTVlZmjDGmW7duJj09vc79jB492kgy06dP99r+1FNPGUnm3//+tzGm4h9kSWbq1Kle5ebNm+f1BW5MRbCLiIgwu3bt8mw7fvy4adq0qbn77rs92+rTvvq+1tq0adPGDB061GvbI488YiSZTz/91Gv7PffcY2w2m/nuu++MMXW/BzV59tlnjSTPl39NGvr5cblc5vDhw15lN23aVO2YG2NM7969Tc+ePU/7dfbo0cPreD7//PNGkhk+fLjX8x944AEjyRMsd+/ebcLCwsz999/vVS4vL8+0bNnS3HTTTZ5t7du3N+3btzfHjx+v9Ri5/wE7+bN27733moiICK/wW1VZWZkpKSkxr7/+ugkNDfU6bn379q3xWHTp0sUMGjTI83tNwc7pdJoHHnig1vZWrf/zzz/3bDt06JAJDQ01kZGRXiHuq6++MpLMX/7ylzrrfOWVV4wks3v3bmOMMU8++aTp3LmzGT58uCe4FhcXm+joaPPb3/7W87yaAkBt32fuADFkyBCv7fPnz/eElrq4w9n69etNSUmJycvLM0uXLjUJCQkmJibG8913OsHOGGNatGhhzj///DrbMHbsWGO3283XX39da5mGngtpaWleofazzz4zksycOXM828aNG1ftOLvVdu5eeumlpnnz5l7/3pSWlppu3bqZ5ORkz2e7PsGuIeed+3v+1VdfrfUYwfcYig2A+Ph4ffzxx9qwYYP++Mc/6mc/+5m2bdumSZMmKS0trV6z8JYuXapu3brpggsuUGlpqecxaNCgarOYJKl///5e14eEhobq5ptv1vfff689e/accn/Dhw+X3W73/P7999/r22+/9Vy3UrUNQ4YM0U8//eQZQundu7eWL1+uRx55RB988IGOHz9e635Ovg7mtttukyTPsOOaNWskVXTpVzVixAhFR0dr9erVXtsvuOACpaSkeH6PiIhQx44dvYZmTtW+hrzWhlizZo26dOmi3r17e20fM2aMjDGe1+p28ntQm4svvliSdNNNN2n+/PleswLdGvr5ueaaaxQXF+e1LS0tTT179vQM80nSN998o88++8xr2Lehr3PIkCFelyScf/75klRtIoF7++7duyVJ7733nkpLS3XHHXd4vaaIiAj17dvX85q2bdumH374Qb/61a8UERFR80GsYvjw4V6/d+/eXYWFhV7DwF9++aWGDx+u+Ph4hYaGym6364477lBZWZm2bdvm9fyWLVtWOxbdu3c/5XBh7969NWvWLD355JNav359tWFet8TERPXs2dPze9OmTdW8eXNdcMEFSkpK8mx3H79T7XfAgAGS5BnyXbVqlQYOHKgBAwZo1apVkqR169apoKDAU/Z01XSs69NGt0svvVR2u10xMTG6/vrr1bJlSy1fvvyMr40zxpyyzPLly9WvXz/Pca1JQ8+FoUOHKjQ01PN7Q4+HVP3cLSgo0Keffqobb7xRTqfTsz00NFS333679uzZ06Dvs/qed1X94he/qHf9OHMEuwDq1auXHn74Yb311lvat2+fxo8fr507d9ZrAsX+/fu1adMm2e12r0dMTIyMMdXCYcuWLavV4d526NChU+4vMTGx2v4laeLEidXacO+990qSpw1/+ctf9PDDD2vhwoXq16+fmjZtqvT0dG3fvt2rzrCwMMXHx9fZxkOHDiksLEwJCQle5Ww2m1q2bFnttZxcn1RxYXrV8Haq9jXktTbEoUOHqh1XSZ5/fE9+LTWVrclVV12lhQsXer5sk5OT1a1bN69rBhv6+alt32PHjtW6dev07bffSqqYWehwOHTrrbee9uts2rSp1+/h4eF1bi8sLPS8Jqki2J78uubNm+d5TdnZ2ZJU7wv7T/4MuSesuD9Du3fv1pVXXqm9e/dq+vTpnv9pc1/7dPL/KNTnM1mTefPmafTo0XrllVd02WWXqWnTprrjjjuUlZXlVe7k4yRVHKtTHb/atGnTRu3bt9f777+vY8eOad26dZ5g5w4B77//viIjI9WnT5866zqVUx3rU3n99de1YcMGffnll9q3b582bdqkyy+//IzaVFBQoEOHDnmF4ppkZ2ef8jPV0HPhTI+HVP3cPXLkiIwxDWpHXep73rlFRUUpNja23vXjzDEr1iJ2u10ZGRn685//rC1btpyyfLNmzRQZGVltIkDVv1d18pd/1W01/UNzspPXLXLXP2nSJN1www01PqdTp06SpOjoaD3++ON6/PHHtX//fk/v2LBhwzyBQKroCTt06JBXe05uY3x8vEpLS5Wdne0V7owxysrK8vRWNcSp2teQ19oQ8fHx+umnn6pt37dvn6Tq72FD1o762c9+pp/97GcqKirS+vXrNWXKFN12221q27atLrvssgZ/fmrb96233qoJEyZo1qxZeuqpp/TGG28oPT3dq4egoa/zdLnrWbBggdq0aVNrOffnpj491fWxcOFCFRQU6F//+pfXfr/66iuf1O/WrFkzPf/883r++ee1e/duLV68WI888ogOHDhwykkQZ6p///5atGiRPvzwQ5WXl+vqq69WTEyMkpKStGrVKr3//vu68sorLZ8pf/7553vNbPWFd999V2VlZbr66qvrLJeQkHDKz1SgzoWqTj533RNffNWO+p53tbUH/kePXQDUdEJJFcNYkrz+z7C2/5O//vrr9cMPPyg+Pl69evWq9jh5ttnq1au9ZmaVlZVp3rx5at++/WktSdCpUyelpqZq48aNNe6/V69eiomJqfa8Fi1aaMyYMbr11lv13XffVZvxOnv2bK/f//nPf0qS50vVPYPqzTff9Cr39ttvq6Cg4IxnWNXUvtN9rafSv39/ff311/riiy+8tr/++uuy2Wzq16/fGb0WqeLz07dvXz3zzDOS5Jml1tDPT23i4uKUnp6u119/XUuXLlVWVla12beBeJ2SNGjQIIWFhemHH36o9X2SpI4dO6p9+/Z69dVXVVRUdMb7df9DVTXUGGP08ssvn3HdtUlJSdF9992ngQMHVjuu/jBgwADt379fzz//vC699FLP571///565513tGHDhnoNw9anZ7Ix2b17tyZOnCiXy6W77767zrKDBw/W2rVr6xzG9Me50NBevOjoaF1yySX617/+5fWc8vJyvfnmm0pOTlbHjh3rvf/6nnewDj12ATBo0CAlJydr2LBh6ty5s8rLy/XVV1/pueeek9Pp1P/7f//PUzYtLU1z587VvHnz1K5dO0VERCgtLU0PPPCA3n77bV111VUaP368unfvrvLycu3evVsrV67Ub37zG11yySWeepo1a6ZrrrlGf/jDHxQdHa0ZM2bo22+/rdeSJ7V56aWXNHjwYA0aNEhjxoxRq1atdPjwYX3zzTf64osv9NZbb0mSLrnkEl1//fXq3r274uLi9M033+iNN97QZZdd5rV+UXh4uJ577jnl5+fr4osv1n/+8x89+eSTGjx4sK644gpJ0sCBAzVo0CA9/PDDys3N1eWXX65NmzYpIyNDF154YY3Lb5xKfdpX39faEOPHj9frr7+uoUOHavLkyWrTpo3effddzZgxQ/fcc0+DvlyrevTRR7Vnzx71799fycnJOnr0qKZPny673a6+fftKUoM/P3UZO3as5s2bp/vuu0/JycnV/oH31+s8Wdu2bTV58mT97ne/048//qjrrrtOcXFx2r9/vz777DNPz6xUsTzJsGHDdOmll2r8+PFKSUnR7t279d5771X7n4tTGThwoMLDw3XrrbfqoYceUmFhoV544QUdOXLEJ69LknJyctSvXz/ddttt6ty5s2JiYrRhwwatWLGi1l5kX7rmmmtks9m0cuVKr8VwBwwYoNGjR3t+PpXavs8agy1btniuDztw4IA+/vhjzZw5U6GhoXrnnXeqXf5xssmTJ2v58uW66qqr9Nvf/lZpaWk6evSoVqxYoQkTJqhz585+ORfcx++ZZ57R4MGDFRoaqu7du3uG2msyZcoUDRw4UP369dPEiRMVHh6uGTNmaMuWLZozZ06DetUact7BIpZN2ziHzJs3z9x2220mNTXVOJ1OY7fbTUpKirn99turzajauXOnufbaa01MTIxnKQi3/Px88/vf/9506tTJhIeHG5fLZdLS0sz48eO9ZsBKMuPGjTMzZsww7du3N3a73XTu3NlrqYLauGdn/elPf6rx7xs3bjQ33XSTad68ubHb7aZly5bmmmuuMS+++KKnzCOPPGJ69epl4uLijMPhMO3atTPjx483Bw8e9JQZPXq0iY6ONps2bTJXX321iYyMNE2bNjX33HOPyc/P99rn8ePHzcMPP2zatGlj7Ha7SUxMNPfcc485cuSIV7maZqIaUzFzsOrMvPq0r76vtTa1tWXXrl3mtttuM/Hx8cZut5tOnTqZP/3pT16zQk/1Hpxs6dKlZvDgwaZVq1YmPDzcNG/e3AwZMsR8/PHHXuUa+vmpTVlZmWndurWRZH73u9/VWOZMXmdNMxmNqX0248KFC02/fv1MbGyscTgcpk2bNubGG28077//vle5devWmcGDBxuXy2UcDodp3769GT9+vOfv7tl/2dnZNe636nIzS5YsMT169DARERGmVatW5sEHHzTLly+vNqOwb9++pmvXrtWOz+jRo73O7ZNnxRYWFppf//rXpnv37iY2NtZERkaaTp06mYyMDFNQUHDK+mv7/J3qva3qwgsvNJLMJ5984tm2d+9eI8nEx8dXmyVc06zY2r7PanuPa5odXJP6zGytbT/u57of7nOmb9++5umnnzYHDhyos86qMjMzzdixY03Lli2N3W43SUlJ5qabbjL79+/3lDnTc16SycjI8PxeVFRk7rzzTpOQkGBsNpvXZ7Ou9/fjjz8211xzjYmOjjaRkZHm0ksvNUuWLKnxeJ1quRNj6nfeub/nEVg2Y+ox/QdnFZvNpnHjxun//u//rG5KrcaMGaMFCxYoPz/f6qYAABA0uMYOAAAgSBDsAAAAggRDsQAAAEGCHjsAAIAgQbADAAAIEgQ7AACAIEGwAwAACBIEOwAAgCBBsAMAAAgSBDsAAIAgQbADAAAIEgQ7AACAIEGwAwAACBIEOwAAgCBBsAMAAAgSBDsAAIAgQbADAAAIEgQ7AACAIEGwAwAACBIEOwAAgCBBsAMAAAgSYVY3wN/Ky8u1b98+xcTEyGazWd0cAACABjHGKC8vT0lJSQoJqbtPLuiD3b59+9S6dWurmwEAAHBGMjMzlZycXGeZoA92MTExkioORmxsrMWtAQAAaJjc3Fy1bt3ak2nqEvTBzj38GhsbS7ADAABnrfpcUmbZ5ImMjAx16dJFISEhmjt3bq3lJkyYoHbt2ikmJka9evXSRx99FMBWAgAAnD0sC3apqamaPn26evfuXWc5l8ullStXKicnRw8//LDS09OVl5cXoFYCAACcPSwLdqNGjdLAgQMVERFRZ7mMjAx16NBBISEhGjFihCIjI7Vt27YAtRIAAODscVZdY7dz504dPnxYHTp0qLVMUVGRioqKPL/n5uYGomkAAACWO2sWKC4pKdHo0aP14IMPyuVy1VpuypQpcrlcngdLnQAAgHPFWRHsjDEaM2aMmjdvrscee6zOspMmTVJOTo7nkZmZGZhGAgAAWOysGIq9//77tW/fPq1YseKUKy47HA45HI4AtQwAAKDxsCzYlZSUqKysTOXl5SopKVFhYaHCw8OrBbeMjAx98skn+vDDDwlsAAAAdbAZY4wVOx4zZoxee+01r21r167V3r179fTTT2vr1q0VDbTZ5HA4FBZ2IoO+9NJLGjlyZL32k5ubK5fLpZycHBYoBgAAZ52GZBnLgl2gEOwAAMDZrCFZ5qyYPAEAAIBTI9gBAAAECYIdAABAkDgrljs5lxljtHlvjuZuyNR3WXk6PzFGV3Ropmu7tFRIiM3q5gEAgEaEYNeIGWM0eenXmvnJTs+2/+46ojfX79YVHZrpTyO6K9EVaV0DAQBAo8JQbCP2+rpdmvnJTtls0s8uSNKfbuyuMX3aKsIeon9/f1DXPf+xNu/JsbqZAACgkWC5k0bqPz8c1KhXPlW5kX47pLP+56r2nr/9kJ2vB+Z+pc17c+SKtGvOXZeqS9LZ89oAAED9sdzJWc4Yo2dWfKdyI/3iomTddWU7r7+3T3Dqn3ddogtaN1HO8RLd/o9PtefIMYtaCwAAGguCXSP0+a4j2ph5VOFhIZo0pLNstuqTJGIi7HptbG91SYzVoYJi3fPmFyosKbOgtQAAoLEg2DVCL3/0oyTpFxe1UjNn7ffHdUXa9fc7eiouyq7Ne3P0h4VbAtVEAADQCBHsGpkdBwu06pv9kqRfXdHuFKWl5Lgo/d9tFynEJr313z16d9NP/m4iAABopAh2jcxbn2fKGOmazs3VobmzXs+5vEMzjevXQZL0+4WbdSCv0J9NBAAAjRTBrpH54LtsSdLwHkkNet7916Sqa1Ksjhwr0aS3NyvIJzsDAIAaEOwakQO5hfr6p1zZbNKVqc0a9NzwsBBNu+kChYeGaPW3B/TW53v81EoAANBYEewakQ+3VfTWdW/lUnwdkyZq06lljCZc21GSNHnp18o8zBIoAACcSwh2jYg72PXtmHDaddx1ZTv1ahOn/KJSPbRgE0OyAACcQwh2jURpWbk+3n5QktS30+kHu9AQm567qYci7aFa9+Mhzfks01dNBAAAjRzBrpHYuCdHOcdL5Iq0q0dykzOqq018tCYO6iRJmrLsG/2Uc9wHLQQAAI0dwa6R+GzHYUlSn/bxCgs987dlTJ+2ujClifKKSvX7d7YwJAsAwDmAYNdIbNmXI0nqfoa9dW6hITZN/UV3zyzZxRv3+aReAADQeBHsGomv9+VKkrq1ivVZnaktYnT/NRULFz+2eKsO5hf5rG4AAND4EOwagbzCEu04WCBJ6prk8mndv766vTq3jNGRYyV6bPFWn9YNAAAaF4JdI+DurUtyRahpdLhP67aHhuhPN/ZQaIhNSzf9pJVbs3xaPwAAaDwIdo3A1spg18XHvXVuacku3XVlO0nS7xduUc7xEr/sBwAAWItg1wi4J0748vq6kz0wIFXtmkXrQF6RJi/52m/7AQAA1iHYNQLuoVhfX19XVYQ9VFNv7K4Qm/T2F3u0fPNPftsXAACwBsHOYoUlZdp+IF+Sf3vsJKlX26b6dd/2kqRJ72zW/txCv+4PAAAEFsHOYt9m5ams3KhpdLhaxkb4fX8PDOiobq1idfRYiR7kXrIAAAQVgp3Ftu3PkyR1bhkjm83m9/2Fh4Xo+ZsvkCMsRB9ty9br63b5fZ8AACAwCHYW233omCSpbbPogO2zQ/MY/XbI+ZKkp5d94wmXAADg7Eaws9jOQxULE7eNjwrofu+4rI36dkxQUWm5fv3mf5VXyBIoAACc7Qh2Ftt9uKLHrk184HrsJMlms+m5m3oo0RWhH7ML9OBbXG8HAMDZjmBnsZ2VtxJrE+AeO0lq5nRoxsiLFB4aohVbs/Tihz8GvA0AAMB3CHYWOnqsWLmFpZKklKaBD3aSdGFKnDKGd5Ek/em9b/XJ9wctaQcAADhzBDsL7aycONEi1qGo8DDL2nFb7xSN6JmsciPdP+dLZVYODwMAgLMLwc5CuyonTrRpGtjr605ms9n0RHo3pbVy6XBBscbM/ExHjxVb2iYAANBwBDsL7TrknjhhzTBsVRH2UL0yupeSXBH6IbtA//P6f1VYUmZ1swAAQAMQ7CzUmIKdJLWIjdDMX/ZWjCNMn+08rHtnf6Hi0nKrmwUAAOqJYGchz1BsgJc6qUunljF6ZXQvOcJCtObbAxo/7yuVlhHuAAA4GxDsLLSrcpJC20YU7CTpknbxeun2nrKH2vTu5p903z+/pOcOAICzAMHOIgVFpcrOK5IkpTSSodiqru7UXC+M7OlZ4+7uNz7XseJSq5sFAADqQLCziPuOE3FRdrki7Ra3pmYDurTQK6N7KcIeorXfZevWlz/Vwfwiq5sFAABqQbCzyL6jxyVJreIiLW5J3a7qmKDZd16iJlF2bcw8qvS/faKv9+Va3SwAAFADgp1F9udW9Hy1jI2wuCWn1rNNU719Tx+lNI3SniPHdcMLn+idL/dY3SwAAHASgp1FsnILJVUsMXI2aJ/g1OL7LtdVHRNUWFKu8fM2asL8r5RfxHV3AAA0FgQ7ixw4y4KdJDWJCtfMMRfrgQGpCrFJ//pir66d9qFWbMmSMcbq5gEAcM4j2FnE3WN3NgzFVhUaYtMDAzpq3t2XqXXTSO3LKdSv3/yvfvXa59p9iHvMAgBgJYKdRdzX2DWPdVjcktNzcdumWvlAX93Xr4PsoTat+faABv75Q01Z/o1nGRcAABBYBDuLnI1DsSeLDA/VxEGdtOKBq9SnfbyKSsv10oc/6opn1uixxVv1U85xq5sIAMA5xbJgl5GRoS5duigkJERz586ttdzx48c1atQoxcTEKCUlRXPmzAlgK/2jqLRMhwqKJZ19Q7E1aZ/g1Ow7L9E/RvfSBa2bqKi0XLP+s1NXTV2re978r9Z8u5/bkgEAEABhVu04NTVV06dP1x/+8Ic6y2VkZOjw4cPau3evtmzZoiFDhqhnz57q2LFjgFrqe+6hyvDQEDWJapyLEzeUzWZT//Nb6JrOzfWfHw7pL6u369Mdh7V8S5aWb8lSQoxD6RckacD5LXRRmzjZQ+ksBgDA1ywLdqNGjZIkPfXUU3WWe+ONN7Rw4ULFxsaqT58+Gj58uObOnatHH300EM30i/2Vw7DNYx2y2WwWt8a3bDabLu/QTJd3aKZvfsrVW5/v0cKv9io7r0gvf7xDL3+8QzERYboytZmuTE3QhSlNlNo8RqEhwXUcAACwgmXBrj6OHDmirKwspaWlebb16NFDn332Wa3PKSoqUlHRiYv3c3Mb310SzqbFic/E+YmxenRYFz0yuLPWfHtA723N0ofbsnW4oFjLNmdp2eYsSVJ0eKjSkl3qluRSh+ZOtW/uVIcEp+Kiwy1+BcHJGKNyI5Ubo7Jyc+K/5VJZ5c/GGM/PVbeXm5rLV63Lvb28vGJbmams76Tt5cbIVLbDSJV1S6r8b9V2qvLvFeWrbCuvLCvv51atU+ZE3eak+qrWKVW0vdbnVttW8dyKZ6ryZ1N5jN3bjNff3YsCebZ7nl9RV7XfPW/aiW0n6jNV6qsse9L+aq5bXssTmVPUrVpfS5XXWmW1I6/nqur2GrbVUPLkcvWtq6aSNe+zpvpqeG499lvf59W00aftOIPXXnPbfHss6+tMF82yctWt3w89X3de2c66BlTRqINdfn6+QkNDFRUV5dkWGxur/Pz8Wp8zZcoUPf7444Fo3mnbHwQTJxoiPCxE13Vrqeu6tVRZudGmPUf1wXfZ+mzHYW3ac1QFxWVa/+Nhrf/xsNfzosND1cIVoRYxEWoR61ALV4Sax0QoNiJMMRF2xUSEVT7sig4PlT00RGGhNtlDQ2QPDTntXsCycqOSsnKVlRuVlhmVlJd7tpWWGZWWG5WWV/m5rLzyv5Vlyyr+XlJmvOoqKTcqc5etfJ6njOd51euueF7l9sr9eJWppS3uv5VVeQ1llUEIABCcGnWwczqdKisr07FjxzzhLjc3V06ns9bnTJo0SRMmTPD8npubq9atW/u9rQ1xtt11wpdCQ2y6MCVOF6bESaoIUdsP5Omr3Uf13f48fX8gXz9mF2jv0eMqKC7Tj9kF+jG74LT2ZbNJ9pAQ2UNtCrHZvHoiqvZSuDtajCrCEGstVxy7UJtNISE2hdpsCg2xKcSmyv+etD3kRNkQm+3E80K866h4XpU6Kp9vU8UQfoitYr/uv6nyZ5ukkMqf5fm7ZFNFfZLN83dblf/a5F2nzfP3E/XaKvfl3m6rWoeq1OXZpxQSUllX5XGq+Mn9c8V/K1pVuUHy7MtW5fie/FxVljlR/kQ9thNVVW63Vfl7zXVXbcOJv9lqrNtdj2p8PTW/vlO2wfOb9+fqVGoqc3JdNZY53efVsw0nl6x/XbZ6lKmprlPvryYnl6vpcp/6tKG+7189DtUZq6ktZ1ynj6uMDm88carxtKQGcXFxatmypTZv3qxLLrlEkrRx40Z17dq11uc4HA45HI17bbgDlUOxLc7SNex8KTTEps4tY9W5ZazX9mPFpcrKKdT+3CLtzy2sfBTpQF6h8gpLlVdYovyiUuUVliq/sFT5xaU1DJNIxWXlKi4783aGhVSEEHdPoD3UprCQKj+HhigsxKawyu1eP4faKn4PCVFoqE32EJtCKwNn1fIVfztRp7tMaEiV+qvtw7v+Gn+ufG5oiM0TqtxBzTu4ndgebNd+AsC5wrJgV1JSorKyMpWXl6ukpESFhYUKDw9XSIj3bMlRo0bpiSee0Jw5c7R161YtXrxYn376qUWt9o2snHO3x66+osLD1C7BqXYJtffOnsw97OkeMi2pHMYsKS2X0YneBq9eCncvTeXPVUOZO8SFVfbQAADQ2FkW7O666y699tprkqSPP/5Yd9xxh9auXau9e/fq6aef1tatWyVJkydP1p133qnExETFxcVpxowZ6tSpk1XN9on9eQQ7f6jokQpVhD3U6qYAAGAJmwnyu7fn5ubK5XIpJydHsbGxp35CAHTLeE/5RaVa85u+DeqRAgAA556GZBlWiQ2w/KJS5ReVSqLHDgAA+BbBLsDcS504HWGKdjTquSsAAOAsQ7ALsCOV94iNd7L4LgAA8C2CXYAdrgx2cVEEOwAA4FsEuwA7cqwi2DXldlkAAMDHCHYBdrigRBI9dgAAwPcIdgHm7rHjGjsAAOBrBLsA4xo7AADgLwS7AHPPim0abbe4JQAAINgQ7ALs8DF67AAAgH8Q7ALscAGzYgEAgH8Q7ALMc40dwQ4AAPgYwS6ASsrKlVdYcZ/YpgzFAgAAHyPYBZB7qZMQmxQbyeQJAADgWwS7ADpSuThxk6hwhYbYLG4NAAAINgS7ADqxhh29dQAAwPcIdgHEfWIBAIA/EewCiLtOAAAAfyLYBdAR1rADAAB+RLALIM9dJwh2AADADwh2AeTpsWMoFgAA+AHBLoAOH6tY7oQeOwAA4A8EuwA6cY0dy50AAADfI9gFELNiAQCAPxHsAoh17AAAgD8R7AKksKRMx4rLJHGNHQAA8A+CXYDkHK+YOBEaYlOMI8zi1gAAgGBEsAuQ3MpgFxMRJpvNZnFrAABAMCLYBUhuYakkKTaCGbEAAMA/CHYBklt4oscOAADAHwh2AZJHjx0AAPAzgl2AVL3GDgAAwB8IdgHiHoqNjaTHDgAA+AfBLkDcQ7H02AEAAH8h2AWIeyiWa+wAAIC/EOwChB47AADgbwS7AOEaOwAA4G8EuwBhuRMAAOBvBLsAOXGNHUOxAADAPwh2AcJQLAAA8DeCXYAweQIAAPgbwS4ASsrKday4TBLX2AEAAP8h2AVAfmVvnSQ56bEDAAB+QrALAPf1dVHhobKHcsgBAIB/kDICgOvrAABAIBDsAoDbiQEAgEAg2AVALj12AAAgAAh2AcAadgAAIBAIdgHgHoqNYSgWAAD4EcEuAE7cJ5ahWAAA4D+WBbvs7GwNHTpUUVFR6tSpk1avXl1juR07dujaa69VkyZN1KpVK02ZMiXALT1zDMUCAIBAsCzYjRs3TklJSTp48KCeeeYZjRgxQkeOHKlW7v7771e7du2UnZ2tf//73/rrX/9aawhsrFjuBAAABIIlwS4/P1+LFi3S5MmTFRUVpfT0dHXr1k1LliypVnbXrl26+eabZbfbdd555+mKK67Q119/XWvdRUVFys3N9XpYjeVOAABAIFgS7LZv3y6Xy6XExETPth49emjr1q3Vyo4bN05z585VUVGRtm/frvXr1+vqq6+ute4pU6bI5XJ5Hq1bt/bHS2gQeuwAAEAgWNZjFxsb67UtNjZW+fn51cr26dNH69atU3R0tDp27Khf/epXSktLq7XuSZMmKScnx/PIzMz0efsbimvsAABAIFgS7JxOZ7Uh0tzcXDmdTq9tZWVlGjJkiO666y4VFhZqx44deuutt7RgwYJa63Y4HIqNjfV6WI1ZsQAAIBAsCXapqanKyclRVlaWZ9vGjRvVtWtXr3KHDx/Wvn37dM899ygsLExt27ZVenq61q5dG+gmnxFPjx3X2AEAAD+yrMdu+PDhysjI0PHjx7V48WJt2bJFw4YN8yqXkJCg1q1b6+WXX1Z5ebn27NmjRYsW1TkU29gYY6pcY0ewAwAA/mPZciczZsxQZmam4uPjNXHiRM2fP19xcXGaPXu2V8/dggUL9MYbbyguLk4XX3yx+vfvr7vuusuqZjdYUWm5ysqNJMnJUCwAAPAjmzHGWN0If8rNzZXL5VJOTo4l19sdyi9SzyfflyT98PQQhYbYAt4GAABw9mpIluGWYn52rLhMkhRpDyXUAQAAvyLY+Vl+UcX1ddGOUItbAgAAgh3Bzs+OFVcEu6hwrq8DAAD+RbDzs4KiiqHYaAfBDgAA+BfBzs/cPXbR4QzFAgAA/yLY+Zm7xy6KHjsAAOBnBDs/K6DHDgAABAjBzs88PXZMngAAAH5GsPMz9zV2TpY7AQAAfkaw8zOusQMAAIFCsPMzZsUCAIBAIdj5mfvOE1xjBwAA/I1g52fue8VySzEAAOBvBDs/K/DcK5YeOwAA4F8EOz/z9NgxFAsAAPyMYOdn7gWKo5g8AQAA/Ixg52cMxQIAgEAh2PnZMc+dJ+ixAwAA/kWw8yNjjGco1kmPHQAA8DOCnR8VlZar3FT8zJ0nAACAvxHs/Mh9fZ0kRdoZigUAAP5FsPMj931iI+2hCg2xWdwaAAAQ7Ah2fuS+vo67TgAAgEAg2PnRsWKWOgEAAIFDsPOjAs9SJwQ7AADgfwQ7P/L02LGGHQAACACCnR/lu3vsGIoFAAABQLDzo2OexYnpsQMAAP5HsPMjrrEDAACBRLDzI66xAwAAgUSw86MCrrEDAAABRLDzI/ctxeixAwAAgUCw86MCFigGAAABRLDzo2PFFUOx0UyeAAAAAUCw8yP3UGwUy50AAIAAINj5ET12AAAgkAh2fuTpsWPyBAAACACCnR8xeQIAAAQSwc6P3EOxkfTYAQCAACDY+VFRSbkkKdJOsAMAAP5HsPOT0rJyFZcR7AAAQOAQ7PyksLTc8zNDsQAAIBAIdn5SWFLm+dkRxmEGAAD+R+Lwk+OVEyci7CGy2WwWtwYAAJwLCHZ+4u6x4/o6AAAQKAQ7PymsnBEbQbADAAABQrDzk+P02AEAgAAj2PmJO9jRYwcAAAKFYOcnVSdPAAAABEK9bmI6derU+lUWFqYJEybUq2x2drbGjBmjtWvXqnXr1poxY4b69+9fY9mZM2fq6aef1r59+5SSkqJFixapY8eO9dqPVYpKuZ0YAAAIrHoFu9///vcaOXLkKcstWLCg3sFu3LhxSkpK0sGDB7Vy5UqNGDFCP/zwg+Li4rzKLVmyRM8995wWLlyoLl266Mcff6xWpjFy99hxjR0AAAiUegU7l8ulmTNnnrLcihUr6rXT/Px8LVq0SDt37lRUVJTS09M1bdo0LVmyRHfccYdX2SeeeEJ//vOf1bVrV0lS+/bt66y7qKhIRUVFnt9zc3Pr1SZf4xo7AAAQaPW6ACw7O7telf3000/1Krd9+3a5XC4lJiZ6tvXo0UNbt271KldWVqYvv/xSmzdvVnJyss477zxNnjxZxpha654yZYpcLpfn0bp163q1yddY7gQAAATaaV3ZX1RUpEOHDnn1jDVEfn6+YmNjvbbFxsYqPz/fa9v+/ftVWlqq1atXa8uWLfrwww81b948zZo1q9a6J02apJycHM8jMzPztNp4pljuBAAABFq9g11paakee+wxtW/fXlFRUUpISFBUVJQ6dOigxx9/XCUlJfXeqdPprDZEmpubK6fT6bUtMjJSkvTwww+rSZMmSklJ0bhx47Rs2bJa63Y4HIqNjfV6WMFz5wkmTwAAgACpd7C7++679dFHH+mVV15Rdna2iouLlZ2drb///e/6+OOP9etf/7reO01NTVVOTo6ysrI82zZu3Oi5js4tLi5OSUlJXtvqGoZtTNzBLiKM5U4AAEBg1Dt1vP3221q0aJH69eunpk2bKiwsTE2bNtU111yjt99+WwsWLKj3Tp1Op4YPH66MjAwdP35cixcv1pYtWzRs2LBqZceMGaOpU6cqLy9P+/bt04svvqihQ4fWe19W8axjR48dAAAIkHoHu5iYGH3//fc1/m3Hjh2KiYlp0I5nzJihzMxMxcfHa+LEiZo/f77i4uI0e/Zsr567jIwMJSYmKjk5WRdffLFuuOEGjR49ukH7sgLX2AEAgECr13InUsWyIwMGDNAtt9yitLQ0xcbGKjc3V5s2bdJbb72l5557rkE7TkhIqPFauZEjR3qtmRceHq6XX35ZL7/8coPqt1ohy50AAIAAq3ewGzNmjHr27Kk5c+ZoxYoVys/Pl9PpVJcuXbR27Vp169bNn+0867iXO6HHDgAABEq9g50kpaWlKS0tzV9tCSosUAwAAAKtXtfYLV68uF6VLV269IwaE0w8txRj8gQAAAiQegW7UaNG1auyk28Hdi4rLGW5EwAAEFj1GorNz89XVFRUnWWMMQoJIcS4FdJjBwAAAqxewW7Hjh2SKsLbO++8o6FDh8rhcFQrZ7PZfNu6sxjLnQAAgECrV7Br06aN5+e3335bTz75pNLT0zVy5Ej169ePQFcD96xYJk8AAIBAafDY6b///W99+eWX6tSpkyZMmKDk5GSNHz9en3/+uT/ad1YyxjArFgAABNxpXRSXkpKihx56SF999ZUWLlyolStX6pJLLlFqaqqmTJmi/Px8X7fzrFJUWu75mWvsAABAoJxWsCspKdGiRYt066236rrrrlPHjh01f/58vfHGG9q8ebOuvfZaX7fzrOJe6kRiViwAAAicBi1QLEljx47VokWL1K1bN40cOVIzZsxQXFyc5+89e/aUy+XyaSPPNu6lTuyhNoWFEuwAAEBgNDjYdejQQV988YXXhIqq7Ha79uzZc8YNO5u5e+y4vg4AAARSg4Pdb3/721OWadq06Wk1Jliw1AkAALAC44R+wFInAADACgQ7Pyikxw4AAFiAYOcHnmvsWOoEAAAEEMHOD9yzYlnqBAAABBLJww/cPXYsTgwAAAKJYOcHXGMHAACsQLDzA5Y7AQAAViDY+YF7uRMHwQ4AAAQQwc4P6LEDAABWINj5wYnJExxeAAAQOCQPPyjyLHdCjx0AAAgcgp0fsNwJAACwAsHOD9zX2HGvWAAAEEgEOz9wz4ol2AEAgEAi2PkBs2IBAIAVCHZ+4LnzBLNiAQBAAJE8/MAd7JgVCwAAAolg5wdFpdx5AgAABB7Bzg+K3LcUC+PwAgCAwCF5+IF7gWKCHQAACCSShx94hmK5xg4AAAQQwc4Pij3X2HF4AQBA4JA8fKy0rFyl5UaSFB7K4QUAAIFD8vCx4rJyz8/02AEAgEAiefiYe0asRI8dAAAILJKHj7knToSF2BRGsAMAAAFE8vAxz8QJljoBAAABRvrwMfcaduEEOwAAEGCkDx9jDTsAAGAVgp2Pee46wYxYAAAQYKQPH+M+sQAAwCqkDx8rKmMoFgAAWINg52PuHjsmTwAAgEAjffiY5xo7gh0AAAgw0oePFbGOHQAAsAjpw8eKWe4EAABYxLJgl52draFDhyoqKkqdOnXS6tWr6yy/c+dORUZG6te//nWAWnh6PD12LHcCAAACLMyqHY8bN05JSUk6ePCgVq5cqREjRuiHH35QXFxcjeXHjx+viy66KMCtbDjPnSe4TywAAAgwS9JHfn6+Fi1apMmTJysqKkrp6enq1q2blixZUmP59957T8YYDRw48JR1FxUVKTc31+sRSJ517OixAwAAAWZJ+ti+fbtcLpcSExM923r06KGtW7dWK1tcXKwHH3xQzz77bL3qnjJlilwul+fRunVrn7W7PrilGAAAsIplPXaxsbFe22JjY5Wfn1+t7LRp0zRkyBB16NChXnVPmjRJOTk5nkdmZqZP2lxfxcyKBQAAFrHkGjun01ltiDQ3N1dOp9Nr2969e/Xqq6/qv//9b73rdjgccjgcPmnn6fBcY0ewAwAAAWZJsEtNTVVOTo6ysrLUsmVLSdLGjRt15513epXbsGGDMjMzlZqaKqmip6+8vFw7d+7UihUrAt7u+mAoFgAAWMWyHrvhw4crIyNDzz//vFatWqUtW7Zo2LBhXuUGDx6sHTt2eH5/9tlnlZ2drWnTpgW6yfXGAsUAAMAqlqWPGTNmKDMzU/Hx8Zo4caLmz5+vuLg4zZ49W127dpVUMazasmVLz8PpdCoyMlLx8fFWNfuUikoqbynGrFgAABBgNmOMsboR/pSbmyuXy6WcnJxqEzb8YczMz/TBd9l6dkQP3dgz2e/7AwAAwa0hWYZuJR9zr2PH5AkAABBopA8fc8+K5Ro7AAAQaKQPH2PyBAAAsArpw8eKWe4EAABYhGDnY54eO2bFAgCAACN9+JjnzhOhHFoAABBYpA8fc/fYRdBjBwAAAoz04WPu5U64xg4AAAQawc7HisuYFQsAAKxB+vCh0rJylZVX3MiDBYoBAECgkT58yH19ncRQLAAACDyCnQ9VDXb02AEAgEAjffiQe6kTe6hNoSE2i1sDAADONQQ7H+KuEwAAwEoEOx9yD8UyDAsAAKxAAvGhE2vYcVgBAEDgkUB8yH2NHcEOAABYgQTiQ1xjBwAArESw8yH3NXYO7hMLAAAsQALxIfdQbHgohxUAAAQeCcSH6LEDAABWIoH40IlZsVxjBwAAAo9g50NFZSx3AgAArEMC8aGikspr7Ah2AADAAiQQH/JcY0ewAwAAFiCB+FAR69gBAAALEex8iDtPAAAAK5FAfKiY5U4AAICFSCA+5B6KDQ9lKBYAAAQewc6HPOvY0WMHAAAsQALxIa6xAwAAViKB+FAxs2IBAICFCHY+xDp2AADASiQQH3IPxXLnCQAAYAUSiA+VlBlJBDsAAGANEogPFXuWO+GwAgCAwCOB+FBJWUWwsxPsAACABUggPlRcGewYigUAAFYggfiQeyjWHmqzuCUAAOBcRLDzIYZiAQCAlUggPuSeFcs6dgAAwAokEB86MRTLYQUAAIFHAvEh9+QJOz12AADAAiQQHzHGVLnGjskTAAAg8Ah2PlJWbmQqLrGTIzTU2sYAAIBzEsHOR9zDsJJkD6PHDgAABB7BzkdKSo3nZyZPAAAAK5BAfMTdY2ezSWEh9NgBAIDAI9j5SHGVxYltNoIdAAAIPMuCXXZ2toYOHaqoqCh16tRJq1evrrHchAkT1K5dO8XExKhXr1766KOPAtzS+impXMMunGFYAABgEctSyLhx45SUlKSDBw/qmWee0YgRI3TkyJFq5Vwul1auXKmcnBw9/PDDSk9PV15engUtrpt7qZNw1rADAAAWsSSF5Ofna9GiRZo8ebKioqKUnp6ubt26acmSJdXKZmRkqEOHDgoJCdGIESMUGRmpbdu21Vp3UVGRcnNzvR6BUMwadgAAwGKWBLvt27fL5XIpMTHRs61Hjx7aunVrnc/buXOnDh8+rA4dOtRaZsqUKXK5XJ5H69atfdbuunA7MQAAYDXLeuxiY2O9tsXGxio/P7/W55SUlGj06NF68MEH5XK5ai03adIk5eTkeB6ZmZk+a3ddSsoqljvhGjsAAGCVMCt26nQ6qw2R5ubmyul01ljeGKMxY8aoefPmeuyxx+qs2+FwyOFw+Kqp9cY1dgAAwGqWpJDU1FTl5OQoKyvLs23jxo3q2rVrjeXvv/9+7du3T2+++aZCQhpncGIoFgAAWM2SFOJ0OjV8+HBlZGTo+PHjWrx4sbZs2aJhw4ZVK5uRkaFPPvlEixYtsqQnrr6YPAEAAKxmWffSjBkzlJmZqfj4eE2cOFHz589XXFycZs+e7dVzN3nyZH3zzTdKSkqS0+mU0+nU7NmzrWp2rRiKBQAAVrPkGjtJSkhI0LJly6ptHzlypEaOHOn53RhTrUxjxFAsAACwGinERzw9dgQ7AABgEVKIjxS7lzthKBYAAFiEFOIjJQzFAgAAi5FCfOTErFgOKQAAsAYpxEfcPXbhYSx3AgAArEGw8xEmTwAAAKuRQnykiKFYAABgMVKIj5SUVsyKtTMrFgAAWIQU4iMMxQIAAKuRQnykuJRbigEAAGuRQnykxHONHbNiAQCANQh2PsI6dgAAwGqkEB/xXGPHUCwAALAIKcRHirmlGAAAsBgpxEdKyiqWO2FWLAAAsAopxEeKGYoFAAAWI4X4CEOxAADAaqQQH2G5EwAAYDWCnY8wKxYAAFiNFOIjTJ4AAABWI4X4CNfYAQAAq5FCfIQ7TwAAAKuRQnyEa+wAAIDVSCE+4h6K5Ro7AABgFVKIj3iWOwljuRMAAGANgp0PGGOYFQsAACxHCvEB98QJSbJzjR0AALAIKcQH3L11Ej12AADAOqQQHygprdJjR7ADAAAWIYX4gHviRGiITaEhTJ4AAADWINj5QJHnrhOEOgAAYB2CnQ+UcNcJAADQCJBEfMA9ecLBjFgAAGAhkogPFJfSYwcAAKxHEvGBYoZiAQBAI0AS8QH3NXbhDMUCAAALkUR8gMkTAACgMSCJ+ID7GrtwljsBAAAWItj5AD12AACgMSCJ+EBx5XInXGMHAACsRBLxAZY7AQAAjQFJxAcYigUAAI0BScQH3MGOO08AAAArkUR84MRQLLNiAQCAdQh2PsCdJwAAQGNAEvGBklJmxQIAAOuRRHyAyRMAAKAxIIn4QDH3igUAAI0AScQHmDwBAAAaA8uCXXZ2toYOHaqoqCh16tRJq1evrrHc8ePHNWrUKMXExCglJUVz5swJcEtPzT0UGx4aanFLAADAuSzMqh2PGzdOSUlJOnjwoFauXKkRI0bohx9+UFxcnFe5jIwMHT58WHv37tWWLVs0ZMgQ9ezZUx07drSo5dV5euzC6LEDAADWsaTHLj8/X4sWLdLkyZMVFRWl9PR0devWTUuWLKlW9o033lBGRoZiY2PVp08fDR8+XHPnzrWg1bU70WPHyDYAALCOJT1227dvl8vlUmJiomdbjx49tHXrVq9yR44cUVZWltLS0rzKffbZZ7XWXVRUpKKiIs/vubm5Pmx5zUrKWO4EAABYz7Ieu9jYWK9tsbGxys/Pr1YuNDRUUVFRdZarasqUKXK5XJ5H69atfdv4GvQ/v7nuvOI8dUmMPXVhAAAAP7Ek2Dmdzmo9abm5uXI6ndXKlZWV6dixY3WWq2rSpEnKycnxPDIzM33b+BrccFGyfn99F/Vq29Tv+wIAAKiNJcEuNTVVOTk5ysrK8mzbuHGjunbt6lUuLi5OLVu21ObNm+ssV5XD4VBsbKzXAwAA4FxgWY/d8OHDlZGRoePHj2vx4sXasmWLhg0bVq3sqFGj9MQTTygvL0/r16/X4sWLdfPNN1vQagAAgMbNsqv9Z8yYoczMTMXHx2vixImaP3++4uLiNHv2bK8eucmTJ3smWowYMUIzZsxQp06drGo2AABAo2UzxhirG+FPubm5crlcysnJYVgWAACcdRqSZVifAwAAIEgQ7AAAAIIEwQ4AACBIEOwAAACCBMEOAAAgSBDsAAAAggTBDgAAIEgQ7AAAAIIEwQ4AACBIEOwAAACCRJjVDfA39x3TcnNzLW4JAABAw7kzTH3uAhv0wS4vL0+S1Lp1a4tbAgAAcPry8vLkcrnqLGMz9Yl/Z7Hy8nLt27dPMTExstlsftlHbm6uWrdurczMzFPenBf+xXvRePBeNA68D40H70XjcDa+D8YY5eXlKSkpSSEhdV9FF/Q9diEhIUpOTg7IvmJjY8+aD0mw471oPHgvGgfeh8aD96JxONveh1P11LkxeQIAACBIEOwAAACCBMHOBxwOhzIyMuRwOKxuyjmP96Lx4L1oHHgfGg/ei8Yh2N+HoJ88AQAAcK6gxw4AACBIEOwAAACCBMEOAAAgSBDsAAAAggTB7gxlZ2dr6NChioqKUqdOnbR69Wqrm3TOuvrqqxURESGn0ymn06nBgwdb3aRzQkZGhrp06aKQkBDNnTvX629//OMflZCQoKZNm+qhhx6q130Ocfpqey9mzZqlsLAwz7nhdDq1e/duC1sa3IqKivTLX/5SycnJcrlcuvrqq7V582bP3zkvAqeu9yJYzwuC3RkaN26ckpKSdPDgQT3zzDMaMWKEjhw5YnWzzlmzZs1Sfn6+8vPztXz5cqubc05ITU3V9OnT1bt3b6/ty5Yt0wsvvKBPP/1UW7du1dKlSzVz5kyLWnluqO29kKQBAwZ4zo38/HylpKRY0MJzQ2lpqdq1a6f169fr8OHDGj58uNLT0yVxXgRaXe+FFJznBcHuDOTn52vRokWaPHmyoqKilJ6erm7dumnJkiVWNw0ImFGjRmngwIGKiIjw2v7GG2/o3nvvVbt27ZSYmKiJEyfqzTfftKiV54ba3gsEVnR0tP7whz8oOTlZoaGhuu+++7Rjxw4dOnSI8yLA6novghXB7gxs375dLpdLiYmJnm09evTQ1q1bLWzVue3+++9XQkKCBg4cqE2bNlndnHPa119/rbS0NM/vnBvW+uSTTxQfH68uXbroxRdftLo555R169apRYsWio+P57ywWNX3QgrO8yLM6gaczfLz86vdQDg2NlZHjx61pkHnuKlTp6pLly4KDQ3VX//6Vw0ZMkTffvutnE6n1U07J518fsTGxio/P9/CFp27+vbtq82bNyslJUUbNmzQz3/+c7Vo0UI///nPrW5a0MvJydHdd9+tp556ShLnhZVOfi+C9bygx+4MOJ1O5ebmem3Lzc0lSFikd+/ecjqdioyM1EMPPSSn06nPPvvM6mads04+Pzg3rHPeeeepbdu2CgkJ0SWXXKL//d//1TvvvGN1s4JeYWGh0tPTNXToUI0dO1YS54VVanovgvW8INidgdTUVOXk5CgrK8uzbePGjeratauFrYJbSAgfbyt16dLFayYg50bjwbnhf6WlpbrllluUlJSkZ5991rOd8yLwansvThYs50VwvAqLOJ1ODR8+XBkZGTp+/LgWL16sLVu2aNiwYVY37Zxz9OhRrVq1SkVFRSouLtaf//xnHT58WL169bK6aUGvpKREhYWFKi8v9/p51KhReuGFF7Rjxw5lZWVp2rRpGjVqlNXNDWq1vRcrVqxQdna2JOmLL77QX/7yF11//fUWtza43XXXXTp+/LhmzZolm83m2c55EXi1vRdBe14YnJEDBw6YwYMHm8jISJOammpWrVpldZPOSQcOHDA9e/Y00dHRJi4uzvTr18/897//tbpZ54TRo0cbSV6PtWvXGmOMefrpp018fLxp0qSJefDBB015ebm1jQ1ytb0XEyZMMAkJCSY6Otp07NjR/OUvf7G6qUFt586dRpKJiIgw0dHRnsdHH31kjOG8CKS63otgPS9sxrAyIgAAQDBgKBYAACBIEOwAAACCBMEOAAAgSBDsAAAAggTBDgAAIEgQ7AAAAIIEwQ4AACBIEOwAAACCBMEOwDlj9+7datasmV/3sXPnTtlsNjmdTi1cuNBn9W7YsEFOp1MhISFav369z+oFEFzCrG4AAPiS0+n0/FxQUKCoqCjP/SG//vprHTx40O9tcDgcys/P92mdF198sfLz89W2bVuf1gsguBDsAASVqoEqIiJCW7duJQwBOGcwFAvgnLFz505FRER4frfZbHrhhReUkpKiZs2aad68eVq6dKnatWun5s2ba968eZ6yhw8f1m233abmzZurXbt2eu211+q938cee0y333670tPT5XQ6NXDgQB04cEA33XSTYmNjdd111ykvL0+StG3bNl1xxRWKjY1Vs2bN9Jvf/MZ3BwBA0CPYATinffLJJ9q2bZteeOEF3XvvvXr77be1ZcsW/eMf/9B9992nsrIySdLtt9+u1q1bKzMzU8uWLdOkSZO0cePGeu9n4cKFevjhh3XgwAEdPXpUV1xxhe6//34dOHBA+fn5evXVVyVJjz76qIYOHaqcnBzt2rVLN998s19eN4DgRLADcE576KGHFBERoRtuuEFHjx7Vvffeq6ioKA0bNkx5eXnat2+fsrKy9PHHH+vpp5+Ww+FQ586dddttt+lf//pXvfczcOBAXXbZZYqKitKQIUOUmpqqK6+8UhERERo6dKg2bdokSbLb7dqxY4eysrIUHR2t3r17++ulAwhCBDsA57TmzZtLkkJDQ2W325WQkOD5W0REhAoKCrR7924VFBQoPj5eTZo0UZMmTfTSSy9p//79Dd6PJEVGRnrtJzIyUgUFBZKkqVOnqrS0VBdccIF69OihJUuWnOlLBHAOYfIEAJxCq1at1KRJEx06dMjv+0pMTNSrr74qY4wWL16sm2++WUePHlV4eLjf9w3g7EePHQCcQqtWrXTxxRfr0Ucf1bFjx1RaWqovvvhCX3/9tc/3tWDBAu3bt082m01NmjSRzWbzLNcCAKdCsAOAepg9e7Z27drlmTH7wAMP6Pjx4z7fz2effaaePXvK6XTqnnvu0T//+U/Z7Xaf7wdAcLIZY4zVjQCAYLFr1y517txZDodDr7/+uoYPH+6Tej///HMNGDBARUVF+vDDD5lUAaBGBDsAAIAgwVAsAABAkCDYAQAABAmCHQAAQJAg2AEAAAQJgh0AAECQINgBAAAECYIdAABAkCDYAQAABAmCHQAAQJAg2AEAAASJ/w/T9oJqkxzJSgAAAABJRU5ErkJggg==", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "# Compute the transfer function from r to y\n", - "T_shape = ct.feedback(ltf_shape)\n", - "ct.step_response(T_shape).plot(time_label=\"Time [ms]\")\n", - "plt.suptitle(\"Step response for servomechanism with PID controller\")" - ] - }, - { - "cell_type": "markdown", - "id": "JL99vo4trep5", - "metadata": { - "id": "JL99vo4trep5" - }, - "source": [ - "### Closed loop frequency response\n", - "\n", - "We can also look at the closed loop frequency response to understand how different inputs affect different outputs. The `gangof4` function computes the standard transfer functions:" - ] - }, - { - "cell_type": "code", - "execution_count": 14, - "id": "ceqcg3oM619g", - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "ct.gangof4(P_tf, ctrl_shape);" - ] - }, - { - "cell_type": "markdown", - "id": "gel18-iqwYYs", - "metadata": { - "id": "gel18-iqwYYs" - }, - "source": [ - "### Stability margins\n", - "\n", - "Another standard set of analysis tools is to identify the gain, phase, and stability margins for the sytem:\n", - "\n", - "* **Gain margin:** the maximimum amount of additional gain that we can put into the loop and still maintain stability.\n", - "* **Phase margin:** the maximum amount of additional phase (lag) that we can put into the loop and still maintain stability.\n", - "* **Stability margin:** the maximum amount of combined gain and phase at the critical frequency that can be put into the loop and still maintain stability.\n", - "\n", - "The first two of the items can be computed either by looking at the frequeny response or by using the `margin` command.\n", - "\n", - "The stabilty margin is the minimum distance between -1 and $L(jw)$, which is just the minimum value of $|1 - L(j\\omega)|$.\n", - "\n" - ] - }, - { - "cell_type": "code", - "execution_count": 15, - "id": "m-8ItbHwxLrv", - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "Gm = inf (at nan rad/ms)\n", - "Pm = 47 deg (at 0.15 rad/ms)\n", - "Sm = 0.6 (at 0.19 rad/ms)\n" - ] - }, - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "plt.figure(figsize=[7, 4])\n", - "\n", - "# Gain and phase margin on Bode plot\n", - "ax1 = plt.subplot(2, 2, 1)\n", - "plt.title(\"Bode plot for Lnew, with margins\")\n", - "ax2 = plt.subplot(2, 2, 3)\n", - "ct.bode_plot(Lnew, ax=[ax1, ax2], margins=True)\n", - "\n", - "# Compute gain and phase margin\n", - "gm, pm, wpc, wgc = ct.margin(Lnew)\n", - "print(f\"Gm = {gm:2.2g} (at {wpc:.2g} rad/ms)\")\n", - "print(f\"Pm = {pm:3.2g} deg (at {wgc:.2g} rad/ms)\")\n", - "\n", - "# Compute the stability margin\n", - "resp = ct.frequency_response(1 + Lnew)\n", - "sm = np.min(resp.magnitude)\n", - "wsm = resp.omega[np.argmin(resp.magnitude)]\n", - "print(f\"Sm = {sm:2.2g} (at {wsm:.2g} rad/ms)\")\n", - "\n", - "# Plot the Nyquist curve\n", - "ax3 = plt.subplot(1, 2, 2)\n", - "ct.nyquist_plot(Lnew, ax=ax3)\n", - "plt.title(\"Nyquist plot for Lnew [zoomed]\")\n", - "plt.axis([-2, 3, -2.6, 2.6])\n", - "\n", - "#\n", - "# Annotate it to see the margins\n", - "#\n", - "\n", - "# Gain margin (special case here, since infinite)\n", - "Lgm = 0\n", - "plt.plot([-1, Lgm], [0, 0], 'k-', linewidth=0.5)\n", - "plt.text(-0.9, 0.1, \"1/gm\")\n", - "\n", - "# Phase margin\n", - "theta = np.linspace(0, 2 * pi)\n", - "plt.plot(np.cos(theta), np.sin(theta), 'k--', linewidth=0.5)\n", - "plt.text(-1.3, -0.8, \"pm\")\n", - "\n", - "# Stability margin\n", - "Lsm = Lnew(wsm * 1j)\n", - "plt.plot([-1, Lsm.real], [0, Lsm.imag], 'k-', linewidth=0.5)\n", - "plt.text(-0.4, -0.5, \"sm\")\n", - "\n", - "plt.suptitle(\"\")\n", - "plt.tight_layout()" - ] - }, - { - "cell_type": "markdown", - "id": "WsOzQST9rFC-", - "metadata": { - "id": "WsOzQST9rFC-" - }, - "source": [ - "## Unstable system: inverted pendulum\n", - "\n", - "When we have a system that is open loop unstable, the Nyquist curve will need to have encirclements to be stable. In this case, the interpretation of the various characteristics can be more complicated.\n", - "\n", - "To explore this, we consider a simple model for an inverted pendulum, which has (normalized) dynamics:\n", - "\n", - "$$\n", - "\\dot x = \\begin{bmatrix} 0 & 1 & \\\\ -1 & 0.1 \\end{bmatrix} x + \\begin{bmatrix} 0 \\\\ 1 \\end{bmatrix} u, \\qquad\n", - "y = \\begin{bmatrix} 1 & 0 \\end{bmatrix} x\n", - "$$\n", - "\n", - "Transfer function for the system can be shown to be\n", - "\n", - "$$\n", - "P(s) = \\frac{1}{s^2 + 0.1 s - 1}.\n", - "$$\n", - "\n", - "This system is unstable, with poles $\\sim\\pm 1$." - ] - }, - { - "cell_type": "code", - "execution_count": 16, - "id": "ZbPzrlPIrHnp", - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "array([-1.05124922+0.j, 0.95124922+0.j])" - ] - }, - "execution_count": 16, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "ct.set_defaults('freqplot', freq_label=\"Frequency [{units}]\")\n", - "\n", - "P = ct.tf([1], [1, 0.1, -1])\n", - "P.poles()" - ] - }, - { - "cell_type": "markdown", - "id": "W-sBWxKi6SPx", - "metadata": { - "id": "W-sBWxKi6SPx" - }, - "source": [ - "### PD controller\n", - "\n", - "We construct a proportional-derivative (PD) controller for the system,\n", - "\n", - "$$\n", - "u = k_\\text{p} e + k_\\text{d} \\dot{e}\n", - "$$\n", - "\n", - "which is roughly the equivalent of using state feedback (since the system states are $\\theta$ and $\\dot\\theta$)." - ] - }, - { - "cell_type": "code", - "execution_count": 17, - "id": "hjQS_dED7yJE", - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - ": L\n", - "Inputs (1): ['u[0]']\n", - "Outputs (1): ['y[0]']\n", - "\n", - "\n", - " 2 s + 10\n", - "---------------\n", - "s^2 + 0.1 s - 1\n", - "\n", - "Zeros: [-5.+0.j]\n", - "Poles: [-1.05124922+0.j 0.95124922+0.j]\n" - ] - } - ], - "source": [ - "# Transfer function for a PD controller\n", - "kp = 10\n", - "kd = 2\n", - "C = ct.tf([kd, kp], [1])\n", - "\n", - "# Loop transfer function\n", - "L = P * C\n", - "L.name = 'L'\n", - "print(L)\n", - "print(\"Zeros: \", L.zeros())\n", - "print(\"Poles: \", L.poles())" - ] - }, - { - "cell_type": "code", - "execution_count": 18, - "id": "YI_KJo0E9pFd", - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "# Bode and Nyquist plots\n", - "plt.figure(figsize=[7, 4])\n", - "ax1 = plt.subplot(2, 2, 1)\n", - "plt.title(\"Bode plot for L\", size='medium')\n", - "ax2 = plt.subplot(2, 2, 3)\n", - "ct.bode_plot(L, ax=[ax1, ax2])\n", - "\n", - "ax3 = plt.subplot(1, 2, 2)\n", - "ct.nyquist_plot(L, ax=ax3)\n", - "plt.title(\"Nyquist plot for L\", size='medium')\n", - "\n", - "ct.suptitle(\"Loop analysis for inverted pendulum\")\n", - "plt.tight_layout()" - ] - }, - { - "cell_type": "code", - "execution_count": 19, - "id": "8dH03kv9-Da8", - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "N = encirclements: -1\n", - "P = RHP poles of L: 1\n", - "Z = N + P = RHP zeros of 1 + L: 0\n", - "Poles of L = [-1.05124922+0.j 0.95124922+0.j]\n", - "Zeros of 1 + L = [-1.05+2.8102491j -1.05-2.8102491j]\n", - "\n" - ] - }, - { - "name": "stderr", - "output_type": "stream", - "text": [ - "/Users/murray/src/python-control/murrayrm/control/timeresp.py:1027: UserWarning: Non-zero initial condition given for transfer function system. Internal conversion to state space used; may not be consistent with given X0.\n", - " warnings.warn(\n" - ] - }, - { - "data": { - "image/png": "iVBORw0KGgoAAAANSUhEUgAAAnYAAAHbCAYAAABGPtdUAAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjguNCwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy8fJSN1AAAACXBIWXMAAA9hAAAPYQGoP6dpAABY10lEQVR4nO3deXhTZfo+8PskadOmadJ9o2Vp6UJpBQQEUQQ3UFmsC+MGggyo44JOR8dhRJYOijrqKM4wbr8BR+qCyurXQRBBURZlLy1LKS2UQumeNF3SJjm/P9JEaltoadNzkt6f68rVNjk55zlhu3ne875HEEVRBBERERG5PYXUBRARERFR12CwIyIiIvIQDHZEREREHoLBjoiIiMhDMNgREREReQgGOyIiIiIPwWBHRERE5CEY7IiIiIg8BIMdERERkYdgsCOSMUEQsHbt2otuM2PGDKSlpbV7nwUFBRAEAQcOHOhUbT3JwoULER4e3q5fD7lYuHAhBEGAIAh48803u/3427Ztcx6/I78/iahzGOyIuklHAxgAnDt3DrfeeiuAtgPZW2+9hRUrVnRNkdTCkSNHsGjRIrz77rvNfj3cwcCBA3Hu3Dk8/PDDzufee+89jB07FjqdDoIgoKqqqsX7KisrMW3aNOj1euj1ekybNq3ZdgcPHsR9992HmJgY+Pr6YsCAAXjrrbea7WPUqFE4d+4cfve737nq9IioFSqpCyCitkVERFxyG71e7/I6Ghoa4O3t7fLjyFFeXh4A4Pbbb4cgCJe9n8bGRnh5eXVVWe2iUqla/B6qra3FLbfcgltuuQVz585t9X33338/zpw5g40bNwIAHn74YUybNg0bNmwAAOzduxehoaFYuXIlYmJisGPHDjz88MNQKpV44oknAADe3t6IiIiAr68vzGazC8+SiC7Ejh2RRMaOHYs5c+bgz3/+M4KCghAREYGFCxc22+bCob9+/foBAIYMGQJBEDB27FgALTuBGzduxLXXXouAgAAEBwdj4sSJznDSXn379sXixYsxY8YM6PV6zJ49GwCwY8cOXHfddfD19UVMTAzmzJmDmpoa5/uWLVuG+Ph4+Pj4IDw8HHfffXez833iiSfwxBNPOGubN28eRFF0blNZWYkHH3wQgYGB0Gg0uPXWW5Gbm+t8fcWKFQgICMA333yDAQMGQKvV4pZbbsG5c+ec22zbtg1XXXUV/Pz8EBAQgGuuuQanTp1yvr5hwwYMHToUPj4+iI2NxaJFi2CxWFr9HBYuXIhJkyYBABQKhTPY2Ww2ZGRkIDo6Gmq1GoMHD3aGIODX7uqqVaswduxY+Pj4YOXKlW0eo3fv3lCr1YiKisKcOXMAABkZGUhNTW2x/dChQzF//vx2nWtrnn76afzlL3/ByJEjW339yJEj2LhxIz744ANcffXVuPrqq/H+++/jq6++wrFjxwAAM2fOxNKlSzFmzBjExsZi6tSpeOihh7B69eqLHpuIXI/BjkhCH374Ifz8/LB79268+uqryMjIwObNm1vd9ueffwYAfPvttzh37lyb/4jW1NQgPT0dv/zyC7Zs2QKFQoE77rgDNputQ7X9/e9/R0pKCvbu3YsXXngBWVlZGD9+PO68804cOnQIn332GX788Udnh2bPnj2YM2cOMjIycOzYMWzcuBHXXXddi/NVqVTYvXs3li5din/84x/44IMPnK/PmDEDe/bswfr167Fz506IoojbbrsNjY2Nzm1qa2vx2muv4aOPPsIPP/yA06dP45lnngEAWCwWpKWlYcyYMTh06BB27tyJhx9+2BnIvvnmG0ydOhVz5sxBTk4O3n33XaxYsQIvvvhiq5/BM888g+XLlwOwD4s7AuRbb72F119/Ha+99hoOHTqE8ePHY/Lkyc1CKAA899xzmDNnDo4cOYLx48e32P8XX3yBf/zjH3j33XeRm5uLtWvXOsPczJkzkZOTg19++cW5/aFDh7B//37MmDHjkud6uXbu3Am9Xo8RI0Y4nxs5ciT0ej127NjR5vsMBgOCgoI6dWwi6gIiEXWL6dOni7fffrvz5zFjxojXXntts22GDx8uPvfcc86fAYhr1qwRRVEU8/PzRQDi/v37L7rf3yopKREBiFlZWRfdz4X69OkjpqWlNXtu2rRp4sMPP9zsue3bt4sKhUKsq6sTv/zyS1Gn04lGo7HVfY4ZM0YcMGCAaLPZnM8999xz4oABA0RRFMXjx4+LAMSffvrJ+XpZWZno6+srrlq1ShRFUVy+fLkIQDxx4oRzm3/9619ieHi4KIqiWF5eLgIQt23b1moNo0ePFl966aVmz3300UdiZGRkm5/FmjVrxN/+VRkVFSW++OKLzZ4bPny4+Nhjj4mi+Otn/Oabb7a5X1EUxddff11MSEgQGxoaWn391ltvFf/whz84f3766afFsWPHiqJ46XNdsGCBOGjQoDaPvXXrVhGAWFlZ2ez5F198UYyPj2+xfXx8fIvPzmHHjh2il5eXuGnTphavXer3JxF1LXbsiCR0xRVXNPs5MjISJSUlndpnXl4e7r//fsTGxkKn0zmHcE+fPt2h/QwbNqzZz3v37sWKFSug1Wqdj/Hjx8NmsyE/Px8333wz+vTpg9jYWEybNg2ZmZmora1tto+RI0c26yhdffXVyM3NhdVqxZEjR6BSqZp1ioKDg5GYmIgjR444n9NoNIiLi3P+fOFnFhQUhBkzZmD8+PGYNGkS3nrrrWbDtHv37kVGRkazc5g9ezbOnTvXota2GI1GnD17Ftdcc02z56+55ppmdbb2Gf7WlClTUFdXh9jYWMyePRtr1qxpNiw8e/ZsfPLJJ6ivr0djYyMyMzMxc+bMdp1rZ7TW9RNFsdXns7Ozcfvtt2P+/Pm4+eabu+T4RHT5GOyIJPTbi+kFQejwkOlvTZo0CeXl5Xj//fexe/du7N69G4B9AkRH+Pn5NfvZZrPhkUcewYEDB5yPgwcPIjc3F3FxcfD398e+ffvwySefIDIyEvPnz8egQYNanXXZGvGCa+1++/yFgaK1z+zC9y5fvhw7d+7EqFGj8NlnnyEhIQG7du1ynsOiRYuanUNWVhZyc3Ph4+PTrjovPO7F6gRafoa/FRMTg2PHjuFf//oXfH198dhjj+G6665zDj1PmjQJarUaa9aswYYNG2A2m3HXXXe161wvV0REBM6fP9/i+dLSUoSHhzd7LicnBzfccANmz56NefPmdeq4RNQ1GOyI3IRjVqrVam1zm/Lychw5cgTz5s3DjTfeiAEDBqCysrJLjn/llVciOzsb/fv3b/Fw1KZSqXDTTTfh1VdfxaFDh1BQUIDvvvvOuY/fho5du3YhPj4eSqUSycnJsFgsziDqOJ/jx49jwIABHap1yJAhmDt3Lnbs2IGUlBR8/PHHznM4duxYq+egULTvr0OdToeoqCj8+OOPzZ7fsWNHh+sEAF9fX0yePBlLly7Ftm3bsHPnTmRlZQGwf57Tp0/H8uXLsXz5ctx7773QaDTtOtfLdfXVV8NgMDiv6QSA3bt3w2AwYNSoUc7nsrOzcf3112P69OltXqNIRN2Py50QuYmwsDD4+vpi48aNiI6Oho+PT4ulTgIDAxEcHIz33nsPkZGROH36NP7yl790yfGfe+45jBw5Eo8//jhmz54NPz8/HDlyBJs3b8bbb7+Nr776CidPnsR1112HwMBAfP3117DZbEhMTHTuo7CwEOnp6XjkkUewb98+vP3223j99dcBAPHx8bj99tsxe/ZsvPvuu/D398df/vIX9OrVC7fffnu7aszPz8d7772HyZMnIyoqCseOHcPx48fx4IMPAgDmz5+PiRMnIiYmBlOmTIFCocChQ4eQlZWFxYsXt/uzePbZZ7FgwQLExcVh8ODBWL58OQ4cOIDMzMwOfKL2Wb5WqxUjRoyARqPBRx99BF9fX/Tp08e5zaxZs5yB8aeffmr3ubaluLgYxcXFOHHiBAAgKysL/v7+6N27N4KCgjBgwADccsstzl8HwL7cycSJE52/lo5QN27cOKSnp6O4uBgAoFQqERoa2qHPgIi6FoMdkZtQqVRYunQpMjIyMH/+fIwePRrbtm1rto1CocCnn36KOXPmICUlBYmJiVi6dKlzaZTOuOKKK/D999/j+eefx+jRoyGKIuLi4nDPPfcAAAICArB69WosXLgQ9fX1iI+PxyeffIKBAwc69/Hggw+irq4OV111FZRKJZ588slmi+cuX74cTz31FCZOnIiGhgZcd911+Prrr9u9/ptGo8HRo0fx4Ycfory8HJGRkXjiiSfwyCOPAADGjx+Pr776ChkZGXj11Vfh5eWFpKQkzJo1q0OfxZw5c2A0GvGnP/0JJSUlSE5Oxvr16xEfH9+h/QQEBODll19Geno6rFYrUlNTsWHDBgQHBzu3iY+Px6hRo1BeXt7s+sNLnWtb3nnnHSxatMj5s2Pm8vLlyzFjxgwAQGZmJubMmYNx48YBACZPnox//vOfzvd8/vnnKC0tRWZmZrMw26dPHxQUFHToMyCiriWIbV3YQkTUhcaOHYvBgwdLcnsrdyaKIpKSkvDII48gPT293e9buHAh1q5dK/mt42bMmIGqqiq3uRUbkbvjNXZERDJVUlKCN954A0VFRXjooYc6/P6srCxotVosW7bMBdVd3Pbt26HVajs8PE1EncOhWCIimQoPD0dISAjee+89BAYGdui9c+bMwdSpUwFAkuvehg0b5uwWarXabj8+UU/FoVgiIiIiD8GhWCIiIiIPwWBHRERE5CEY7IiIiIg8BIMdERERkYdgsCMiIiLyEAx2RERERB6CwY6IiIjIQzDYEREREXkIBjsiIiIiD8FgR0REROQhGOyIiIiIPASDHREREZGHYLAjIiIi8hAMdkREREQegsGOiIiIyEMw2BERERF5CAY7IiIiIg/BYEdERETkIVRSF+AObDYbzp49C39/fwiCIHU5RERE1IOIoojq6mpERUVBobh4T47Brh3Onj2LmJgYqcsgIiKiHqywsBDR0dEX3YbBrh38/f0B2D9QnU4ncTVERETUkxiNRsTExDjzyMUw2LWDY/hVp9Mx2BEREZEk2nM5GCdPEBEREXkIBjsiIiIiD8FgR0REROQhGOyIiIiIPASDHREREZGHYLAjIiIi8hAMdkREREQegsGOiIiIyEMw2BERERF5CAY7IiIiIg/BYEdERETkIRjsiIiIiDwEgx0RERGRh2Cwc3NVtQ14+tP9WLolF/WNVqnLISIiIgmppC6AOmfh+mysPXAWALBmfxFevCMFo+JCJK6KiIiIpMCOnRvbnHMeaw+chUIAQv3VyC+rwf3v78aznx9EZU2D1OURERFRN2Owc1NVtQ3465osAMDD18Vhy5/GYNrIPhAE4PO9Z3DjG99j27ESiaskIiKi7sRg56YyvspBabUZcaF+ePqmeOh8vPC3tBR88egoJIb7o6KmAemrDsJs4XV3REREPQWDnRv67uh5rN5XBIUA/H3KIPh4KZ2vDe0TiA1PXosInQ8qahrwTfZ5CSslIiKi7iT7YFdaWooJEyZAo9EgMTERW7ZsaXW79PR0xMbGwt/fH8OGDcMPP/zgfG3btm1QKBTQarXOx/bt27vrFLqUoa4Rc1fbh2BnjY7Flb0DW2zjrVLgnuExAIDMXae6tT4iIiKSjuyD3eOPP46oqCiUlZXhlVdewZQpU1BZWdliO71ej02bNsFgMOC5555DWloaqqurna8nJCTAZDI5H6NHj+7O0+gyi7/KwXmjGbEhfki/OaHN7e69KgYKAdidX4ETJaZurJCIiIikIutgZzKZsG7dOmRkZECj0SAtLQ0pKSnYsGFDi20XLFiA/v37Q6FQYMqUKfD19cXx48clqNp1Dp2pwud7z0AQgFfvvqLZEOxvRep9cUNSOADg492nu6tEIiIikpCsg11ubi70ej0iIyOdzw0aNAjZ2dkXfV9BQQEqKirQv3//Zs+FhYUhPj4eGRkZsFrbnlRgNpthNBqbPeRg69FSAMAtAyMwrG/QJbd/YGRvAMAXewu5eDEREVEPIOtgZzKZoNPpmj2n0+lgMrU9tNjY2Ijp06fj2WefhV6vBwAkJSXhwIEDKC4uxrp167Bq1SosXbq0zX0sWbIEer3e+YiJiemaE+qkHXllAIDR8aHt2v66+FD0CvCFsd6C/zt0zpWlERERkQzIOthptdoW3TKj0QitVtvq9qIoYsaMGQgLC8PChQudz0dERCApKQkKhQLJycmYN28e1qxZ0+Zx586dC4PB4HwUFhZ2yfl0Rn2jFftPVwEAro4Lbtd7lAoB94+wd+0yd3MSBRERkaeTdbCLj4+HwWBAcXGx87mDBw9i4MCBrW7/5JNP4uzZs1i5ciUUirZP7WKvAYBarYZOp2v2kNreU5VosNoQqfdB32BNu983ZVg0VAoB+05X4cg5eQwpExERkWvIOthptVpMnjwZCxYsQF1dHdavX4/Dhw9j0qRJLbZdsGABfvrpJ6xbtw5qtbrZa9u2bXN23XJzc7F48WJMnDixW86hqziGYa+ODYYgCO1+X5i/D8YN5CQKIiKinkDWwQ4Ali1bhsLCQgQHB+OZZ57BqlWrEBgYiMzMzGadu4yMDBw5cgRRUVHOteoyMzMBAHv37sXIkSPh5+eHcePGIS0tDenp6VKd0mXZmVcOoP3DsBd6YEQfAMCa/UWoMVu6tC4iIiKSD0EURVHqIuTOaDRCr9fDYDBIMixrMlswaNEmWG0ifnzuekQHtn8oFgBsNhE3vvE98stqsOTOVNx3VW8XVUpERERdrSM5RPYdOwJ+KaiA1Said5Cmw6EOABQKAfddZZ/Z+9kv0k8EISIiItdgsHMDzmHY2I4PwzpMHtQLgH2RY2N9Y5fURURERPLCYOcGHMFuVP/LD3YReh/0C/GDTQR+ya/oqtKIiIhIRhjsZM5Q24jDZw0AOtexA4CRsfa7VTiCIhEREXkWBjuZ251fDlEE4kL9EKbz6dS+RjYFw135DHZERESeiMFO5nZ0YpmT33IEu+yzRhhqeZ0dERGRp2Gwk7ldJ5uur4sL6fS+wnU+iA3xgygCPxfwOjsiIiJPw2AnY2UmM44WVwP4tdvWWSObOn+OwEhERESeg8FOxhzhKynCH0F+3l2yT0dA5AQKIiIiz8NgJ2OduY1YWxwzY48UG1FV29Bl+yUiIiLpMdjJmHP9ui64vs4hzN8HcaH26+x2cz07IiIij8JgJ1PFhnqcLKuBQgCu6hfUpft2LnvC6+yIiIg8CoOdTO07XQkAGBCpg97Xq0v3fbVzAgU7dkRERJ6EwU6m8kpMAICkCF2X73tEP3uwO3LOiMoaXmdHRETkKRjsZOpkWQ0AIDbUr8v3HeqvRnyYFgCvsyMiIvIkDHYydbLU3rGLc0GwA3idHRERkSdisJMhURSRV2rv2MWFal1yDAY7IiIiz8NgJ0Ol1WaYzBYoBKB3sMYlxxjRtJ7d0eJqVPA6OyIiIo/AYCdDJ5qGYXsHaaBWKV1yjBCtGgnhTdfZsWtHRETkERjsZOhkqWPihGuGYR2u5nAsERGRR2GwkyFnsAtxzcQJh1+vs+PMWCIiIk/AYCdDeY4ZsWGu7dhd2ScQAJBbUo26BqtLj0VERESux2AnQyfL7MHO1R27MH81QrRq2ETgaLHRpcciIiIi12Owk5n6RivOVNYBcH3HThAEDIyy39ni8FkGOyIiInfHYCczBeU1EEVA56NCsJ+3y4+X0sse7LKLDC4/FhEREbkWg53MXDgjVhAElx8vJUoPADh8lsGOiIjI3THYyUxeieNWYq4dhnVI6WUPdseLTWiw2LrlmEREROQaDHYyc7LM0bFz7cQJh+hAX+h8VGiw2pBbUt0txyQiIiLXYLCTGedSJ90U7ARBcHbtsos4gYKIiMidMdjJiCiKzmvsumsoFsAFM2N5nR0REZE7Y7CTkdJqM0xmCxQC0DtY023HdXTsDnNmLBERkVtjsJORE03DsL2DNFCrlN123IFNM2OPnKuG1SZ223GJiIioazHYyciFS510p34hftB4K1HXaEV+010viIiIyP0w2MmIY+KEq28l9ltKhYDkyKbr7DiBgoiIyG0x2MmIc+KEi28l1hrnBApeZ0dEROS2GOxk5GSZNB07ABjoWPKE94wlIiJyWwx2MlHfaMWZyjoA0nTsLry1mChyAgUREZE7YrCTiYLyGogioPNRIdjPu9uPHx+uhbdSgep6Cwor6rr9+ERERNR5DHYykVfy64xYQRC6/fheSgWSIv0BcKFiIiIid8VgJxMnnbcS6/5hWAfHBIpsBjsiIiK3xGAnEyfLHB277p844eBYqJhLnhAREbkn2Qe70tJSTJgwARqNBomJidiyZUur26WnpyM2Nhb+/v4YNmwYfvjhh2avr1ixAtHR0dDpdHjooYfQ0NDQHeW3W54MOnYX3lqMEyiIiIjcj+yD3eOPP46oqCiUlZXhlVdewZQpU1BZWdliO71ej02bNsFgMOC5555DWloaqqurAQBZWVlIT0/H2rVrUVhYiIKCAixevLi7T6VNoij+uoadhB27pAh/KBUCymsacN5olqwOIiIiujyyDnYmkwnr1q1DRkYGNBoN0tLSkJKSgg0bNrTYdsGCBejfvz8UCgWmTJkCX19fHD9+HADw8ccf45577sGwYcOg1+vxwgsvYOXKld19Om0qqTbDZLZAIQC9gzWS1eHjpUR801IrvM6OiIjI/cg62OXm5kKv1yMyMtL53KBBg5CdnX3R9xUUFKCiogL9+/cHAOTk5CA1NbXZPvLz81FX1/qyHmazGUajsdnDlRzDsL2DNFCrlC491qUkR/HWYkRERO5K1sHOZDJBp9M1e06n08FkavtG9Y2NjZg+fTqeffZZ6PX6Vvfj+L6t/SxZsgR6vd75iImJ6eypXNR5Yz0Ugn2pE6lduFAxERERuReV1AVcjFarbdEtMxqN0GpbD0CiKGLGjBkICwvDwoUL29yP4/u29jN37lykp6c3296V4e6OIdG4LTUS1fUWlx2jvRwTKHJ4azEiIiK3I+uOXXx8PAwGA4qLi53PHTx4EAMHDmx1+yeffBJnz57FypUroVD8emrJycnIyspqto9+/frB19e31f2o1WrodLpmD1dTq5QI0apdfpxLSQy3L1JcVFUHk1n6oElERETtJ+tgp9VqMXnyZCxYsAB1dXVYv349Dh8+jEmTJrXYdsGCBfjpp5+wbt06qNXNA9L999+PVatWYd++fTAYDHjxxRcxderU7joNt6LXeCHM3/755Z6vlrgaIiIi6ghZBzsAWLZsGQoLCxEcHIxnnnkGq1atQmBgIDIzM5t17jIyMnDkyBFERUVBq9VCq9UiMzMTAJCamorXX38dkyZNQnR0NGJiYvD8889LdUqyl9DUtcs93/a1jERERCQ/gsiVaC/JaDRCr9fDYDB0y7Cs1BZtyMbynwow69p+mDcxWepyiIiIerSO5BDZd+yo+zk6dsdL2LEjIiJyJwx21EJCuH22MK+xIyIici8MdtRC/zB7x+6coR7G+kaJqyEiIqL2YrCjFvS+XgjXOWbGcjiWiIjIXTDYUasc19mdKOFwLBERkbtgsKNWxTcNxx5nx46IiMhtMNhRqxwTKI5zAgUREZHbYLCjVsVzkWIiIiK3w2BHrYpv6tgVG+thqOPMWCIiInfAYEet0vl4IVLvA4ATKIiIiNwFgx21yTEcywkURERE7oHBjtqUEMYJFERERO6EwY7aFO+8tRg7dkRERO6AwY7a9OtQLDt2RERE7oDBjtoU3zQUW1JthqGWM2OJiIjkjsGO2uTv44WoppmxxzkzloiISPYY7OiiOBxLRETkPhjs6KISOIGCiIjIbTDY0UWxY0dEROQ+GOzoohK4SDEREZHbYLCji3LMjC0zmVFZ0yBxNURERHQxDHZ0UX5qFXoF+AIAckvYtSMiIpIzBju6JMcdKHidHRERkbwx2NElOa6zy2WwIyIikjUGO7okx3V2nEBBREQkbwx2dEnOjh3vPkFERCRrDHZ0SbGhfgCAMlMDDHW8ZywREZFcMdjRJfn7eCFcpwYAnCzlcCwREZFcMdhRu8SF2q+zyyutkbgSIiIiaguDHbWLYzg2jx07IiIi2WKwo3ZxdOw4FEtERCRfDHbULhyKJSIikj8GO2oXx1DsqfIaWKw2iashIiKi1jDYUbtE6X3h46VAo1VEYWWd1OUQERFRKxjsqF0UCgGxIU3DsSW8zo6IiEiOGOyo3TgzloiISN4Y7Kjdfp0ZywkUREREcsRgR+0WF+aYGcuOHRERkRwx2FG7xYbYh2JPlrFjR0REJEcMdtRujmvsKmoaUFHTIHE1RERE9FsMdtRuGm8VegX4AuAdKIiIiORI9sGutLQUEyZMgEajQWJiIrZs2dLqdsuWLcPgwYOhUqnw8ssvN3tt27ZtUCgU0Gq1zsf27du7o3yP4+jacQIFERGR/KikLuBSHn/8cURFRaGsrAybNm3ClClTkJeXh8DAwGbbRUVFYfHixfjPf/7T6n4SEhJw9OjR7ijZo8WFarE9t4wTKIiIiGRI1h07k8mEdevWISMjAxqNBmlpaUhJScGGDRtabJuWloaJEydCp9NJUGnPEce17IiIiGRL1sEuNzcXer0ekZGRzucGDRqE7OzsDu+roKAAYWFhiI+PR0ZGBqxWa5vbms1mGI3GZg+yi+VadkRERLIl62BnMpladOB0Oh1Mpo51i5KSknDgwAEUFxdj3bp1WLVqFZYuXdrm9kuWLIFer3c+YmJiLqt+T+RYpPhURS0aLDaJqyEiIqILyTrYabXaFt0yo9EIrVbbof1EREQgKSkJCoUCycnJmDdvHtasWdPm9nPnzoXBYHA+CgsLL6t+TxSuU8PPWwmrTcTpCnbtiIiI5ETWwS4+Ph4GgwHFxcXO5w4ePIiBAwd2ar8KxcVPW61WQ6fTNXuQnSAIzuHYPA7HEhERyYqsg51Wq8XkyZOxYMEC1NXVYf369Th8+DAmTZrUYluLxYL6+npYrdZm3wP25U4cXbfc3FwsXrwYEydO7NZz8SScQEFERCRPsg52gH19usLCQgQHB+OZZ57BqlWrEBgYiMzMzGadu8WLF8PX1xcrV67ECy+8AF9fX3z00UcAgL1792LkyJHw8/PDuHHjkJaWhvT0dKlOye05O3Yl7NgRERHJiSCKoih1EXJnNBqh1+thMBg4LAvg/w6dw+Mf78OQ3gFY89g1UpdDRETk0TqSQ2TfsSP5iQtrGootMYH/LyAiIpIPBjvqsL7BfhAEwFhvQXlNg9TlEBERURMGO+owHy8logN9Adi7dkRERCQPDHZ0WeK45AkREZHsMNjRZYkNcdxajB07IiIiuWCwo8vinEDBYEdERCQbDHZ0WTgUS0REJD8MdnRZYpvuPnGmshZmi1XiaoiIiAhgsKPLFKpVQ6tWwSYCp8trpS6HiIiIwGBHl0kQBGfX7mQZh2OJiIjkgMGOLlu/kKZgx+vsiIiIZIHBji6bY8mT/DLOjCUiIpIDBju6bP1C2bEjIiKSEwY7umyxTUOx+bzGjoiISBYY7OiyOa6xK69pgKG2UeJqiIiIiMGOLpufWoUInQ8A4CSvsyMiIpIcgx11CmfGEhERyQeDHXWKYy07XmdHREQkPQY76hRnx45DsURERJJjsKNOiQu1r2XHoVgiIiLpMdhRpzg6dgXlNbDZRImrISIi6tkY7KhTogN94aUUUN9owzljvdTlEBER9WgMdtQpKqUCvYM0AICTpbzOjoiISEoMdtRpsaGOe8byOjsiIiIpMdhRp8VyLTsiIiJZYLCjTnOsZXeSHTsiIiJJMdhRp/ULcSx5wmvsiIiIpMRgR53m6NgVVdWhvtEqcTVEREQ9F4MddVqwnzf8fVQQReBUea3U5RAREfVYDHbUaYIgXDAzlsOxREREUmGwoy7hmBmbx5mxREREkmGwoy7hCHZcy46IiEg6DHbUJfo5ljzhzFgiIiLJMNhRl4gN4d0niIiIpMZgR12ib4j9frGVtY2orGmQuBoiIqKeicGOuoTGW4UovQ8A3oGCiIhIKgx21GV4nR0REZG0GOyoy/A6OyIiImkx2FGX6Rfi6Ngx2BEREUmBwY66jOOesSd59wkiIiJJMNhRl3EMxRaU18JqEyWuhoiIqOeRfbArLS3FhAkToNFokJiYiC1btrS63bJlyzB48GCoVCq8/PLLLV5fsWIFoqOjodPp8NBDD6GhgUtydLVegb7wVinQYLHhbFWd1OUQERH1OLIPdo8//jiioqJQVlaGV155BVOmTEFlZWWL7aKiorB48WJMnjy5xWtZWVlIT0/H2rVrUVhYiIKCAixevLg7yu9RlAoBfYPt69nlcWYsERFRt5N1sDOZTFi3bh0yMjKg0WiQlpaGlJQUbNiwocW2aWlpmDhxInQ6XYvXPv74Y9xzzz0YNmwY9Ho9XnjhBaxcubI7TqHHcQzHcgIFERFR95N1sMvNzYVer0dkZKTzuUGDBiE7O7tD+8nJyUFqamqzfeTn56OurvXhQrPZDKPR2OxB7cMJFERERNKRdbAzmUwtOnA6nQ4mU8dCw2/34/i+rf0sWbIEer3e+YiJielg5T1XbCg7dkRERFKRdbDTarUtumVGoxFarbZT+3F839Z+5s6dC4PB4HwUFhZ2sPKey9mxY7AjIiLqdqr2bPTqq6+2b2cqFdLT0ztV0IXi4+NhMBhQXFyMiIgIAMDBgwcxa9asDu0nOTkZWVlZzp8PHjyIfv36wdfXt9Xt1Wo11Gr15Rfeg8U1XWNXbKxHjdkCP3W7fosRERFRF2jXv7rz5s3DAw88cMntvvjiiy4NdlqtFpMnT8aCBQvw5ptvYvPmzTh8+DAmTZrUYluLxQKLxQKr1QqLxYL6+np4eXlBqVTi/vvvx9ixYzF79mzExcXhxRdfxNSpU7usTvqVXuOFYD9vlNc0IL+sBim99FKXRERE1GO0K9jp9XosX778kttt3Lix0wX91rJlyzB9+nQEBwcjOjoaq1atQmBgIDIzM/HSSy85J1IsXrwYixYtcr7vhRdewPLlyzFjxgykpqbi9ddfx6RJk2A0GnHXXXfh+eef7/JayS421A/lNQ3IKzUx2BEREXUjQRRF3iLgEoxGI/R6PQwGQ6vLqVBzz31xCJ/tKcRTN8bjjzcnSF0OERGRW+tIDrmsyRNmsxnl5eUwm82XVSB5tl+XPOEECiIiou7U7mBnsViwcOFCxMXFQaPRIDQ0FBqNBv3798eiRYvQ2NjoyjrJjfy65AnXsiMiIupO7Q52jzzyCH744Qd88MEHKC0tRUNDA0pLS/Hee+9h+/btePTRR11ZJ7kRR8cuv6wGHOknIiLqPu2+xi4gIACFhYXw9/dv8ZrBYEDv3r1hMBi6vEA54DV2HdNotWHACxthsYnYOfcGROpbX1aGiIiILs0l19j5+/vjxIkTrb6Wn5/fauCjnslLqUDvIA0ALlRMRETUndq9euzf/vY33HTTTbj33nuRmpoKnU4Ho9GIQ4cO4fPPP8frr7/uyjrJzcSG+uFkWQ1OlppwTf8QqcshIiLqEdod7GbMmIGhQ4fik08+wcaNG2EymaDVapGcnIytW7ciJSXFlXWSm4kN1QJHSjgzloiIqBt16H5PqampSE1NdVUt5EFiQ3jPWCIiou7Wrmvs1q9f366dffXVV50qhjyHc8mTMi55QkRE1F3aFezae1/VBx98sFPFkOdwLHlyprIO9Y1WiashIiLqGdo1FGsymaDRaC66jSiKUCgu60YW5IGC/byh81HBWG/BqfJaJEZw1jQREZGrtSvY5efnA7CHtzVr1mDChAlQq9UtthMEoWurI7clCAJiQ7U4UFiFk6UmBjsiIqJu0K5g16dPH+f3X375JRYvXoy0tDQ88MADuP766xnoqFWxoX72YMeZsURERN2iw2OnP/74I/bv34/ExESkp6cjOjoaf/zjH7Fnzx5X1EduzDEzNo/3jCUiIuoWl3VRXO/evfHnP/8ZBw4cwNq1a7Fp0yaMGDEC8fHxWLJkCUwm/kNOF8yM5ZInRERE3eKygl1jYyPWrVuH++67D7fccgsSEhKwatUqfPTRR8jKysK4ceO6uk5yQ46ZsSdLTWjnLYmJiIioEzq0QDEAzJw5E+vWrUNKSgoeeOABLFu2DIGBgc7Xhw4dCr1e36VFknvqG+wHQQCM9RaU1zQgRNtywg0RERF1nQ4Hu/79+2Pfvn3NJlRcyMvLC2fOnOl0YeT+fLyU6BXgizOVdThZWsNgR0RE5GIdHor961//2maocwgKCrrsgsiz/HqdHa+7JCIicjWuKEwu5bxnLJc8ISIicjkGO3KpuAsmUBAREZFrMdiRS3HJEyIiou7DYEcuFdcU7E5V1KLBYpO4GiIiIs/GYEcuFa5TQ6tWwWoTcaqcXTsiIiJXYrAjlxIEwXmd3YkSXmdHRETkSgx25HJxYfbhWN4zloiIyLUY7Mjl+jcFO3bsiIiIXIvBjlyuf9MEihPs2BEREbkUgx25nKNjl1dSA5tNlLgaIiIiz8VgRy7XO0gDb6UCdY1WnDXUSV0OERGRx2KwI5dTKRXoG6IBwOvsiIiIXInBjroFJ1AQERG5HoMddQvHBAoueUJEROQ6DHbULeLYsSMiInI5BjvqFo57xjLYERERuQ6DHXWLuFAtBAGorG1EucksdTlEREQeicGOuoWvtxK9AnwBsGtHRETkKgx21G2cM2M5gYKIiMglGOyo2zhnxpbUSFwJERGRZ2Kwo27Djh0REZFrMdhRt/n1nrEMdkRERK4g+2BXWlqKCRMmQKPRIDExEVu2bGl1u7q6OkydOhX+/v7o3bs3PvnkE+dr27Ztg0KhgFardT62b9/eXadATRzBrqiqDjVmi8TVEBEReR6V1AVcyuOPP46oqCiUlZVh06ZNmDJlCvLy8hAYGNhsuwULFqCiogJFRUU4fPgwbrvtNgwdOhQJCQkAgISEBBw9elSKU6AmARpvhGi9UWZqwMnSGqRG66UuiYiIyKPIumNnMpmwbt06ZGRkQKPRIC0tDSkpKdiwYUOLbT/66CMsWLAAOp0Oo0aNwuTJk/Hpp59KUDVdjHOh4tJqiSshIiLyPLIOdrm5udDr9YiMjHQ+N2jQIGRnZzfbrrKyEsXFxUhNTW1zu4KCAoSFhSE+Ph4ZGRmwWq1tHtdsNsNoNDZ7UNfgrcWIiIhcR9bBzmQyQafTNXtOp9PBZDK12E6pVEKj0bS6XVJSEg4cOIDi4mKsW7cOq1atwtKlS9s87pIlS6DX652PmJiYLjyrnq0/by1GRETkMrIOdlqttkW3zGg0QqvVttjOarWitra21e0iIiKQlJQEhUKB5ORkzJs3D2vWrGnzuHPnzoXBYHA+CgsLu/Cserb+7NgRERG5jKyDXXx8PAwGA4qLi53PHTx4EAMHDmy2XWBgICIiIpCVlXXR7RwUiouftlqthk6na/agruEIdqfKa9FotUlcDRERkWeRdbDTarWYPHkyFixYgLq6Oqxfvx6HDx/GpEmTWmw7depU/O1vf0N1dTV27dqF9evX45577gFgX+7E0XXLzc3F4sWLMXHixG49F7KL1PvAz1sJi03EqXLegYKIiKgryTrYAcCyZctQWFiI4OBgPPPMM1i1ahUCAwORmZnZrCOXkZHhnGgxZcoULFu2DImJiQCAvXv3YuTIkfDz88O4ceOQlpaG9PR0qU6pRxMEgRMoiIiIXEQQRVGUugi5MxqN0Ov1MBgMHJbtAumfHcDq/UV4ZlwCnrghXupyiIiIZK0jOUT2HTvyPI6OXV4ph2KJiIi6EoMddTvOjCUiInINBjvqdhcGO5uNVwIQERF1FQY76nZ9gjTwVilQ12jFmco6qcshIiLyGAx21O1USoXzDhRHi3m7NiIioq7CYEeSSIrwBwAcP18tcSVERESeg8GOJJHQFOyOFjPYERERdRUGO5JEYjg7dkRERF2NwY4kkdjUsTtZWoMGC+8ZS0RE1BUY7EgSkXof+PuoYLGJOFnG9eyIiIi6AoMdSUIQBOdw7DFeZ0dERNQlGOxIMo4JFAx2REREXYPBjiTDJU+IiIi6FoMdSSYhnEueEBERdSUGO5KM4xq7M5V1MJktEldDRETk/hjsSDKBft4I81cD4HAsERFRV2CwI0k51rM7zuFYIiKiTmOwI0kl8jo7IiKiLqOSugDq2RI4M9Zj1TdaYahrhKGuEVW1jaiqbYDFJiIqwBfRgb4I9vOGIAhSl0lE5FEY7EhSSVzLzmM0WGzYU1CBrcdKsPVYKU6UXPyOIr5eSkQH+qJfiB9Gx4fg+qQwRAdquqlaIiLPxGBHkooP84cgAOU1DSgzmRGiVUtdEnWAKIrYcqQEX+w9gx9PlLWY3awQAL2vFwI03tD5ekEpAGer6nG+uh51jVbklpiQW2LCppzzwLpsxIdpcX1SGG5MCsNV/YLY0SMi6iAGO5KUr7cSfYI0KCivxbHiaoT0Z7BzF7tPluOVjUex73SV87kQrRpjE0NxfWIYRsYGIVDjDYWiZTgzW6w4W1WPM5W1yCoyYNvRUuw9XekMeu/9cBJxoX548Oq+uGtoNLRq/lVFRNQegiiKotRFyJ3RaIRer4fBYIBOp5O6HI/z8H/3YFPOecyfmIyZ1/aTuhy6hOyzBvz9m2PYdqwUAODjpcD0q/ti4hVRGBilazXItYehthE/5JZi69ESbMo57+z+adUq3HVlL0y7ui/6h2m77DyIiNxFR3II/xtMkkuK8MemnPO8zk7m6hutyPgqBx/vPg0AUCkE3HtVDObcEI8wnU+n96/XeGHSoChMGhQFk9mC1fvO4MMdBcgrrcGHO0/hw52nMGlQFP54UzxiQxnwiIhaw2BHknPMjD3GmbGyVVRVhz+s3ItDZwwAgEmDovCnmxPQN8TPJcfTqlV48Oq+mDayD346UY4VOwrw7ZHz2HDwLL7OOocpQ6Mx58Z4RAX4uuT4RETuisGOJJd0wZInNpt42UN55Bo/nSjDk5/sR0VNAwI0Xlh67xBclxDaLccWBAHXxofg2vgQ5Jw14o3Nx/DtkRJ8+kshVu8rwgMje+OpG+MRoPHulnqIiOSOCxST5PoE+8FbqUBtgxVFVXVSl0NNRFHEO9/nYdr/242Kmgak9NJhwxPXdluo+63kKB0+mD4cX/5hFEbGBqHBasPynwow9rVtWLnrFKw2Xi5MRMRgR5LzUioQ13RRPO9AIQ9Wm4j0VQfx8v+OwiYCU4ZG44tHRyEmSPp15ob2CcQns0fio99fhcRwf1TVNmLe2sOY/M8fsaegQuryiIgkxWBHspAYbg92vAOF9Gw2EX/58hDW7C+Cl1LAi3ek4NW7r4CPl1Lq0pwEQcDo+FD835xrsXBSMvx9VMg+a8Td7+zEHz87gNJqs9QlEhFJgsGOZMExgYIdO2mJoohFG7Lx+d4zUCoEvH3fEDwwoo9sFwpWKRWYcU0/bH1mLO4ZFgNBANbsL8KNr2/DJz+fho3Ds0TUwzDYkSw4J1Aw2ElGFEW8svEYPtx5CoIAvDblCtySEil1We0SolXjlbuvwNrHrkFKLx2M9RbMXZ2Fe97biVx2gYmoB2GwI1lIjLAvuJhXaoLZYpW4mp7pn9+dwDvf5wEAFqel4I4h0RJX1HGDYgKw9rFrMG/CAGi8lfiloBK3Ld2O1zcdQ30jf18RkedjsCNZiNL7IEDjBYtNxPHii988nrre8p/y8frm4wCAeRMG4IERfSSu6PKplArMGh2LzeljcNOAMDRaRbz93Qnc9tZ27DpZLnV5REQuxWBHsiAIAlJ76QEAh88aJK6mZ9mRV4a/fZUDAEi/OQGzRsdKXFHX6BXgi/cfHIZ/P3AlwvzVOFlWg3vf24XnvjgEQ22j1OUREbkEgx3JxsAoe7DLKmKw6y7njfWY88l+2ETgriuj8eQN/aUuqUsJgoBbUyOxOX0M7h/RGwDw2Z5C3PjG99hw8Cx4q2wi8jQMdiQbKb3s19llM9h1i0arDU98vA9lpgYkRfhjcVqKbGe/dpbe1wsv3ZGKzx+9GnGhfigzmfHkJ/vx0IpfUFhRK3V5RERdhsGOZCOlqWN3pLgajVabxNV4vlc3HsUvBZXQqlX499Sh8PWWzzp1rjK8bxC+fmo0nroxHt5KBbYdK8XN//gey7adQIOFv+eIyP0x2JFs9A7SwF+tQoPFhhMlnEDhShsPn8P72/MB2Jc16RfiJ3FF3UetUuKPNyfgf0+PxsjYINQ32vDqxmOY+PZ2/MI7VxCRm2OwI9lQKAQkR9mHYw9zONZl8stq8OznhwAAs67t5zZr1XW1uFAtPpk9Em/8bhCC/Lxx/LwJU97ZifRVB1BirJe6PCKiy8JgR7KS0jQzNvusUeJKPFOj1YYnP9mHarMFw/sG4rlbk6QuSVKCIODOK6Px3Z/G4N7hMQCA1fuKcP1r2/DvbXlcU5GI3A6DHcmKYwIFO3au8d4PJ3G4yIgAjRfevu9KeCn5VwAABGi88fJdV2Dt49dgcEwAahqseGXjUYz/xw/4Nuc8Z88SkdtQSV3ApZSWlmLGjBnYunUrYmJisGzZMtx4440ttqurq8Ps2bOxbt06BAYG4pVXXsF9993nfH3FihWYN28ejEYj7rrrLrz77rvw9vbuzlOhdnCsZZdzzgirTYRS4ZmzNKVwosSEt7bkAgDmT0xGhN5H4orkZ3BMAFb/YRTW7C/CyxuPoqC8FrP+uwcjY4Pw51uScGXvQKlLpIswW6ww1DXCWNcIQ50FNWYLahusqGts+tpgRYPVBotVhMVqQ6NNhNUmthrcFQoBKoUAlUJh/6pUwFulgFqlgI+X0vnV10sJX28lNN5K+Hmr4OuthFatgo+XwmNnmZO8yT7YPf7444iKikJZWRk2bdqEKVOmIC8vD4GBzf+CXbBgASoqKlBUVITDhw/jtttuw9ChQ5GQkICsrCykp6dj06ZNiI+PR1paGhYvXoyMjAyJzora0i9EC18vJWobrMgvM6F/mL/UJXkEm03EX748hAaLDWMSQnHHkF5SlyRbCoWAu4ZGY3xKBP753Qn856d87DpZgTuX7cDNyeF4dnwiEsL5+7K7iKKI8poGnKuqR1FVHc4Z6lBabUZptRllJjPKTA0oM5lRWduA+kb5zGxWKgT4eSvh7+MFP7U97Pn7eMHfR9X08ILO8dVXBX+1F3S+9tcdX7XeKij4n1vqIEGU8RiDyWRCcHAwCgoKEBlpv8D7uuuuw6xZs/Dggw822zYyMhJr167FiBEjAAAPPvgg+vfvj/nz52Pu3LmoqqrCv//9bwDAd999h1mzZuHkyZPtqsNoNEKv18NgMECn03XhGVJr7vr3Duw9VYk37xmMNAaQLvHfnQWYvy4bft5KbEofg14BvlKX5DaKqurw1rfH8cXeM7CJgCAAdwzphSeu74/YUK3U5XmERqsNpytqcaq8BgVl9q+nKmpxurwWRVV1MHdgKRpBAPzVKug1XvDzVkHjrYSmqZOm8VbCW6mASqmAl7KpG6cU0KKxJgI2UUSj1d7Rs9hsaLSKaLDYYLZYUd/469f6RitqGiyoa7CitunRVRzn8ttA6O+jglatgtZHBX+143svaNX2c/VTq+CnVjY7f3YQL87x62y1Nf91t9pEWJp+toqi82eb2Pw5q03EwCgd/H28XFJfR3KIrDt2ubm50Ov1zlAHAIMGDUJ2dnaz7SorK1FcXIzU1NRm2/38888AgJycHIwfP77Za/n5+airq4Ovb8t/4MxmM8xms/Nno5EX8nenlCgd9p6qxOEiA4NdFzhTWYtX/ncUAPCXW5MY6jqoV4AvXr17EB6+LhavbzqO/x0uxup9RVizvwjjkyPwyJhYDOEQbbs0WGw4WWbCseJqnCgxOR8F5TVotLbdYxAEIFSrRlSAL6ICfBDm74NQfzVCtN4I0aoRolUjUOMNfVOnS8oul80morbRihqzBSazBaZ6+9fqeguq6xubvl7wvbkRxjr7z8am5411FjRYbRBFwFhvgbHe0iW1+XrZw62PlxI+XgqoVfavjqFlr6bhZseQs5dSAZWiKQQrfx2WVigEKBUClIL9e4UACLB3uwUAEJq+Amj2qyqKsDWFZvGCr45wZLPZX7f/bIOl6TmLzRG0RFitIhovCFwWm31o3T6sbg/gFqv9vc1ftzW9t+l1q31/lqbjdEWLa81jo2Txd4Gsg53JZGqRTHU6Haqqqlpsp1QqodFomm1nMpla3Y/je5PJ1GqwW7JkCRYtWtRVp0EdNJD3jO0yoijir2sOo6bBiuF9A/HAiD5Sl+S2+of5499Th+JgYRXe/i4X3x4pwcbsYmzMLsaIfkF4dEwcxiSEcuisSZnJjOyzRuScNeJosRHHiquRV2pqM8D5einRL8QPfYI16BPsh77BGvQO1iAmUINwnQ+8Ve4x0UehEOwdNLUK4Z3YT32jFdX1FhidYfC3X+2BscZsQXVTcKxtCpO1Db8Gywu7nXWNVtQ1cqZ3eykE+5C6sulaS4UAqJQKKAT79ZdKhQCFAlAK9u/l8ntU1sFOq9W26JYZjUZotdoW21mtVtTW1jrD3YXb/XY/ju9/ux+HuXPnIj09vdn2MTExnT8hahfHHSiyi4yw2UT+Q9kJq/cV4YfjpfBWKfDyXVfws+wCg2IC8MH04cg9X413fziJdQeKsDu/ArvzKxAT5IvfDY3B3cOiEanvGZ1RURRRVFWHw0VGZJ81IPus/et5o7nV7f3VKiRG+CM+3B/9w7TOR6TOh78/L2DvqikR6q/u1H6sNhH1jVbn5JHaRotzCNn+sA8rmy02NDgeVvvXRmfnq6kT1tQpsz/gHI60iaK9M3dBF06ECEff7sIRYEdXTyHYh8AVggCFIECpsIeoX39uCk9KwRmcHEPnKsWvrzuG1ZWK5sPrzueatnG8z9GBVCoEe0fygk6kUinAS6Fw7ttdfz/KOtjFx8fDYDCguLgYERERAICDBw9i1qxZzbYLDAxEREQEsrKynNfYHTx4EAMHDgQAJCcnIysry7n9wYMH0a9fv1a7dQCgVquhVnfuDxNdvvhwLbyVClSbLSisrEWf4J5zV4SuZKhtxOL/ywEAPH1TPOJ4PViXig/3x2tTBuFP4xLwnx/z8enPhSisqMPrm4/jH98ex5iEUNwzPAZjE8Pg4+UZt2uz2UScqqhF9lkDDhcZcbjIgMNnDaiqbWyxrSAA/YL9MCBKh+RIHZIi/JEY4Y9eAb681qsbKRVC0zV3sv7nnrqQrCdPAMCUKVMQFBSEN998E5s3b8aMGTNanRX77LPP4siRI/jkk0+QnZ2NW265Bbt370ZiYiKysrIwduxYbN68GXFxcbjzzjtxzTXXtHtWLCdPdL/J//wRh84Y8K/7r8SEK3rmnRE6629f5eD//ZiP+DAtvn5qNNesc7G6Biv+d/gcPv2lED/n/3prMo23EtfFh2LcwHDckBSGAI17LLPUYLEht6QaR85VI+esEYfPGpBz1giTueX1Xl5KAQnh/hgYpcPAKD0GRumQFKmDlmGCqEt4zOQJAFi2bBmmT5+O4OBgREdHY9WqVQgMDERmZiZeeukl50SKjIwMzJo1C5GRkQgMDMSyZcuQmJgIAEhNTcXrr7+OSZMmOdexe/7556U8LbqElF56HDpj7wYw2HVcXqkJH+4oAAC8MDGZoa4b+HorceeV0bjzymicLDVh1Z4zWHegCOcM9c5r8ZQKAcP6BGJkbDCG9Q3E4JgAl82iay+bTcSZyjrkllTj+HkTcs9XI+ecESdKTLDYWv6/31ulwIBIHQZG6ZDaS4+UKD0SIrRQqzyjK0nk7mTfsZMDduy638e7T+Ova7IwOj4EH/1+hNTluJ3fr/gFW46W4IakMPxnxnCpy+mxRFHE4SIjNucUY1POeRwtrm72ukIAEiN0uLJ3ABLC/REb6ofY0K6/3qzRakNptRmnymtxuqIGp8prcappeZETJaY213/T+agwIFKHAZE6pPTSI6WXDnGhWv5HgaibeVTHjnqmC28tJooir8npgB+Ol2LL0RKoFAKenzBA6nJ6NEEQkBqtR2q0HunjElFYUYttx0uxt6ACe05V4kxlHY6cM+LIueaTxHy8FOgb7GdfxsPPG4EaLwRqvBGg8WqalQfnUhOAfQalyWxBrdn+1WS2oLTajJJqM0qM9aiobbjocg7eSgViQ/0QH+6PhDAtkiJ1SI7SIUrvwz97RG6GwY5kKSHcHyqFgMraRpw11HPttXayWG3421f2CRMPXt2XEyZkJiZIg2kj+2DaSPuyM+eN9dh7qhIHC6uQV1qD/DITTlfUor7R1tTdq774DjtApRDQK9AXvYM09iVFgvzQO1iD/mFa9AnSQMUuHJFHYLAjWfLxUiI+3B9Hztln3jHYtc/HP59GbokJgRovPHVjvNTl0CWE63xwW2okbkv99TpSi9WGM5V1OFVRi4oaMypqGlFV24CKmgZU1TXCZvt1iQnHYq+O+5Q67jig8VYhVKtGmE6NMH8fhOnUCNJ4u+3yDUTUfgx2JFspUTocOWdEdpEB4wdGSF2O7BlqG/HG5uMAgPSbE6DXSHtRPl0elVKBviF+6BvCZX6IqOPYeyfZSnHegYK3dGuPt7bkoqq2EQnhWtx3VW+pyyEiIgkw2JFsOSZQZDVNoKC2FVbU4qNdBQCAeROSeb0UEVEPxb/9SbaSI/VQKQSUVptRVFUndTmy9ua3uWi0ihgdH4LrEkKlLoeIiCTCYEey5eutxMAoe9du76lKiauRr9zz1Viz/wwA4JlxiRJXQ0REUmKwI1kb2icIALCngMGuLW9sPg6bCIwfGI5BMQFSl0NERBJisCNZG9bXfk/gPezYterQmSr873AxBAH4E7t1REQ9HoMdydrQPvZgd6zYiOr6RomrkZ/XNtmXN7ljcC8khPtLXA0REUmNwY5kLVzng+hAX9hE4EBhldTlyMquk+X44XgpVAoBT9+UIHU5REQkAwx2JHvDmrp2vM7uV6Io4rVvjgEA7r0qBr2DNRJXREREcsBgR7I3tK99AgVnxv5q27FS7DlVCbVKgSdv4K3DiIjIjsGOZM/Rsdt/uhIWq03iaqQniiJe22Tv1s0Y1RfhOh+JKyIiIrlgsCPZSwj3h79ahZoGK44WV0tdjuQ255xH9lkj/LyVeGRMnNTlEBGRjDDYkewpFQKGNHXt9p3u2cOxoihi6Xe5AIDpo/oiyM9b4oqIiEhOGOzILQztzQkUAPDd0RIcLjJC463ErNGxUpdDREQyw2BHbsGxUHFPnkAhiiLe2mLv1k27ug+7dURE1AKDHbmFwTEBUCoEFFXV4ZyhTupyJLHteCkOnTHA10uJh9mtIyKiVjDYkVvwU6swINJ+Z4WeOBwriiLe+vbXbl2wVi1xRUREJEcMduQ2hvXpuevZ/ZBbhgOFVfDxUmA2u3VERNQGBjtyG477xva0YGfv1tnvCfvAiD4I9We3joiIWsdgR27DMYEi55wRNWaLxNV0n59OlGPf6SqoVQo8MobdOiIiahuDHbmNSL0vegX4wmoTcbCwSupyuoV9Jqy9W3f/iN4I8+ddJoiIqG0MduRWrmwajt3TQ4Zjd52swC8FlfBWKfAo7zJBRESXwGBHbmVYD7vO7p9b7TNh7xkWw3vCEhHRJTHYkVtxTKDYd6oSFqtN4mpca++pSvx0ohwqhYBHx7JbR0REl8ZgR25lQKQOARovVJstOHimSupyXOqfTfeEvevKaPQK8JW4GiIicgcMduRWlAoBo+NDAQDbjpVKXI3rHC4yYOuxUigE4A/s1hERUTsx2JHbGZNgD3bfH/fcYPd2U7fu9sG90DfET+JqiIjIXTDYkdu5LiEEAHDojAFlJrPE1XS9Y8XV+Cb7PAQBeIzdOiIi6gAGO3I7Yf4+GBilAwBsz/W8rt0/t54AANyaEoH4cH+JqyEiInfCYEduyTkc62HX2eWVmvDVobMAgCeuj5e4GiIicjcMduSWxiaGAQB+yC2DzSZKXE3XWbY1D6II3DQgDMlNXUkiIqL2YrAjtzSkdwD81SpU1DQgq8ggdTld4lR5DdYeKAIAPHEDu3VERNRxDHbklryUClzT3z6JwlNmx/5r6wlYbSKuSwjF4JgAqcshIiI3xGBHbmtsomM9uxKJK+m8woparN5n79Y9dSO7dUREdHkY7MhtXdc0geJAYRWqahskrqZz/rX1BCw2EaPjQ5y3TSMiIuooBjtyW1EBvkgI18ImAttzy6Qu57IVVtTii71nAABP38RuHRERXT4GO3Jrjtmx7nyd3bJt9m7dtf1DMLRPkNTlEBGRG5N1sPvll18waNAgaDQajBkzBqdOnWpz27y8PFxzzTXQaDS48sorcfDgQedrCxcuhJeXF7RarfNBnuHC24uJovste3Kmshaf77F3655it46IiDpJtsHObDbjzjvvxFNPPYWKigqMHDkS06ZNa3P7++67D+PGjUNFRQVmzpyJO+64AxaLxfn673//e5hMJueDPMOwvoHQeCtRWm1Gzjmj1OV02LJtebDYRIyKC8bwvuzWERFR58g22G3btg1arRYzZ86Ej48P5s+fjz179rTatTt27BiOHTuGuXPnwsfHB0888QSsVit27NghQeXUndQqJUbFBQNwv+HYoqo6fL6nEABnwhIRUdeQbbDLyclBamqq82c/Pz/ExcUhJyen1W0TExPh7e3tfO6KK65Adna28+dPP/0UQUFBGDJkCFavXn3RY5vNZhiNxmYPki/HcOw2N7u92L+3nUCjVcTI2CCMiA2WuhwiIvIAsg12JpMJOl3zWyrpdLpWh1Evte3vfvc7HD16FCUlJXjllVfw0EMPYc+ePW0ee8mSJdDr9c5HTExMF5wRuYpjAsXeU5UoM5klrqZ9Citq8dkvjm5dgsTVEBGRp5As2I0bNw4+Pj6tPhYvXgytVtuiU2Y0Glud+HCpbZOTkxEREQGVSoVx48bhvvvuw/r169usbe7cuTAYDM5HYWFhF5wxuUpMkAaDovWw2kSsP3BW6nLa5R+bj6PRap8Je3Ucu3VERNQ1JAt2mzZtQn19fauPefPmITk5GVlZWc7ta2pqkJeXh+Tk5Bb7Sk5OxrFjx9DY2Oh87tChQxg4cGCrx1YoLn7aarUaOp2u2YPk7a6h0QCAL/edkbiSSztabMSapnvCPjs+UeJqiIjIk8h2KHbs2LEwmUxYsWIFzGYzFi9ejGHDhqFPnz4ttk1MTERiYiJefvllmM1mLFu2DEqlEqNGjQIArF+/HgaDATabDd999x0yMzNx2223dfcpkQtNuiIKXkoB2WeNOFos72siX/vmGEQRuC01AoN4T1giIupCsg12arUaq1evxhtvvIGAgAD89NNP+Oijj5yvP/roo3j00UedP3/88cfYuHEjAgIC8P7772P16tVQqVTO1/r16we9Xo+nn34a7733HkaOHNnt50SuE+jnjRuTwgEAX+6Vb9ful4IKfHukBEqFgD+NY7eOiIi6liC646qu3cxoNEKv18NgMHBYVsY255zH7P/uQYhWjV1zb4BKKa//t4iiiCnv7MSeU5W476oYLLnzCqlLIiIiN9CRHCKvf/mIOmFsYiiC/bxRZjLL8t6xW4+VYM+pSqhVCs6EJSIil2CwI4/hpVRg8uAoAMAXMhuOtdpEvLrxGABgxjV9EaH3kbgiIiLyRAx25FHuutI+O3ZzznkYahsvsXX3WX+wCEeLq+Hvo8IfxsRJXQ4REXkoBjvyKAOjdEiK8EeD1YYNh+Sxpl19oxWvbzoOAHh0TBwCNN6XeAcREdHlYbAjjyIIAu6W2Zp2y7aewJnKOkTofPDQNX2lLoeIiDwYgx15nNsH94JSIWD/6Srklba8BV13OllqwjvfnwQALJiUDI23StJ6iIjIszHYkccJ9VdjTEIoAGC1hF07URQxf102Gqw2jEkIxS0pEZLVQkREPQODHXkkxySK1fuK0Gi1SVLD/2Wdw48nyuCtUmDR5IEQBEGSOoiIqOdgsCOPdOOAMIRovXHOUI9Pfyns9uObzBb87ascAMBjY+PQN8Sv22sgIqKeh8GOPJKPlxJzbowHALz1bS5qzJZuPf6bm4/jvNGMPsEaPMrlTYiIqJsw2JHHund4b/QO0qDMZMZ/fszvtuMeOWfE8h0FAIBFkwfCx0vZbccmIqKejcGOPJa3SoE/jbPfuuvdH06ioqbB5ce0WG14fk0WrDYRt6VGYGximMuPSURE5MBgRx5t0hVRGBilg8lswT+/O+Hy47226Tj2na6CVq3CCxOTXX48IiKiCzHYkUdTKAQ8d0sSAGDlrlM4U1nrsmNtzjmPd77PAwC8evcViNT7uuxYRERErWGwI483Oj4Eo+KC0WC14Y3Nx11yjFPlNUhfdQAAMPOafrgtNdIlxyEiIroYBjvyeILwa9duzf4iHDln7NL91zda8YeV+1Bdb8GVvQPwl1uTunT/RERE7cVgRz3CoJgATEiNhCgCL//vKERR7LJ9L1yfjZxzRgT5eeNfD1wJbxX/WBERkTT4LxD1GM+MT4RKIeD746V4eePRLtnn53sK8ekvhRAEYOm9Q3hdHRERSYrBjnqMfiF+ePGOFADAu9+fxLJtnZsl++nPpzF3dRYA4I83JeDa+JBO10hERNQZKqkLIOpO9wzvDWOdBS9+fQSvbjwGfx8vTBvZp0P7sNlEvPLNUbz7/UkAwJ1DeuGJ6/u7olwiIqIOYbCjHmf2dbEw1DXin1tPYP66w9D5qHD74F7tem9dgxV//OwANmYXAwCevikeT90YD0EQXFkyERFRuzDYUY/0p3EJMNQ14qNdp/CnVQehVikwfmDERQNaibEes/67B4fOGOCtVODVu69A2pD2BUIiIqLuwGBHPZIgCFg0eSCM9Y1Yd+AsHl25D7Ehfph4RSQmDYpCfLg/AKC02oytR0vw7ZHz2J5bhrpGKwI1XnjvwWEY3jdI4rMgIiJqThC7ct0HD2U0GqHX62EwGKDT6aQuh7pQo9WGBeuz8eXeMzBbbM7nkyL84eutxIHCKlz4JyQx3B/vThuKviF+ElRLREQ9UUdyCINdOzDYeT6T2YJvc85jw8Gz+CG3FI3WX/9YpPTS4aYB4bhpQDgGRul4PR0REXWrjuQQDsUSAdCqVUgb0gtpQ3qhqrYB3x4pgcVqw5jEUK5NR0REboPBjug3AjTeuHtotNRlEBERdRgXKCYiIiLyEAx2RERERB6CwY6IiIjIQzDYEREREXkIBjsiIiIiD8FgR0REROQhGOyIiIiIPASDHREREZGHYLAjIiIi8hAMdkREREQegsGOiIiIyEMw2BERERF5CAY7IiIiIg/BYEdERETkIVRSF+AORFEEABiNRokrISIiop7GkT8ceeRiGOzaobq6GgAQExMjcSVERETUU1VXV0Ov1190G0FsT/zr4Ww2G86ePQt/f38IguCSYxiNRsTExKCwsBA6nc4lx/AU/Kw6hp9X+/Gz6hh+Xu3Hz6r9+Fm1JIoiqqurERUVBYXi4lfRsWPXDgqFAtHR0d1yLJ1Ox9/I7cTPqmP4ebUfP6uO4efVfvys2o+fVXOX6tQ5cPIEERERkYdgsCMiIiLyEAx2MqFWq7FgwQKo1WqpS5E9flYdw8+r/fhZdQw/r/bjZ9V+/Kw6h5MniIiIiDwEO3ZEREREHoLBjoiIiMhDMNgREREReQgGOyIiIiIPwWAnA6WlpZgwYQI0Gg0SExOxZcsWqUuSrQULFiA5ORkKhQKffvqp1OXImtlsxkMPPYTo6Gjo9XqMHTsWWVlZUpclWw8//DAiIyOh0+mQmpqKr776SuqSZG/nzp1QKBR4+eWXpS5F1saOHQsfHx9otVpotVrceuutUpckey+//DJiYmLg7++PwYMHo6qqSuqS3AaDnQw8/vjjiIqKQllZGV555RVMmTIFlZWVUpclS/Hx8Xjrrbdw1VVXSV2K7FksFsTGxmLXrl2oqKjA5MmTkZaWJnVZspWeno6CggIYjUb85z//wdSpU/nn8CJsNhv++Mc/Yvjw4VKX4hZWrFgBk8kEk8mE//3vf1KXI2tvv/02/ve//+HHH3+E0WjEypUr4ePjI3VZboPBTmImkwnr1q1DRkYGNBoN0tLSkJKSgg0bNkhdmixNnToVN998M/+Qt4Ofnx9eeOEFREdHQ6lU4oknnkB+fj7Ky8ulLk2WkpKSnOtmCYKA+vp6nDt3TuKq5Ou9997DiBEjMGDAAKlLIQ9itVrx0ksv4YMPPkCfPn0gCAJSUlL4d34HMNhJLDc3F3q9HpGRkc7nBg0ahOzsbAmrIk+0c+dOhIeHIzg4WOpSZOuxxx6Dr68vhg8fjltuuQXJyclSlyRLFRUVePPNN7Fw4UKpS3EbTz75JEJDQ3HzzTfj0KFDUpcjW2fOnEFdXR0+//xzhIeHIzExEe+8847UZbkVBjuJmUymFjc51ul0MJlMElVEnshgMOCRRx7Biy++KHUpsrZs2TKYTCZs3rwZY8aMkboc2frrX/+Kp59+GoGBgVKX4hZeffVV5Ofn4/Tp07j55ptx22238e/4NhQVFcFgMCAvLw8FBQVYvXo1Fi1ahK1bt0pdmttgsJOYVquF0Whs9pzRaIRWq5WoIvI09fX1SEtLw4QJEzBz5kypy5E9pVKJm266CVu2bME333wjdTmys3//fvz888+YPXu21KW4jauuugparRa+vr7485//DK1Wi59//lnqsmTJ19cXgH2inK+vLwYOHIhp06bh66+/lrgy96GSuoCeLj4+HgaDAcXFxYiIiAAAHDx4ELNmzZK4MvIEFosF9957L6KiovDaa69JXY5bsdlsyMvLk7oM2fn+++9x/Phx9OrVC4C9G6xSqZCXl4f3339f4urcg0LBnkpbEhIS4O3t3ew53vm0Y/i7S2JarRaTJ0/GggULUFdXh/Xr1+Pw4cOYNGmS1KXJUmNjI+rr62Gz2Zp9T62bPXs26urqsGLFCgiCIHU5smUymZCZmQmTyQSLxYIvv/wSW7duxejRo6UuTXYefvhhnDhxAgcOHMCBAwcwefJkPPXUU/j73/8udWmyVFVVhc2bN8NsNqOhoQH/+Mc/UFFRgWHDhkldmiz5+fnh7rvvxuLFi2E2m3Hs2DFkZmbitttuk7o09yGS5EpKSsRbb71V9PX1FePj48XNmzdLXZJsTZ8+XQTQ7LF161apy5KlgoICEYDo4+Mj+vn5OR8//PCD1KXJjslkEq+//npRr9eLOp1OvPLKK8XVq1dLXZZbmD59urhkyRKpy5CtkpIScejQoaKfn58YGBgoXn/99eLevXulLkvWKisrxTvvvFPUarVinz59xGXLlkldklsRRJE9TiIiIiJPwKFYIiIiIg/BYEdERETkIRjsiIiIiDwEgx0RERGRh2CwIyIiIvIQDHZEREREHoLBjoiIiMhDMNgREREReQgGOyKiSzh9+jRCQkJceoyCggIIggCtVou1a9dedNsvv/wSWq0WgiCguLjYpXURkXvhnSeIiGC/b7NDTU0NNBqN8/66OTk56N27t0uPX1BQgKSkJNTX17f7PYIg4Ny5c4iIiHBhZUTkTlRSF0BEJAcmk8n5vY+PD7Kzs9G3b1/pCiIiugwciiUiuoSCggL4+Pg4fxYEAf/+97/Ru3dvhISE4LPPPsNXX32F2NhYhIWF4bPPPnNuW1FRgfvvvx9hYWGIjY3Fhx9+2O7j7tq1C0OGDIG/vz8iIiLwxhtvdOl5EZHnYceOiOgy/PTTTzh+/Dg2bNiARx99FJMnT8bhw4exZcsWzJw5E3fffTeUSiWmTZuGlJQUFBYWIj8/HzfccAMGDx6MQYMGXfIYTz/9NJ599lncf//9qKysREFBgetPjIjcGjt2RESX4c9//jN8fHxw5513oqqqCo899hg0Gg0mTZqE6upqnD17FsXFxdi+fTteeuklqNVqJCUl4f7778fq1avbdQwvLy8cO3YMFRUVCAwMxJAhQ1x8VkTk7hjsiIguQ1hYGABAqVTCy8sLoaGhztd8fHxQU1OD06dPo6amBsHBwQgICEBAQADeffddnD9/vl3H+OCDD3DkyBH0798fo0aNws6dO11yLkTkOTgUS0TkIr169UJAQADKy8sv6/2JiYlYtWoVLBYL3nnnHUydOhV5eXldXCUReRJ27IiIXKRXr14YPnw45s+fj9raWlgsFuzbtw85OTnten9mZibKy8uhUqng7+8PpVLp4oqJyN0x2BERuVBmZiZOnTrlnDH79NNPo66url3v/frrr5GYmAh/f38sXboUy5cvd3G1ROTuuEAxEZEMnDp1CklJSVCr1fjvf/+LyZMnt7nt6tWrMXPmTNTX1+PUqVMIDw/vxkqJSM4Y7IiIiIg8BIdiiYiIiDwEgx0RERGRh2CwIyIiIvIQDHZEREREHoLBjoiIiMhDMNgREREReQgGOyIiIiIPwWBHRERE5CEY7IiIiIg8BIMdERERkYf4/0XMOvXgGwnoAAAAAElFTkSuQmCC", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "# Check the Nyquist criterion\n", - "nyqresp = ct.nyquist_response(L)\n", - "print(\"N = encirclements: \", nyqresp.count)\n", - "print(\"P = RHP poles of L: \", np.sum(np.real(L.poles()) > 0))\n", - "print(\"Z = N + P = RHP zeros of 1 + L:\", np.sum(np.real((1 + L).zeros()) >= 0))\n", - "print(\"Poles of L = \", L.poles())\n", - "print(\"Zeros of 1 + L = \", (1 + L).zeros())\n", - "print(\"\")\n", - "\n", - "T = ct.feedback(L)\n", - "ct.initial_response(T, X0=[0.1, 0]).plot();" - ] - }, - { - "cell_type": "markdown", - "id": "VXlYhs8X7DuN", - "metadata": { - "id": "VXlYhs8X7DuN" - }, - "source": [ - "### Gang of 4\n", - "\n", - "Another useful thing to look at is the transfer functions from noise and disturbances to the system outputs and inputs:" - ] - }, - { - "cell_type": "code", - "execution_count": 20, - "id": "oTmOun41_opt", - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "ct.gangof4(P, C);" - ] - }, - { - "cell_type": "markdown", - "id": "U41ve1zh7XPh", - "metadata": { - "id": "U41ve1zh7XPh" - }, - "source": [ - "We see that the response from the input $r$ (or equivalently noise $n$) to the process input is very large for large frequencies. This means that we are amplifying high frequency noise (and comes from the fact that we used derivative feedback)." - ] - }, - { - "cell_type": "markdown", - "id": "YROqmZTd8WYs", - "metadata": { - "id": "YROqmZTd8WYs" - }, - "source": [ - "### High frequency rolloff\n", - "\n", - "We can attempt to resolve this by \"rolling off\" the derivative action at high frequencies:" - ] - }, - { - "cell_type": "code", - "execution_count": 21, - "id": "vhKi_L-F_6Ws", - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - ": Cnew\n", - "Inputs (1): ['u[0]']\n", - "Outputs (1): ['y[0]']\n", - "\n", - "\n", - " 800 s + 4000\n", - "----------------\n", - "s^2 + 40 s + 400\n", - "\n" - ] - }, - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "Cnew = (kp + kd * s) / (s/20 + 1)**2\n", - "Cnew.name = 'Cnew'\n", - "print(Cnew)\n", - "\n", - "Lnew = P * Cnew\n", - "Lnew.name = 'Lnew'\n", - "\n", - "plt.figure(figsize=[7, 4])\n", - "ax1 = plt.subplot(2, 2, 1)\n", - "ax2 = plt.subplot(2, 2, 3)\n", - "ct.bode_plot([Lnew, L], ax=[ax1, ax2])\n", - "ax1.loglog([1e-1, 1e2], [1, 1], 'k', linewidth=0.5)\n", - "ax1.set_title(\"Bode plot for L, Lnew\", size='medium')\n", - "\n", - "ax3 = plt.subplot(1, 2, 2)\n", - "ct.nyquist_plot(Lnew, ax=ax3)\n", - "ax3.set_title(\"Nyquist plot for Lnew\", size='medium')\n", - "\n", - "plt.suptitle(\"Stability analysis for inverted pendulum\")\n", - "plt.tight_layout()" - ] - }, - { - "cell_type": "markdown", - "id": "WgrAE9XE7_nJ", - "metadata": { - "id": "WgrAE9XE7_nJ" - }, - "source": [ - "While not (yet) a very high performing controller, this change does get rid of the issues with the high frequency noise:" - ] - }, - { - "cell_type": "code", - "execution_count": 22, - "id": "FknwW6GkBLLU", - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "# Check the gang of 4\n", - "ct.gangof4(P, Cnew);" - ] - }, - { - "cell_type": "code", - "execution_count": 23, - "id": "wJHJLjXwCNz-", - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "array([[list([])]],\n", - " dtype=object)" - ] - }, - "execution_count": 23, - "metadata": {}, - "output_type": "execute_result" - }, - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "# See what the step response looks like\n", - "Tnew = ct.feedback(Lnew)\n", - "ct.step_response(Tnew, 10).plot()" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "id": "WUhz529a-w3q", - "metadata": {}, - "outputs": [], - "source": [] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Python 3 (ipykernel)", - "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.12.2" - } - }, - "nbformat": 4, - "nbformat_minor": 5 -} diff --git a/examples/cds110_invpend-dynamics.ipynb b/examples/cds110_invpend-dynamics.ipynb deleted file mode 100644 index 0543452dd..000000000 --- a/examples/cds110_invpend-dynamics.ipynb +++ /dev/null @@ -1,610 +0,0 @@ -{ - "cells": [ - { - "cell_type": "markdown", - "metadata": { - "id": "t0JD8EbaVWg-" - }, - "source": [ - "# Inverted Pendulum Dynamics\n", - "\n", - "CDS 110, Winter 2024
\n", - "Richard M. Murray\n", - "\n", - "In this lecture we investigate the nonlinear dynamics of an inverted pendulum system. More information on this example can be found in [FBS2e](https://fbswiki.org/wiki/index.php?title=FBS), Examples 3.3 and 5.4.\n" - ] - }, - { - "cell_type": "code", - "execution_count": 1, - "metadata": {}, - "outputs": [], - "source": [ - "# Import the packages needed for the examples included in this notebook\n", - "import numpy as np\n", - "import matplotlib.pyplot as plt\n", - "from math import pi\n", - "\n", - "import control as ct" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "id": "P_ZMCccjvHY1" - }, - "source": [ - "## System model" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "id": "Msad1ficHjtc" - }, - "source": [ - "The dynamics for an inverted pendulum system can be written as:\n", - "\n", - "$$\n", - " \\dfrac{d}{dt} \\begin{bmatrix} \\theta \\\\ \\dot\\theta\\end{bmatrix} =\n", - " \\begin{bmatrix}\n", - " \\dot\\theta \\\\\n", - " \\dfrac{m g l}{J_\\text{t}} \\sin \\theta\n", - " - \\dfrac{b}{J_\\text{t}} \\dot\\theta\n", - " + \\dfrac{l}{J_\\text{t}} u \\cos\\theta\n", - " \\end{bmatrix}, \\qquad\n", - " y = \\theta,\n", - "$$\n", - "\n", - "where $m$ and $J_t = J + m l^2$ are the mass and (total) moment of inertia of the system to be balanced, $l$ is the distance from the base to the center of mass of the balanced body, $b$ is the coefficient of rotational friction, and $g$ is the acceleration due to gravity.\n", - "\n", - "We begin by creating a nonlinear model of the system:" - ] - }, - { - "cell_type": "code", - "execution_count": 2, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - ": invpend\n", - "Inputs (1): ['tau']\n", - "Outputs (2): ['theta', 'thdot']\n", - "States (2): ['theta', 'thdot']\n", - "\n", - "Update: \n", - "Output: None\n" - ] - } - ], - "source": [ - "invpend_params = {'m': 1, 'l': 1, 'b': 0.5, 'g': 1}\n", - "def invpend_update(t, x, u, params):\n", - " m, l, b, g = params['m'], params['l'], params['b'], params['g']\n", - " umax = params.get('umax', 1)\n", - " usat = np.clip(u[0], -umax, umax)\n", - " return [x[1], -b/m * x[1] + (g * l / m) * np.sin(x[0] + usat/m)]\n", - "invpend = ct.nlsys(\n", - " invpend_update, states=['theta', 'thdot'],\n", - " inputs=['tau'], outputs=['theta', 'thdot'],\n", - " params=invpend_params, name='invpend')\n", - "print(invpend)" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "id": "IAoQAORFvLj1" - }, - "source": [ - "## Open loop dynamics" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "id": "vOALp_IwjVxC" - }, - "source": [ - "The open loop dynamics of the system can be visualized using the `phase_plane_plot` command in python-control:" - ] - }, - { - "cell_type": "code", - "execution_count": 3, - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "[]" - ] - }, - "execution_count": 3, - "metadata": {}, - "output_type": "execute_result" - }, - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "ct.phase_plane_plot(\n", - " invpend, [-2*pi - 1, 2*pi + 1, -2, 2], 8),\n", - "\n", - "# Draw lines at the downward equilibrium angles\n", - "plt.plot([-pi, -pi], [-2, 2], 'k--')\n", - "plt.plot([pi, pi], [-2, 2], 'k--')" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "id": "WZuvqNzeJinm" - }, - "source": [ - "We see that the vertical ($\\theta = 0$) equilibrium point is unstable, but the downward equlibrium points ($\\theta = \\pm \\pi$) are stable.\n", - "\n", - "Note also the *separatrices* for the equilibrium point, which gives insights into the regions of attraction (the red dashed line separates the two regions of attraction)." - ] - }, - { - "cell_type": "markdown", - "metadata": { - "id": "2JibDTJBKHIF" - }, - "source": [ - "## Proportional feedback\n", - "\n", - "We now stabilize the system using a simple proportional feedback controller:\n", - "\n", - "$$u = -k_\\text{p} \\theta.$$\n", - "\n", - "This controller can be designed as an input/output system that has no state dynamics, just a mapping from the inputs to the outputs:" - ] - }, - { - "cell_type": "code", - "execution_count": 4, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - ": p_ctrl\n", - "Inputs (2): ['theta', 'r']\n", - "Outputs (1): ['tau']\n", - "States (0): []\n", - "\n", - "Update: . at 0x13c3c37e0>\n", - "Output: \n" - ] - } - ], - "source": [ - "# Set up the controller\n", - "def propctrl_output(t, x, u, params):\n", - " kp = params.get('kp', 1)\n", - " return -kp * (u[0] - u[1])\n", - "propctrl = ct.nlsys(\n", - " None, propctrl_output, name=\"p_ctrl\",\n", - " inputs=['theta', 'r'], outputs='tau'\n", - ")\n", - "print(propctrl)" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "id": "AvU35WoBMFjt" - }, - "source": [ - "Note that the input to the controller is the reference value $r$ (which we will always take to be zero), the measured output $y$, which is the angle $\\theta$ for our system. The output of the controller is the system input $u$, corresponding to the force applied to the wheels.\n", - "\n", - "To connect the controller to the system, we use the [`interconnect`](https://python-control.readthedocs.io/en/latest/generated/control.interconnect.html) function, which will connect all signals that have the same names:" - ] - }, - { - "cell_type": "code", - "execution_count": 5, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - ": invpend w/ proportional feedback\n", - "Inputs (1): ['r']\n", - "Outputs (2): ['theta', 'tau']\n", - "States (2): ['invpend_theta', 'invpend_thdot']\n", - "\n", - "Update: .updfcn at 0x13dc72700>\n", - "Output: .outfcn at 0x13dc728e0>\n" - ] - }, - { - "name": "stderr", - "output_type": "stream", - "text": [ - "/Users/murray/src/python-control/murrayrm/control/nlsys.py:1208: UserWarning: Unused output(s) in InterconnectedSystem: (0, 1) : invpend.thdot\n", - " warn(msg)\n" - ] - } - ], - "source": [ - "# Create the closed loop system\n", - "clsys = ct.interconnect(\n", - " [invpend, propctrl], name='invpend w/ proportional feedback',\n", - " inputs=['r'], outputs=['theta', 'tau'], params={'kp': 1})\n", - "print(clsys)" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "id": "IIiSaHNuM1u_" - }, - "source": [ - "We can now linearize the closed loop system at different gains and compute the eigenvalues to check for stability:" - ] - }, - { - "cell_type": "code", - "execution_count": 6, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "kp = 0 ; poles = [ 0.78077641+0.j -1.28077641+0.j]\n", - "kp = 1 ; poles = [ 0. +0.j -0.5+0.j]\n", - "kp = 10 ; poles = [-0.25+2.98956519j -0.25-2.98956519j]\n" - ] - } - ], - "source": [ - "# Solution\n", - "for kp in [0, 1, 10]:\n", - " print(\"kp = \", kp, \"; poles = \", clsys.linearize([0, 0], [0], params={'kp': kp}).poles())" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "id": "iV4u31DsNWP9" - }, - "source": [ - "We see that at $k_\\text{p} = 10$ the eigenvalues (poles) of the closed loop system both have negative real part, and so the system is stabilized." - ] - }, - { - "cell_type": "markdown", - "metadata": { - "id": "Jg87a3iZP-Qd" - }, - "source": [ - "### Phase portrait\n", - "\n", - "To study the resulting dynamics, we try plotting a phase plot using the same commands as before, but now for the closed loop system (with appropriate proportional gain):" - ] - }, - { - "cell_type": "code", - "execution_count": 7, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "ct.phase_plane_plot(\n", - " clsys, [-2*pi, 2*pi, -2, 2], 8, params={'kp': 10});" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "id": "5nss-eU_vevc" - }, - "source": [ - "### Improved phase portrait" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "id": "jhU2gidqi-ri" - }, - "source": [ - "This plot is not very useful and has several errors. It shows the limitations of the default parameter values for the `phase_plane_plot` command.\n", - "\n", - "Some things to notice in this plot:\n", - "* The equilibrium point at $\\theta = 0$ is not showing up. This happens because the grid spacing is such that we don't find that point.\n", - "\n", - "To fix these issues, we can do a couple of things:\n", - "* Restrict the range of the plot from $-\\pi$ to $\\pi$, which means that grid used to calculate the equilibrium point is a bit finer.\n", - "* Reset the grid spacing, so that we have more initial conditions around the edge of the plot and a finer search for equilibrium points.\n", - "\n", - "Here's some improved code:" - ] - }, - { - "cell_type": "code", - "execution_count": 8, - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "[,\n", - " ]" - ] - }, - "execution_count": 8, - "metadata": {}, - "output_type": "execute_result" - }, - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "kp_params = {'kp': 10}\n", - "ct.phase_plane_plot(\n", - " clsys, [-1.5 * pi, 1.5 * pi, -2, 2], 8,\n", - " gridspec=[13, 7], params=kp_params,\n", - " plot_separatrices={'timedata': 5})\n", - "plt.plot([-pi, -pi], [-2, 2], 'k--', [ pi, pi], [-2, 2], 'k--')\n", - "plt.plot([-pi/2, -pi/2], [-2, 2], 'k:', [ pi/2, pi/2], [-2, 2], 'k:')" - ] - }, - { - "cell_type": "code", - "execution_count": 9, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "# Play around with some paramters to see what happens\n", - "fig, axs = plt.subplots(2, 2)\n", - "for i, kp in enumerate([3, 10]):\n", - " for j, umax in enumerate([0.2, 1]):\n", - " ct.phase_plane_plot(\n", - " clsys, [-1.5 * pi, 1.5 * pi, -2, 2], 8,\n", - " gridspec=[13, 7], plot_separatrices={'timedata': 5},\n", - " params={'kp': kp, 'umax': umax}, ax=axs[i, j])\n", - " axs[i, j].set_title(f\"{kp=}, {umax=}\")\n", - "plt.tight_layout()" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "id": "dYeVbfG4kU-9" - }, - "source": [ - "## State space controller\n", - "\n", - "For the proportional controller, we have limited control over the dynamics of the closed loop system. For example, we see that the solutions near the origin are highly oscillatory in both the $k_\\text{p} = 3$ and $k_\\text{p} = 10$ cases.\n", - "\n", - "An alternative is to use \"full state feedback\", in which we set\n", - "\n", - "$$\n", - "u = -K (x - x_\\text{d}) = -k_1 (\\theta - \\theta_d) - k_2 (\\dot\\theta - \\dot\\theta_d).\n", - "$$\n", - "\n", - "To compute the gains, we make use of the `place` command, applied to the linearized system:" - ] - }, - { - "cell_type": "code", - "execution_count": 10, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "K=array([[2.01, 1.5 ]])\n" - ] - } - ], - "source": [ - "# Linearize the system\n", - "P = invpend.linearize([0, 0], [0])\n", - "\n", - "# Place the closed loop eigenvalues (poles) at desired locations\n", - "K = ct.place(P.A, P.B, [-1 + 0.1j, -1 - 0.1j])\n", - "print(f\"{K=}\")" - ] - }, - { - "cell_type": "code", - "execution_count": 11, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - ": k_ctrl\n", - "Inputs (4): ['theta', 'thdot', 'theta_d', 'thdot_d']\n", - "Outputs (1): ['tau']\n", - "States (0): []\n", - "\n", - "Update: . at 0x13dd50a40>\n", - "Output: \n" - ] - } - ], - "source": [ - "def statefbk_output(t, x, u, params):\n", - " K = params.get('K', np.array([0, 0]))\n", - " return -K @ (u[0:2] - u[2:])\n", - "statefbk = ct.nlsys(\n", - " None, statefbk_output, name=\"k_ctrl\",\n", - " inputs=['theta', 'thdot', 'theta_d', 'thdot_d'], outputs='tau'\n", - ")\n", - "print(statefbk)" - ] - }, - { - "cell_type": "code", - "execution_count": 12, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - ": invpend w/ state feedback\n", - "Inputs (2): ['theta_d', 'thdot_d']\n", - "Outputs (2): ['theta', 'tau']\n", - "States (2): ['invpend_theta', 'invpend_thdot']\n", - "\n", - "Update: .updfcn at 0x13dd507c0>\n", - "Output: .outfcn at 0x13dd50860>\n" - ] - } - ], - "source": [ - "clsys_sf = ct.interconnect(\n", - " [invpend, statefbk], name='invpend w/ state feedback',\n", - " inputs=['theta_d', 'thdot_d'], outputs=['theta', 'tau'], params={'kp': 1})\n", - "print(clsys_sf)" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "id": "aGm3usQIvmqN" - }, - "source": [ - "### Phase portrait" - ] - }, - { - "cell_type": "code", - "execution_count": 13, - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "[,\n", - " ]" - ] - }, - "execution_count": 13, - "metadata": {}, - "output_type": "execute_result" - }, - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "ct.phase_plane_plot(\n", - " clsys_sf, [-1.5 * pi, 1.5 * pi, -2, 2], 8,\n", - " gridspec=[13, 7], params={'K': K})\n", - "plt.plot([-pi, -pi], [-2, 2], 'k--', [ pi, pi], [-2, 2], 'k--')\n", - "plt.plot([-pi/2, -pi/2], [-2, 2], 'k:', [ pi/2, pi/2], [-2, 2], 'k:')" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "id": "A7UNUtfJwLWQ" - }, - "source": [ - "Note that the closed loop response around the upright equilibrium point is much less oscillatory (consistent with where we placed the closed loop eigenvalues of the system dynamics)." - ] - }, - { - "cell_type": "markdown", - "metadata": { - "id": "eVSa1Mvqycov" - }, - "source": [ - "## Things to try\n", - "\n", - "Here are some things to try with the above code:\n", - "* Try changing the locations of the closed loop eigenvalues in the `place` command\n", - "* Try resetting the limits of the control action (`umax`)\n", - "* Try leaving the state space controller fixed but changing the parameters of the system dynamics ($m$, $l$, $b$). Does the controller still stabilize the system?" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Python 3 (ipykernel)", - "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.11.4" - } - }, - "nbformat": 4, - "nbformat_minor": 4 -} diff --git a/examples/cds110_lti-systems.ipynb b/examples/cds110_lti-systems.ipynb deleted file mode 100644 index 2f28f06c9..000000000 --- a/examples/cds110_lti-systems.ipynb +++ /dev/null @@ -1,827 +0,0 @@ -{ - "cells": [ - { - "cell_type": "markdown", - "metadata": { - "id": "gQZtf4ZqM8HL" - }, - "source": [ - "# Python Tools for Analyzing Linear Systems\n", - "\n", - "CDS 110, Winter 2024
\n", - "Richard M. Murray\n", - "\n", - "In this lecture we describe tools in the Python Control Systems Toolbox (python-control) that can be used to analyze linear systems, including some of the options available to present the information in different ways.\n" - ] - }, - { - "cell_type": "code", - "execution_count": 1, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "python-control version: 0.10.1.dev32+gdbc998de\n" - ] - } - ], - "source": [ - "import numpy as np\n", - "%matplotlib inline\n", - "import matplotlib.pyplot as plt\n", - "\n", - "import control as ct\n", - "print(\"python-control version:\", ct.__version__)" - ] - }, - { - "attachments": {}, - "cell_type": "markdown", - "metadata": { - "id": "qMVGK15gNQw2" - }, - "source": [ - "## Coupled mass spring system\n", - "\n", - "Consider the spring mass system below:\n", - "\n", - "\n", - "\n", - "We wish to analyze the time and frequency response of this system using a variety of python-control functions for linear systems analysis.\n", - "\n", - "### System dynamics\n", - "\n", - "The dynamics of the system can be written as\n", - "\n", - "$$\n", - "\\begin{aligned}\n", - " m \\ddot{q}_1 &= -2 k q_1 - c \\dot{q}_1 + k q_2, \\\\\n", - " m \\ddot{q}_2 &= k q_1 - 2 k q_2 - c \\dot{q}_2 + ku\n", - "\\end{aligned}\n", - "$$\n", - "\n", - "or in state space form:\n", - "\n", - "$$\n", - "\\begin{aligned}\n", - " \\dfrac{dx}{dt} &= \\begin{bmatrix}\n", - " 0 & 0 & 1 & 0 \\\\\n", - " 0 & 0 & 0 & 1 \\\\[0.5ex]\n", - " -\\dfrac{2k}{m} & \\dfrac{k}{m} & -\\dfrac{c}{m} & 0 \\\\[0.5ex]\n", - " \\dfrac{k}{m} & -\\dfrac{2k}{m} & 0 & -\\dfrac{c}{m}\n", - " \\end{bmatrix} x\n", - " + \\begin{bmatrix}\n", - " 0 \\\\ 0 \\\\[0.5ex] 0 \\\\[1ex] \\dfrac{k}{m}\n", - " \\end{bmatrix} u.\n", - "\\end{aligned}\n", - "$$\n", - "\n" - ] - }, - { - "cell_type": "code", - "execution_count": 2, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - ": coupled spring mass\n", - "Inputs (1): ['u[0]']\n", - "Outputs (2): ['q1', 'q2']\n", - "States (4): ['x[0]', 'x[1]', 'x[2]', 'x[3]']\n", - "\n", - "A = [[ 0. 0. 1. 0. ]\n", - " [ 0. 0. 0. 1. ]\n", - " [-4. 2. -0.1 0. ]\n", - " [ 2. -4. 0. -0.1]]\n", - "\n", - "B = [[0.]\n", - " [0.]\n", - " [0.]\n", - " [2.]]\n", - "\n", - "C = [[1. 0. 0. 0.]\n", - " [0. 1. 0. 0.]]\n", - "\n", - "D = [[0.]\n", - " [0.]]\n", - "\n" - ] - } - ], - "source": [ - "# Define the parameters for the system\n", - "m, c, k = 1, 0.1, 2\n", - "# Create a linear system\n", - "A = np.array([\n", - " [0, 0, 1, 0],\n", - " [0, 0, 0, 1],\n", - " [-2*k/m, k/m, -c/m, 0],\n", - " [k/m, -2*k/m, 0, -c/m]\n", - "])\n", - "B = np.array([[0], [0], [0], [k/m]])\n", - "C = np.array([[1, 0, 0, 0], [0, 1, 0, 0]])\n", - "D = 0\n", - "\n", - "sys = ct.ss(A, B, C, D, outputs=['q1', 'q2'], name=\"coupled spring mass\")\n", - "print(sys)" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "id": "kobxJ1yG4v_1" - }, - "source": [ - "Another way to get these same dynamics is to define and input/output system:" - ] - }, - { - "cell_type": "code", - "execution_count": 3, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - ": sys[0]\n", - "Inputs (1): ['u[0]']\n", - "Outputs (2): ['y[0]', 'y[1]']\n", - "States (4): ['x[0]', 'x[1]', 'x[2]', 'x[3]']\n", - "\n", - "A = [[ 0. 0. 1. 0. ]\n", - " [ 0. 0. 0. 1. ]\n", - " [-4. 2. -0.1 0. ]\n", - " [ 2. -4. 0. -0.1]]\n", - "\n", - "B = [[0.]\n", - " [0.]\n", - " [0.]\n", - " [2.]]\n", - "\n", - "C = [[1. 0. 0. 0.]\n", - " [0. 1. 0. 0.]]\n", - "\n", - "D = [[0.]\n", - " [0.]]\n", - "\n" - ] - } - ], - "source": [ - "coupled_params = {'m': 1, 'c': 0.1, 'k': 2}\n", - "def coupled_update(t, x, u, params):\n", - " m, c, k = params['m'], params['c'], params['k']\n", - " return np.array([\n", - " x[2], x[3],\n", - " -2*k/m * x[0] + k/m * x[1] - c/m * x[2],\n", - " k/m * x[0] -2*k/m * x[1] - c/m * x[3] + k/m * u[0]\n", - " ])\n", - "def coupled_output(t, x, u, params):\n", - " return x[0:2]\n", - "coupled = ct.nlsys(\n", - " coupled_update, coupled_output, inputs=1, outputs=['q1', 'q2'],\n", - " states=['q1', 'q2', 'q1dot', 'q2dot'], name='coupled (nl)',\n", - " params=coupled_params\n", - ")\n", - "print(coupled.linearize([0, 0, 0, 0], [0]))" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "id": "YmH87LEXWo1U" - }, - "source": [ - "### Initial response\n", - "\n", - "The `initial_response` function can be used to compute the response of the system with no input, but starting from a given initial condition. This function returns a response object, we can be used for plotting." - ] - }, - { - "cell_type": "code", - "execution_count": 4, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "response = ct.initial_response(sys, X0=[1, 0, 0, 0])\n", - "out = response.plot()" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "id": "Y4aAxYvZRBnD" - }, - "source": [ - "If you want to play around with the way the data are plotted, you can also use the response object to get direct access to the states and outputs." - ] - }, - { - "cell_type": "code", - "execution_count": 5, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "# Plot the outputs of the system on the same graph, in different colors\n", - "t = response.time\n", - "x = response.states\n", - "plt.plot(t, x[0], 'b', t, x[1], 'r')\n", - "plt.legend(['$x_1$', '$x_2$'])\n", - "plt.xlim(0, 50)\n", - "plt.ylabel('States')\n", - "plt.xlabel('Time [s]')\n", - "plt.title(\"Initial response from $x_1 = 1$, $x_2 = 0$\");" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "id": "Cou0QVnkTou9" - }, - "source": [ - "There are also lots of options available in `initial_response` and `.plot()` for tuning the plots that you get." - ] - }, - { - "cell_type": "code", - "execution_count": 6, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "# Do some Python magic to get different colors\n", - "from itertools import cycle\n", - "prop_cycle = plt.rcParams['axes.prop_cycle']\n", - "colors = cycle(prop_cycle.by_key()['color'])\n", - "\n", - "for X0 in [[1, 0, 0, 0], [0, 2, 0, 0], [1, 2, 0, 0], [0, 0, 1, 0], [0, 0, 2, 0]]:\n", - " response = ct.initial_response(sys, T=20, X0=X0)\n", - " response.plot(color=next(colors), label=f\"{X0=}\")" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "id": "b3VFPUBKT4bh" - }, - "source": [ - "### Step response\n", - "\n", - "Similar to `initial_response`, you can also generate a step response for a linear system using the `step_response` function, which returns a time response object:" - ] - }, - { - "cell_type": "code", - "execution_count": 7, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "out = ct.step_response(sys).plot()" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "id": "iHZR1Q3IcrFT" - }, - "source": [ - "We can analyze the properties of the step response using the `stepinfo` command:" - ] - }, - { - "cell_type": "code", - "execution_count": 8, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "Input 0, output 0 rise time = 0.6153902252990775 seconds\n", - "\n" - ] - }, - { - "data": { - "text/plain": [ - "[[{'RiseTime': 0.6153902252990775,\n", - " 'SettlingTime': 89.02645259326653,\n", - " 'SettlingMin': -0.13272845655369417,\n", - " 'SettlingMax': 0.9005994876222034,\n", - " 'Overshoot': 170.17984628666102,\n", - " 'Undershoot': 39.81853696610825,\n", - " 'Peak': 0.9005994876222034,\n", - " 'PeakTime': 2.3589958636464634,\n", - " 'SteadyStateValue': 0.33333333333333337}],\n", - " [{'RiseTime': 0.6153902252990775,\n", - " 'SettlingTime': 73.6416969607896,\n", - " 'SettlingMin': 0.2276019820782241,\n", - " 'SettlingMax': 1.13389337710215,\n", - " 'Overshoot': 70.08400656532254,\n", - " 'Undershoot': 0,\n", - " 'Peak': 1.13389337710215,\n", - " 'PeakTime': 6.564162403190159,\n", - " 'SteadyStateValue': 0.6666666666666665}]]" - ] - }, - "execution_count": 8, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "step_info = ct.step_info(sys)\n", - "print(\"Input 0, output 0 rise time = \",\n", - " step_info[0][0]['RiseTime'], \"seconds\\n\")\n", - "step_info" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "id": "F8KxXwqHWFab" - }, - "source": [ - "Note that by default the inputs are not included in the step response plot (since they are a bit boring), but you can change that:" - ] - }, - { - "cell_type": "code", - "execution_count": 9, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "stepresp = ct.step_response(sys)\n", - "out = stepresp.plot(plot_inputs=True)" - ] - }, - { - "cell_type": "code", - "execution_count": 10, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "out = stepresp.plot(plot_inputs='overlay')" - ] - }, - { - "cell_type": "code", - "execution_count": 11, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "stepresp.time.shape=(1348,)\n", - "stepresp.inputs.shape=(1, 1, 1348)\n", - "stepresp.states.shape=(4, 1, 1348)\n", - "stepresp.outputs.shape=(2, 1, 1348)\n" - ] - } - ], - "source": [ - "# Look at the \"shape\" of the step response\n", - "print(f\"{stepresp.time.shape=}\")\n", - "print(f\"{stepresp.inputs.shape=}\")\n", - "print(f\"{stepresp.states.shape=}\")\n", - "print(f\"{stepresp.outputs.shape=}\")" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "id": "FDfZkyk1ly0T" - }, - "source": [ - "## Forced response\n", - "\n", - "To compute the response to an input, using the convolution equation, we can use the `forced_response` function:" - ] - }, - { - "cell_type": "code", - "execution_count": 12, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "T = np.linspace(0, 50, 500)\n", - "U1 = np.cos(T)\n", - "U2 = np.sin(3 * T)\n", - "\n", - "resp1 = ct.forced_response(sys, T, U1)\n", - "resp2 = ct.forced_response(sys, T, U2)\n", - "resp3 = ct.forced_response(sys, T, U1 + U2)\n", - "\n", - "# Plot the individual responses\n", - "resp1.sysname = 'U1'; resp1.plot(color='b')\n", - "resp2.sysname = 'U2'; resp2.plot(color='g')\n", - "resp3.sysname = 'U1 + U2'; resp3.plot(color='r');" - ] - }, - { - "cell_type": "code", - "execution_count": 13, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "# Show that the system response is linear\n", - "out = resp3.plot()\n", - "axs = ct.get_plot_axes(out)\n", - "axs[0, 0].plot(resp1.time, resp1.outputs[0] + resp2.outputs[0], 'k--')\n", - "axs[1, 0].plot(resp1.time, resp1.outputs[1] + resp2.outputs[1], 'k--')\n", - "axs[2, 0].plot(resp1.time, resp1.inputs[0] + resp2.inputs[0], 'k--');" - ] - }, - { - "cell_type": "code", - "execution_count": 14, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "# Show that the forced response from non-zero initial condition is not linear\n", - "X0 = [1, 0, 0, 0]\n", - "resp1 = ct.forced_response(sys, T, U1, X0=X0)\n", - "resp2 = ct.forced_response(sys, T, U2, X0=X0)\n", - "resp3 = ct.forced_response(sys, T, U1 + U2, X0=X0)\n", - "\n", - "out = resp3.plot()\n", - "axs = ct.get_plot_axes(out)\n", - "axs[0, 0].plot(resp1.time, resp1.outputs[0] + resp2.outputs[0], 'k--')\n", - "axs[1, 0].plot(resp1.time, resp1.outputs[1] + resp2.outputs[1], 'k--')\n", - "axs[2, 0].plot(resp1.time, resp1.inputs[0] + resp2.inputs[0], 'k--');" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "id": "mo7hpvPQkKke" - }, - "source": [ - "### Frequency response" - ] - }, - { - "cell_type": "code", - "execution_count": 15, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "# Manual computation of the frequency response\n", - "resp = ct.input_output_response(sys, T, np.sin(1.35 * T))\n", - "\n", - "out = resp.plot(\n", - " plot_inputs='overlay', \n", - " legend_map=np.array([['lower left'], ['lower left']]),\n", - " label=[['q1', 'u[0]'], ['q2', None]])" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "id": "muqeLlJJ6s8F" - }, - "source": [ - "The magnitude and phase of the frequency response is controlled by the transfer function,\n", - "\n", - "$$\n", - "G(s) = C (sI - A)^{-1} B + D\n", - "$$\n", - "\n", - "which can be computed using the `ss2tf` function:" - ] - }, - { - "cell_type": "code", - "execution_count": 16, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - ": u to q1\n", - "Inputs (1): ['u[0]']\n", - "Outputs (2): ['q1', 'q2']\n", - "\n", - "\n", - "Input 1 to output 1:\n", - " 4\n", - "-------------------------------------\n", - "s^4 + 0.2 s^3 + 8.01 s^2 + 0.8 s + 12\n", - "\n", - "Input 1 to output 2:\n", - " 2 s^2 + 0.2 s + 8\n", - "-------------------------------------\n", - "s^4 + 0.2 s^3 + 8.01 s^2 + 0.8 s + 12\n", - "\n" - ] - } - ], - "source": [ - "# Create SISO transfer functions, in case we don't have slycot\n", - "G = ct.ss2tf(sys, name='u to q1')\n", - "print(G)" - ] - }, - { - "cell_type": "code", - "execution_count": 17, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "G(1.35j)=array([[3.33005647-2.70686327j],\n", - " [3.80831226-2.72231858j]])\n", - "Gain: [[4.29143157]\n", - " [4.681267 ]]\n", - "Phase: [[-0.6825322 ]\n", - " [-0.62061375]] ( [[-39.10621449]\n", - " [-35.55854848]] deg)\n" - ] - } - ], - "source": [ - "# Gain and phase for the simulation above\n", - "from math import pi\n", - "val = G(1.35j)\n", - "print(f\"{G(1.35j)=}\")\n", - "print(f\"Gain: {np.absolute(val)}\")\n", - "print(f\"Phase: {np.angle(val)}\", \" (\", np.angle(val) * 180/pi, \"deg)\")" - ] - }, - { - "cell_type": "code", - "execution_count": 18, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "G(0)=array([[0.33333333+0.j],\n", - " [0.66666667+0.j]])\n", - "Final value of step response: 0.33297541813724874\n" - ] - } - ], - "source": [ - "# Gain and phase at s = 0 (= steady state step response)\n", - "print(f\"{G(0)=}\")\n", - "print(\"Final value of step response:\", stepresp.outputs[0, 0, -1])" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "id": "I9eFoXm92Jgj" - }, - "source": [ - "The frequency response across all frequencies can be computed using the `frequency_response` function:" - ] - }, - { - "cell_type": "code", - "execution_count": 19, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "freqresp = ct.frequency_response(sys)\n", - "out = freqresp.plot()" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "id": "pylQb07G2cqe" - }, - "source": [ - "By default, frequency responses are plotted using a \"Bode plot\", which plots the log of the magnitude and the (linear) phase against the log of the forcing frequency.\n", - "\n", - "You can also call the Bode plot command directly, and change the way the data are presented:" - ] - }, - { - "cell_type": "code", - "execution_count": 20, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "iVBORw0KGgoAAAANSUhEUgAAAnYAAAHbCAYAAABGPtdUAAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjguMywgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy/H5lhTAAAACXBIWXMAAA9hAAAPYQGoP6dpAAC3kElEQVR4nOzdd3xUVdrA8d+dkknvQBISeuhFkS4gKKACChZEXRV2bSirrqDvLgsq2NdeNuguuqKsKBZcRFApUpUmvfcSIJCQkN6mnPePIUMCCWSSmUzJ8+Uzn5m5955znzmTQ07uKVdTSimEEEIIIYTP03k6ACGEEEII4RrSsBNCCCGE8BPSsBNCCCGE8BPSsBNCCCGE8BPSsBNCCCGE8BPSsBNCCCGE8BPSsBNCCCGE8BPSsBNCCCGE8BPSsBNCCCGE8BPSsBOiHhg7diwjR450+3k0TeN///ufy/NVSvHQQw8RHR2Npmls2bLF5efwtJkzZxIZGVnrfNz1HXjreYUQFUnDTggvMXbsWDRNczxiYmK44YYb2LZtm6dDc5vqNjh/+uknZs6cyQ8//EBaWhodO3Z0f3DCKWlpadx4442eDkOIek8adkJ4kRtuuIG0tDTS0tJYunQpBoOB4cOHezosjzt48CDx8fH06dOHuLg4DAaD03kopbBYLG6Irn4rLS0FIC4uDpPJ5OFohBDSsBPCi5hMJuLi4oiLi+OKK67gr3/9K6mpqWRkZDiO2b59O9deey1BQUHExMTw0EMPkZ+f79hvtVqZMGECkZGRxMTE8H//938opSqcRynFa6+9RosWLQgKCqJLly588803l4ytWbNmvPDCC9x9992EhoaSkJDA+++/f8k0l4p16tSpfPrpp8ybN89xlXL58uUX5TF27Fgee+wxjh07hqZpNGvWDICSkhIef/xxGjZsSGBgIH379mXDhg2OdMuXL0fTNH7++We6deuGyWRi1apVlcZ5/Phx7rzzTqKjowkJCaFbt26sW7fOsf+DDz6gZcuWBAQE0KZNG2bNmuXYd+TIkYu6h7Ozsyt8nrJYFixYQJcuXQgMDKRnz55s3779kuU3f/58rrrqKgIDA2nRogXTpk2r0Djdv38//fv3JzAwkPbt27N48eJL5gfwzTff0KlTJ8d3MmjQIAoKChxlPXLkSKZNm0bDhg0JDw/n4YcfdjTeAAYMGMCf//xnJkyYQGxsLIMHDwYqdsWWlcncuXMZOHAgwcHBdOnShTVr1lSIZcaMGSQlJREcHMwtt9zCW2+9dcnu6LJ8v/rqK/r160dQUBDdu3dn3759bNiwgW7duhEaGsoNN9xQoc5s2LCBwYMHExsbS0REBNdccw2bNm2qkPfUqVNp0qQJJpOJhIQEHn/8cce+6dOnk5ycTGBgII0aNeL222+/bDkL4TFKCOEVxowZo0aMGOF4n5eXpx5++GHVqlUrZbValVJKFRQUqISEBHXrrbeq7du3q6VLl6rmzZurMWPGONL94x//UBEREeqbb75Ru3btUvfff78KCwurkPff//531bZtW/XTTz+pgwcPqk8++USZTCa1fPnyKuNr2rSpCgsLU6+88orau3eveu+995Rer1eLFi1yHAOo7777rlqx5uXlqTvuuEPdcMMNKi0tTaWlpamSkpKLzpudna2ef/55lZiYqNLS0lR6erpSSqnHH39cJSQkqIULF6qdO3eqMWPGqKioKJWZmamUUmrZsmUKUJ07d1aLFi1SBw4cUGfOnLko/7y8PNWiRQvVr18/tWrVKrV//341Z84c9dtvvymllJo7d64yGo0qJSVF7d27V7355ptKr9erX375RSml1OHDhxWgNm/e7Mjz7NmzClDLli2rEEu7du3UokWL1LZt29Tw4cNVs2bNVGlpqVJKqU8++URFREQ48vjpp59UeHi4mjlzpjp48KBatGiRatasmZo6dapSSimr1ao6duyoBgwYoDZv3qxWrFihrrzyygrfwYVOnjypDAaDeuutt9Thw4fVtm3bVEpKisrLy1NK2X8GQ0ND1ejRo9WOHTvUDz/8oBo0aKD+/ve/O/K45pprVGhoqHr66afVnj171O7duy/67svKpG3btuqHH35Qe/fuVbfffrtq2rSpMpvNSimlVq9erXQ6nXr99dfV3r17VUpKioqOjq5QBhcqn+9PP/2kdu3apXr16qW6du2qBgwYoFavXq02bdqkWrVqpcaNG+dIt3TpUjVr1iy1a9cuR51o1KiRys3NVUop9fXXX6vw8HC1cOFCdfToUbVu3Tr173//Wyml1IYNG5Rer1ezZ89WR44cUZs2bVLvvvtulTEK4WnSsBPCS4wZM0bp9XoVEhKiQkJCFKDi4+PVxo0bHcf8+9//VlFRUSo/P9+xbcGCBUqn06lTp04ppZSKj49Xr776qmO/2WxWiYmJjoZdfn6+CgwMdDRcytx///3qrrvuqjK+pk2bqhtuuKHCttGjR6sbb7zR8b78L/fqxHphY7Yqb7/9tmratKnjfX5+vjIajerzzz93bCstLVUJCQnqtddeU0qdb0z973//u2Te//rXv1RYWJijQXihPn36qAcffLDCtlGjRqmhQ4cqpZxr2H355ZeOYzIzM1VQUJCaM2eOUurihl2/fv3Uyy+/XOG8s2bNUvHx8UoppX7++Wel1+tVamqqY/+PP/54yYbdxo0bFaCOHDlS6f4xY8ao6OhoVVBQ4Nj2wQcfqNDQUMcfF9dcc4264oorLkpbWcPuo48+cuzfuXOnAhwNwdGjR6thw4ZVyOMPf/hDtRp25fP94osvFKCWLl3q2PbKK6+oNm3aVJmPxWJRYWFhav78+Uoppd58803VunVrRyO7vG+//VaFh4c7GoFCeDvpihXCiwwcOJAtW7awZcsW1q1bx5AhQ7jxxhs5evQoALt376ZLly6EhIQ40lx99dXYbDb27t1LTk4OaWlp9O7d27HfYDDQrVs3x/tdu3ZRXFzM4MGDCQ0NdTw+++wzDh48eMn4yudb9n737t2VHnu5WGvj4MGDmM1mrr76asc2o9FIjx49Loqn/GevzJYtW7jyyiuJjo6udP/u3bsrnAfsn6Oqz30p5csvOjqaNm3aVJnPxo0bef755yt8Rw8++CBpaWkUFhaye/dumjRpQmJiYqX5V6ZLly5cd911dOrUiVGjRjFjxgzOnj170THBwcEV8szPzyc1NdWx7XJlWqZz586O1/Hx8QCkp6cDsHfvXnr06FHh+AvfVyffRo0aAdCpU6cK28rOU3bOcePG0bp1ayIiIoiIiCA/P59jx44BMGrUKIqKimjRogUPPvgg3333naPLe/DgwTRt2pQWLVpw77338vnnn1NYWFitOIXwBOdHIAsh3CYkJIRWrVo53l911VVEREQwY8YMXnzxRZRSaJpWadqqtl/IZrMBsGDBAho3blxhX00Gv1d1XlfEWhV1bszghflUds7yDcvKBAUFXfZ8lzqPTqerEBOA2Wy+bJ5V5V3GZrMxbdo0br311ov2BQYGXjRu8lJ5ldHr9SxevJjffvuNRYsW8f777zN58mTWrVtH8+bNqx3n5cq0jNFovCh92c9fZd9VZZ+puvleuK3sPGAfO5iRkcE777xD06ZNMZlM9O7d2zF2MCkpib1797J48WKWLFnCo48+yuuvv86KFSsICwtj06ZNLF++nEWLFvHss88ydepUNmzY4JLlaYRwNbliJ4QX0zQNnU5HUVERAO3bt2fLli2Owe4Av/76KzqdznE1Ij4+nrVr1zr2WywWNm7c6Hjfvn17TCYTx44do1WrVhUeSUlJl4ynfL5l79u2bVvpsZeLFSAgIACr1VrN0jivVatWBAQEsHr1asc2s9nM77//Trt27ZzKq3PnzmzZsoWsrKxK97dr167CeQB+++03x3kaNGgA2Jf7KFPVOnvly+/s2bPs27evyvLr2rUre/fuveg7atWqFTqdjvbt23Ps2DFOnjzpSHPh5ITKaJrG1VdfzbRp09i8eTMBAQF89913jv1bt251/LyVxRwaGlrhyqArtG3blvXr11fY9vvvv7v0HGVWrVrF448/ztChQ+nQoQMmk4kzZ85UOCYoKIibb76Z9957j+XLl7NmzRrH5BaDwcCgQYN47bXX2LZtG0eOHOGXX35xS6xC1JZcsRPCi5SUlHDq1CnA/ov/n//8J/n5+dx0000A/OEPf+C5555jzJgxTJ06lYyMDB577DHuvfdeR5fUE088wauvvkpycjLt2rXjrbfeIjs723GOsLAwnnrqKZ588klsNht9+/YlNzeX3377jdDQUMaMGVNlfL/++iuvvfYaI0eOZPHixXz99dcsWLCg0mOrE2uzZs34+eef2bt3LzExMURERFS48lKVkJAQHnnkEZ5++mmio6Np0qQJr732GoWFhdx///3VKusyd911Fy+//DIjR47klVdeIT4+ns2bN5OQkEDv3r15+umnueOOO+jatSvXXXcd8+fPZ+7cuSxZsgSwNwh69erFq6++SrNmzThz5gxTpkyp9FzPP/88MTExNGrUiMmTJxMbG1vlOn7PPvssw4cPJykpiVGjRqHT6di2bRvbt2/nxRdfZNCgQbRp04b77ruPN998k9zcXCZPnnzJz7pu3TqWLl3KkCFDaNiwIevWrSMjI6NCY7i0tJT777+fKVOmcPToUZ577jn+/Oc/O65Muspjjz1G//79eeutt7jpppv45Zdf+PHHH2t9NbcyrVq1YtasWXTr1o3c3FyefvrpCldqZ86cidVqpWfPngQHBzNr1iyCgoJo2rQpP/zwA4cOHaJ///5ERUWxcOFCbDYbbdq0cXmcQriEx0b3CSEqGDNmjAIcj7CwMNW9e3f1zTffVDhu27ZtauDAgSowMFBFR0erBx980DGrUSn7ZIknnnhChYeHq8jISDVhwgR13333VZikYLPZ1LvvvqvatGmjjEajatCggbr++uvVihUrqoyvadOmatq0aeqOO+5QwcHBqlGjRuqdd96pcAwXDNy/XKzp6elq8ODBKjQ0tMJkgwtdOHlCKaWKiorUY489pmJjY5XJZFJXX321Wr9+vWN/2YSFs2fPVvmZyhw5ckTddtttKjw8XAUHB6tu3bqpdevWOfZPnz5dtWjRQhmNRtW6dWv12WefVUhfNjszKChIXXHFFWrRokWVTp6YP3++6tChgwoICFDdu3dXW7ZsceRx4eQJpewzY/v06aOCgoJUeHi46tGjh2O2plJK7d27V/Xt21cFBASo1q1bq59++umSkyd27dqlrr/+etWgQQNlMplU69at1fvvv+/YXzaZ5dlnn1UxMTEqNDRUPfDAA6q4uNhxzDXXXKOeeOKJi/KmkskTl5pQopR9gk3jxo1VUFCQGjlypHrxxRdVXFxcpbFXlW9l3/OFZblp0ybVrVs3ZTKZVHJysvr6669V06ZN1dtvv62UUuq7775TPXv2VOHh4SokJET16tVLLVmyRCml1KpVq9Q111yjoqKiVFBQkOrcubNjwosQ3khTqpqDGoQQ9VqzZs34y1/+wl/+8hdPh+Jzli9fzsCBAzl79qxXj8saO3Ys2dnZHrs12IMPPsiePXuqXG9QCHF50hUrhBDCI9544w0GDx5MSEgIP/74I59++inTp0/3dFhC+DRp2AkhhPCI9evX89prr5GXl0eLFi147733eOCBBzwdlhA+TbpihRBCCCH8hCx3IoQQQgjhJ6RhJ4QQQgjhJ6RhJ4QQQgjhJ6RhJ4QQQgjhJ6RhJ4QQQgjhJ6RhJ4QQQgjhJ6RhJ4QQQgjhJ6RhJ4QQQgjhJ6RhJ4QQQgjhJ6RhJ4QQQgjhJ6RhJ4QQQgjhJ6RhJ4QQQgjhJ6RhJ4QQQgjhJ6RhJ4QQQgjhJ6RhJ4QQQgjhJ6RhJ4QQQgjhJ6RhJ4QQQgjhJ6RhJ4QQQgjhJ6RhJ4QQQgjhJ6RhJ4QQQgjhJ/y2YZeamkrXrl0JDAzEYrF4OhwhhBBCCLfz24ZdgwYN+OWXX+jVq5enQxFCCCGEqBMGTwfgLoGBgQQGBtYorc1m4+TJk4SFhaFpmosjE0IIIYSoPqUUeXl5JCQkoNNd5pqc8gHPPvusateundI0TX3xxRcV9qWnp6uhQ4eqoKAg1bp1a7VkyZIK+6+55hplNpudOl9qaqoC5CEPechDHvKQhzy85pGamnrZNoxPXLFLTk7m3Xff5Zlnnrlo3/jx40lISODMmTMsWrSIUaNGcfDgQaKiomp8vrCwMAA++ugjRo4cidForFY6s9nMokWLGDJkyGXTOHNsfedrZeXpeN19flfnX9v8apO+JmmlnruHr5WVp+OVeu7etN5Wz3Nzc0lKSnK0Ty7FJxp299xzDwAvvfRShe35+fnMmzePI0eOEBwczMiRI3nrrbeYP38+9913X7XzLykpoaSkxPE+Ly8PgODgYIKCgqr9RRkMhmqncebY+s7XysrT8br7/K7Ov7b51SZ9TdJKPXcPXysrT8cr9dy9ab2tnpvNZoBqDQ/TlFLKLVG4wYABAxg3bhx33nknAJs3b+b6668nPT3dccxjjz1GcHAw06ZNY/jw4WzcuJGuXbsydepU+vXrV2m+U6dOZdq0aRdtnz17NsHBwe75MEIIIYQQ1VBYWMjdd99NTk4O4eHhlzzWp2fF5ufnX/QBw8PDyc/PJzAwkCVLlnD27FmWLl1aZaMOYNKkSeTk5PDGG2/Qpk0bWrVq5e7QhRBCCCFczie6YqsSGhpKbm5uhW25ubmEhoY6lY/JZMJkMjFx4kQmTpxIbm4uERERAAwcOBCDoXrFZLFYWLZsWbXSOHNsfedrZeXpeN19flfnX9v8apO+JmmlnruHr5WVp+OVeu7etN5Wzy9s61yKT3fF5ufnExMTw9GjR4mLiwOgf//+PPDAA06NsSuTkpJCSkoKVquVffv2SVesEEIIITzOma5Y7/+zCPugQavVis1mw2w2U1xcTEBAAKGhodx8880899xzvPPOOyxevJgdO3Zw00031eg848ePZ/z48XLFzsv4Wll5Ol75S969aX26nluKSVvwMpZjv3Oi4QCuuGUCgQFeEBdeWFaX4el4pZ67N6231XO/u2I3duxYPv300wrbli1bxoABA8jIyGDMmDEsX76cxMREpk+fzqBBg2p0HrliJ4TwW8pG+73vkFy0xbFpluE2wjqOQNZhF8K7OXPFzicadnWt7Ird7NmzGTFihFPr3ixevJjBgwdXa92b6h5b3/laWXk6Xnef39X51za/2qSvSVpfrecF62cRufhJipWRX4Ov47qinyhVen68Zh5D+3n+1oveVFbV4el4pZ67N6231fPc3FxiY2P9f1asEEKIaigtQLfcvg7o50F/oNfjn5Ea1YsAzYpx5asUlFg8HKAQwlXkil050hUrhPBHzY/PpXPG/zhma8AXzV6lbYyRsIIjXLvvWaxK4/nYt+jaJMbTYQohqiBdsbUkXbHexdfKytPxSheNe9P6XD3PTYOUbhhtJbwS+lcmPv6UY/X6rA9vpFHmBj7WbuH2pz4g2IMTKbyirJzg6Xilnrs3rbfVc+mKFUIIAYB16QsYbSVssLXmisH3VbglUWT/RwAYaVvC12sPeipEIYQLyRW7cqQrVgjhTyIKDzNg73MA3K89z01dmlWYAaspK/23TSTSlsVk2ziuuKIPAXoPBSuEqJJ0xdaSdMV6F18rK0/HK1007k3rM/Vc2WDmMIwnNzDX2hfDrR9yY8e4iw9b+SYBq15hi60lmwZ/zb29mtRtnOd4ut44y9PxSj13b1pvq+fOdMV6/yqQHmY0Gp3+opxJU5P86ytfKytPx+vu87s6/9rmV5v0flnPN82CkxsoUCa+jvgTn3dJRKerZMG6nvdjXf0GV+gO8u7KJfyh9wOYDJ67bOfKslJKsfS7/5B0fD6Nh08itEVPl+RbntTzus2vvtZzZ/KVht1lmM1mp4+tThpnjq3vfK2sPB2vu8/v6vxrm19t0tckrU/U88Is9IueQQe8bbmdu67rgdVqwWqt5FhTJLS7Gf2ubxla9ANfrR/Cnd0T6zZe3FNWP65YzdCtT2HQbOR/vgnzhG0QEOKSvKWe121+9b2eO5O3dMWWI2PshBD+4Mqj/6ZJ1mr22JJ4SP8iT3bRqOxiXZmogv303/cCJcrI9ep9/nxlMEY/mFpXuPkL7uJHx/v1CWNJa3StByMSomb87l6xdaWye8X6cp+8v/C1svJ0vDL2xr1pvb2ea7vnYdi8GpvSmGz+E38f1Z3r2ja8dCKlsH70P0zp27nesoK0sCcZd02LOom3jKvLat/pPAI3/hV0sFNLpoPaT1LpXq4c+oYLopV6Xtf51fd67sy9YqVhdxm+3Cfvb3ytrDwdr4y9cW9ar6znZ4/AwokATLfejDWxJ9d3TKiwxEmVej0M3/+Ze/RLGLryZkb3bErDsED3xlsJV5XVyk07eESXhg2NLR0n0WH7n2h4Zj16SwEERdY+0HOkntdtfvW1nssYOxfy5T55f+FrZeXpeGXsjXvTem09L8nDMPtOtOJsttha8K71NuYMa4PFUs3bhbW9GcOiKSQVZ9Cz9Hde+zGBV27p4N6Yy3FlWSmlyNy+BICciHYktL+a/Vsbk6w7gWXPj6iOt9f6HFLP6za/+l7PZYxdDckYOyGET1I2ehx+l/iczWQQyfDiF2nZMJLRLW1OZdP+xByS0xew0ZbMbaVTGd/eRusI3/sVcSQPEvZ8xCjDSvY0GMa2+NFkbvqaRwzzORTek+0tx3s6RCGcImPsakjG2HknXysrT8crY2/cm9br6rnNiv6Hx9HlbMaiBfBA8QRKghrxzv1XExUc4FxeeV1RKUu4iv300u3mfye78sOtfQg1uf9XhSvL6qUFu7lNvwuAVoPG0rLFQP5+JB1y55NUuJOk6weB3smycWO83nh+qefeVc9ljJ0L+XKfvL/xtbLydLwy9sa9ab2intussPBJ2D4Hpel5rHQ8W1Ur3hvZkYYRNVjWIzoJrrwHfv+YCYHzuSO7Pa8t2s8rt3Z2fexVqG1ZWW2KbTu2kqidwaYzYmh+NRiNRLbuTcaGcBpYcuHEemg50Cvi9fbzSz33gnqOc2Ps/GBCuxBC1EOlhfDVfbB5FkrTMS3gSX60dmfkFQnc3CWh5vle/QRoenrYttJFO8AX61OZu+m46+J2s18PnKFN0Wb7m8TujnXrerRowFJrV/v2vT9WkVoI3ycNOyGE8DU5J+DTm2DPDyh9AB/G/p2ZOV1pHBnEtBEda5d3VFPoPBqA9xr+AMCkudvZcSKntlHXiTkbUrlatwMAXYtrHNu7N4tiqboKAOuehSDDy4WfkoadEEL4kv2L4cO+cOJ3CIzkizbv8Y/U9pgMOj64pysRQS7oChrwN9AH0DRnPeObHKPEYuOhz34nLaeo9nm7UUZeCUt2neRq3U77hhYDHPsigwPIaNCbIhWAPjcVTu/0TJBCuJmMsbsMX54e7S98raw8Ha8sg+DetB6r56X56Fa8gn79vwBQjToxL/kl/r4kH4CXR3agXaMQ15wrNAHdVX9Ev/5fPMl/+TH6eQ5lFXPvR+uY/UB35ydlVIMryuo/qw+SbDtMlJaPCgjF0rAzlMuvS/M4Vmd2YrB+I9bt32KLaePReGtD6rl703rb73NZ7qSGZLkTIYQ3apizlS7HPyW49AwAh2IH8XngXfznQCAKjSGNbQxr4tzSJpcTYMlj0M6JGG3FLG/8CE+k9iWnVCMpRPFIOyshXjaPqdgCUzfpGct8/mr8krSIK1nf4skKx2zL0ji9fz3/DHifQmM0izu8BZp0XAnvJ8ud1JAsd+KdfK2sPB2vLIPg3rR1Ws/TtqJf9gK6w8sBUBFNsN74Opvz2/Pp3B0oFH/okcRzw9tW7+4STtJFn4AVL3NN/gK+/NMT3P3ZdlILzMw8FsnMsVfRIMzksnPVtqzeWryfIuthBofsBCs07Dmaod2HVjimd2Ep/V6xkqOCiTBnMaxdKKpcd21dxltbUs/dm9bbfp/Lcicu5MvTo/2Nr5WVp+OVZRDcm9at9fzUdlj9Nuz41v5eZ4Re49AGTGL2xgye+347SsGtXRvzwshO6HSub9QBcPWfYfNnaDnHaHf4E+Y8/Bj3fLSOfen53DFjPTPu60a7+EtfPXBWTb6L1KxCPllzlEBKuELtAUDfehD6C/JpGGGkeVwM35/pw72GJRi2fwltBtd5vK4k9dy9ab3l97ksdyKEEL5GKTj4C3w20j45oqxR1+kOeOx3bINe4PVlqTw7bydKwdg+zXjj9i7ua9SBfamQG162v179Dq0N6Xw9rjdNY4I5fraIW6f/xoJtae47fzXYbIq/zd1GsdnG/QlH0NnMEJEEMa0qPb5Py1i+tp6bLbv7e8g7XYfRCuF+0rATQghPyjsNq9+Bf3aHWbfAoWX2cV8dboWHV8JtM8gJbMwDn/1OyrKDADxxXTLP3dTevY26Mu1uhpbXgrUEfvwrTaODmTf+avolx1JktjJ+9iYmf7edgpJq3pPWxd7/5QC/Hsgk0KhjXMPd9o1th0EVXdMD2zZgm2rBNq01WEvh3GQUIfyFXzfsJkyYQL9+/Xj88cc9HYoQQpxXlA1bvoDZo+GtdrDkOcjcD8YQ6DkOHt8Moz6B+C5sO57NyJRf+WVPOiaDjrfu6MKTg1u7ZUxdpTQNbnzd3h18YDHs/p7I4AA+Gdudh/q3AODzdce48d1VrDmYWTcxnfPj9jTeXrIPgBduakvY0SX2HW2HV5mmR/NoggMM/LNkmH3Dho+gJM/doQpRZ/y2Ybdp0yby8/NZtWoVZrOZDRs2eDokIUR9lp0KG2fCf2+D11vB/8bBvp9AWSGxB9z8Pjy1F278B0Q1w2K18d7S/dw6/TcOnykgISKQb8b14dauiXUfe2wr+x0pABY8BYVZGPQ6/j60HZ8/0JOEiECOZRVy14y1PPr5RlKzCt0e0oJtaTz2hf0OE2P7NGNUwxNQlAVBUdCkd5XpTAY9fVvFsth2FWeDmkBxDqyf4fZ4hagrftuwW7NmDYMGDQJg0KBBrF271sMRCSHqlZI8tP0/0+n4LAwf9oJ3OsL8J+DAErCZoUE7uOZvMH49PLAYut4HpjAAdp3M5fYP1/DW4n1YbIphneJZ8Hg/OiVGeO7z9H8aYttAQTr8NMmx+epWsfz0ZH/+0LMJOg0Wbj/FdW+uYPJ32zmW6foGns2meHfJfv78xSYsNsWIKxKYMqwd7J5vP6D1jaC/9LzAa9s2RKFjpmGUfcPqt6Ggbq82CuEuPtGwe+6552jfvj06nY4vv/yywr6MjAyGDRtGcHAwbdq0YenSpQBkZ2c71nqJiIjg7NmzdR63EKKeUAqyDsO2r2DBRPiwH7zaFMNXf6BFxmK0zAOg6SGpJ1w7BcZvgPFrYeAkaHB+kdzcYjNTv9/J8PdXsSU1m7BAA++MvoJ/3n0lUSGuXxTYKcZAGJFiH/+37UvY97NjV3igkZdu6cSCx/txdasYSq02Pl93jAFvLOPRzzeyfG86Vlvtl0zdfjyH2z/8jbeX7EMp+EPPJrx1xxUYsMGOufaD2t982XwGtm2IpsF7GVdibtARSnJh5Wu1jk8Ib+ATy50kJyfz7rvv8swzz1y0b/z48SQkJHDmzBkWLVrEqFGjOHjwIJGRkY51X3Jzc4mMjKzjqIUQfslmJbT4JNqu7yBjN5zeASe32K9kXUBFNuOIoQVJ14zB0GoABEVWmmWJxcqX61N5/5f9nMkvBWBYp3imDG9HfESQ+z6Ls5K6Q69HYc0/7VcfH11b4TO1iw/nv/f3ZN3hLKYvP8jKfRks3H6KhdtP0SjcxKB2jbi2bUN6tYghxFS9Xz9FpVaW703nyw2prNiXAUBIgJ5pIzpy+1XnuqX3L7OXf3AMtBp02TwbhQfSvVk06w9nsajxeIZlPGLvjr3yHojr5HSxCOFNfKJhd8899wDw0ksvVdien5/PvHnzOHLkCMHBwYwcOZK33nqL+fPn07t3b/71r39xxx13sGTJEsaOHeuByIUQPstSYr8Kl3ng3GM/nN6FIX0311mKYPcFx+uMkHCFfbxckv1hCWrAtoULSWw7FCpZh8pitfHd5hO8s2Q/J7Lt92FtERvC1Js70L91A/d/xpoYOBn2LoSsQ7BoCoz4Z4XdmqbRq0UMvVrEsDstlzkbUvnflhOczi3h83XH+HzdMTQNWjUIpVPjCBKjgoiLCCLYqLElU8O2LY3sYivHzxax40QOW49nU2y231VDp8GIKxrz1xvaEhcReP6kW8/15HS8DfTVW+/rpi4JrD+cxb+ON2FYu5vtS598/xg8sBR0epcUlRCe4BMNu6rs37+fiIgI4uPjHdu6dOnCzp07ue+++wgKCqJfv3506dKFHj16VJlPSUkJJSUljvflV3j25XvL+QtfKytPxyv3kKwmpTDnpBFZcAjbju+wFpyC7GNoWQfRsg5CTiqauvg2XRpg0QWgNeoIcR2hUUdUo06ouE5gCKxwbFWxFZRY+GbTCWb+dpTj2cUANAwzMX5AC27v2pgAg857f941I9qwdzHMugk2z8LSZjiq5XWVHtoqNojJN7bmqcGtWHMok+V7z7BiXwbHs4vZn57P/vT8C1LoYd/2i/JJjAzk+g6NuKtHEk2j7bd5dJRPSR6GPQvs30v721HVLLfBbWKYqtPYdjyHwzc+Q7NDy9FObsa68i1sV//lsumlntdtfnKvWD+9V+yAAQMYN24cd955JwCrVq3ij3/8IwcOHHAcM3nyZLKzs0lJSal2vlOnTmXatGkXbZd7xQrhm/S2EkzmHEzmHAIt2ZjMuZgsOQSVZhJcmkmQOZOg0iz06tL/WZp1QeQHxpFviqPA1Ii8wERygpIoMDWq0T1Gz5bA6lM6fj2tUWS1L1cSYlAMamyjbyNFgA9dKOp4/L+0zFhEkTGKX9q+jMUQUu20OaWQmq9xshCySzWyS6HECkppaBqEGhURRmgcokgKVcQHVbksHUmZq+h6bAb5pjiWtvtH1QdW4oNdOvbk6Lgh0cZDwSvoemwGNnT8mvx3skJbVzsfIdyt3twrNjQ09KL7p+Xm5hIaGupUPpMmTWLChAnMmDGDGTNmYLVaKzQWhRCeoykrRksBAdZ8x3OApQCjNZ8ASz4B1gICLLkEmnMwWXIINOdgsBVXK2+FRrExkqKAGAqNsRQFxJRryMVRYgh3qqFQGYsNdp7VWJOusSdbQ2HPr0GgYkC8jR4NfKtBV2Z3wiga5W4ltOQ0nU58zuamD1U7bUQAREQrOkYD1O7aQpPMlQCkRl/t9HfVvYFiTw6sTde4/sq+NMjbSdLZ3+h2ZDrL2r6A2RBWq9iE8ASfbtglJyeTk5PDqVOniIuLA2Dr1q088MADTuVjMpkwmUxMnDiRiRMnkpubS0SEfVmBgQMHYjBUr5gsFgvLli2rVhpnjq3vfK2sPB2vu89f7fyVDUoL0UrzoDQfrbQASvPQSvPtS4Gce6+KczlxaC+JDSPRmQvQSvPRirOhOButKNuevgaUIRAV0gAV0tD+HNwAFRaPCm+MCk9EhSdiDopl2cpfGThwINEurOc2pdiSmsPCHaf5fusJ8s3nGxw9mkZyb69EBraORVdXiwy7ia5DQ9TskTTJWk2jAQ9ibTWkxnnV5OdWy9hN0Oa9KE1Ps5GTaRoWf/lE5fS3WPn+7d/ILrIQ1OIqYgZ8iu2zGwg6e5Drz86i5I4vwWByWbyu5DX1vI7yq036mqT1tt/nF17EuhSf6Io1m81YrVaGDBnCgw8+yKhRowgICECn0zFq1Ciio6N55513WLx4MWPHjuXgwYNERUU5fZ6UlBRSUlKwWq3s27dPumKFz9OUFZ2yoLNZ0CkLmrKgd7w3o1NW+zabGU1Z0SvzufcW9KoUna0Ug83+rLeVoLeVolel9ucLHxduv0w3p7NK9cGY9aGUGkIw60Mo1YdiNoRQqg+hxBhOiSGSYmMEJYZwSoyRWHSBtb7a5gybgqP5sCVTx5ZMjezS8+cONyp6NFT0amCjgRdNcnWF9ie+IDn9R4oNEfzS7hXMBud6TGqjc+pMmp/5hZOR3dnQ/LEa5TH3sI4Vp3R0jrZxfxsbYUXH6bfvBYy2IlKj+rCp6cN1+nMkRGWc6Yr1iYbd2LFj+fTTTytsW7ZsGQMGDCAjI4MxY8awfPlyEhMTmT59umNh4poqu2I3e/Zshg0b5rMtfK/g+PFS516rctsveF3hWEcGWCxmVq1cSb++V2PQ6+xXgpQCZTs3uN1WYdvFj4rb7WkuPFadf+bi9Npl8gQb2Gxgs2Czmtm/ZzetW7VAhwJlAZsFbFY0m/Xce6tjGzYLms1iz8d2/tiy4+z7rOXSlEunrPbZmzYzWErRbKVgNWMrLUKHtdLB/3VNaXoICEWZQu3PAWEQEIIyhUFAKFZDCEdOZtC0dSd0gWGogFBUYCQERaICI1FBUWCKqHKmoif/ks8vVfx6KIsV+zNZfSCL7KLzjdmQAD0DW8cQb0njkZHXEBhQvdmaPsdcROCnQ9BlHcDS7hZKb5peo2yc/i5K8gmafgWauYDi0V9ha9qvRufdn17AiA/Xo9c0fnqsJ40jg9AdWYHp6z+gKSvmbg9hHjj1osadp/8Plyt27k3rbb/Pc3NziY+P95+GXV2pyyt2V+97iUBLDhXGl5z7Kuz/fZxv5Gjl9jneVzgGtPINJcdxleVdrvFUdq4q8z7fwNKqyltdfC6tlmNmhPtYNSM2TY9NM2DTlb02YtMMKE2PVWd/bdMMWHUBjodNF4BVC6iwzVphmwmrzljxWQvAqrc/+8sVj2IrHM7TOJCjcSBX42h+xVoTpFe0i1R0jVW0jVQYfWIJ+NqLKjhIv33Po6FY3/wx0iK7u/2czTKW0uX4p+SZ4vml3au1+hlL2aVjX46Oa+Jt3NrM/sdQk8yVXHnsIwD2NxzKroTRfvNzLHyP312xq2vlr9iNGDECYyXrT1XGbDazePFiBg8efNk0+nc6oCs47Ypw6y2l6ewzEys8tEq26YAqtmta5Wmw73PqHJoOdHps6DidkUmj+MboDEbQDKDToXQG0BnsV57KXp/bx4X7NPtrVf7YC/Y53usDwGBC6YygD8CidKxas46+11yHMTDYvq6X3nQube1/MTnzc14X+dUm/eXSZuaXsPVELhuOnGX9kSx2nsy76A4KrRuGMqBNLNe0juXKpEiM+vOtOVeXlTfTLXsR/W/voIJjsTy0GkJinUrvVFkphWFGf7SM3VgHv4Stx8O1iBxW7j/D/Z9tIiRAz8qn+hMeZD+/buMn6H96GgBrrz9ju/Y5Rx3y9Hfr7vPXp3pe2zR18bOQm5tLbGys/8+K9WWlt3zMhnVr6N69OwbDuR8ETaPsel2F12jnXp67llfVcWWvtfLpqnrNpfOoTn6O4y53rgtfV3UuKm53/AdqYekvy7hu0GCMAabzjSsvZTab+d2D/+Ers5migIMQ2rDSRXFF5fKKLew4mcO247lsP5HD9hO5nMy5eHZt48hAGhsLubl3e/olNyAh0s8GzdWQrd/T6Pb/hJaxB/3Pf8V668duO5d2fB1axm6UIQhb5ztrnV+/VjG0bhjKvvR8vvz9OA/1aw6A7ao/grKh//mv6Nf+E63wDNahb1d7EWQhPEGu2JUjkyeE8H8WG6QXw6lCjbRCjbRCSCvUyCyp2K0K9mEFDYOgeZiiVbiiZbgiuvJJkgKIKDxM/73T0GFjQ7PxnIzq6ZbzXHVkOoln13I05hq2NLnfJXmuTdf44qCeCKPima7WCt3oTTJX0OXYJ+iwcTqsE783/zMWvTToRd2RrthaqouuWE9fxvclvlZWno5XumhAKUVmQSlHMws5klnI0axCjmYWciC9gMOZBZitlf+31zgykE6NI+jUOJwuiRG0jw8nLLBix4bU80vTrXgV/eo3UEHR9i7Z0IbVSlftsirIwPBeZzSbGfOflkJ8F5fEXWKxMfid1aTlFDN5aBvG9m5aYb+2fxH67x5AMxeiYpIpHvkxizYdkXpeR/lJV6x0xQoh/FxesZmT2cWkZhWw+pTGjqUHOZFT4mjIFZRYq0wbajLQulEoLWODsWWlMrzfVbRrHElMSEAdfgL/ZOs7Ad2+n9DSd6D/8Smst3/q0qETui3/RbOZsSV0dVmjDsBk0PHoNS145vtdfLjiMHdc1ZjggPO/IlXyEKz3zEP/zX1omfsJnDWUuMb3A4NdFoMQriBX7MqRrlghPM+qIN8MeWbILdXIM9tvQXW2VONsCWSXaJwthWLrpRsLGoooE8QGKhoE2p8bBUF8sCLKfybqeqXwwmNcs+85dMrKhmaPcjKql2syVjYG75xAsDmLTU0eIjWmr2vyPcdqg5e26Mks0bi5iZXrGl/869FkzqHbkX8Sm78XgIMNrmdXwihsOvmjQLiPdMXWknTFehdfKytPx+ttXTSlFhs5RWayi8xkF5rJKTJzttBMdlEpmfmlZOQVs/doGsoUxpmCUs4Wmqnu/0qRQUbiIkwYSnLp3CqJpjEhNI0OpmlMMElRQZiMl75Xlz900Xgr3cp/oF/1OiosAcu4NRBw6XvJVqestH0/Yvj6XlRQFJbHt4Mh0OVxz918gr/O3UlEkIElf+lHZHAlsVjNsOQ5jL//GwDVsD2WER9Cw/Yuj6cq3lbP3Z2fdMVKV6zLGI1Gp78oZ9LUJP/6ytfKytPxuuL8SilKLDbyii3kl1jIL7aQXVDM9iyN0p0ZFFmUY19esb3BllNo5mxhKdmFZrILSykorbpL9DwdUHD+nQYxoSYahJpoEGZ/JEQG0TgykPiIIBIig0iIDCQ4wIDZbGbhwoUMHdqhxp9X6rkb9J8I2+egZR/DuPZ9uO6ZaiW7ZFlt+gQA7cp7MQa55z6ut13VhP/8eoy9p/NIWXGYqTd3qCxIzNe/zJqsMHqd/gwtfRfG/wyCa5+BXo+Cvu5+tbr7Z8vV+dc2v9qk9+V67ky+0rC7DLO5+rdFKju2OmmcOba+87Wyqst4bTZFqdVGqcVGicVGkdlKflEJR/Pg1/3pmJVGUamVYrN9X7HZSuEF7+3P9vdFpVYKSs414kqs5JdYsNgqu3ymh707qh2npkFEoJHIYCMRQfbnyCAjMSEBRAUbOH1kHwN6dqVRZDANQgOIDA5Ar7tcX6nCbDbXqrxrklbqeXUZ0K57AcO3Y1C/vYel02iIal7l0Zctq6yDGA/+gkLDcsV94MYy/fuNrRkzcyOz1h7ljqsSSG548W3SzGYz6RFdKLrxFwIXPYVu/8+w+Bls27/BOuxtiOvstvjKzl/+2dvzr21+9b2eO5O3dMWWI2Ps6g+lwFb2fO4GG0rZx3dZz22zYR9zU+H53D77s3bB+/Ovq9puf7ans9jAcuFzhW0a1sqOKfdsU3UzUExDYdJDYIWHIlCPfbvBvi3EoAg2QIgBgg3q3DMEGexX4UQ9oxS9D75Gw7ydpEV0ZX2Lv9Q4qw7HZ9Mq4ydOhXdhXcuJrouxCh/v1bEtS0ebCBuPtLNdekymUjTJWkmHE18QYC1EoXGw4Q3sibsVq17WxxG1J2PsaqkuxtjNWnOELTt2k5ycjHbuHphKKUcDQ5V7b7+zlyq33f6eC96XT0cl+ZS9p8L7ivlSyXkqpKtqX6VxqnL5VnxvVQqlFFabfbtNKayKc9uUvbGlFNZz73Ny8wgJCUVhv0plK5eHTZVtU+e2YX99ibz9kaZBkFFPoEEH1lIiw0IIDjAQFKAnyKgj0Ki37zfa3wcZ9QQF6B3by44JMRkINekJNRkIDTQQajIQbNSj07lnxX0Ze+PnMvba7xKhrFjG/oRq3K3Swy5ZVuYiDO91QivOxjL6C1Qr989EPZZVyA3v/YrZqph+1xUMbl9x2ZZK480/jX7xZHS7/geACm+M9drnUO1vcflsHRlj59603lbPZYydC7mrT/7DVUdJz9PDsUO1Ca8e0aCw4PKHuYhBp6HXaRj1OvQ6DYNOw6DXMOh0GPTa+W3n3pe91us09DrIOpNBQlwjjAZ9hXyMjrQ6TAYdAQYdAXodxnPPAee2mS54f/E+/fl9ZXnoNTRNKzfmrK+MvXFjWm8Ze+P1EjpCl7tgy38xrHwV7pt3ycMrLavd/4PibIhsgqHN9fbb6blZy0YRPNS/BSnLDvL8gj30bdOQ8MCLv8MK8UYlwh2fwr5FsGAiWs4xDP97CDb+B254BRp3dXmcMsbOvWm9pZ7LGDsXclef/JB2Ddh7+BiNExLQ6XT224+inXsu++Ou4vvy+9G0cttBK/eeyt5XSHvxubRztxm7MK+y95S9vyhtuX2VpC3beeFn0Gn2BpBO0849zr3W2V/rNQ3t3GtltbJ582a6d7uKAKMB7dx+nWbPS6/TqszH8Vxuv15nbwA5zlMulrIGXdnnqonzf711rKNf5gqUFYvl/PnLP7uajL3xrrE3PuHqCRi2zUE7tBzLwRWoJn0uOuRSZaXfPAsdYO10JzarzT42og6M69eMH7amcTSrkFcW7OL5m8/Per3kd9t8IDz8K7q1KejWvIeWuhZmDMTW+S6s1/wNwhvXOjap5+5N6231XMbY1ZCMsRNCCPfonDqT5md+4UxoW35N/nu10wWVnmHwzoloKBa3f5NCUwM3Rnmx/Tka/9xlv0L4WAcLrS7dC3aRwNIs2p/8mqSzvwJg1Ywcib2WfY1uotToZGai3nL7GLuioiKeffZZvv76a7KyssjNzeXnn39m9+7d/OUvf6lp3F5D1rHzLr5WVp6OV8beuDet1PMayj2JIeUqNJsZy9hFqAu6JasqK93qt9CveBlb06ux3nPpblx3mfy/nXy18QTNYoKZ92gvxzI7zny32omN6H6Ziu7YGgCUMQRbj3HYej0KgRFOxyT13L1pva2eu32M3aOPPorZbOaHH36gX79+AHTu3JknnnjCLxp25flyn7y/8bWy8nS8MvbGvWmlnjsppil0GgVbZ2PY8CE0+6TSwyqUlVKw/UsAdFfeg85DZTh5eAdW7s/kSGYh/1h0gJdv6eTYV+3vtlkv+OOPcPAXWPo8WtoW9L++iX7jx9DnMejxYI0aeFLP3ZvWW+q5M/nqanKCBQsW8PHHH9OxY0fHWKT4+HjS0tJqkp0QQoj6oPej9udd8yD72OWPP7EJsg6BMQTa3eze2C4hIsjIm3fY70s7e90xFu86XbOMNA1aXQcPLYfR/4UGbe2TQn55Ad7uBL+8CAWZLotb1E81athFRkaSkZFRYdvhw4dJSEhwSVBCCCH8UFwnaDEAlBV+/8/lj9/9vf259RAwXbxIcF26ulUsD/azL7D812+3kZFXUvPMNA3a3QSP/Aa3zoDYNlCSAytfh3c6ws+TIVculIiaqVHD7oknnuCmm27im2++wWq18sMPP3DXXXf5XTesEEIIF+t2v/15y2z7PVerohTs+cH+uu1w98dVDU9d34Z28eFkFZTy17k7ar8mpk4Pne+AR9fCHZ/Z71ZhLoQ1/4R3O8P8JyBjn0tiF/VHjcbYjR8/noYNG/Lxxx+TmJjIe++9x5NPPsno0aNdHZ/H+fL0aH/ha2Xl6XhlGQT3ppV6XkstrsMQ0gAt/zSW3QtRbYYClZRVxl6MmQdQ+gAsza916y3EqksHvHl7R275YC2rDmQSWqxxvaviSh4KrW5EO7gU3a9vozu+DjbOhI0zsbUajK3nI6im/RxrWEk9d29ab6vnstxJDclyJ0II4X7tT3xJcvrCS94erPWpebRL+7bObiHmjPXpGp8f1KOheLitjXZRrv81Gp2/l1bpPxGXswnt3P19cgKTONjwBk5E9cKmq+eTceoZtyx38tprr1Xr5P/3f/9XreO8mSx34l18raw8Ha8sg+DetFLPXSDzAMYPe6E0PZbHt0Now4vKyvDxtWintmEZ+jbqyns9HfFFpvxvB3M2niQ80MD/Hu1FUpSbLgJkHUK34d/ots5GMxcCoEIaYr5yDL9kJ9F/6Cip525I62313C3LnezevdvxurCwkO+++46ePXuSlJREamoq69ev59Zbb6151F7Kl6dH+xtfKytPxyvLILg3rdTzWohrB427oZ34HeOeeedny3KurArS4NQ20HQY2t8EXlh2zwxvz9q9Jziab+HxOdv4ZlwfAo1uuNVZozYw/E24djJs+hTW/QstL42A1a8zRNODbRm6ng9Bk94uvx8tSD33lnruluVOPvnkE8fDYrHw9ddfs2rVKmbPns2qVav4+uuvZRyJEEKI6ulyp/1525cX79uzwP6c1AtC6/ZOE9VlMugY29pKVLCRHSdy+eu323DryKbgaOj7JDyxDW6dga1xd3TKim7Xd/DJjfDB1bDhYyjJd18MwifUaFbskiVLGDZsWIVtQ4cOZfHixS4JSgghhJ/rcCvoDJC2FdL3VNy3e779ud1NdR+XE6JN8O7ozhh0GvO2nOS9pQfcf1JDAHS+A+vYH1ne5nlsV9wDhiBI3wkLJsCbbWHh0xeXaT1ltVopKSnBYDBQXFzs1MOZNDXJv6qH1Wqt1Weu0azYjh078uKLLzJlyhQMBgMWi4WXX36ZDh061CoYV0pNTWXEiBHs2rWL/Px8DIYafVQhhBDuEBIDrQbDvh9h2xy45tz9YwvOwLnbbtF2WNXpvUTvFjG8MLIjk+Zu5+0l+2jeIISbu9TNmq45wc2wDn0U3fUvwpYvYMNHkHUQ1v/b/mjSB7reB+1HQED9mwiYn5/P8ePHsdlsxMXFkZqa6ripwuUopaqdxpljq0PTNBITEwkNrdnajTVq7cyaNYu7776bN998k4YNG5Kenk779u35/PPPaxSEOzRo0IBffvmFkSNHejoUIYQQleky2t6w2/419P8bANr+n0DZ7Gu6RTX1cIDVc1ePJhxMz+ej1Yd56uutJEYF0bVJVN0FEBRlH6fYcxwcXm7vkt27EI79Zn/8+H/227l1vQ8Srqi7uDzIarVy/PhxgoODiYmJoaCggNDQUHS66nVU2mw28vPzq5XGmWMvRylFRkYGx48fJzk5Gb3e+XGbNWrYtWjRgrVr13Ls2DHS0tKIj4+nSZMmNcnKbQIDAwkMDPR0GEIIIarS+kYwRUBOKtqx3wDQ+Ug37IUmDW3HkcxCluw+zYOf/s43j/SheWxI3Qah00HLa+2P3JP2RaA3fQbZR+H3j+2PuE7QdQx0ut3eIPRTZrMZpRQNGjTAZDJhNpsJDAx0qmFXWlparTTOHFsdDRo04MiRI5jN5ho17GoUQXp6Ounp6QQGBtK8eXMCAwMd22rqueeeo3379uh0Or78suJg2oyMDIYNG0ZwcDBt2rRh6dKlNT6PEEIIL2EMhA4jANBt/xqTOQft8HL7vo63eS6uGtDrNN698wo6Ng4ns6CUez9ex+ncYs8FFJ4A/Z+Cx7fAfd9Dx9tBHwCntsPCp+xj8eY+BEdWg83muTjdzBVdo3WttjHX6IpdXFwcmqY5ZgCVD6Kmg/6Sk5N59913eeaZZy7aN378eBISEjhz5gyLFi1i1KhRHDx4kJKSEu68884Kx4aGhvLDDz/UKAYhhBB1rPOdsOkztD3fkxRjQVNWSOgKMS09HZnTQkwGPhnbg9s//I2jmYWM+c965jzcm4ggDy7XotNBi2vsj8Is2PaV/Spe+k772MZtcyCyqX2Wcpc7IbqF52KtJx5//HHmzJlD8+bNWbt2rcvzr9EVO5vNhtVqxWazYbPZOHHiBI888ggzZ86scSD33HMPgwcPvqj7ND8/n3nz5vH8888THBzMyJEj6dixI/PnzycuLo7ly5dXeEijTgghfEiT3hCRhFaSR4eTc+zbOvvu7SkbhJmY9aeeNAgzsedUHg9++jvF5trNcnSZ4GjoNQ4e+RUe/AWuGgsBYfau2hX/gPeuhI+vt9/KrDjH09H6rTvvvJOFCxe6LX+XTBWNi4vjrbfeokWLFtx7r2tXCN+/fz8RERHEx8c7tnXp0oWdO3deMl1xcTHDhw9n69atXH/99UydOpV+/fpVemxJSQklJSWO97m5uY7XvnxvOX/ha2Xl6XjlHpLuTSv13PV03R5Av/Q5AGyhcVg73ekV94a9lEt9t/HhRj6+tyt3f7yB9UeyGP/5Rt6/swtGfe3HX1Xn/NXSsDPc8AZc9zzavh/RbZuDdng5WupaSF2LQf9/dAvrgnWPDloPsi9N48F4nU1fNsau7AJUUakVfYnZqVmxl0sTZNRX6L0sO195zz77LN988w3NmjXDarUyadIkBgwYwJEjRwAuOr5sm1Kqwhg7j9wrdtWqVYwaNYpTp07VKp8BAwYwbtw4RxfrqlWr+OMf/8iBA+fXB5o8eTLZ2dmkpKTU6lxlpk6dyrRp0y7aLveKFUKIOqBsJJ9eQGThYfbE30peUKKnI3KJA7nwwS49FqVxRbSN+1rb0HvxkK9A81kSs34jKWs14cUnHNuLDREcj+pNanRfcoO9a6JkVQwGA3FxcSQlJWFFT++3XN/luWZCL4ICqp7csHHjRiZNmsSCBQtIT0+nV69efPHFF/Tt25djx45x//33V7r+b2lpKampqZw6dQqLxQI4d6/YGjXB27VrV6EFW1hYSGZmJu+++25Nsruk0NDQClfQwH5Frabru1Rm0qRJTJgwgRkzZjBjxgysVmuFhqQQQgg30nTsj/OtWbDV0Soc7m9j46O9OrZk6dDth3uTbei8tHFXbIziQKNhHGg4lIiioyRlrSbx7BoCLTm0yviJVhk/kROYxPHoPhyP6kVxQIynQ/Zq69evZ/jw4RiNRho3bkyvXr3q5Lw1ath9+OGHFd6HhITQunXry7YiayI5OZmcnBxOnTpFXFwcAFu3buWBBx5w2TlMJhMmk4mJEycyceJEcnNziYiIAGDgwIHVXtzYYrGwbNmyaqVx5tj6ztfKytPxuvv8rs6/tvnVJn1N0ko9dw9fK6vqxjsY6Lz3DE98vYNNmTqSGifw0oi26Go587Fu6nkzGtz9IaSuQr/za/QHFhFRnErEyTl0ODkHa2IvrO1vwdJmOARFuzVeZ9OXlJRw8uRJQkJCMJlMrJnQi9Aw5y4I5eflXzJNWVcsQF5eHmFhYRX2BwQEoNPpHNsNBgNBQUGEhYUREhJSYV95xcXFBAYG0qdPH0wmE8BFF7gupUZdsW+88QZPPfXURdvfeustJkyY4Gx2gL3/2Gq1MmTIEB588EFGjRrlKJRRo0YRHR3NO++8w+LFixk7diwHDx4kKsq1a/CkpKSQkpKC1Wpl37590hUrhBDCJbZmaszcp8OGRq+GNka38N4rd1UxWvJJyF5P4tm1xOafv2WZDT3p4Z04HtWbUxFdsepNHozSrnxXbEBAgEdi8FRXbI0aduHh4ZW2HmNiYsjMzHQ2OwDGjh3Lp59+WmHbsmXLGDBgABkZGYwZM4bly5eTmJjI9OnTGTRoUI3OUx1lV+xmz57NsGHD5C95D/O1svJ0vHLFzr1ppZ67h6+VVU3i/XHnaZ6euwubgluviGfa8Dboa9i683Q913JPoN/zPYZdc9Gl73BsV8YgrK1uwNL+VmzNrgG90SXx1vSKXbNmzQgMDKz0itrlOJOmqmOfffZZ5s6dS9u2bSkuLuapp55izpw5zJ8/n6ysLBo0aMA///lPbrrp/FCE4uJijhw5QkJCQoUrdvHx8a5v2H311VfA+UZY+aRHjhxhxowZ7N+/v7rZeR25YieEEMKdfs/Q+O8BHQqNrjE27mllw4WTZT0itPgEiWfX0jhrDaGl529UUKIP5WRUD45H9SYrJBm0uvug3nDF7kJ/+tOf+NOf/kTfvn0veVydTp744IMPHCedPn26Y7umaTRs2LBW69h5g/HjxzN+/PgKY+wGDx6M0Vi9xSXNZjOLFy+uVhpnjq3vfK2sPB2vu8/v6vxrm19t0tckrdRz9/C1sqppvEOB7jtOMeHr7WzK1BHTMI637+iMyeBco8f76vmDoBSWk5vRdn6Lbtd3mArSaX7mF5qf+QVbWAIHg64g8YbHMSReBU6OMXQ2nuLiYlJTUwkNDcVkMjmuqDmz3El101T3WKPRSHBw8GUbZsXFxQQFBdG/f3/H2r7OjLFzqmG3bNkyAF588UWmTJniTFIhhBBCADd2jMNk1PPYl1tZvDudR2dvJuWuKwg0On9fUK+iaajGXVGNu2IbNA3t6K/odnyLtnc+uryTJOedhM8WoiKbYWs/Alu7kdCoo9ONPF/1xRdf1Ml5qt0Ve+bMGWJjYwEueU/Yhg0buiYyD5CuWCGEEHVlb7bGR3t1lNo0WoXbeLCtjUAfb9tVRmcrpVHuVhqfXUej3C0YbKWOffmmRpyI7MmJqJ7kBSa6rJHnjV2x1VVnkyfCwsLIy8sDQKfTVVht2ZGZptX4XrHepPzkiREjRkgXjYf5Wll5Ol7v66Jxb37SFesffK2sXBXv70fP8sCsTRSUWOnUOJwZ91xJTOjlZ5X6bD2/5moCji5Dt3se2oHFaJZixzEqJhlbuxHY2t8CDdrUKp6yrthmzZp5TVdsdZVNnkhKSqrQFRsbG1uthl21O/XLGnVw8b1iyx7+0KgTQggh6kq3plF8NrYbUcFGtp/IZfSMDaSeLfR0WO4TEIxqPxLrbZ9geXIPlpH/wtZ6KEpvQsvcj371Gxj/fTWGf/dFt+p1yPTdCZme4rJbivkD6YoVQgjhCelF8MFuPVklGuFGxcPtrCSGeDqqumOwFhGXs4mEs+tplLcNnTp/oSgnMImTUT05EdmDgsC46uUnXbHOSU1N5fnnn2fr1q3k5+dX2Ldr1y5ns/M60hXrXXytrDwdr8920UhXbL3ma2XljnhP5xbzwGeb2HM6n1CTgQ//cAU9m1d+Rwe/rufFOWj7fkS3639oh5ej2SyOXbaGHVHtR2BrexPEtKo6Cy/tis3MzOTOO+8kLS0Ng8HAs88+y6233npR7LXpiq3RqoajR48mOTmZadOm+f0VLaPR6PQPtTNpapJ/feVrZeXpeN19flfnX9v8apNe6rn38LWycmW8iTFG5ozrw0Of/c66w1n86dNNvD36CoZ1jq+T89dF/tXKzxgLV91rfxRmwZ4F2HbMhUPL7Yshp+9Av/wlaNge2t0M7UdAw3YVJl5YrVY0TXPMCQAc76vDZrNVO40zxxoMBl599VW6d+9ORkYGV111FcOHD3c04OD8PIbyZeXMd1Cjht2OHTtYvXp1tQvIl5nNZqePrU4aZ46t73ytrDwdr7vP7+r8a5tfbdLXJK3Uc/fwtbJyV7zBBvj43iuZ+M12ft6VzvjZmziamcwDVzercDWo3tRzYxh0uhNz29tY8eNcrk0owrj/R7QjK9DSd0H6LljxKiq6Jba2N2NrOxziOmM2m1FKYbPZUDYbmAtRJTpsTlyxu2waY7B9iZdzHZ9l5yvv2Wef5ZtvvqFZs2ZYrVYmTZrEgAEDsNlsxMTEEBkZyZkzZ0hISHCksdlsKKUwm83o9Xqny61GXbF33HEHf/nLX+jTp4+zSb2ajLETQgjhDWwK5h7RseqU/QJK74Y2RjX3/btUuIrRUkBczmbiszfQMG8HenW+4VMQ0IDUuCEUdR5D46RmBOisRKa0c3kM2eN32xt3VbjUvWIBtmzZwiOPPMKaNWsqpKvTO0+UCQoK4oYbbmDIkCEXrVtX/o4UvkbuPOGdfK2sPB2vX4+9cXF6GWPnPXytrOoi3uHAp2uO8vKPe1mTrkMX1oD37+xMWKBR6jkAowCwleShDixCt+cHtANLCCnNoFnWSg6bRxBWehpT4OWXj6mJ8LAwCAipcozdtm3buP3224mJiSEmJoa+ffs67jxx9uxZHnvsMT766KOLGmp1eueJMi1atGDixIk1SepzZOyN9/C1svJ0vH459sZN6aWeew9fKyt3x/tA/1Y0bxDGY19s5teDmYyesYH/jO1OXNj5sVf1vp4bo+GKO+2P0gLYvxgOrARNh6Ys6Eot8McfUToDWmAEBEZCQMglF0O22Wzk5uURHhZW5bAz3bmu2EuNsSu/rey11WrljjvuYOLEiVx99dUX5+uJMXbPPfdcTZL5JBl743m+VlaejrfejL1xQXoZY+c9fK2s6jLe/q2imX1/dx7+72b2p+czMuVX/jm6o1vP77P1XAuA1sMwN7kOlXoMFd4AZStEFeegwz7WDnMhSmcAUzgERqJMoUDFRp5SCoxWlDG46jF2SoFSVY6x6927NxMmTODxxx/n9OnTrFq1iqeeeopHHnmEbt26cd999100Jg88NMbutddeq3S7yWQiMTGR6667jsjISGez9TgZYyeEEMJbZZfAv/foOVGoYdQUd7ey0TVWlqKtzEXr2CmFwVaE0VKA0Vpob+SdY0OHWR+MWR+MRR8EmusGMr700kt8//33tG7dmuLiYgYPHsxf//pXOnTo4Oi2nTFjBm3btnWk8cg6dnfeeSffffcdPXv2JDExkePHj7Nu3TpuuukmTp48ya5du5g7dy7XXnuts1l7BVnHzrv4Wll5Ol4Ze+PetFLP3cPXyspT8RaUWHjy620s23sGgAeubsJTQ9qg17nmHqtlfL2eX24dO600H4qz7WvmlVsnT2k6MIWhTBHklkJYeKTL1rG76667ePjhhxkwYMBlY6/zdewsFgvffvstw4cPd2xbsGABM2fO5LfffuPzzz9nwoQJbNmypSbZexUZe+M9fK2sPB2vjL1xb1qp5+7ha2VV1/FGGo18NKYH//hxF/9edYSPfj3GwTNFvHvXlYQHuj4OX63nl13HLjDc/lDKPi6vOBuKstFsZntjrziHCADbWbTASAiMAH3l563uOnZl+y+3VFxtx9jV6Hrj4sWLufHGGytsu/7661m0aBFgb5UeOnSoJlkLIYQQ4hL0Oo2nh7TmvmQrJoOOZXszGJnyKwcz8i+fWFSkaWAKhYhEaNQBYltDaCP7vWsBrSQPclLh9A44sw/y08FSUqNTffnll5e9WucKNWrYtW/fnpdfftnR92u1Wnn11Vdp186+TkxqaqpPjrETQgghfMVVsYovH+hBfEQghzIKGJnyK8v2pns6LN+lafbZsuEJqAZtyQ1sjAqLB2OQfX9pAeSesC+KnLEH8k6BudizMVeiRg27Tz/9lHnz5hEdHU2rVq2Iiopi3rx5zJo1C4DTp0/zzjvvuDJOIYQQQlygY+Nwvv9zX7o3iyKv2MKfZm7gwxUHqcHweb9Um3Kw6QJQIQ2hQVv77cvCG0NAqH2nuQjy0iBjN1rGHgJLs6DcWD1PxQw1HGPXunVrfv/9d44cOcLp06eJi4ujadOmjv09evSgR48etQrMW8gyCJ7na2Xl6XhluRP3ppV67h6+Vlaejrf8+SMDjcwccxXPL9jDnN+P8+qPe9h67Cwv39KBUFONfs37TT3PyMggOjqa0tJSioqKLjsRooxS6uI0ulAIDoVAC1ppAZTkgrkQzVKMopiiolg0fe0ad0opMjMzHe9r8rlrNCu2TGFhIZmZmRVal02aNKlpdh4ny50IIYTwVUrBr6c1vj2iw6Y0GgUp/tTaSlw9/TUWEBBAdHQ0BkPNGrfVoaHQ2UrRKStmvWsK2mKxkJWVRWlpqWOb25c72b59O/fddx/btm2zZ3KuNRsQEEBhYaGz2XkdWe7Eu/haWXk6XlnuxL1ppZ67h6+VlafjvdT5Nx/L5rE5WzmdW0JIgJ6XR3ZgaKc4l+Xv6njdmd5qtVJUVMRvv/1Gnz59qt3Is1gs1U7jzLGXo2kaBoPBsTBxGbcvdzJu3DhGjBjBmjVriI+PJy0tjWeffZaWLVvWJDuvJssgeA9fKytPxyvLnbg3rdRz9/C1svJ0vJWdv0fLBix4vB+Pzd7MmkOZPPHVNraeyGPS0LYY9c4Nrff1em40GtHr9VgsFkJDQ536A666aZw5tqbcvtzJzp07efbZZx0L5wUGBvLiiy/ywgsv1CQ7IYQQQrhQbKiJWff3YNw19gsu//n1MHfPWEt6rvfN4hSuVaOGXWRkJNnZ2QA0btyYrVu3cvr0afLzZQ0dIYQQwhsY9Dr+dmNb/nXvVYSZDGw4cpah761m3aHMyycWPqtGDbsHHniAFStWAPDEE0/Qr18/OnXqxIMPPujS4GprxYoV9O7dm759+zJhwgRPhyOEEELUues7xPH9Y31p0yiMM/kl3P3ROj5YfhCbTZZE8Uc1GmM3ZcoUx+sHH3yQIUOGkJ+fT4cOHVwWmCu0atWK5cuXYzKZuPvuu9m+fTudOnXydFhCCCFEnWoeG8J34/sw+bsdfLf5BP/4aQ/rDmfy5qguxISaPB2ecCGnGnbt27e/7DG7du2qcTCu1rhxY8frsgGUQgghRH0UHGDgrTu60KN5NFO/38nyvRkMfW8V7915JT1bxHg6POEiTjXsDh8+TJMmTfjDH/5A//79q73QX3U999xzfP311+zZs4fZs2dz5513OvZlZGQwduxYli1bRlJSEtOnT+e6666rVr6bNm3izJkz1WqYCiGEEP5K0zTu6tGEK5tEMv7zTRzMKOCuGWt5clBrHh3YCr3Otb/XRd1zqmGXnp7O3Llz+fzzz5k5cyajRo3iD3/4A507d3ZJMMnJybz77rs888wzF+0bP348CQkJnDlzhkWLFjFq1CgOHjxISUlJhQYgQGhoKD/88AMAp06d4vHHH+fbb791SYxCCCGEr2sbZ78V2TPzdjB30wneXLyPdYezeHv0FTQIk65ZX+bU5ImwsDDGjBnDokWLWLNmDQkJCTz00EN06tTJJV2w99xzD4MHD3Yso1ImPz+fefPm8fzzzxMcHMzIkSPp2LEj8+fPJy4ujuXLl1d4lDXqiouLufvuu3n//fdp1KhRreMTQggh/EWIycBbd1zB67d3JsioZ/WBMwx9bxW/HTjj6dBELdR4iWSTyURQUBCBgYFkZmZis9lcGVcF+/fvJyIigvj4eMe2Ll26sHPnzkum++STT9i1axdPPvkkAK+88gq9e/e+6LiSkhJKSkoc73Nzcx2v5R6SnudrZeXpeOVese5NK/XcPXytrDwdryvPP7JLHB3iQ3lizlb2pxfwh4/XMa5fM1orqefeUs/ddq/YkpISvv/+e/773/+yefNmRo4cyd13302vXr1qFGhVBgwYwLhx4xxdrKtWreKPf/wjBw4ccBwzefJksrOzSUlJqfX5pk6dyrRp0y7aLveKFUIIUV+UWmHuER1r0u2deS3DFPckW4mWnlmPc+ZesU51xTZq1IhnnnmGrl278uWXX3LPPfeg0+lYv3694+EOoaGhFa6igf2qWmhoqEvynzRpEjk5Obzxxhu0adOGVq1auSRfIYQQwlcE6OHOljbubWXFpFcczNN4bauezWdkQoUvcaorNjIykpKSEmbOnMmnn37KhRf7NE3j0KFDLg0Q7JMqcnJyOHXqFHFx9hsZb926lQceeMAl+ZtMJkwmExMnTmTixInk5uYSEREBwMCBA526afCyZcuqlcaZY+s7XysrT8fr7vO7Ov/a5leb9DVJK/XcPXytrDwdrzvPPxi4KyOPR2Zt4Gi+xsz9enJC4vj7DcmEBNTsXFLPa+fCi1uX4lRXrLuZzWasVitDhgzhwQcfZNSoUQQEBKDT6Rg1ahTR0dG88847LF68mLFjx3Lw4EGioqJcdv6UlBRSUlKwWq3s27dPumKFEELUW1Yb/HRcx+ITGgqNBoGK+5KtNHFNZ5lwgjNdsV7VsBs7diyffvpphW3Lli1jwIABZGRkMGbMGJYvX05iYiLTp09n0KBBbomj7Ird7NmzGTZsmM+28P2Fr5WVp+OVK3buTSv13D18raw8HW9d1vMtJ/L5v+92cSq3BINO4/GBzflTnybonFjLVup57eTm5hIfH+97DTtPkyt2QgghxMUKLTDnkI4tmfah+cnhNu5pZSNSJlbUCZ+9Yuctyl+xGzFiBEajsVrpzGYzixcvZvDgwZdN48yx9Z2vlZWn43X3+V2df23zq036mqSVeu4evlZWno7XE/VcKcW3m0/ywoI9FJZaiQwy8tLI9gxpf/l1YqWe105ubi6xsbGunxUrhBBCiPpJ0zRu79qYeY/2olPjcLKLzIz/YitT5u2koMTi6fDEOXLFrhzpihVCCCEuz2KDhak6fjlpn1gRa7Kvedc8zNOR+Sfpiq0l6Yr1Lr5WVp6OV7pi3ZtW6rl7+FpZeTpeb6nnaw9l8X9zd5CWU4xOg4f7NefPA1sSYKjYISj1vHakK1YIIYQQbterRTQ/jO/NyC7x2BR8sPIwo/69jv3p+Z4Ord6SK3blSFesEEIIUTNbMjXmHNJRaNEwaIqbmtroH6fQyY0rak26YmtJumK9i6+Vlafj9ZYumrrKr7530fgLXysrT8frrfU8Pa+Ev3+3kxX7zwDQu0U0r97SgQYhBqnnteBMV6z3rwLpYUaj0ekvypk0Ncm/vvK1svJ0vO4+v6vzr21+tUkv9dx7+FpZeTpeb6vnjaONzPxTD2avP8aLP+xmzaEshv9zDc8Nb4tBST2vKWfylYbdZZjNZqePrU4aZ46t73ytrDwdr7vP7+r8a5tfbdLXJK3Uc/fwtbLydLzeXs/v6JpAz6aRPPXtdrak5vDUtzu4IlpHj76FNIhwfohTfa/nzuQtXbHlyBg7IYQQwnWsCpae0PjxuA6b0gg3Ku5qaaN9lDQ9nCFj7GpJxth5F18rK0/H661jb9yVX30fe+MvfK2sPB2vr9XzrceyGP/fDZwuss+kGHVVYybd0IawwOp1HNb3ei5j7FzIl/vk/Y2vlZWn4/W2sTfuzq++jr3xN75WVp6O11fqeZcm0TzVycouQ0tmrjnK1xtP8OuBTF67vQt9k2PrJB5frucyxs6FfLlP3l/4Wll5Ol5vH3vj6vzq+9gbf+FrZeXpeH2xngfo4elBLRjcriF/+24Hx7KKuOfjddzVPZH/u741oaaqmyT1vZ7LGLsakjF2QgghhPuVWGH+MR2rTtnvkxBtUtzd0kZyhDRJKiNj7GpJxth5F18rK0/H62tjb2SMnQDfKytPx+sv9XztoSwmfbeD49nFANzbqwlPDW5FcIChWund9Vm8rZ7LGDsX8uU+eX/ja2Xl6Xh9ZeyNq/Krr2Nv/I2vlZWn4/X1et6vTSN+ejKGVxbu5vN1x5i19hgr95/h9du70KN5tEvj8eV67ky+cq9YIYQQQnhMqMnAS7d0Ytb9PUiICORoZiGj/72GF37YRVGp1dPh+Rxp2AkhhBDC4/olN+CnJ/szulsSSsHHqw8z7L1VbDx61tOh+RRp2AkhhBDCK4QHGvnH7Z355I/daRRu4tCZAkZ9+Bv/+HkfZpuno/MNMsbuMnx5erS/8LWy8nS8vrgMQm3yq+/LIPgLXysrT8fr7/W8b4soFvy5Dy8t3MN3W9L4aPURGgbqiW9/hh4tqr/uXU3O7WwaWe7Ei8lyJ0IIIYR32Z6l8dUhHblmDQ1F/zjFsCY2THpPR1Z3ZLmTWpLlTryLr5WVp+P1l2UQ6iK9PyyD4C98raw8HW99q+dncgv5y8yVrMuwjyBLjAri5ZHt6d0ixi3n9rZ6LsuduJAvT4/2N75WVp6O19eXQajL9FLPvYevlZWn460v9Tw2PJi7W9l4+MZuTJm3i+Nni7jvk43c3bMJk25sS1jg5fP05Xouy50IIYQQwu/0S47l5yf7c0+vJgDMXneMIW+vZNnedA9H5j2kYSeEEEIInxEWaOTFkZ344sFeNIkOJi2nmD9+soEJX20hu7DU0+F5nN827E6ePEmfPn3o378/w4cPp7Cw0NMhCSGEEMJFereM4ae/9OP+vs3RNJi76QSD3lrJTztOeTo0j/Lbhl2jRo1YvXo1K1eu5KqrrmLBggWeDkkIIYQQLhQcYOCZ4e35ZlwfWjYI4Ux+CeP+u5HxszdxJr/E0+F5hN827PR6PTqd/eNpmkabNm08HJEQQggh3OGqplEseLwf4we2RK/TWLAtjcFvrWDelhPUt8U/vKZh99xzz9G+fXt0Oh1ffvllhX0ZGRkMGzaM4OBg2rRpw9KlS6uV5+rVq7nqqqtYsmQJTZs2dUfYQgghhPACgUY9T1/flnnjr6ZtXBhnC8088eUWxn2+hex6dPHOaxp2ycnJvPvuu/To0eOifePHjychIYEzZ87wj3/8g1GjRnH27FlOnTrFgAEDKjyGDx/uSNe3b182btzIyJEj+c9//lOXH0cIIYQQHtCxcQTf/7kvEwa3xqjX+GVvBq9u1fPV78frxdU7r1nH7p577gHgpZdeqrA9Pz+fefPmceTIEYKDgxk5ciRvvfUW8+fP57777mP58uWV5ldSUoLJZAIgIiICq9Va5blLSkooKTnfnM/NzXW89uVbkPgLXysrT8fr77cacmV6f7jVkL/wtbLydLxSzy9NAx7p34zr2sTwt7k72H4yj8nzdvH9tjReHNGeZjEhLjuf3FLsMgYMGMC4ceO48847Adi8eTPXX3896enn16h57LHHCA4O5h//+EeV+axevZrJkyej0+mIjo5m1qxZVd4ebOrUqUybNu2i7XJLMSGEEMK3WRWsSNNYmKrDbNMwaoobkmwMjFfovabf8tKcuaWY11yxq0p+fv5FHyI8PJzs7OxLpuvbty8rVqyo1jkmTZrEhAkTHO9zc3NJSkoCYODAgRgM1Ssmi8XCsmXLqpXGmWPrO18rK0/H6+7zuzr/2uZXm/Q1SSv13D18raw8Ha/Uc+fS6pct4+Gh3Xnhp4OsOXyW+cf07C8N5YXhbemQEFar89XFz0L5nsTL8dsrdjWRkpJCSkoKVquVffv2yRU7IYQQwo8oBRsyNL47oqPQqqGhGBivuDHJRoDe09FVza+u2CUnJ5OTk8OpU6eIi4sDYOvWrTzwwAMuP9f48eMZP348ubm5REREAHLFzhv4Wll5Ol75S969aaWeu4evlZWn45V6XvO0Q4CH80t55ef9/LgznV/SNPYXBzN1WBt6t4h2+nxyxa4KZrMZq9XKkCFDePDBBxk1ahQBAQHodDpGjRpFdHQ077zzDosXL2bs2LEcPHiQqKgol8YgV+yEEEKI+mNHlsbXh3Vkl2oA9GxgY0RTGyFGDwd2AWeu2HlNw27s2LF8+umnFbYtW7aMAQMGkJGRwZgxY1i+fDmJiYlMnz6dQYMGuS2Wsit2s2fPZtiwYfKXvIf5Wll5Ol75S969aaWeu4evlZWn45V67rq0+SUW3vnlEF9sOIECYkICmDSkBYa0HVx7rXfU89zcXOLj432rYecN5IqdEEIIUT8dyoUvD+k5XWS/etcxysao5jYiTR4ODB+9YudNyl+xGzFiBEZj9a7Jms1mFi9ezODBgy+bxplj6ztfKytPx+vu87s6/9rmV5v0NUkr9dw9fK2sPB2v1HP3pC2x2PhwxSE+XHkYi00REqDn6etbc1e3RHQ6zeWxVVdubi6xsbHVatj5yAouQgghhBDuZTLoeOK6Vnz7UDeahioKSq1Mnb+bP/xnAwczCjwdXrXIFbtypCtWCCGEEAA2BatPacw/pqPUpqHXFNcn2rguQWGo48ti0hVbS9IV6118raw8Ha900bg3rdRz9/C1svJ0vFLP3Zu2fJr0AgvPfb+bFfvPANC6YSgvjWzPFUmRtY6tuqQrVgghhBDCBRpHBjHj3it5a1QnooKN7EvP544Z63lhwR7ySyyeDu8icsWuHOmKFUIIIURV8s3wvyM6NpyxXxeLDFCMamGjY5R7m1LSFVtL0hXrXXytrDwdr3TRuDet1HP38LWy8nS8Us/dm/ZyaVYfyOSZ73dx/GwRAFfE2Hh3TF8SokKdiq26nOmK9f5VID3MaDQ6/UPkTJqa5F9f+VpZeTped5/f1fnXNr/apJd67j18raw8Ha/Uc/emrSrNwHZxLG7ZgHeW7uOjVYfZeVbDis5t34Uz+UrD7jLMZrPTx1YnjTPH1ne+Vlaejtfd53d1/rXNrzbpa5JW6rl7+FpZeTpeqefuTVudNAYNnhrUiiFtopm3bB1xoUa3fx/VIV2x5cgYOyGEEEJ4GxljV0syxs67+FpZeTpeGXvj3rRSz93D18rK0/FKPXdvWm+r5zLGzoVk7I338LWy8nS8MvbGvWmlnruHr5WVp+OVeu7etN5Sz2WMnQvJ2BvP87Wy8nS8MvbGvWmlnruHr5WVp+OVeu7etN5Wz2WMXQ3JGDshhBBCeBsZY1dLOTk5REZG8tFHHzFs2DCn+uSXLVvGwIEDq9UnX91j6ztfKytPx+vu87s6/9rmV5v0NUkr9dw9fK2sPB2v1HP3pvW2ep6Xl0fz5s3Jzs4mIiLiksdKw64Sx48fJykpydNhCCGEEEI4pKamkpiYeMljpGFXCZvNxsmTJ7n22mv5/fffnUrbvXt3NmzYcNnjcnNzSUpKIjU19bKXVUX1y9VbeDped5/f1fnXNr/apK9JWqnn7uHpeuMsT8cr9dy9ab2pniulyMvLIyEhAZ1Od8ljZfJEJXQ6HYmJiRgMBqe/JL1e71Sa8PBw+Q+/GpwtV0/zdLzuPr+r869tfrVJX5O0Us/dw9P1xlmejlfquXvTels9v1wXbJlLN/vqufHjx9dJGnF5vlauno7X3ed3df61za826aWeew9fK1dPxyv13L1pPf391pR0xXpI2SLI1ZnhIoTwTVLPhfB/3lbP5Yqdh5hMJp577jlMJpOnQxFCuInUcyH8n7fVc7liJ4QQQgjhJ+SKnRBCCCGEn5CGnRBCCCGEn5CGnRBCCCGEn5CGnRBCCCGEn5CGnRBCCCGEn5CGnRBCCCGEn5CGnRBCCCGEn5CGnRBCCCGEn5CGnRBCCCGEn5CGnRBCCCGEn5CGnRBCCCGEn5CGnRBCCCGEnzB4OgBvZLPZOHnyJGFhYWia5ulwhBBCCFGPKaXIy8sjISEBne7S1+SkYVeJkydPkpSU5OkwhBBCCCEcUlNTSUxMvOQx0rArJyUlhZSUFCwWCwAfffQRwcHBHo5KCCGEEPVZYWEhDzzwAGFhYZc9VlNKqTqIyafk5uYSERHB7NmzGTFiBEajsVrpzGYzixcvZvDgwZdN48yx9Z2vlZWn43X3+V2df23zq036mqSVeu4evlZWno5X6rl703pbPc/NzSU2NpacnBzCw8MveaxcsbsMo9Ho9BflTJqa5F9f+VpZeTped5/f1fnXNr/apJd67j18raw8Ha/Uc/em9ZZ67ky+fj0rNiMjg2HDhhEcHEybNm1YunSpp0MSQgghhHAbv75iN378eBISEjhz5gyLFi1i1KhRHDx4kKioKE+HJoQQQgjhcn57xS4/P5958+bx/PPPExwczMiRI+nYsSPz58/3dGhCCCGEEG7ht1fs9u/fT0REBPHx8Y5tXbp0YefOnRcdW1JSQklJieN9bm6u47XZbK72OcuOrU6atFe7co0li8LNoNDQsD8DqAvWznNsp2x72XsueK+BVrZduyh9lem0yvZXkV4r/77q/RqXOO6i82nl315cHkBbs5nUXa+US1sugaZVmu78dtDQzn/uSvIoS+vYd0GMaOf2n/uMl9quULQoKOTYkRloOt25fRpo5/6O0s5vU+dea5qG0jR7nJqGpl2Yzv6saefTaeX3a6ChA52GUtDwdDrHv1mFTq+3fxRNfy5cnSONdu48mk5D0+zHaZoOnU6HprPv1+nKH6dDp+lQykbj9P2UrjuJzWA8d4zOHodOfy5//bnX+nLby23T6Rz7rDZFZMEhLKkbIcBU7rgL0qE7n65cPmaLDc1mwVxSDEpd8P1emjN1tiZpapJ/feVrZeXpeN19flfnX9v8apPeH+q5M3n77azYVatW8cc//pEDBw44tk2ePJns7GxSUlIqHDt16lSmTZt2UR6zZ89223InvTc9TkMt2y15C1GfWdBj1QzYzj2Xf600PTbNgNKde9b0KJ3hXCPx/PuyfVZdgP2hBZx/rTNh1QVg0QVgc+w3YTm3z6wPtucphBAuUlhYyN13312/Z8WGhoZWuPIG9itxoaGhFx07adIkJkyYUOG4sgWK3TU9eldSI37csolOHTuh1+lQnLvYgLL/K2tvK1VuO+e3Y9+ulA0ATalzV6Ts28uuu1XIB3X+ct25fBXKnve512X7qCwvm80Rv2O7UjhSVpXu3PayGC+MSXMcX5bcdv7qmlJYbTZOHj9OQuPG6M5dkaKKWLULYnGcu1yZVjzu/GeyF4/Nkb7sPMpeOBW+F1vZF2b/RI73ClA2K2fPZhMZGW6/qlZ2DmU7n6bC63LPyuZ4rWFDKYWmAGz2a47l0mllZX/u2LLy1ZSV0pJSAgKMaOfK157Gdi4NaNguOp99/7mfiUrOAwrdufw0QIfNcb1Th0KHDf25OPXY0Gs2x7ayZ32543Tltuu0c2kqHGu74FjlOPZSDFgxKKvjO/UEmyEIZYqAwHCyixWRjZqgBUWiAiMgOAZCGqJCG0FoI/tzSAMwmDwTrJfw9PIhzvJ0vLLciXvTeuNyJ9Xltw275ORkcnJyOHXqFHFxcQBs3bqVBx544KJjTSYTJlPl/6m6a3p0+05XcST1NJ2u7OUT/4l5ktlsZuHChVw3dKhPlFVZvEM9FK+7zm+zKaxKUVJSysKffmbQ4CHo9QasSmG1KWznnsu/tj/jeG0+l4ft3HFWpSg1W1i7bj1XdeuGQofFpjBbbZitCovVhtl27rlsm8WG1WbGYrFgtVixmEs5evQI8fFx9j8KLGZs1lKwmlFWM5q1FKylKKsFZSlFWUuxWUrBZgaL/bVRs2LEghH7swErAZoZE2aCKCEQM0FaCUGUEkgJQVrpue2lBJ57HUQpQVopADpLEViKoOAUMQCH9l++gEMbQVRziG4B0c0hpiXEdYbolvYu6HrC08uHOMvT8cpyJ+5N64vLnfhtwy40NJSbb76Z5557jnfeeYfFixezY8cObrrpJk+HJoRP0uk0dGhg1GPSQ1igwWV/yefsVQxo3aDGf8kvXHiaoUOvrtFf8gsWLGTIDTdgRUex2UaJxUqx2Uax2UqJxUaJ2UqxxUpBiZXMEgs5hSVs3rGbhCYtKLLYyC+xkl9spqDESkFxCbaSXFRRDvqSXMK1AsIpPPdcQIRWQAx5NNSyaVD2IJsAzQr5p+2P1LUVgwwIhbhOkNQDWgyEJr3BGOh0OQkh6ge/bdgBTJ8+nTFjxhATE0NiYiJfffWVLHUihKhA08Co1xFsNBJWjfaS2WxmYc4uht7Y5pINyVKLjYzcQub9tJSOV/Ukp9hGVkEppwtK2ZZTzMmcIk5m2x+B5mwStTM01U47Hq10J2inHSOoNB+OrbE/fn0XDIHQ8lrocie0vqHed+EKISry64ZdgwYNWLhwoafDEELUQwEGHQ3DTDQOgd4tYqpsBCqlyC40cyyrkAPp+exPz2dReh7vn87jZFY+zbU0OmuH6KPfRV/dduIsZ2HvQvsjKAp6PgI9H4agyLr9gEIIr+TXDTtX8OXp0f7C18rK0/HKMgjuTeuOeh4aoNE+LoT2cSFAI8f2zIJStqRms/lYDp8dyuSpEzm00VIZqf+VkfpfiS/KguUvo9amYBswGVvXseeX1fExnq43zvJ0vFLP3ZvW236fy3InNZSSkkJKSgpWq5V9+/a5dbkTIYRwVk4p7DirsTFDx+E8xVDdOh43zKW17gQA6WEd+L3ZeMyGi2f/CyF8lzPLnUjDrhK5ublEREQwe/ZsRowY4bPTo/2Fr5WVp+OVZRDcm9Zb6vn+0/l8uPIwC7af4F7dIv7POIdgSlBRzbHc9TVENXPp+dytWmVVnIu26zt0qWuh8AwEhKESrsTW8XYIi688jSfj9eHzSz33jnpeJjc3l9jY2Pq9jp2r+PL0aH/ja2Xl6XhlGQT3pvV0PW+fGMV7d0fxSForJs2N5pbj7fnI+CZJZw9j+PwWtPsXQXiCS89ZFyotK6Vg40xY8hwU51Tct+d79Mtfgr5PwjV/BX3d1jmp53WbX32r5+Xzri7fHIwhhBACgHbx4XwzrjfXXTOQW0unccgWh5aTCl/dB5aSy2fg7ZSCnybBD3+xN+pi28CASTDyAxj8gn35F5sFVr4OX48FS6mnIxbCo6RhJ4QQPs6g1/F/N7TlL7f0ZYz5r+SoYDi+wd7Y8XVr/gnrPgA0GDQNHl0DA/4GV9wNVz8Of/oJbvsY9CbY8wMsvfj2kELUJ9IVexm+PIvGX/haWXk6Xpkt59603lzP7+iawJncq/nbsgf5IOBd1Kq3sbQdCQ3a1Mn5a6PSssrcj2HpC2iAdfAL2HqM49ytTCombjsCbaQew7djUWtSsLYeikrsUffx1iGp5+5N6231XGbF1pDMihVC+Dql4D97NR7Lf5vB+k2ciOjO7y0e83RYNdLj0NvE52zmdFgn1rZ8yr6a9CVcefTfNMlaTXpYR9a0+r86ilII95NZsbUks2K9i6+Vlafjldly7k3rC/U8q6CUR975gm/UU+g0hfmBFdCoQ52dvyYuKqvMAxg/7GXf9/AaiE2+fCbZRzFM74GmrJjv/8V+r926ireOST13b1pvq+cyK9aFfHkWjb/xtbLydLwyW869ab25njeKNDL0umtZuKgHw/Xr0G36BP3N79bZ+WvDUVab/mPf0PpGjPHtq5e4QStoPwJ2zsW47QtIusp9gZ4j9bxu86uv9bxezYp99dVX0TSNtWvP3zh77NixmEwmQkNDCQ0NpUMH7/5LVQghXO3e3k2Zb7wRANu2r6G0wMMROcFmg13f2193v9+5tFfcbX/eNc+ejxD1jE837E6cOMHs2bOJi4u7aN+0adPIz88nPz+fnTt3eiA6IYTwHJNBT/vewzhsa4TRUgC753s6pOo7uRnyT0FAKDTv71za5teAMQQK0uH0dvfEJ4QX8+mG3cSJE5k2bRomk8nToQghhNe5u1dT5tv6AFC47XsPR+OEvQvtz62uA4OT/78bAqB5P/vrQytcG5cQPsBnx9gtX76cM2fOcMstt/Dkk09etP/111/n9ddfp02bNrz66qv071/1X30lJSWUlJxfyDM3N9fx2penR/sLXysrT8cryyC4N60v1fPIQB3p8QMg4zsMR5ZhLsp3vqFUR8qXlf7IanSApcV1qBqUnS6xB/p9P2FLXY/VR+qBt51f6rl31XO/X+7EYrHQvXt3Zs2aRceOHWnWrBlffvklvXrZZ1Bt3ryZZs2aERISwtdff82jjz7Kjh07SEpKqjS/qVOnMm3axYtaynInQghft+aUYsLJJ2ioZfNby6fJCO/k6ZAuSVNWhm57GIOtlKXtXiE/sLHTecTk76Hv/pcpMkaxqKNvTBoR4lJ8frmTIUOGsHLlykr3TZkyhbCwMA4cOMD7778PcFHD7kI33HADd9xxB3/6058q3V/ZFbukpCRZ7sRL+FpZeTpeWQbBvWl9rZ5nFpSy6o07GWVYSX63P2O6fqpH4ricsrIa0qUxQTOvQwWEYnnqEGg1GDFUkofxjeb2fJ/cB8HRLo7W89+t1HP3pvW2eu7zy50sWrTokvtHjhzJypUr+frrrwHIyMhg2LBhvPHGG/zxj3+86Hid7tL/MZhMpirH6fny9Gh/42tl5el4ZRkE96b1lXoeF2nkePgVULiSksNrCPXyOmTMsE940BKuxBhQw25jYzRENoHsYxjP7oeIvi6M8IJTST2v0/zqaz33++VOZs6cya5du9iyZQtbtmwhISGBWbNmMXr0aAC+/fZbCgoKsFgszJkzh9WrV3Pttdd6OGohhPAMU4urAQjP2g6Wkssc7Vnayc32F4271i6jhufWvkvfXbt8hPAxXnnF7nIiIyMrvNfr9URHRzvGw7399tv86U9/QtM02rRpw3fffUezZs3qPlAhhPAC7TpcyZnt4cSSCye3QJOeng6pStqZvfYXjWo5FjCmlf0561Dt8hHCx/hkw+5CR44cqfB+9erVnglECCG8UNdm0ayzJTNEv5HCQ2sJ9uaGXVlDLKZl7TKKbmF/zjpcu3yE8DF+0bBzJ1+eHu0vfK2sPB2vLIPg3rS+WM+DDXA8sDWYN5JzeCPGq72vLpnNZgzWIrSCdPv78KZQi3LTwptgAFTWQSxuKH9Pf7dSz92b1tvqud8vd+IuKSkppKSkYLVa2bdvnyx3IoTwG7t3b+ZvxW+Tqm/Cps4vejqcSkUUHmHA3mcpMYTxU6eUWuUVXHKawbuexqIFsKDLDNA0F0UpRN1zZrkTuWJXzvjx4xk/fjy5ublEREQA+PT0aH/ha2Xl6XhlGQT3pvXVel4QGA1r3ibeepKh1w8CfYBH47mQ2Wxm11cvAGCMa8/QoUNrl6GlGHY9jUGVMvTaqyEosvZBluPp71bquXvTels9L3/jhMuRht1l+PL0aH/ja2Xl6XhlGQT3pvW1ep7cuj05vwUToRVC9iGI876FikNKTgGgi22FrrblZTRCUBQUncVYfAbCG7ggwspOI/W8LvOrr/Xc75c7EUII4Zw28eHsVk0BKDy2xbPBVCGk5LT9RdnEh9oKS7A/5550TX5C+ABp2AkhRD0QHmjkhMHesMtJ3enhaCoXXJppfxHVzDUZhsXZn/NOuSY/IXyAdMVehi/PovEXvlZWno5XZsu5N60v1/PCsOaQA+bTe7wmpjJms5mg0iwALCGNUC6ITx/SCB1gzT6OzcWf19PfrdRz96b1tnous2JrSGbFCiH82b79O3k6/x+c0CXwe5dXPR1ORcrG8K0PoFcWFrV/kyJT7cfEtT35DW1Of8/h2GvZljS29jEK4SEyK7aGZFasd/K1svJ0vDJbzr1pfbmeq9UNYcU/aGRLZ+j1g0Hv+ZjKmLPT0G+xoNAYePPdLolNt/EU/PQ9TaNNJNZ2lu0FPP3dSj13b1pvq+cyK9aFfHkWjb/xtbLydLwyW869aX2xnjdt0ZrC5SaCtRLIPwmxrTwd0nlF5yZOhDbEGOiinpLIJAB0+adqP8u2Cp7+bqWeuzett9RzmRUrhBDiIi0bhXNY2ScUFKbt8nA0FWnnZq6q8Mauy7Rs8kRumuvyFMLL+WzDbs6cOSQnJxMaGsrNN99MVlaWY19RURH33HMPYWFhNGnShC+++MKDkQohhHcIDzRyXJ8IQPYxb2vYnbC/cGnDLt7+XJABNpvr8hXCi/lkw2737t08/PDDfPHFF5w9e5amTZsyfvx4x/7nnnuOrKwsTpw4wZdffskjjzzCvn37PBixEEJ4h7xQ+xpxJaf2ejiSC+Sdu2JXtvacK4TE2p+VFYqyLn2sEH7CJ8fYLVmyhOuvv55u3boB8Pe//52mTZtSUFBASEgIs2bN4n//+x/h4eH06dOHm2++mS+//JJnn3220vxKSkooKSlxvC8/SNGXp0f7C18rK0/HK8sguDetr9dzc1QLyAPj2f1eFZeWfRwAa0icS5cmMQTHoBVmYs4+AQERLsvX09+t1HP3pvW2eu73y528//77rFq1iq+++gqAkydP0rhxYzZv3kzTpk2Jjo6moKDAsVTJm2++yfr165kzZ06l+U2dOpVp06ZdtF2WOxFC+Jv9x47xVOYU8gjhlyumg6Z5OiQA+u57kZiCfWxoNp6TUT1dlu/A3X8nvPg4v7X8PzLCO7osXyHqkt8vd3LdddcxZcoU1q9fT5cuXXjllVfQNI3CwkLy8/PR6/UVGmTh4eHk5+dXmd+kSZOYMGGC431ubi5JSfbZVL48Pdpf+FpZeTpeWQbBvWl9vZ7/uicVvp1CGAUMHdDzfHelh+kP/h2ATlffwBXNersu37MfwZHj9OjQDNXJdUueePq7lXru3rTeVs99frmTIUOGsHLlykr3TZkyhSlTpvDBBx8wZswYMjMzeeKJJwgLC6Nx48aEhoZitVopLCx0NO5yc3MJDQ2t8nwmkwmTyVTpPl+eHu1vfK2sPB2vLIPg3rS+Ws+Tk+I5rmJJ1M6gnT2IITLe0yGBzYbKt9/2Sx/d1LVldW5mrKEoE9zwHXj6u5V67t603lLPfX65k0WLFlFcXFzpY8qUKQDcfffd7N69m/T0dEaPHk1QUBCJiYlERUURFxfH9u3bHflt3bqVDh06eOrjCCGE14gPD+Qw9pmnZ4/u8HA05xSko9nsixMT2tC1eZfll3/atfkK4aW8smFXHZs2bcJms3HixAkefvhh/va3v6HX6wG45557eOGFF8jLy2Pt2rV8//33jB492sMRCyGE5+l0GhlBzQEoOrHTw9Gck2OfOFFkjAKdizuSQhvZn/PTXZuvEF7KZxt2jzzyCOHh4XTr1o3+/fvzxBNPOPY9//zzREREEB8fz6hRo5g+fTpt2rTxYLRCCOE9iiLt/x/qMnZ7OJJzso8BUBTghvF+ZVfsCqRhJ+oHrxxjVx3r1q2rcl9QUBCff/65S87jy9Oj/YWvlZWn45VlENyb1i/qeYO2cAoi8g54RWy6rMPogcKAWIJcHI8WGIMBUHmnsbgwb09/t1LP3ZvW2+q5y5c7KVtW5HL0ej233XZbtU/ubVJSUkhJScFqtbJv3z5Z7kQI4Zd2pJcw+cSDAPzY8Z+UGi+9fIK7dU79lOZnlrKv0U3sThjl0rzDilK5ds9kSgxh/NQpxaV5C1FXnFnupFoNO4PBQP/+/bncoRs2bLjksiK+Ijc3l4iICGbPns2IESN8dnq0v/C1svJ0vLIMgnvT+kM933Mqj/AZPWmqS8d891xo3t+j8ejn3IXuwGK2JP2R1ne97NqyKsjA+E47FBqWv50EvWvy9vR3K/XcvWm9rZ7n5uYSGxvrunXsgoKC+OWXXy57XFRUVPUi9CG+PD3a3/haWXk6XlkGwb1pfbmeJ8dFsFIl0ZR0Sk7tJrT1dZ4N6NzkicKAWNeXVXgj0PRoyoqxNAfCXbu8i6e/W6nn7k3rLfXc5cudHDp0qFqZyf1YhRDC+wUa9aSZ7DNjC1O3X+ZoN1MKclIBN02e0OkhpIH9tSx5IuqBajXsGjRoUK3MqnucEEIIzyqMbG1/4emZsUVnodQ+hKcwIMY95wg997upIMM9+QvhRZyeFXvjjTeiVXJvQZPJRGJiIrfccgvXXnutS4ITQgjhHgEJneAMRObsBasF9B5aJOHsYQBUSENsugD3nCO0EbBdrtiJesHpmtytWzc+++wzxowZQ2JiIsePH2fWrFnceeedaJrGXXfdxd/+9jeefPJJd8Rb53x5erS/8LWy8nS8sgyCe9P6Sz1v2LwjuVuDCKcI88mtENfZI3Fop3ZhAGwxyYB7ykof0ggdYD2bis1Lfm69/fxSz72rnrt8uZPyunXrxhdffEFycrJj2/79+7nrrrv4/fff2bhxI6NGjar2uDxvIsudCCHqi8xiaLXjdfrrt7O58X0cazjII3G0PzGH5PQFHIodxPak+9xyjtan5tEu7VuORvdjS9MH3XIOIdzJmeVOnL5id/DgQRo3blxhW3x8PAcOHACga9euZGT45jiG8ePHM378eMdyJ4BPT4/2F75WVp6OV5ZBcG9af6nnSik+3v09/dlOU1MOHYcO9Ugc+jn/hXRIvPI6tp9x7v/c6tJ2FMK8b0kKtZLgos/p6e9W6rl703pbPc/Nza32sU437IYMGcKoUaN45plnHF2xL774IjfccAMA69evp2nTps5m67V8eXq0v/G1svJ0vLIMgnvT+kM9z4m9Es58Q0DaBowGA1QyftrtMu2rKegatYMzue4pq9hW9nNkH0Pn4rw9/d1KPXdvWm+p5y5f7qS8jz/+mDZt2nDXXXeRnJzM3XffTZs2bfjoo48AaNy4MfPmzXM224tYLBZuu+02GjdujKZpnDp1qsL+5557jqSkJMLDw0lOTuaTTz5x7Fu+fDk6nY7Q0FDHY9WqVbWOSQgh/Eloq76UKAOhRSch82DdB1BaCGePAqBi3Xg/76hm9ufcE2Apcd95hPACTjfsQkNDeeuttzh8+DBFRUUcOnSIN998k9DQUAASExNp2bKlS4Lr378/3377baX77rnnHvbs2UNubi4LFy5k8uTJ7Ny507G/devW5OfnOx79+vVzSUxCCOEvrkpOYr2tLQBq/891H0D6LkBBcAwEu2ENuzIhsWAMtp/r3GLIQvirGs1vX7BgAd988w0ZGRn88MMPbNiwgezsbAYPHuy6wAwGnnjiiSr3l5+8AWCz2Th69CgdOnRw+lwlJSWUlJz/K658X7Yvz6LxF75WVp6OV2bLuTetP9XzTvEhvMeV9GMHhTsWEtDtoTo9v+7wKvSArXE3zBYL4L6yMkQ2RcvYjSXjACq8Sa3z8/R3K/XcvWm9rZ67dVbsa6+9xqxZsxg3bhyTJ08mOzubPXv2MGbMGNatW+d0sNUKUtNIS0sjLi6uwvZXX32VF154gcLCQnr06MGKFSsIDAxk+fLl3HDDDYSHhxMREcG9997L5MmT0ev1leY/depUpk2bdtF2mRUrhPB3c3dk8Kl5IlZ0LO74LiXGiDo7d49D7xCfs4mdCaM50GiYm8/1NvE5m9mWeB+HG3hmBrAQNeXMrFinG3ZNmjRh/fr1xMXFERUVxdmzZ1FKERMTQ1ZWVq0CrzLIKhp2YJ/ZtX79epYsWcJf//pXDAYDp06dIjs7m9atW7Nnzx7uuOMO7r///irX1qvsil1SUhKzZ89mxIgRPjuLxl/4Wll5Ol6ZLefetP5Wz2esPkzvZXdxpe4A1kHPY+v5aN2cWNkwvN0WrSgLy9ifKG3Yxa1lpVv2Evrf3sZ2xT1Yh71T6/w8/d1KPXdvWm+r57m5ucTGxrpnuROr1epYCqTsDhS5ubmOMXbVNWTIEFauXFnpvilTpjBlypRq5aNpGj179mTWrFl8/PHHPPzww8TFxTkage3bt2fKlClMnz69yoadyWTCZDJVus+XZ9H4G18rK0/HK7Pl3JvWX+r5sM6N+feS/lypOwCb/4uxz2Ogc3r4tfPStkFRFhiCMCRehVL23yduK6ukqwDQpW116cxYT3+3Us/dm9Zb6rlbZ8XecsstjBs3jjNnzgCQn5/P008/zW233eZUPosWLaK4uLjSR3UbdeXZbDYOHqx8VpeuLv6TEkIIH9Q0JoQ9Da4nVwWhz9wHexfWzYl3zrU/t7oODG66lVh5CV3tz+m77LNxhfBTTrd43njjDUJDQ2natCnZ2dk0atQIg8HAyy+/7PLgSkpKKC4uvug1wEcffUR2djY2m40VK1bw+eefM2DAAMC+3ElqaipgvyvGiy++yPDhw10enxBC+IMburbmM+sQANTyV8Bmde8JlYId51Y86HS7e89VJjzBfs9YZYXTO+rmnEJ4gNMNu8DAQFJSUigoKOD06dPk5+czffp0goKCXB5cmzZtHPk2a9aswjkWLlxIy5YtiYiI4NFHH+X1119n6LkVxTdu3EivXr0ICQlhyJAhjBw5kgkTJrg8PiGE8AejuiXyX4aRq4LRTu+ADR+594QHlkL2MTCGQPL17j1XGU07f9Xu2Nq6OacQHlCtMXbr16+vct/hw4cdr3v06FH7iMo5cuRIlfvmzp1b5b6JEycyceJEl8Tgy9Oj/YWvlZWn45VlENyb1h/reYhRo3+XNry2ZTQvGj9BLZmKJbE3NGzn+pMphX75q+gA65X3YtOMYDbXSVnpmvVHv+9HbHsWYO3xSK3y8vR3K/XcvWm9rZ67fLmT5s2bn0+gaRw/fhxN04iJiSEzMxOlFImJiRw6dKhmEXuJlJQUUlJSsFqt7Nu3T5Y7EULUG1kl8NJmjf8YXqO/fjsFAbH82moSRaYGLj1P46zf6Hb0Q6yakcUd3qTEGOnS/C8lsDST63c+iULj547v1enSLkLUhjPLnVTril35q3LTpk2jsLCQqVOnEhQURFFREdOmTSMkJKR2UXuB8ePHM378eHJzcx0zf315erS/8LWy8nS8sgyCe9P6cz1PDdzLE7+N53vDNJJK0xh8/G0sd34JDdq65gSZ+zHMfMz+ut8Erut3t2NXXZWVLeszdGmbGZyQj637XTXOx9PfrdRz96b1tnpe/sYJl+P0cifvv/8+p06dwmCwJw0KCuKFF14gPj6eZ555xtnsvJ4vT4/2N75WVp6OV5ZBcG9af6znT93QlsV70rk9azLzQl8lLvc4xv8MhkFTofv9oK/FZzi9E2bfAcU5kNgd/TVPo68kP7eX1ZV/gLTN6Nd/iL7nQ6Cv0Q2YHDz93Uo9d29ab6nnbl3uJCoqiqVLl1bYtnz5ciIjI53NSgghhBcJDjDw/l1dyTbEMix/MvvDeoKlCH76K0zvBetnQFG2c5mW5MPyf8CM6yD3OMS2hru+rF0jsTau+IP93rTZR2HrbM/EIIQbOf2nyrvvvssdd9xBz549SUpK4tixY2zYsIHPP//cHfEJIYSoQ1ckRfLmHV348+zNDMl4jNea9eH23FlomQdg4VPw82Ro2gea94NGHSGmFYTEQkAY2CxQmm9vNKXvgcMrYff39m0ALa+F2z6G4GjPfcCAYLj6L7D4GVg0BVoNsi+FIoSfcLphN3ToUA4ePMjChQtJS0vjmmuu4YsvviA2NtYd8QkhhKhjwzsnUFRq5W9zt/P0ke58Gdeb6VfuodH+L+0L/B5aZn9UV3RLuHYKdLjFvuyIp/V61L5A8snNMHs0jP0BAmUihfAPNRpcEBsby3333efqWLySL0+P9he+VlaejleWQXBv2vpSz0d2iSMm2MDEb7az8ZSZ3qdbMarrB0wYbCM2Yy3a8XVoZ/bB2SNo5op3clAhDVFRzVFJPVGtBqGSetsbdBZLleer87Ia+W8MM29EO7UN9fH1WG79D8QmVzu5p79bqefuTett9dzly52MHj2aOXPmXDazu+++m9mzfXfMgix3IoQQFeWWwteHdWzLsg/J1muKK2IU/eJsNAu1t9d0tlIM1mJsmh6bzohNVwe3CHOB8MKj9D74JoGWbKyagYMNb+Rgg+spNV56OQkh6pozy51Uq2EXFBTEZ599xuUOfeihh8jOznYqWG9UttzJ7NmzGTFihM9Oj/YXvlZWno5XlkFwb9r6Ws83HDnLm4v3s/FYtmNb48hAhrRvxOB2DbkiKQKjvub35fZYWeWeRL9wArqDSwBQhkBUqyHY2o9ANe1X5XhAT3+3Us/dm9bb6nlubi6xsbGuW8euZ8+eTJ8+vVrH+Rtfnh7tb3ytrDwdryyD4N609a2e90luSJ/khmw7ns2nvx1l4fY0TmQX88lvR/nkt6MEGfV0axZFrxYxdG0SRcfG4YQFOv+Z67ysYprCPd/Anh9g5RtoaVvQ9nyPbs/39v0N2tpvRdagNcS2sXfXhjeGczF6+ruVeu7etN5Sz53Jt1oNu+XLl9c0lhqzWCyMHj2atWvXcvLkSdLS0oiLi3PsP3z4MA8//DDr168nJCSEP//5z0yaNMmxf+bMmUyZMoXc3Fxuu+02/vWvfxEQ4BvdA0II4a06J0by5h2RvDiyIyv3Z/DzjlMs25vO2UIzq/afYdX+M45jm8eG0LFxBB0TwunYOIJ28eFEh3jh/8OaBu1ugrbDIW2rfWLF3p/gzF7I2GN/XMBgCv//9u49vqkqXfj4L0nb9BKaQkulpZVyx0KRF4HxxuAIUkWZ9ngUHQaljOC8CCoWz8cBWikIHmWGMx7fqcrB23ipiB4HZ1CxjogwiuDIrUoFRMqtrYVCm6aXXPf7R9rQTgs0kN2dhOf7+eSTZO+9Vp6szWMfd7JW+IWuG4aal8CU6Jl8ERnnuY9qvo80Q3g0hEdBWJTnvuUWFhkYE0lEyLm4lRlV9vOf/5z/+I//4Jprrmm378EHH6Rfv3588MEHHDt2jOuuu44xY8Ywfvx4SkpKyM3Npbi4mIEDB5Kdnc2yZctYunSpBu9CCCFCT1SEgcyhvcgc2gu3W+FAlZWvfqzmqx+r2XOsluM1jRw6Wc+hk/X8bXe5t12v2EjSk2O5Iqkb6Ulm0pNj6dMjQL7LrNNB8gjP7aalUH8Sjm7zLK58cj+c2AfVB8FRj85mIRYLHDp+4a/XUuyFGT3r+unDPffexxHNj8POPG7eZ9AZuPJ4JfoNmzyLLOsMoDeATt983+q5zgB6fattrY/r+HidopB0eje675Xmq5O65n3N9+hAR6vHrbc3H9fqsc7lJq7+ILryHRAecdbj2vfXfF5cbqJsJ6D22Dni+Zc2LdscTsJcjWCrA3dEq4Ja1/a41tvcTlDcnpvb3dx3cBTiAVvYhYWF8fDDD591/+HDh5k/fz7h4eH07duX66+/nr179zJ+/HiKioq46667GDVqFAD5+fnMnDnzrIWdzWbDZrN5n7f+6Y5gnkUTKoJtrLSOV2bLqdtW8rxj/eIj6Rffm6mjewNQXW9nb7mF78otfFtuobSyjiOnGqm0NFFpaWLj91XettERBgYlxhDj0HPqqzKG9Y5j8GXdiIowaPV2PCLM0H+i59ZCUcBuxXn6CDs3fcBVg3sTZq/1/KJGkwVdU43nsc2CrqkWHI2eRZ4dnpvO3erfgrN53wXQA2kA1T4sO+ODMGAMQJn/+hsHsP/C2ocDEwH2XljbWwH2+NYmC2BX+30KzQVec1EYptMxWVFo+vn3YOrue4Cd4PdZsVrT6XTtPop94YUX2LlzJ88++yxHjhxh/PjxfPDBB2RkZJCVlUVmZiYPPPAAANXV1SQkJNDQ0EBUVFS7/gsKCliyZEm77TIrVggh/KfJCeUNcLxBx/F6z62iARxK+yshOhR6RkJaN4XBZoXBcQrdgvtrigDoFBcGtx2D2+6ZTey2o1cc6BQXesWJXnGha75v+9jZfEzrx050ittzQ2m+d3vvUZQzz1vto4Nj2/TRwTHgOSee7Z57b4mjKGf2obR57nkM4G5/bJt+lObxafVaSut9LcfT/N7w7mtpq7X1w/8HlyFSlb59mRUbsFfszufaa6/lueeeIyYmBpfLRUFBARkZGQBYrdY2b7zlsdVq7bCwW7BgAbm5ud7nFouF1NRUgKCeRRMqgm2stI5XZsup21by3L+cLjdl1Q18e7yGDV99iy0qgX0/WTlhtVPVBFVNOraf8Bw7ItVM9ohkbh3Wi7hobcdT63MbzHke5mN/SmfiUc4UkjQXpjQXgg6HnU8//ZTxN/6C8LCwM722XNfyXt86U0w6HHY+37SJcePGNbc5s6/t64HTaWfz5i3cmHkr4RFGn95bZ7X+JPF8fC7sGhsbefzxx3nnnXc4deoUFouFjz/+mNLSUubNm9fpfiZOnMjmzZs73JeXl0deXt5Z27pcLiZNmsRjjz3G7NmzOXbsGLfddhtDhw7ljjvuwGQytRmElscmk6nD/oxGI0ZjxycjmGfRhJpgGyut45XZcuq2lTz3j/BwuKK3kQGJJiIq9jBp0ijCw8M5UWfju/Jatv5Yzeb9JymtsLDraC27jtby5Ef7uHt0Kg/cMIBeZnWukHQ+fsnzruzvgtqHOXDrIwiPNne+rcOBPawb4eZe52/jcNAU8R3hEcaAmBXr86JDDzzwABUVFaxfvx6DwfP9h+HDh/PCCy/41E9xcTFNTU0d3s5V1AGcOnWK8vJyZs+eTVhYGGlpaWRnZ/PZZ57vGqSnp1NSUuI9fvfu3fTt27fDq3VCCCECT89uRm4YnMiCW67go4fHsm3hePJuvYIhvbphd7p5bethfv77z3hu0w84XW6twxUiYPhc2H3wwQe89NJLDBs2DF3zDJGkpCQqKir8HpzNZqOpqand4549e5Kamsrq1atxu90cO3aM999/3/tR7NSpU1m7di07duygtraW5cuXM23aNL/HJ4QQomtcFhvJzLH9+OjhsRTN+hlj0npgd7pZsWEfU1dv43S9XesQhQgIPhd2cXFxnDhxos22Q4cOkZyc7LegWgwePNh7lS0tLa3NFbd3332X119/ne7duzN69GjGjx/PrFmzAMjIyGDlypVMnjyZlJQUUlNTWbRokd/jE0II0bV0Oh3X9k/g7d9ezR/uvBKTMYztZaeYsmorNQ1S3Anh83fsHn74YSZPnsyiRYtwuVysX7+eZcuW+fT9us4qKys7677Ro0fz5ZdfnnV/Tk4OOTk5Fx2DLIOgvWAbK63jleVO1G0rea6OCxmrrOGXkX5ZDDP+/A0HqqzMeu2fvD5jFAa9+uuNaX1uJc/VbRtoea76cifvvPMOL7/8MkeOHKF3797cd9993HXXXb52E3AKCwspLCzE5XKxf/9+We5ECCGCQHkDPPOtAZtLx+TLXUzoHRjLXwjhL74sdxIU69h1NYvFgtlspqioiKysLFkGQWPBNlZaxxvMyyDIcieXrosdq3d3HGfBX77DGKbns9yx9OymzrITLbQ+t5Ln6rYNtDy3WCwkJCSos47dM888wy9+8QuuvPJKtm3bxrRp0zAYDLzyyisd/vRXsJNlEAJHsI2V1vHKMgjqtpU8V8eFjtXdY/qw9pvj7DxSw0tfHiH/tnQVomtP63Mrea5u20DJc1WXO1mxYgVpaWkAzJ8/n3nz5rFgwQIeeughX7sSQggh/EKn0/HIhEEAFG07QoPdqXFEQmjD58LOarViNps5ffo0paWlzJ49m+nTp7N//wX+AJwQQgjhB2MHJtAnPppGh4tP9v6kdThCaMLnwm7AgAGsWbOGZ599lgkTJqDX6zl16hQRERFqxCeEEEJ0ik6nI+tKz9Jbf91VrnE0QmjD5+/YPf/888ybN4+IiAhefPFFADZs2EBmZqbfgwsEwTw9OlQE21hpHa8sg6BuW8lzdfhrrG4emsizG39g84ETWOqbiIow+CO8drQ+t5Ln6rYNtDxXfbmTUCXLnQghRHBTFCjYYaDGrmP2FS6GxMmfOBH8fFnuxOcrduD57dUvvviC6upqWteFjz/++IV0FzDmzJnDnDlzvMudAEE9PTpUBNtYaR2vLIOgblvJc3X4c6w+byrhL7sq0CUOZNKEAX6KsC2tz63kubptAy3PLRZLp4/1ubD705/+RF5eHpMmTeIvf/kL//Zv/8YHH3xAVlaWr10FhWCeHh1qgm2stI5XlkFQt63kuTr8MVYj0+L5y64Kvq2oU33ctT63kufqtg2UPFd1uZOVK1eyceNGioqKMBqNFBUVsX79ehobG33t6pz27dvHbbfdRkJCAj179mTatGmcPn3auz83N5d+/frRrVs3Ro0axebNm737Nm3ahF6vx2QyeW9btmzxa3xCCCEC05Upnk9c9hyrQb5tJC41Phd2p06dYuTIkQBERERgt9sZO3YsxcXFfg2straWKVOmcPDgQcrKyrDb7Tz66KPe/WazmeLiYmpra3nsscfIzs6mrq7Ou3/QoEFYrVbvbezYsX6NTwghRGAadFk39DqoaXBwos6mdThCdCmfP4odPHgwu3btYsSIEYwYMYKnn34as9lMz549/RrYmDFjGDNmjPf5rFmzyM3N9T5fvHix9/Gdd97JvHnz2L9/P1dddZXPr2Wz2bDZziR/68+yg3kWTagItrHSOl6ZLaduW8lzdfhzrAzA5T2iKatuYG95Dd2j4i+6z3+l9bmVPFe3baDluaqzYr/66isiIiIYOXIke/fuZe7cudTV1fH0009z4403+hxsZy1ZsoTS0lLWrFnTbl9ZWRlXXHEFlZWVmM1mNm3axM0330xsbCxms5l77rmHRYsWYTB0PO29oKCAJUuWtNsus2KFECI4vfi9npLTem5PczEuST6OFcHNl1mxQbHcya5duxg/fjybN29m6NChbfY5HA4mTJjAuHHjWLp0KQCVlZXU1NQwaNAgvv/+e6ZMmcJ9993HI4880mH/HV2xS01NpaioiKysrKCdRRMqgm2stI5XZsup21byXB3+HqunNuzjpS8OM+PaPiy8ZbAfImxL63Mrea5u20DLc4vFQkJCgnrLnRw5coRvv/0Wq9XaZvuUKVM63cfEiRPbTHhoLS8vj7y8PAAOHTrE5MmTeemll9oVdYqikJOTQ2JiIgUFBd7tvXr1olevXgCkp6eTl5fHc889d9bCzmg0YjQaO9wXzLNoQk2wjZXW8cpsOXXbSp6rw19jldojBoCKWltQ5UGgvb7keWDkuS/9+lzYrVixgoKCAjIyMtp8TKnT6Xwq7Doz2aKyspKbbrqJ/Px8srOz2+1/8MEHKS8vZ8OGDej1Z58Hcq59QgghQk/v7p6/T8dr/LtigxCBzufC7g9/+ANff/11u6tn/lZbW0tmZib33nsv999/f7v9ixcv5osvvuDzzz9vd7Vt06ZN9O/fn9TUVA4cOMCyZcuYNm2aqvEKIYQIHL3jogAp7MSlx+dLWSaTif79+6sRSxvr1q1jz549rFixos16dC2WLl1KaWkpycnJ3n1vvvkmAN988w1XX301MTExTJw4kezs7DYzaoUQQoS23t09hd2pejsNdqfG0QjRdTp1xa6qqsr7eMGCBcycOZMFCxa0W+IkMTHRb4FNnz6d6dOnn3X/ueZ8zJ8/n/nz5/sljmCeHh0qgm2stI5XlkFQt63kuTr8PVbRYWAyhmG1OTl8oo4BiabzN/KB1udW8lzdtoGW535f7kSv16PT6c5ZTOl0OlwuV6dfOBAVFhZSWFiIy+Vi//79styJEEIEsad3Gyhv0PF/h7i4onvALwAhxFn5stxJp67Yud1uvwQW6ObMmcOcOXOwWCyYzZ6fpAnm6dGhItjGSut4ZRkEddtKnqtDjbF6/9ROyvedIHnQMCaNTvVLny20PreS5+q2DbQ8b/3DCefT6ckTiqKwevVqvv32W0aMGMFvfvObCwou2ATz9OhQE2xjpXW8sgyCum0lz9Xhz7FKap5AcbLeqeoyFJLnXdffpZrnvvTb6ckT8+fPZ/HixVRWVrJo0SLvOnNCCCFEIErsFgnAibomjSMRout0urBbu3YtmzdvZu3atXz22Wcd/rSXEEIIESgSYz1LYVVZbOc5UojQ0enCzmKxMHDgQACGDBnCqVOnVAtKCCGEuFg9TZ7C7oRVCjtx6ej0d+xcLhdff/21d2bsvz4HGDNmjP8j1FgwT48OFcE2VlrHK8sgqNtW8lwdaoxVj2gDAD9Zmvx+DrQ+t5Ln6rYNtDz3+3InAGlpaeh0urN3pNPx448/dvqFA5EsdyKEEKGjxgaLd4Sh1yms/JkL/dn/hAkR0HxZ7qTThd2lpGW5k6KiIrKysoJ2enSoCLax0jpeWQZB3baS5+pQY6wcLjdDl/wdRYGvfncD8TERfukXtD+3kufqtg20PLdYLCQkJPhvHbtLWTBPjw41wTZWWscryyCo21byXB3+HKvwcOgRHUF1vZ3TjS56xfn/HGh9biXP1W0bKHmuynInXW3fvn3cdtttJCQk0LNnT6ZNm8bp06e9+4cOHdrmN2T1ej0rV6707n/11VdJSUkhNjaWGTNmYLfbtXgbQgghNNSzW/PM2DqZQCEuDQFb2NXW1jJlyhQOHjxIWVkZdrudRx991Lv/u+++w2q1YrVaOXz4MOHh4WRlZQFQUlJCbm4u69at4+jRo5SVlbFs2TKt3ooQQgiNtBR2J6SwE5eIgP0odsyYMW1m2c6aNYvc3NwOj127di0jR45kwIABABQVFXHXXXcxatQoAPLz85k5cyZLly7tsL3NZsNmO5P0rX+6I5hn0YSKYBsrreOV2XLqtpU8V4daY5Vg8nyvrrKmwa99a31uJc/VbRtoea7KrFitLVmyhNLS0g4XRr7++uu5++67mTt3LgBZWVlkZmbywAMPAFBdXU1CQgINDQ1ERUW1a19QUMCSJUvabZdZsUIIEdz+eljPp+V6xvVyc3vfS+N3z0Xo8WVWbMBesWtt165dPPvss2zevLndvrKyMrZv3857773n3Wa1Wtu88ZbHVqu1w8JuwYIFba4GWiwWUlM9PxgdzLNoQkWwjZXW8cpsOXXbSp6rQ62xqtp6mE/L9xGTkMSkSVf6rV+tz63kubptAy3PW3+SeD6aFXYTJ07ssFADyMvL8/4W7aFDh5g8eTIvvfQSQ4cObXdsUVEREyZMIDEx0bvNZDK1GYSWxyaTqcPXMxqNGI3GDvcF8yyaUBNsY6V1vDJbTt22kufq8PdYJcV5PnU5aXWocg60PreS5+q2DZQ896VfzQq74uLi8x5TWVnJTTfdRH5+PtnZ2R0eU1RUxIIFC9psS09Pp6SkxPt89+7d9O3bt8OrdUIIIUKX/KyYuNQE9KzYzMxM7r33Xu6///4Oj9m1axdlZWXtir6pU6eydu1aduzYQW1tLcuXL2fatGldELUQQohAkhgbCUCVpUnjSIToGgFb2K1bt449e/awYsWKNuvVtfbmm2+SlZVFTExMm+0ZGRmsXLmSyZMnk5KSQmpqKosWLerK8IUQQgSAxOblTurtLuptTo2jEUJ9ATt5Yvr06UyfPv2cx/z+978/676cnBxycnIuOo5gnh4dKoJtrLSOV5ZBULet5Lk61BqrCD1ERxhosLuoOF1Pn3j/rHSg9bmVPFe3baDleUgud9IVCgsLKSwsxOVysX//flnuRAghQsATOw2cbNLx0FAn/c+9UoQQASnkljvpKnPmzGHOnDlYLBbMZjMgy50EgmAbK63jlWUQ1G0rea4ONcfq9fLtnDxcQ/+hI5mU0csvfWp9biXP1W0baHkeFMudBItgnh4daoJtrLSOV5ZBULet5Lk61Biry2KjgBpONTr93rfW51byXN22gZLnvvQbsJMnhBBCCH9o+b3YKvm9WHEJkMJOCCFESPMWdhYp7ETok8JOCCFESGtZ8kQWKRaXAvmO3XkE8/ToUBFsY6V1vLIMgrptJc/VoeZYxUd7/tRV1TYGzL/bQH99yfPAynNZ7uQCyXInQggReo7Xw4o9YcSEKTw52qV1OEL4zJflTqSw60DLcidFRUVkZWUF7fToUBFsY6V1vLIMgrptJc/VoeZY1TU5Gbl8IwDfLPwFsVHa/7sN9NeXPA+sPLdYLCQkJMg6dv4QzNOjQ02wjZXW8coyCOq2lTxXhxpj1SM8nCRzJBW1TZSdtnFVrP8+idH63Eqeq9s2UPI8JJY7sVqtXH/99cTHx9O9e3fGjx/P999/793/3HPPMWLECMLCwnjqqafatN20aRN6vb7Nb8xu2bKlq9+CEEKIADEg0fNb4werrBpHIoS6ArawMxqNrF69mhMnTlBdXc3tt9/e5rdjk5OTWbZsGb/85S87bD9o0CCsVqv3Nnbs2K4KXQghRIDp39NT2B2oqtM4EiHUFbAfxYaHh3PFFVcA4HK50Ov1HDp0yLs/OzsbgHfffVeL8IQQQgSRgZd5Crsf5IqdCHEBW9i1GD58OKWlpbjdblasWNHpdmVlZSQmJmI2m7nnnntYtGgRBoOhw2NtNhs225n1jVr/JlswT48OFcE2VlrHK8sgqNtW8lwdao9VWo9IAA78VOeX19D63Eqeq9s20PI85JY7aWxs5I033qB3795MmjSpzb6cnByGDBnC7373O++2yspKampqGDRoEN9//z1Tpkzhvvvu45FHHumw/4KCApYsWdJuuyx3IoQQoaHBCQu/NqCg44mrnMRGaB2REJ0XFMudTJw4kc2bN3e4Ly8vj7y8vDbbFEUhKSmJ0tJSunfv7t3eUWH3r9asWcNzzz131tfr6IpdamqqLHcSIIJtrLSOV5ZBULet5Lk6umKssp7byt6KOp6ZMpxbM3pdVF9an1vJc3XbBlqeB8VyJ8XFxT4drygKVquVioqKNoVdZ+j1554jYjQaMRqNHe4L5unRoSbYxkrreGUZBHXbSp6rQ82xuqZ/Ansr6vj6cA3ZI1P90qfW51byXN22gZLnIbHcye7du9m8eTN2u536+noWLlxIXFwcAwcOBMDpdNLU1ITL5WrzGDzLnRw9ehSAAwcOsGzZMm677TbN3osQQgjtXd0vHoCtB6s1jkQI9QRsYedwOHj44YeJj4/n8ssvZ9euXXz44YfeqnXZsmVERUXxxhtvkJ+fT1RUFK+//joA33zzDVdffTUxMTFMnDiR7OxscnNztXw7QgghNDambw8iDHp+PFnPd+W1WocjhCoCdlbsqFGj2Llz51n3FxQUUFBQ0OG++fPnM3/+fL/EEcyzaEJFsI2V1vHKbDl120qeq6Mrxio6DMYP6clH3/3E2q+PkDdpyAX3pfW5lTxXt22g5XnIzYrtKoWFhRQWFuJyudi/f7/MihVCiBDz3Wkd//O9gegwhcX/x0VkwF7eEOKMoJgVG8gsFgtms1lmxQaIYBsrreOV2XLqtpU8V0dXjZXT5ebWP33JjycbePAX/XjoxgEX1I/W51byXN22gZbnQTErNlgE8yyaUBNsY6V1vDJbTt22kufqUP/fLfxH5hBmv7mD/9lSxuQRKQy6rNtF9Cd53pX9Xap5HhKzYoUQQgg13DysFz8f1BOb080Db+7gdL1d65CE8Bsp7IQQQlxSdDodf7hzOJfFGvmhysqvX9zGsdMNWoclhF9IYSeEEOKSk9gtkjfu+xnxMRHsrbAw+f/9g7/sPIZ87VwEO/mO3XkE8/ToUBFsY6V1vLIMgrptJc/VocVYpfWI5L3/+zPmrtlNyXELj7y9mxe3/EjONX24ZVgvjGFnv/ah9bmVPFe3baDluSx3coFkuRMhhLj0ON3wWYWO4mN67G4dAJEGhfQ4hYweCv1jFcwRGgcpLmmy3MlFkuVOAkuwjZXW8coyCOq2lTxXRyCMVXW9nXf+eYw3tx+l0mJrsy/ZHMmIVDMDEk0M6BnD5XFGfti1lUmZkudd0d+lnuey3IkfBfP06FATbGOldbyyDIK6bSXP1aHlWPWKC+fBCYOZc+Mgdh6t4ZO9P7FpXxX7f6qjvLaJ8tom4KdWLcJ46rsvSDJH0cscSZI5kstiI+kRE0H36HDioiPoHn3mccQ5Ptq9UJLn6rYNlDz3pd+ALeysVis333wzpaWluN1uRo4cSWFhIUOGnPkJmFdeeYUnn3yS8vJyLr/8ct5//30GDRoEwKuvvkpeXh4Wi4V///d/Z9WqVUREyLV0IYQQ56bX67iqT3eu6tOd390yBKvNyZ6jNew5XsvBKisHT1j5ocqKpcnJSaudk1Y7JcfP/9uzMREGYoxhmIxhxBjDiDEaMBnDiI4Ia97u2R8dYcAYZsAYpicy3HNvDNcTGWbAGK7HGGZAj5vqJqiqs2GKBGO4nnCDHoNe1wUjJAJZwBZ2RqOR1atXM3jwYACef/55pk+fzrZt2wD429/+xsqVK1m3bh3p6en8+OOPdO/eHYCSkhJyc3MpLi5m4MCBZGdns2zZMpYuXarZ+xFCCBGcTMYwrh2QwLUDErzb7HY77/z1I4aNuZ6T9U4qapuorG2i0tLE6Xo7pxvs1DQ4PPeNDhQF6u0u6u0uqups53g1X4SxdOfnbbbodBCu1xNm0BFu0BNu0BHW/DzC4LkP03u2hxvOHBembznes02vg/Jjer58fy/hYXoMOh16vQ6DTofB0Hyv16FvvvfevMeBwaBvPg4Ut5tvT+hw7akgIjzsnP3pdZ7iWq/zLE2j1+lwu5wctcJ35RYiwsPR6/EeC81tmo/VtW6PDpfLicXu+ajdGK6g1+lAR/s2ujOvGczfUgvYwi48PJwrrrgCAJfLhV6v59ChQ979TzzxBH/84x8ZOnQoAP379/fuKyoq4q677mLUqFEA5OfnM3PmTCnshBBC+IVOp8MUDulJsef9mMztVrA0OTjd4KDe5vTc7E6sNteZ5zZX8zYnTXYXNqcbm9NFk8Nzb3O6sTncNDld2Jq31TfZcSg6WtcgigJ2lxu7C8B1ke9Sz7YTxy6yj9YMvPFDyUW0D+MPJV9dcNv8bzb53OaRr4q9xd+5ikG73cC48U7iAuArFwFb2LUYPny49+PYFStWAJ5Cb+fOnZSUlDBjxgzCw8OZMWMG+fn56HQ69u7dS2ZmprePK6+8kkOHDtHY2EhUVFS717DZbNhsZ/4PymKxeB8H8/ToUBFsY6V1vLIMgrptJc/VEWxj5Wu8MeE6YswRgH++EtTyhf0JEyagM4TR5HDjdLtxuhScbgW7q/mxy932uduNw6XgcJ051uHybGvZ53S5sTmc7Nt/gH79B6Cgw6UouN003yu4FAWX23NzKwquVvuc7jPHtNw7XW6qTpwkrnsPFHTNbVr3g/dYRQFFUXAr4FYUFMWzvbGxCaMxEgXPdnfzsWfuW9q1bkvzPjcKvn9M3dIPnO8Kng6H04HDoU5ZFXLLnTQ2NvLGG2/Qu3dvJk2aRHl5uffxm2++icVi4ZZbbuHRRx9lxowZjB8/nhkzZjBt2jTAMyARERFUVVXRs2fPdv0XFBSwZMmSdttluRMhhBAiNCiKpzxTmh9DczHYapvSwXEt9+5/6cf9L8dfFgVqfcXRl+VONLtiN3HiRDZv3tzhvry8PPLy8rzPo6KimDlzJklJSZSWlnqvuj322GPExcURFxfHnDlz+PDDD5kxYwYmk6nNVbeWxyaTqcPXW7BgAbm5uW2OT01NBQjq6dGhItjGSut4ZRkEddtKnqsj2MZK63glz31vO3Fi8OZ565rmfDQr7IqLi306XlEUrFYrFRUVpKenk5yc3G5/i/T0dEpKznyOv3v3bvr27dvhx7DgmahhNBo73BfM06NDTbCNldbxyjII6raVPFdHsI2V1vFKnqvbNlDy3Jd+A/a3Ynfv3s3mzZux2+3U19ezcOFC4uLiGDhwIAA5OTmsWLGCuro6ysvLeeGFF7j11lsBmDp1KmvXrmXHjh3U1tayfPly78eyQgghhBChKmALO4fDwcMPP0x8fDyXX345u3bt4sMPP/RWrYsXLyYpKYmUlBRGjx7N7bffzvTp0wHIyMhg5cqVTJ48mZSUFFJTU1m0aJGWb0cIIYQQQnUBOyt21KhR7Ny586z7IyIiWL16NatXr+5wf05ODjk5ORcdh8yW016wjZXW8cqsWHXbSp6rI9jGSut4Jc/VbRtoeR5ys2K7SmFhIYWFhTidTg4cOMCLL74os2KFEEIIoamGhgZmzpxJTU0NZrP5nMdKYdeBY8eOeWfFCiGEEEIEgqNHj5KSknLOY6Sw64Db7aa8vJwbb7yRf/7znz61HT16NF9//fV5j2tZUuXo0aPnXZNGdH5cA4XW8ar9+v7u/2L7u5j2F9JW8lwdWueNr7SOV/Jc3baBlOeKolBXV0dycjJ6/bmnRwTsd+y0pNfrSUlJISwszOeTZDAYfGoTGxsr/8HvBF/HVWtax6v26/u7/4vt72LaX0hbyXN1aJ03vtI6XslzddsGWp6f7yPYFgE7KzYQzJkzp0vaiPMLtnHVOl61X9/f/V9sfxfTXvI8cATbuGodr+S5um21Pr8XSj6K1YjFYsFsNnfq50GEEMFJ8lyI0BdoeS5X7DRiNBpZvHjxWX/xQggR/CTPhQh9gZbncsVOCCGEECJEyBU7IYQQQogQIYWdEEIIIUSIkMJOCCGEECJESGEnhBBCCBEipLALYEePHmXkyJFERkbidDq1DkcI4Se5ubmMHTuWhx56SOtQhBAq0PLvtxR2Aaxnz55s3LiRq6++WutQhBB+smPHDqxWK1u2bMHhcATVT2gJITpHy7/fUtgFsMjISOLi4rQOQwjhR1u3bmXChAkATJgwga+++krjiIQQ/qbl328p7Pxo8eLFpKeno9frWbNmTZt9J06c4NZbbyU6OprBgwfz6aefahSlEMJfLiTna2pqvKvTm81mTp8+3eVxCyE6L9j+todpHUAoGThwIP/93/9Nfn5+u31z5swhOTmZkydPUlxczJ133snBgwex2WzcfffdbY41mUysX7++q8IWQlygC8n5uLg4LBYL4PkpIrkqL0Rgu5A87969uwaRNlOE340bN0556623vM/r6uqUiIgIpby83Ltt7Nixyp///OdO9+dwOPwepxDCP3zJ+W+++Ua5//77FUVRlNmzZyvbtm3r8niFEL67kL/tWvz9lo9iu8CBAwcwm80kJSV5t1155ZV8991352zX1NTEhAkT2L17N5mZmWzZskXtUIUQfnCunB85ciRRUVGMHTsWvV7PmDFjNIxUCHGhzpXnWv79lo9iu4DVavV+p6ZFbGwsNTU152wXGRnJ3//+dxUjE0Ko4Xw5/8wzz3R9UEIIvzpXnmv591uu2HUBk8nk/U5NC4vFgslk0igiIYSaJOeFCH2BmudS2HWBgQMHUltbS2VlpXfb7t27GTp0qIZRCSHUIjkvROgL1DyXws6PHA4HTU1NuN3uNo9NJhO//OUvWbx4MY2Njfz1r3/l22+/ZfLkyVqHLIS4CJLzQoS+oMvzLp2qEeKmT5+uAG1un332maIoilJVVaXccsstSlRUlDJw4EDlk08+0TZYIcRFk5wXIvQFW57rFEVRtCkphRBCCCGEP8lHsUIIIYQQIUIKOyGEEEKIECGFnRBCCCFEiJDCTgghhBAiREhhJ4QQQggRIqSwE0IIIYQIEVLYCSGEEEKECCnshBBCCCFChBR2QggRYAoKCggPD6dXr15+6/OGG25gzZo1PrWZN28eUVFRDBkyxG9xCCHUJYWdECIgpaWlER0djclkwmQykZaWpnVIXeq+++5r8+Piahg2bBhlZWVn3f/MM8/w0UcfqRqDEMK/pLATQgSsjRs3YrVasVqtHRYgDoej64MKAP5438eOHcPpdF5yBbMQoU4KOyFE0Ni0aRNDhgxh0aJFJCQk8OSTT9LY2MjcuXNJTk4mJSWFp59+2nt8fX09U6dOJS4ujpEjR7Jw4UJuvvnmNn21ptPpvFfJTp06xdSpU0lMTKRfv378+c9/9h53ww03sHTpUkaNGkVsbCy/+tWvsNvt3v1vv/02w4YNo1u3bmRkZLBv3z6WL1/OjBkz2rzeddddx3vvvdep956WlsaKFSsYPHgw6enpADzwwAMkJycTFxfHxIkTOXLkiPf4r7/+muHDhxMbG8tvf/tb3G53m/4+/vhjMjMzAXj55Zfp06cPJpOJ/v3789lnn3UqJiFE4JHCTggRVH744Qeio6OpqKjgscce49FHH6W2tpb9+/ezfft2XnvtNf72t78BsGTJEqqrqzly5AhFRUW8/vrrnX6de+65h9TUVI4ePcqHH37IggUL2L17t3f/O++8w3vvvceRI0fYs2cPb7/9NgBffPEFc+fOZdWqVdTW1vLOO+8QGxvLr3/9a9atW4fNZgPg8OHD7N27l0mTJnU6pnXr1rFlyxZKSkoAuP766yktLaWyspKUlBQeeughAOx2O7fffjsPPvgg1dXVDBs2jC+//LJNXxs2bCAzM5P6+nrmzZvH3//+d6xWKxs3bpSreEIEMSnshBAB66abbiIuLo64uDgWLFgAQHR0NL/73e8IDw/HaDTyyiuvsHLlSkwmE8nJycyePZt3330X8BRf+fn5xMbGMmTIEKZPn96p162srGTLli08+eSTGI1GhgwZwtSpU9tcXZs1axaXX345cXFx3Hrrrd6i79VXX2X27Nlcd9116PV6hgwZQlJSEmlpaQwbNowPP/wQgDVr1pCdnU1kZGSnx+ORRx4hMTHR22bq1KmYzWYiIyN57LHH+Mc//gHA1q1bMRqNzJo1i/DwcObOnUtSUpK3H5fLxT/+8Q9uuOEGwHOlsqSkBJvNRp8+fejbt2+nYxJCBBYp7IQQAeuTTz6hpqaGmpoa/vM//xOApKQkDAYDACdOnKCxsZFBgwZ5C8CFCxdSVVUFQEVFBampqd7+Wj8+lyNHjlBfX098fLy331WrVvHTTz95j0lMTPQ+jo6Oxmq1Ap7vrvXr16/DfqdNm+admVpUVMTUqVM7OxQApKSktHm+fPlyBgwYQGxsLGPGjKG6uhpo/751Ol2bttu2bWPYsGFER0cTExPDW2+9xZ/+9CcSExO54447KC8v9ykuIUTgkMJOCBFUdDqd93FCQgKRkZEcPnzYWwBaLBbvTM6kpCSOHj3qPb7145iYGBoaGrzPW89A7d27N3Fxcd4+a2pqqKur44UXXjhvfKmpqRw6dKjDfXfeeSfFxcVs376dqqoqbrzxxs6/cdq+988//5xVq1bx0UcfUVtby/bt2737kpKSOHbsWJu2rZ+3fAzbYtKkSWzcuJHjx48TGRlJfn6+T3EJIQKHFHZCiKCl1+uZPn06jz76KDU1NbjdbkpLS71Fzh133MHy5cupq6tj3759vPbaa962gwYNorq6ms8//xybzcYTTzzh3de7d29Gjx7N448/TkNDA06nkx07drB3797zxpSTk8Pzzz/P1q1bURSFffv2UVFRAUCPHj0YN24cOTk5TJkyxXvl8ULU1dURFhZGfHw89fX1LFu2zLvvmmuuobGxkZdeegmHw0FhYaE3Bmg7ceKnn35i/fr1NDY2YjQaiY6Ovqi4hBDaksJOCBHU/uu//ouYmBgyMjLo0aMH9957L6dPnwZg8eLFmM1mUlJS+NWvfsU999zjbWc2m3n22WeZMmUKffv2ZcyYMW36ffPNNzl8+DD9+vUjMTGRefPm0djYeN54rr32Wp555hl+85vfEBsby5133onFYvHunzZtGqWlpT5/DPuvbr75Zq655hr69OlDRkYG1157rXdfREQE//u//8sf//hH4uPj2bNnj3d/dXU1FRUVZGRkAOB2u3n66ae57LLLSExM5Pjx4yxduvSiYhNCaEenKIqidRBCCNEVXn31VdasWcOGDRs0i2Hr1q1MmzaNgwcPnvWYZcuW8dRTTxEXF9fuI9WL9dZbb/HJJ5/w8ssvn/fY3NxcXnzxRfr27dtmRrAQInBJYSeEuGRoXdg5HA7uvfdehg0bxqJFizSJ4eOPPyY+Pp5Ro0Zp8vpCCHWFaR2AEEJcCqqrq0lJSWH48OGsWrVKszhaT5oQQoQeuWInhBBCCBEiZPKEEEIIIUSIkMJOCCGEECJESGEnhBBCCBEipLATQgghhAgRUtgJIYQQQoQIKeyEEEIIIUKEFHZCCCGEECFCCjshhBBCiBAhhZ0QQgghRIj4/wI2W27HeLAdAAAAAElFTkSuQmCC", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "out = ct.bode_plot(sys, overlay_outputs=True)" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "id": "I_LTjP2J6gqx" - }, - "source": [ - "Note the \"dip\" in the frequency response for y[1] at frequency 2 rad/sec, which corresponds to a \"zero\" of the transfer function.\n", - "\n", - "This dip becomes even more pronounced in the case of low damping coefficient $c$:" - ] - }, - { - "cell_type": "code", - "execution_count": 21, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "out = ct.frequency_response(\n", - " coupled.linearize([0, 0, 0, 0], [0], params={'c': 0.01})\n", - ").plot(overlay_outputs=True)" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "id": "c7eWm8LCGh01" - }, - "source": [ - "## Additional resources\n", - "* [Code for FBS2e figures](https://fbswiki.org/wiki/index.php/Category:Figures): Python code used to generate figures in FBS2e\n", - "* [Python-control documentation for plotting time responses](https://python-control.readthedocs.io/en/0.10.0/plotting.html#time-response-data)\n", - "* [Python-control documentation for plotting frequency responses](https://python-control.readthedocs.io/en/0.10.0/plotting.html#frequency-response-data)\n", - "* [Python-control examples](https://python-control.readthedocs.io/en/0.10.0/examples.html): lots of Python and Jupyter examples of control system analysis and design\n" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Python 3 (ipykernel)", - "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.12.2" - } - }, - "nbformat": 4, - "nbformat_minor": 4 -} diff --git a/examples/cds112-L1_python-control.ipynb b/examples/cds112-L1_python-control.ipynb new file mode 100644 index 000000000..3f1a03487 --- /dev/null +++ b/examples/cds112-L1_python-control.ipynb @@ -0,0 +1,444 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "numerous-rochester", + "metadata": {}, + "source": [ + "# Introduction to the Python Control Systems Library (python-control)\n", + "\n", + "## Input/Output Systems" + ] + }, + { + "cell_type": "markdown", + "id": "69bdd3af", + "metadata": {}, + "source": [ + "Richard M. Murray, 13 Nov 2021 (updated 7 Jul 2024)\n", + "\n", + "This notebook contains an introduction to the basic operations in the Python Control Systems Library (python-control), a Python package for control system design. This notebook is focused on state space control design for a kinematic car, including trajectory generation and gain-scheduled feedback control. This illustrates the use of the input/output (I/O) system class, which can be used to construct models for nonlinear control systems." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "macro-vietnamese", + "metadata": {}, + "outputs": [], + "source": [ + "# Import the packages needed for the examples included in this notebook\n", + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "import control as ct\n", + "print(\"python-control version:\", ct.__version__)" + ] + }, + { + "cell_type": "markdown", + "id": "distinct-communist", + "metadata": {}, + "source": [ + "### Installation hints\n", + "\n", + "If you get an error importing the `control` package, it may be that it is not in your current Python path. You can fix this by setting the PYTHONPATH environment variable to include the directory where the python-control package is located. If you are invoking Jupyter from the command line, try using a command of the form\n", + "\n", + " PYTHONPATH=/path/to/control jupyter notebook\n", + " \n", + "If you are using [Google Colab](https://colab.research.google.com), use the following command at the top of the notebook to install the `control` package:\n", + "\n", + " !pip install control\n", + " \n", + "For the examples below, you will need version 0.10.0 or higher of the python-control toolbox. You can find the version number using the command\n", + "\n", + " print(ct.__version__)" + ] + }, + { + "cell_type": "markdown", + "id": "5dad04d8", + "metadata": {}, + "source": [ + "### More information on Python, NumPy, python-control\n", + "\n", + "* [Python tutorial](https://docs.python.org/3/tutorial/)\n", + "* [NumPy tutorial](https://numpy.org/doc/stable/user/quickstart.html)\n", + "* [NumPy for MATLAB users](https://numpy.org/doc/stable/user/numpy-for-matlab-users.html), \n", + "* [Python Control Systems Library (python-control) documentation](https://python-control.readthedocs.io/en/latest/)" + ] + }, + { + "cell_type": "markdown", + "id": "novel-geology", + "metadata": {}, + "source": [ + "## System Definiton\n", + "\n", + "We now define the dynamics of the system that we are going to use for the control design. The dynamics of the system will be of the form\n", + "\n", + "$$\n", + "\\dot x = f(x, u), \\qquad y = h(x, u)\n", + "$$\n", + "\n", + "where $x$ is the state vector for the system, $u$ represents the vector of inputs, and $y$ represents the vector of outputs.\n", + "\n", + "The python-control package allows definition of input/output sytems using the `InputOutputSystem` class and its various subclasess, including the `NonlinearIOSystem` class that we use here. A `NonlinearIOSystem` object is created by defining the update law ($f(x, u)$) and the output map ($h(x, u)$), and then calling the factory function `ct.nlsys`.\n", + "\n", + "For the example in this notebook, we will be controlling the steering of a vehicle, using a \"bicycle\" model for the dynamics of the vehicle. A more complete description of the dynamics of this system are available in [Example 3.11](https://fbswiki.org/wiki/index.php/System_Modeling) of [_Feedback Systems_](https://fbswiki.org/wiki/index.php/FBS) by Astrom and Murray (2020)." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "sufficient-douglas", + "metadata": {}, + "outputs": [], + "source": [ + "# Define the update rule for the system, f(x, u)\n", + "# States: x, y, theta (postion and angle of the center of mass)\n", + "# Inputs: v (forward velocity), delta (steering angle)\n", + "def vehicle_update(t, x, u, params):\n", + " # Get the parameters for the model\n", + " a = params.get('refoffset', 1.5) # offset to vehicle reference point\n", + " b = params.get('wheelbase', 3.) # vehicle wheelbase\n", + " maxsteer = params.get('maxsteer', 0.5) # max steering angle (rad)\n", + "\n", + " # Saturate the steering input\n", + " delta = np.clip(u[1], -maxsteer, maxsteer)\n", + " alpha = np.arctan2(a * np.tan(delta), b)\n", + "\n", + " # Return the derivative of the state\n", + " return np.array([\n", + " u[0] * np.cos(x[2] + alpha), # xdot = cos(theta + alpha) v\n", + " u[0] * np.sin(x[2] + alpha), # ydot = sin(theta + alpha) v\n", + " (u[0] / a) * np.sin(alpha) # thdot = v sin(alpha) / a\n", + " ])\n", + "\n", + "# Define the readout map for the system, h(x, u)\n", + "# Outputs: x, y (planar position of the center of mass)\n", + "def vehicle_output(t, x, u, params):\n", + " return x\n", + "\n", + "# Default vehicle parameters (including nominal velocity)\n", + "vehicle_params={'refoffset': 1.5, 'wheelbase': 3, 'velocity': 15, \n", + " 'maxsteer': 0.5}\n", + "\n", + "# Define the vehicle steering dynamics as an input/output system\n", + "vehicle = ct.nlsys(\n", + " vehicle_update, vehicle_output, states=3, name='vehicle',\n", + " inputs=['v', 'delta'], outputs=['x', 'y', 'theta'], params=vehicle_params)" + ] + }, + { + "cell_type": "markdown", + "id": "intellectual-democrat", + "metadata": {}, + "source": [ + "## Open loop simulation\n", + "\n", + "After these operations, the `vehicle` object references the nonlinear model for the system. This system can be simulated to compute a trajectory for the system. Here we command a velocity of 10 m/s and turn the wheel back and forth at one Hertz." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "likely-hindu", + "metadata": {}, + "outputs": [], + "source": [ + "# Define the time interval that we want to use for the simualation\n", + "timepts = np.linspace(0, 10, 1000)\n", + "\n", + "# Define the inputs\n", + "U = [\n", + " 10 * np.ones_like(timepts), # velocity\n", + " 0.1 * np.sin(timepts * 2*np.pi) # steering angle\n", + "]\n", + "\n", + "# Simulate the system dynamics, starting from the origin\n", + "response = ct.input_output_response(vehicle, timepts, U, 0)\n", + "time, outputs, inputs = response.time, response.outputs, response.inputs" + ] + }, + { + "cell_type": "markdown", + "id": "dutch-charm", + "metadata": {}, + "source": [ + "We can plot the results using standard `matplotlib` commands:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "piano-algeria", + "metadata": {}, + "outputs": [], + "source": [ + "# Create a figure to plot the results\n", + "fig, ax = plt.subplots(2, 1)\n", + "\n", + "# Plot the results in the xy plane\n", + "ax[0].plot(outputs[0], outputs[1])\n", + "ax[0].set_xlabel(\"$x$ [m]\")\n", + "ax[0].set_ylabel(\"$y$ [m]\")\n", + "\n", + "# Plot the inputs\n", + "ax[1].plot(timepts, U[0])\n", + "ax[1].set_ylim(0, 12)\n", + "ax[1].set_xlabel(\"Time $t$ [s]\")\n", + "ax[1].set_ylabel(\"Velocity $v$ [m/s]\")\n", + "ax[1].yaxis.label.set_color('blue')\n", + "\n", + "rightax = ax[1].twinx() # Create an axis in the right\n", + "rightax.plot(timepts, U[1], color='red')\n", + "rightax.set_ylim(None, 0.5)\n", + "rightax.set_ylabel(r\"Steering angle $\\phi$ [rad]\")\n", + "rightax.yaxis.label.set_color('red')\n", + "\n", + "fig.tight_layout()" + ] + }, + { + "cell_type": "markdown", + "id": "alone-worry", + "metadata": {}, + "source": [ + "Notice that there is a small drift in the $y$ position despite the fact that the steering wheel is moved back and forth symmetrically around zero. Exercise: explain what might be happening." + ] + }, + { + "cell_type": "markdown", + "id": "portable-rubber", + "metadata": {}, + "source": [ + "## Linearize the system around a trajectory\n", + "\n", + "We choose a straight path along the $x$ axis at a speed of 10 m/s as our desired trajectory and then linearize the dynamics around the initial point in that trajectory." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "surprising-algorithm", + "metadata": {}, + "outputs": [], + "source": [ + "# Create the desired trajectory \n", + "Ud = np.array([10 * np.ones_like(timepts), np.zeros_like(timepts)])\n", + "Xd = np.array([10 * timepts, 0 * timepts, np.zeros_like(timepts)])\n", + "\n", + "# Now linizearize the system around this trajectory\n", + "linsys = vehicle.linearize(Xd[:, 0], Ud[:, 0])" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "protecting-committee", + "metadata": {}, + "outputs": [], + "source": [ + "# Check on the eigenvalues of the open loop system\n", + "np.linalg.eigvals(linsys.A)" + ] + }, + { + "cell_type": "markdown", + "id": "trying-stereo", + "metadata": {}, + "source": [ + "We see that all eigenvalues are zero, corresponding to a single integrator in the $x$ (longitudinal) direction and a double integrator in the $y$ (lateral) direction." + ] + }, + { + "cell_type": "markdown", + "id": "pressed-delta", + "metadata": {}, + "source": [ + "## Compute a state space (LQR) control law\n", + "\n", + "We can now compute a feedback controller around the trajectory. We choose a simple LQR controller here, but any method can be used." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "auburn-caribbean", + "metadata": {}, + "outputs": [], + "source": [ + "# Compute LQR controller\n", + "K, S, E = ct.lqr(linsys, np.diag([1, 1, 1]), np.diag([1, 1]))" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "independent-lafayette", + "metadata": {}, + "outputs": [], + "source": [ + "# Check on the eigenvalues of the closed loop system\n", + "np.linalg.eigvals(linsys.A - linsys.B @ K)" + ] + }, + { + "cell_type": "markdown", + "id": "handmade-moral", + "metadata": {}, + "source": [ + "The closed loop eigenvalues have negative real part, so the closed loop (linear) system will be stable about the operating trajectory." + ] + }, + { + "cell_type": "markdown", + "id": "handy-virgin", + "metadata": {}, + "source": [ + "## Create a controller with feedforward and feedback\n", + "\n", + "We now create an I/O system representing the control law. The controller takes as an input the desired state space trajectory $x_\\text{d}$ and the nominal input $u_\\text{d}$. It outputs the control law\n", + "\n", + "$$\n", + "u = u_\\text{d} - K(x - x_\\text{d}).\n", + "$$" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "negative-scope", + "metadata": {}, + "outputs": [], + "source": [ + "# Define the output rule for the controller\n", + "# States: none (=> no update rule required)\n", + "# Inputs: z = [xd, ud, x]\n", + "# Outputs: v (forward velocity), delta (steering angle)\n", + "def control_output(t, x, z, params):\n", + " # Get the parameters for the model\n", + " K = params.get('K', np.zeros((2, 3))) # nominal gain\n", + " \n", + " # Split up the input to the controller into the desired state and nominal input\n", + " xd_vec = z[0:3] # desired state ('xd', 'yd', 'thetad')\n", + " ud_vec = z[3:5] # nominal input ('vd', 'deltad')\n", + " x_vec = z[5:8] # current state ('x', 'y', 'theta')\n", + " \n", + " # Compute the control law\n", + " return ud_vec - K @ (x_vec - xd_vec)\n", + "\n", + "# Define the controller system\n", + "control = ct.nlsys(\n", + " None, control_output, name='control',\n", + " inputs=['xd', 'yd', 'thetad', 'vd', 'deltad', 'x', 'y', 'theta'], \n", + " outputs=['v', 'delta'], params={'K': K})" + ] + }, + { + "cell_type": "markdown", + "id": "affected-motor", + "metadata": {}, + "source": [ + "Because we have named the signals in both the vehicle model and the controller in a compatible way, we can use the autoconnect feature of the `interconnect()` function to create the closed loop system." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "stock-regression", + "metadata": {}, + "outputs": [], + "source": [ + "# Build the closed loop system\n", + "vehicle_closed = ct.interconnect(\n", + " (vehicle, control),\n", + " inputs=['xd', 'yd', 'thetad', 'vd', 'deltad'],\n", + " outputs=['x', 'y', 'theta']\n", + ")" + ] + }, + { + "cell_type": "markdown", + "id": "hispanic-monroe", + "metadata": {}, + "source": [ + "## Closed loop simulation\n", + "\n", + "We now command the system to follow in trajectory and use the linear controller to correct for any errors. \n", + "\n", + "The desired trajectory is a given by a longitudinal position that tracks a velocity of 10 m/s for the first 5 seconds and then increases to 12 m/s and a lateral position that varies sinusoidally by $\\pm 0.5$ m around the centerline. The nominal inputs are not modified, so that feedback is required to obtained proper trajectory tracking." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "american-return", + "metadata": {}, + "outputs": [], + "source": [ + "Xd = np.array([\n", + " 10 * timepts + 2 * (timepts-5) * (timepts > 5), \n", + " 0.5 * np.sin(timepts * 2*np.pi), \n", + " np.zeros_like(timepts)\n", + "])\n", + "\n", + "Ud = np.array([10 * np.ones_like(timepts), np.zeros_like(timepts)])\n", + "\n", + "# Simulate the system dynamics, starting from the origin\n", + "resp = ct.input_output_response(\n", + " vehicle_closed, timepts, np.vstack((Xd, Ud)), 0)\n", + "time, outputs = resp.time, resp.outputs" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "indirect-longitude", + "metadata": {}, + "outputs": [], + "source": [ + "# Plot the results in the xy plane\n", + "plt.plot(Xd[0], Xd[1], 'b--') # desired trajectory\n", + "plt.plot(outputs[0], outputs[1]) # actual trajectory\n", + "plt.xlabel(\"$x$ [m]\")\n", + "plt.ylabel(\"$y$ [m]\")\n", + "plt.ylim(-1, 2)\n", + "\n", + "# Add a legend\n", + "plt.legend(['desired', 'actual'], loc='upper left')\n", + "\n", + "# Compute and plot the velocity\n", + "rightax = plt.twinx() # Create an axis in the right\n", + "rightax.plot(Xd[0, :-1], np.diff(Xd[0]) / np.diff(timepts), 'r--')\n", + "rightax.plot(outputs[0, :-1], np.diff(outputs[0]) / np.diff(timepts), 'r-')\n", + "rightax.set_ylim(0, 13)\n", + "rightax.set_ylabel(\"$x$ velocity [m/s]\")\n", + "rightax.yaxis.label.set_color('red')" + ] + }, + { + "cell_type": "markdown", + "id": "weighted-directory", + "metadata": {}, + "source": [ + "We see that there is a small error in each axis. By adjusting the weights in the LQR controller we can adjust the steady state error (try it!)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "f31dd981-161a-49f0-a637-84128f7ec5ff", + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/examples/cds112-L2a_flatness.ipynb b/examples/cds112-L2a_flatness.ipynb new file mode 100644 index 000000000..2b7cfb3a4 --- /dev/null +++ b/examples/cds112-L2a_flatness.ipynb @@ -0,0 +1,490 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "meaning-hypothetical", + "metadata": {}, + "source": [ + "## Differential Flatness\n", + "\n", + "##### Richard M. Murray, 13 Nov 2021 (updated 7 Jul 2024)\n", + "\n", + "This notebook contains an example of using differential flatness as a mechanism for trajectory generation for a nonlinear control system. A differentially flat system is defined by creating an object using the `FlatSystem` class, which has member functions for mapping the system state and input into and out of flat coordinates. The `point_to_point()` function can be used to create a trajectory between two endpoints, written in terms of a set of basis functions defined using the `BasisFamily` class. The resulting trajectory is return as a `SystemTrajectory` object and can be evaluated using the `eval()` member function. " + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "historic-barbados", + "metadata": {}, + "outputs": [], + "source": [ + "# Import the packages needed for the examples included in this notebook\n", + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "import control as ct\n", + "import control.flatsys as fs\n", + "import control.optimal as opt\n", + "import time" + ] + }, + { + "cell_type": "markdown", + "id": "309d3272", + "metadata": {}, + "source": [ + "## Example: bicycle model\n", + "\n", + "To illustrate the methods of generating trajectories using differential flatness, we make use of a simple model for a vehicle navigating in the plane, known as the \"bicycle model\". The kinematics of this vehicle can be written in terms of the contact point $(x, y)$ and the angle $\\theta$ of the vehicle with respect to the horizontal axis:\n", + "\n", + "
\n", + "\n", + "\n", + "\n", + "
\n", + "\n", + " \n", + " \n", + "\n", + "
\n", + "$$\n", + "\\begin{aligned}\n", + " \\dot x &= \\cos\\theta\\, v \\\\\n", + " \\dot y &= \\sin\\theta\\, v \\\\\n", + " \\dot\\theta &= \\frac{v}{l} \\tan \\delta\n", + "\\end{aligned}\n", + "$$\n", + "
\n", + "\n", + "The input $v$ represents the velocity of the vehicle and the input $\\delta$ represents the turning rate. The parameter $l$ is the wheelbase." + ] + }, + { + "cell_type": "markdown", + "id": "35efac80", + "metadata": {}, + "source": [ + "We will generate trajectories for this system that correspond to a \"lane change\", in which we travel longitudinally at a fixed speed for approximately 40 meters, while moving from the right to the left by a distance of 4 meters.\n", + "\n", + "It will be convenient to define a function that we will use to plot the results in a uniform way. In addition to the subplot, we also change the size of the figure to make the figure wider." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "involved-riding", + "metadata": {}, + "outputs": [], + "source": [ + "# Plot the trajectory in xy coordinates\n", + "def plot_motion(t, x, ud):\n", + " # Set the size of the figure\n", + " # plt.figure(figsize=(10, 6))\n", + "\n", + " # Top plot: xy trajectory\n", + " plt.subplot(2, 1, 1)\n", + " plt.plot(x[0], x[1])\n", + " plt.xlabel('x [m]')\n", + " plt.ylabel('y [m]')\n", + " plt.axis([x0[0], xf[0], x0[1]-1, xf[1]+1])\n", + "\n", + " # Time traces of the state and input\n", + " plt.subplot(2, 4, 5)\n", + " plt.plot(t, x[1])\n", + " plt.ylabel('y [m]')\n", + "\n", + " plt.subplot(2, 4, 6)\n", + " plt.plot(t, x[2])\n", + " plt.ylabel('theta [rad]')\n", + "\n", + " plt.subplot(2, 4, 7)\n", + " plt.plot(t, ud[0])\n", + " plt.xlabel(\"Time t [sec]\")\n", + " plt.ylabel(\"v [m/s]\")\n", + " plt.axis([0, Tf, u0[0] - 1, uf[0] + 1])\n", + "\n", + " plt.subplot(2, 4, 8)\n", + " plt.plot(t, ud[1])\n", + " plt.xlabel(\"Time t [sec]\")\n", + " plt.ylabel(r\"$\\delta$ [rad]\")\n", + " plt.tight_layout()" + ] + }, + { + "cell_type": "markdown", + "id": "3dc0d2bf", + "metadata": {}, + "source": [ + "## Flat system mappings\n", + "\n", + "To define a flat system, we have to define the functions that take the state and compute the flat \"flag\" (flat outputs and their derivatives) and that take the flat flag and return the state and input.\n", + "\n", + "The `forward()` method computes the flat flag given a state and input:\n", + "```\n", + " zflag = sys.forward(x, u)\n", + "```\n", + "The `reverse()` method computes the state and input given the flat flag:\n", + "```\n", + " x, u = sys.reverse(zflag)\n", + "```\n", + "The flag $\\bar z$ is implemented as a list of flat outputs $z_i$ and\n", + "their derivatives up to order $q_i$:\n", + "\n", + "         `zflag[i][j]` = $z_i^{(j)}$\n", + "\n", + "The number of flat outputs must match the number of system inputs.\n", + "\n", + "In addition, a flat system is an input/output system and so we define and update function ($f(x, u)$) and output (use `None` to get the full state)." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "above-venezuela", + "metadata": {}, + "outputs": [], + "source": [ + "# Function to take states, inputs and return the flat flag\n", + "def bicycle_flat_forward(x, u, params={}):\n", + " # Get the parameter values\n", + " b = params.get('wheelbase', 3.)\n", + "\n", + " # Create a list of arrays to store the flat output and its derivatives\n", + " zflag = [np.zeros(3), np.zeros(3)]\n", + "\n", + " # Flat output is the x, y position of the rear wheels\n", + " zflag[0][0] = x[0]\n", + " zflag[1][0] = x[1]\n", + "\n", + " # First derivatives of the flat output\n", + " zflag[0][1] = u[0] * np.cos(x[2]) # dx/dt\n", + " zflag[1][1] = u[0] * np.sin(x[2]) # dy/dt\n", + "\n", + " # First derivative of the angle\n", + " thdot = (u[0]/b) * np.tan(u[1])\n", + "\n", + " # Second derivatives of the flat output (setting vdot = 0)\n", + " zflag[0][2] = -u[0] * thdot * np.sin(x[2])\n", + " zflag[1][2] = u[0] * thdot * np.cos(x[2])\n", + "\n", + " return zflag\n", + "\n", + "# Function to take the flat flag and return states, inputs\n", + "def bicycle_flat_reverse(zflag, params={}):\n", + " # Get the parameter values\n", + " b = params.get('wheelbase', 3.)\n", + "\n", + " # Create a vector to store the state and inputs\n", + " x = np.zeros(3)\n", + " u = np.zeros(2)\n", + "\n", + " # Given the flat variables, solve for the state\n", + " x[0] = zflag[0][0] # x position\n", + " x[1] = zflag[1][0] # y position\n", + " x[2] = np.arctan2(zflag[1][1], zflag[0][1]) # tan(theta) = ydot/xdot\n", + "\n", + " # And next solve for the inputs\n", + " u[0] = zflag[0][1] * np.cos(x[2]) + zflag[1][1] * np.sin(x[2])\n", + " thdot_v = zflag[1][2] * np.cos(x[2]) - zflag[0][2] * np.sin(x[2])\n", + " u[1] = np.arctan2(thdot_v, u[0]**2 / b)\n", + "\n", + " return x, u\n", + "\n", + "# Function to compute the RHS of the system dynamics\n", + "def bicycle_update(t, x, u, params):\n", + " b = params.get('wheelbase', 3.) # get parameter values\n", + " dx = np.array([\n", + " np.cos(x[2]) * u[0],\n", + " np.sin(x[2]) * u[0],\n", + " (u[0]/b) * np.tan(u[1])\n", + " ])\n", + " return dx\n", + "\n", + "# Return the entire state as output (instead of default flat outputs)\n", + "def bicycle_output(t, x, u, params):\n", + " return x\n", + "\n", + "# Create differentially flat input/output system\n", + "bicycle_flat = fs.FlatSystem(\n", + " bicycle_flat_forward, bicycle_flat_reverse, \n", + " bicycle_update, bicycle_output,\n", + " inputs=('v', 'delta'), outputs=('x', 'y', 'theta'),\n", + " states=('x', 'y', 'theta'), name='bicycle_model')\n", + "\n", + "print(bicycle_flat)" + ] + }, + { + "cell_type": "markdown", + "id": "75cb8cf6", + "metadata": {}, + "source": [ + "## Point to point trajectory generation\n", + "\n", + "In addition to the flat system description, a set of basis functions\n", + "$\\phi_i(t)$ must be chosen. The `BasisFamily` class is used to\n", + "represent the basis functions. A polynomial basis function of the form\n", + "$1$, $t$, $t^2$, $\\ldots$ can be computed using the `PolyFamily` class,\n", + "which is initialized by passing the desired order of the polynomial\n", + "basis set:\n", + "```\n", + "polybasis = control.flatsys.PolyFamily(N)\n", + "```\n" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "feef608a", + "metadata": {}, + "outputs": [], + "source": [ + "print(fs.BasisFamily.__doc__)\n", + "print(fs.PolyFamily.__doc__)\n", + "\n", + "# Define a set of basis functions to use for the trajectories\n", + "poly = fs.PolyFamily(6)\n", + "\n", + "# Plot out the basis functions\n", + "t = np.linspace(0, 1.5)\n", + "for k in range(poly.N):\n", + " plt.plot(t, poly(k, t), label=f'k = {k}')\n", + " \n", + "plt.legend()\n", + "plt.title(\"Polynomial basis functions\")\n", + "plt.xlabel(\"Time $t$\")\n", + "plt.ylabel(r\"$\\psi_i(t)$\");" + ] + }, + { + "cell_type": "markdown", + "id": "7aacca93", + "metadata": {}, + "source": [ + "### Approach 1: point to point solution, no cost or constraints\n", + "\n", + "Once the system and basis function have been defined, the\n", + "`point_to_point()` function can be used to compute a trajectory\n", + "between initial and final states and inputs:\n", + "```\n", + "traj = control.flatsys.point_to_point(sys, Tf, x0, u0, xf, uf, basis=polybasis)\n", + "```\n", + "The returned object has class `SystemTrajectory` and can be used\n", + "to compute the state and input trajectory between the initial and final\n", + "condition:\n", + "```\n", + "xd, ud = traj.eval(timepts)\n", + "```\n", + "where `timepts` is a list of times on which the trajectory should be\n", + "evaluated (e.g., `timepts = numpy.linspace(0, Tf, M)`)." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "surface-piano", + "metadata": {}, + "outputs": [], + "source": [ + "# Define the endpoints of the trajectory\n", + "x0 = np.array([0., -2., 0.]); u0 = np.array([10., 0.])\n", + "xf = np.array([40., 2., 0.]); uf = np.array([10., 0.])\n", + "Tf = 4\n", + "\n", + "# Generate a normalized set of basis functions\n", + "poly = fs.PolyFamily(6, Tf)\n", + "\n", + "# Find a trajectory between the initial condition and the final condition\n", + "traj = fs.point_to_point(bicycle_flat, Tf, x0, u0, xf, uf, basis=poly)\n", + "\n", + "# Create the desired trajectory between the initial and final condition\n", + "timepts = np.linspace(0, Tf, 500)\n", + "xd, ud = traj.eval(timepts)\n", + "\n", + "# Simulation the open system dynamics with the full input\n", + "t, y, x = ct.input_output_response(\n", + " bicycle_flat, timepts, ud, x0, return_x=True)\n", + "\n", + "# Plot the open loop system dynamics\n", + "plt.figure(1)\n", + "plt.suptitle(\"Open loop trajectory for unicycle lane change\")\n", + "plot_motion(t, x, ud)\n", + "\n", + "# Make sure the initial and final points are correct\n", + "print(\"x[0] = \", xd[:, 0])\n", + "print(\"x[T] = \", xd[:, -1])" + ] + }, + { + "cell_type": "markdown", + "id": "82a3318a", + "metadata": {}, + "source": [ + "### A look inside the code\n", + "\n", + "The code to solve this problem is inside the file [flatsys.py](https://github.com/python-control/python-control/blob/main/control/flatsys/flatsys.py) in the python-control package. Here is what operative code inside the `point_to_point()` looks like:\n", + "\n", + " #\n", + " # Map the initial and final conditions to flat output conditions\n", + " #\n", + " # We need to compute the output \"flag\": [z(t), z'(t), z''(t), ...]\n", + " # and then evaluate this at the initial and final condition.\n", + " #\n", + "\n", + " zflag_T0 = sys.forward(x0, u0)\n", + " zflag_Tf = sys.forward(xf, uf)\n", + "\n", + " #\n", + " # Compute the matrix constraints for initial and final conditions\n", + " #\n", + " # This computation depends on the basis function we are using. It\n", + " # essentially amounts to evaluating the basis functions and their\n", + " # derivatives at the initial and final conditions.\n", + "\n", + " # Compute the flags for the initial and final states\n", + " M_T0 = _basis_flag_matrix(sys, basis, zflag_T0, T0)\n", + " M_Tf = _basis_flag_matrix(sys, basis, zflag_Tf, Tf)\n", + "\n", + " # Stack the initial and final matrix/flag for the point to point problem\n", + " M = np.vstack([M_T0, M_Tf])\n", + " Z = np.hstack([np.hstack(zflag_T0), np.hstack(zflag_Tf)])\n", + "\n", + " #\n", + " # Solve for the coefficients of the flat outputs\n", + " #\n", + " # At this point, we need to solve the equation M alpha = zflag, where M\n", + " # is the matrix constrains for initial and final conditions and zflag =\n", + " # [zflag_T0; zflag_tf].\n", + " #\n", + " # If there are no constraints, then we just need to solve a linear\n", + " # system of equations => use least squares. Otherwise, we have a\n", + " # nonlinear optimal control problem with equality constraints => use\n", + " # scipy.optimize.minimize().\n", + " #\n", + "\n", + " # Start by solving the least squares problem\n", + " alpha, residuals, rank, s = np.linalg.lstsq(M, Z, rcond=None)" + ] + }, + { + "cell_type": "markdown", + "id": "f0397b3e", + "metadata": {}, + "source": [ + "### Approach #2: add cost function to make lane change quicker" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "appreciated-baghdad", + "metadata": {}, + "outputs": [], + "source": [ + "# Define timepoints for evaluation plus basis function to use\n", + "timepts = np.linspace(0, Tf, 20)\n", + "basis = fs.PolyFamily(12, Tf)\n", + "\n", + "# Define the cost function (penalize lateral error and steering)\n", + "traj_cost = opt.quadratic_cost(\n", + " bicycle_flat, np.diag([0, 0.1, 0]), np.diag([0.1, 1]), x0=xf, u0=uf)\n", + "\n", + "# Solve for an optimal solution\n", + "start_time = time.process_time()\n", + "traj = fs.point_to_point(\n", + " bicycle_flat, timepts, x0, u0, xf, uf, cost=traj_cost, basis=basis,\n", + ")\n", + "print(\"* Total time = %5g seconds\\n\" % (time.process_time() - start_time))\n", + "\n", + "xd, ud = traj.eval(timepts)\n", + "\n", + "plt.figure(2)\n", + "plt.suptitle(\"Lane change with lateral error + steering penalties\")\n", + "plot_motion(timepts, xd, ud);" + ] + }, + { + "cell_type": "markdown", + "id": "ff7363ca", + "metadata": {}, + "source": [ + "Note that the solution has a very large steering angle (0.2 rad = ~12 degrees)." + ] + }, + { + "cell_type": "markdown", + "id": "3c533abe", + "metadata": {}, + "source": [ + "### Approach #3: optimal cost with trajectory constraints\n", + "\n", + "To get a smaller steering angle, we add constraints on the inputs." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "stable-network", + "metadata": {}, + "outputs": [], + "source": [ + "constraints = [\n", + " opt.input_range_constraint(bicycle_flat, [8, -0.1], [12, 0.1]) ]\n", + "\n", + "# Solve for an optimal solution\n", + "traj = fs.point_to_point(\n", + " bicycle_flat, timepts, x0, u0, xf, uf, cost=traj_cost,\n", + " trajectory_constraints=constraints, basis=basis,\n", + ")\n", + "xd, ud = traj.eval(timepts)\n", + "\n", + "plt.figure(3)\n", + "plt.suptitle(\"Lane change with penalty + steering constraints\")\n", + "plot_motion(timepts, xd, ud)" + ] + }, + { + "cell_type": "markdown", + "id": "677750b0", + "metadata": {}, + "source": [ + "## Ideas to explore\n", + "* Change the number of basis functions\n", + "* Change the number of time points\n", + "* Change the type of basis functions: BezierFamily" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "1622bccd", + "metadata": {}, + "outputs": [], + "source": [ + "# Define a set of basis functions to use for the trajectories\n", + "poly = fs.BezierFamily(6, 2)\n", + "\n", + "# Plot out the basis functions\n", + "t = np.linspace(0, 2)\n", + "for k in range(poly.N):\n", + " plt.plot(t, poly(k, t), label=f'k = {k}')\n", + " \n", + "plt.legend()\n", + "plt.title(\"Bezier basis functions\")\n", + "plt.xlabel(\"Time $t$\")\n", + "plt.ylabel(r\"$\\psi_i(t)$\");" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "fc566fb2", + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/examples/cds112-L2b_gainsched.ipynb b/examples/cds112-L2b_gainsched.ipynb new file mode 100644 index 000000000..d915f9e3d --- /dev/null +++ b/examples/cds112-L2b_gainsched.ipynb @@ -0,0 +1,408 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "exempt-legislation", + "metadata": {}, + "source": [ + "# Gain Scheduling\n", + "\n", + "##### Richard M. Murray, 19 Nov 2021 (updated 7 Jul 2024)\n", + "\n", + "This notebook contains an example of using gain scheduling for feedback control of a nonlinear system. A gain scheduled controller has feedback gains that depend on a set of measured parameters in the system. For exampe:\n", + "\n", + "$$\n", + " u = u_\\text{d} − K(x_\\text{d}, u_\\text{d}) (x − x_\\text{d}),\n", + "$$\n", + "\n", + "where $K(x_\\text{d}, u_\\text{d})$ depends on the desired system state and input.\n", + "\n", + "In this notebook, we work through the gain scheduled controller in Example 2.1 of OBC." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "corresponding-convenience", + "metadata": {}, + "outputs": [], + "source": [ + "# Import the packages needed for the examples included in this notebook\n", + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "from cmath import sqrt\n", + "import control as ct" + ] + }, + { + "cell_type": "markdown", + "id": "corporate-sense", + "metadata": {}, + "source": [ + "## Vehicle Steering Dynamics\n", + "\n", + "The vehicle dynamics are given by a simple bicycle model:\n", + "\n", + "\n", + "\n", + " \n", + " \n", + "\n", + "
\n", + "$$\n", + "\\begin{aligned}\n", + " \\dot x &= \\cos\\theta\\, v \\\\\n", + " \\dot y &= \\sin\\theta\\, v \\\\\n", + " \\dot\\theta &= \\frac{v}{l} \\tan \\delta\n", + "\\end{aligned}\n", + "$$\n", + "
\n", + "\n", + "We take the state of the system as $(x, y, \\theta)$ where $(x, y)$ is the position of the vehicle in the plane and $\\theta$ is the angle of the vehicle with respect to horizontal. The vehicle input is given by $(v, \\delta)$ where $v$ is the forward velocity of the vehicle and $\\delta$ is the angle of the steering wheel. The model includes saturation of the vehicle steering angle." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "naval-pizza", + "metadata": {}, + "outputs": [], + "source": [ + "# Bicycle model dynamics\n", + "#\n", + "# System state: x, y, theta\n", + "# System input: v, delta\n", + "# System output: x, y\n", + "# System parameters: wheelbase, maxsteer\n", + "#\n", + "def bicycle_update(t, x, u, params):\n", + " # Get the parameters for the model\n", + " l = params.get('wheelbase', 3.) # vehicle wheelbase\n", + " deltamax = params.get('maxsteer', 0.5) # max steering angle (rad)\n", + "\n", + " # Saturate the steering input\n", + " delta = np.clip(u[1], -deltamax, deltamax)\n", + "\n", + " # Return the derivative of the state\n", + " return np.array([\n", + " np.cos(x[2]) * u[0], # xdot = cos(theta) v\n", + " np.sin(x[2]) * u[0], # ydot = sin(theta) v\n", + " (u[0] / l) * np.tan(delta) # thdot = v/l tan(delta)\n", + " ])\n", + "\n", + "def bicycle_output(t, x, u, params):\n", + " return x # return x, y, theta (full state)\n", + "\n", + "# Define the vehicle steering dynamics as an input/output system\n", + "bicycle = ct.nlsys(\n", + " bicycle_update, bicycle_output, states=3, name='bicycle',\n", + " inputs=('v', 'delta'),\n", + " outputs=('x', 'y', 'theta'))" + ] + }, + { + "cell_type": "markdown", + "id": "3cc26675", + "metadata": {}, + "source": [ + "## Gain scheduled controller\n", + "\n", + "For this system we use a simple schedule on the forward vehicle velocity and\n", + "place the poles of the system at fixed values. The controller takes the\n", + "current and desired vehicle position and orientation plus the velocity\n", + "velocity as inputs, and returns the velocity and steering commands.\n", + "\n", + "Linearizing the system about the desired trajectory, we obtain\n", + "\n", + "$$\n", + " \\begin{aligned}\n", + " A(x_\\text{d}) &= \\left. \\frac{\\partial f}{\\partial x} \\right|_{(x_\\text{d}, u_\\text{d})}\n", + " = \\left.\n", + " \\begin{bmatrix}\n", + " 0 & 0 & -\\sin\\theta_\\text{d}\\, v_\\text{d} \\\\ 0 & 0 & \\cos\\theta_\\text{d}\\, v_\\text{d} \\\\ 0 & 0 & 0\n", + " \\end{bmatrix}\n", + " \\right|_{(x_\\text{d}, u_\\text{d})}\n", + " = \\begin{bmatrix}\n", + " 0 & 0 & 0 \\\\ 0 & 0 & v_\\text{d} \\\\ 0 & 0 & 0\n", + " \\end{bmatrix}, \\\\\n", + " B(x_\\text{d}) &= \\left. \\frac{\\partial f}{\\partial u} \\right|_{(x_\\text{d}, u_\\text{d})}\n", + " = \\begin{bmatrix}\n", + " 1 & 0 \\\\ 0 & 0 \\\\ 0 & v_\\text{d}/l\n", + " \\end{bmatrix}.\n", + " \\end{aligned}\n", + "$$\n", + "\n", + "We form the error dynamics by setting $e = x - x_\\text{d}$ and $w = u -\n", + "u_\\text{d}$:\n", + "$$\n", + " \\dot e_x = w_1, \\qquad \\dot e_y = e_\\theta, \\qquad \\dot e_\\theta =\n", + " \\frac{v_\\text{d}}{l} w_2.\n", + "$$\n", + "We see that the first state is decoupled from the second two states\n", + "and hence we can design a controller by treating these two subsystems\n", + "separately. \n", + "\n", + "Suppose that we wish to place the closed loop eigenvalues\n", + "of the longitudinal dynamics ($e_x$) at $-\\lambda_1$ and place the\n", + "closed loop eigenvalues of the lateral dynamics ($e_y$, $e_\\theta$) at\n", + "the roots of the polynomial equation $s^2 + a_1 s + a_2 = 0$.\n", + "\n", + "This can accomplished by setting\n", + "\n", + "$$\n", + " \\begin{aligned}\n", + " w_1 &= -\\lambda_1 e_x \\\\\n", + " w_2 &= -\\frac{l}{v_\\text{r}}(\\frac{a_2}{v_\\text{r}} e_y + a_1 e_\\theta).\n", + " \\end{aligned}\n", + "$$\n", + "\n", + "Note that the gains depend on the velocity $v_\\text{r}$ (or equivalently on\n", + "the nominal input $u_\\text{d}$), giving us a gain scheduled controller." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "another-milwaukee", + "metadata": {}, + "outputs": [], + "source": [ + "# System state: none\n", + "# System input: x, y, theta, xd, yd, thetad, vd, delta\n", + "# System output: v, delta\n", + "# System parameters: longpole, latomega_c, latzeta_c\n", + "def gainsched_output(t, x, u, params):\n", + " # Get the controller parameters\n", + " longpole = params.get('longpole', -2.)\n", + " latomega_c = params.get('latomega_c', 2)\n", + " latzeta_c = params.get('latzeta_c', 0.5)\n", + " l = params.get('wheelbase', 3)\n", + " vref = params.get('vref', None)\n", + " \n", + " # Extract the system inputs and compute the errors\n", + " x, y, theta, xd, yd, thetad, vd, deltad = u\n", + " ex, ey, etheta = x - xd, y - yd, theta - thetad\n", + "\n", + " # Determine the controller gains\n", + " lambda1 = -longpole\n", + " a1 = 2 * latzeta_c * latomega_c\n", + " a2 = latomega_c**2\n", + " \n", + " # Determine the speed to use for computing the gains\n", + " if vref is None:\n", + " vref = vd\n", + "\n", + " # Compute and return the control law\n", + " v = -lambda1 * ex # leave off feedforward to generate transient\n", + " if vd != 0:\n", + " delta = deltad - ((a2 * l) / vref**2) * ey - ((a1 * l) / vref) * etheta\n", + " else:\n", + " # We aren't moving, so don't turn the steering wheel\n", + " delta = deltad\n", + " \n", + " return np.array([v, delta])\n", + "\n", + "# Define the controller as an input/output system\n", + "gainsched = ct.nlsys(\n", + " None, gainsched_output, name='controller', # static system\n", + " inputs=('x', 'y', 'theta', 'xd', 'yd', 'thetad', # system inputs\n", + " 'vd', 'deltad'),\n", + " outputs=('v', 'delta') # system outputs\n", + ")" + ] + }, + { + "cell_type": "markdown", + "id": "6c6c4b9b", + "metadata": {}, + "source": [ + "## Reference trajectory subsystem\n", + "\n", + "The reference trajectory block generates a simple trajectory for the system\n", + "given the desired speed (vref) and lateral position (yref). The trajectory\n", + "consists of a straight line of the form (vref * t, yref, 0) with nominal\n", + "input (vref, 0)." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "significant-november", + "metadata": {}, + "outputs": [], + "source": [ + "# System state: none\n", + "# System input: vref, yref\n", + "# System output: xd, yd, thetad, vd, deltad\n", + "# System parameters: none\n", + "#\n", + "def trajgen_output(t, x, u, params):\n", + " vref, yref = u\n", + " return np.array([vref * t, yref, 0, vref, 0])\n", + "\n", + "# Define the trajectory generator as an input/output system\n", + "trajgen = ct.nlsys(\n", + " None, trajgen_output, name='trajgen',\n", + " inputs=('vref', 'yref'),\n", + " outputs=('xd', 'yd', 'thetad', 'vd', 'deltad'))\n" + ] + }, + { + "cell_type": "markdown", + "id": "4ca5ab53", + "metadata": {}, + "source": [ + "## System construction\n", + "\n", + "The input to the full closed loop system is the desired lateral position and\n", + "the desired forward velocity. The output for the system is taken as the\n", + "full vehicle state plus the velocity of the vehicle.\n", + "\n", + "We construct the system using the InterconnectedSystem constructor and using\n", + "signal labels to keep track of everything. " + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "editorial-satisfaction", + "metadata": {}, + "outputs": [], + "source": [ + "steering_gainsched = ct.interconnect(\n", + " # List of subsystems\n", + " (trajgen, gainsched, bicycle), name='steering',\n", + "\n", + " # System inputs\n", + " inplist=['trajgen.vref', 'trajgen.yref'],\n", + " inputs=['yref', 'vref'],\n", + "\n", + " # System outputs\n", + " outlist=['bicycle.x', 'bicycle.y', 'bicycle.theta', 'controller.v',\n", + " 'controller.delta'],\n", + " outputs=['x', 'y', 'theta', 'v', 'delta']\n", + ")" + ] + }, + { + "cell_type": "markdown", + "id": "61fe3404", + "metadata": {}, + "source": [ + "Note the use of signals of the form `sys.sig` to get the signals from a specific subsystem." + ] + }, + { + "cell_type": "markdown", + "id": "47f5d528", + "metadata": {}, + "source": [ + "## System simulation" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "smoking-trail", + "metadata": {}, + "outputs": [], + "source": [ + "# Set up the simulation conditions\n", + "yref = 1\n", + "T = np.linspace(0, 5, 100)\n", + "\n", + "# Plot the reference trajectory for the y position\n", + "plt.plot([0, 5], [yref, yref], 'k-', linewidth=0.6)\n", + "\n", + "# Find the signals we want to plot\n", + "y_index = steering_gainsched.find_output('y')\n", + "v_index = steering_gainsched.find_output('v')\n", + "\n", + "# Do an iteration through different speeds\n", + "for vref in [5, 10, 15]:\n", + " # Simulate the closed loop controller response\n", + " tout, yout = ct.input_output_response(\n", + " steering_gainsched, T, [vref * np.ones(len(T)), yref * np.ones(len(T))])\n", + "\n", + " # Plot the reference speed\n", + " plt.plot([0, 5], [vref, vref], 'k-', linewidth=0.6)\n", + "\n", + " # Plot the system output\n", + " y_line, = plt.plot(tout, yout[y_index, :], 'r-') # lateral position\n", + " v_line, = plt.plot(tout, yout[v_index, :], 'b--') # vehicle velocity\n", + "\n", + "# Add axis labels\n", + "plt.xlabel(\"Time [s]\")\n", + "plt.ylabel(r\"$\\dot{x}$ [m/s], $y$ [m]\")\n", + "plt.legend((v_line, y_line), (r\"$\\dot{x}$\", \"$y$\"),\n", + " loc='center right', frameon=False);" + ] + }, + { + "cell_type": "markdown", + "id": "8f31bc48", + "metadata": {}, + "source": [ + "## Comparison to fixed controller" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "homeless-gibson", + "metadata": {}, + "outputs": [], + "source": [ + "# Rerun with no gain-scheduling\n", + "\n", + "# Plot the reference trajectory for the y position\n", + "plt.plot([0, 5], [yref, yref], 'k-', linewidth=0.6)\n", + "\n", + "# Do an iteration through different speeds\n", + "for vref in [5, 10, 15]:\n", + " # Simulate the closed loop controller response\n", + " tout, yout = ct.input_output_response(\n", + " steering_gainsched, T, [vref * np.ones(len(T)), yref * np.ones(len(T))], \n", + " params={'vref': 15})\n", + "\n", + " # Plot the reference speed\n", + " plt.plot([0, 5], [vref, vref], 'k-', linewidth=0.6)\n", + "\n", + " # Plot the system output\n", + " y_line, = plt.plot(tout, yout[y_index, :], 'r-') # lateral position\n", + " v_line, = plt.plot(tout, yout[v_index, :], 'b--') # vehicle velocity\n", + "\n", + "# Add axis labels\n", + "plt.xlabel(\"Time [s]\")\n", + "plt.ylabel(r\"$\\dot{x}$ [m/s], $y$ [m]\")\n", + "plt.legend((v_line, y_line), (r\"$\\dot{x}$\", \"$y$\"),\n", + " loc='center right', frameon=False);" + ] + }, + { + "cell_type": "markdown", + "id": "5811a6e4", + "metadata": {}, + "source": [ + "## Things to try\n", + "* Use different reference trajectories (eg, flatness-based trajectory)\n", + "* Try scheduling on the current state rather than the desired state" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "6f571b2b", + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/examples/cds112-L3a_linquad.ipynb b/examples/cds112-L3a_linquad.ipynb new file mode 100644 index 000000000..11ac54771 --- /dev/null +++ b/examples/cds112-L3a_linquad.ipynb @@ -0,0 +1,399 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "dd522981", + "metadata": {}, + "source": [ + "# Linear quadratic optimal control example\n", + "\n", + "Richard M. Murray, 20 Jan 2022 (updated 7 Jul 2024)\n", + "\n", + "This example works through the linear quadratic finite time optimal control problem. We assume that we have a linear system of the form\n", + "$$\n", + "\\dot x = A x + Bu \n", + "$$\n", + "and that we want to minimize a cost function of the form\n", + "$$\n", + "\\int_0^T (x^T Q_x x + u^T Q_u u) dt + x^T P_1 x.\n", + "$$\n", + "We show how to compute the solution the Riccati ODE and use this to obtain an optimal (time-varying) linear controller." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "866842ea", + "metadata": {}, + "outputs": [], + "source": [ + "import numpy as np\n", + "import scipy as sp\n", + "import matplotlib.pyplot as plt\n", + "import control as ct\n", + "import control.optimal as opt\n", + "import control.flatsys as fs\n", + "import time" + ] + }, + { + "cell_type": "markdown", + "id": "83a32e85", + "metadata": {}, + "source": [ + "## System dynamics\n", + "\n", + "We use the linearized dynamics of the vehicle steering problem as our linear system. This is mainly for convenient (since we have some intuition about it). " + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "48c1bd7f-0db6-4488-af41-41f685280ec9", + "metadata": {}, + "outputs": [], + "source": [ + "# Vehicle dynamics (bicycle model)\n", + "\n", + "# Function to take states, inputs and return the flat flag\n", + "def _kincar_flat_forward(x, u, params={}):\n", + " # Get the parameter values\n", + " b = params.get('wheelbase', 3.)\n", + " #! TODO: add dir processing\n", + "\n", + " # Create a list of arrays to store the flat output and its derivatives\n", + " zflag = [np.zeros(3), np.zeros(3)]\n", + "\n", + " # Flat output is the x, y position of the rear wheels\n", + " zflag[0][0] = x[0]\n", + " zflag[1][0] = x[1]\n", + "\n", + " # First derivatives of the flat output\n", + " zflag[0][1] = u[0] * np.cos(x[2]) # dx/dt\n", + " zflag[1][1] = u[0] * np.sin(x[2]) # dy/dt\n", + "\n", + " # First derivative of the angle\n", + " thdot = (u[0]/b) * np.tan(u[1])\n", + "\n", + " # Second derivatives of the flat output (setting vdot = 0)\n", + " zflag[0][2] = -u[0] * thdot * np.sin(x[2])\n", + " zflag[1][2] = u[0] * thdot * np.cos(x[2])\n", + "\n", + " return zflag\n", + "\n", + "# Function to take the flat flag and return states, inputs\n", + "def _kincar_flat_reverse(zflag, params={}):\n", + " # Get the parameter values\n", + " b = params.get('wheelbase', 3.)\n", + " dir = params.get('dir', 'f')\n", + "\n", + " # Create a vector to store the state and inputs\n", + " x = np.zeros(3)\n", + " u = np.zeros(2)\n", + "\n", + " # Given the flat variables, solve for the state\n", + " x[0] = zflag[0][0] # x position\n", + " x[1] = zflag[1][0] # y position\n", + " if dir == 'f':\n", + " x[2] = np.arctan2(zflag[1][1], zflag[0][1]) # tan(theta) = ydot/xdot\n", + " elif dir == 'r':\n", + " # Angle is flipped by 180 degrees (since v < 0)\n", + " x[2] = np.arctan2(-zflag[1][1], -zflag[0][1])\n", + " else:\n", + " raise ValueError(\"unknown direction:\", dir)\n", + "\n", + " # And next solve for the inputs\n", + " u[0] = zflag[0][1] * np.cos(x[2]) + zflag[1][1] * np.sin(x[2])\n", + " thdot_v = zflag[1][2] * np.cos(x[2]) - zflag[0][2] * np.sin(x[2])\n", + " u[1] = np.arctan2(thdot_v, u[0]**2 / b)\n", + "\n", + " return x, u\n", + "\n", + "# Function to compute the RHS of the system dynamics\n", + "def _kincar_update(t, x, u, params):\n", + " b = params.get('wheelbase', 3.) # get parameter values\n", + " #! TODO: add dir processing\n", + " dx = np.array([\n", + " np.cos(x[2]) * u[0],\n", + " np.sin(x[2]) * u[0],\n", + " (u[0]/b) * np.tan(u[1])\n", + " ])\n", + " return dx\n", + "\n", + "def _kincar_output(t, x, u, params):\n", + " return x # return x, y, theta (full state)\n", + "\n", + "# Create differentially flat input/output system\n", + "kincar = fs.FlatSystem(\n", + " _kincar_flat_forward, _kincar_flat_reverse, name=\"kincar\",\n", + " updfcn=_kincar_update, outfcn=_kincar_output,\n", + " inputs=('v', 'delta'), outputs=('x', 'y', 'theta'),\n", + " states=('x', 'y', 'theta'))" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "fbdd78c0-30e9-43f7-9e8d-198ae38c2988", + "metadata": {}, + "outputs": [], + "source": [ + "# Utility function to plot lane change manuever\n", + "def plot_lanechange(t, y, u, figure=None, yf=None):\n", + " # Plot the xy trajectory\n", + " plt.subplot(3, 1, 1, label='xy')\n", + " plt.plot(y[0], y[1])\n", + " plt.xlabel(\"x [m]\")\n", + " plt.ylabel(\"y [m]\")\n", + " if yf is not None:\n", + " plt.plot(yf[0], yf[1], 'ro')\n", + "\n", + " # Plot the inputs as a function of time\n", + " plt.subplot(3, 1, 2, label='v')\n", + " plt.plot(t, u[0])\n", + " plt.xlabel(\"Time $t$ [sec]\")\n", + " plt.ylabel(\"$v$ [m/s]\")\n", + "\n", + " plt.subplot(3, 1, 3, label='delta')\n", + " plt.plot(t, u[1])\n", + " plt.xlabel(\"Time $t$ [sec]\")\n", + " plt.ylabel(\"$\\\\delta$ [rad]\")\n", + "\n", + " plt.suptitle(\"Lane change manuever\")\n", + " plt.tight_layout()" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "de9d85f3", + "metadata": {}, + "outputs": [], + "source": [ + "# Initial conditions\n", + "x0 = np.array([-40, -2., 0.])\n", + "u0 = np.array([10, 0]) # only used for linearization\n", + "Tf = 4\n", + "\n", + "# Linearized dynamics\n", + "sys = kincar.linearize(x0, u0)\n", + "print(sys)" + ] + }, + { + "cell_type": "markdown", + "id": "c5c0abe9", + "metadata": {}, + "source": [ + "## Optimal trajectory generation\n", + "\n", + "We generate an trajectory for the system that minimizes the cost function above. Namely, starting from some initial function $x(0) = x_0$, we wish to bring the system toward the origin without using too much control effort." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "02e9f87c", + "metadata": {}, + "outputs": [], + "source": [ + "# Define the cost function and the terminal cost\n", + "# (try changing these later to see what happens)\n", + "Qx = np.diag([1, 1, 1]) # state costs\n", + "Qu = np.diag([1, 1]) # input costs\n", + "Pf = np.diag([1, 1, 1]) # terminal costs" + ] + }, + { + "cell_type": "markdown", + "id": "62c76e5e", + "metadata": {}, + "source": [ + "### Finite time, linear quadratic optimization\n", + "\n", + "The optimal solution satisfies the following equations, which follow from the maximum principle:\n", + "\n", + "$$\n", + " \\begin{aligned}\n", + " \\dot x &= \\left(\\frac{\\partial H}{\\partial \\lambda}\\right)^T\n", + " = A x + Bu, \\qquad & x(0) &= x_0, \\\\\n", + " -\\dot \\lambda &= \\left(\\frac{\\partial H}{\\partial x}\\right)^T\n", + " = Q_x x + A^T \\lambda, \\qquad\n", + " & \\lambda(T) &= P_1 x(T), \\\\\n", + " 0 &= \\left(\\frac{\\partial H}{\\partial u}\\right)^T\n", + " = Q_u u + B^T \\lambda. &&\n", + " \\end{aligned}\n", + "$$\n", + "\n", + "The last condition can be solved to obtain the optimal controller\n", + "\n", + "$$\n", + " u = -Q_u^{-1} B^T \\lambda,\n", + "$$\n", + "\n", + "which can be substituted into the equations for the optimal solution.\n", + "\n", + "Given the linear nature of the dynamics, we attempt to find a solution\n", + "by setting $\\lambda(t) = P(t) x(t)$ where $P(t) \\in {\\mathbb R}^{n \\times\n", + "n}$. Substituting this into the necessary condition, we obtain\n", + "\n", + "$$\n", + " \\begin{aligned}\n", + " & \\dot\\lambda =\n", + " \\dot P x + P \\dot x = \\dot P x + P(Ax - BQ_u^{-1} B^T P) x, \\\\\n", + " & \\quad\\implies\\quad\n", + " -\\dot P x - PA x + PBQ_u^{-1}B P x = Q_xx + A^T P x.\n", + " \\end{aligned}\n", + "$$\n", + "\n", + "This equation is satisfied if we can find $P(t)$ such that\n", + "\n", + "$$\n", + " -\\dot P = PA + A^T P - P B Q_u^{-1} B^T P + Q_x,\n", + " \\qquad P(T) = P_1.\n", + "$$" + ] + }, + { + "cell_type": "markdown", + "id": "b63aed88", + "metadata": {}, + "source": [ + "To solve a final value problem with $P(T) = P_1$, we set the \"initial\" condition to $P_1$ and then invert time, so that we solve\n", + "\n", + "$$\n", + "\\frac{dP}{d(-t)} = -\\frac{dP}{dt} = -F(P), \\qquad P(0) = P_1\n", + "$$\n", + "\n", + "Solving this equation from time $t = 0$ to time $t = T$ will give us an solution that goes from $P(T)$ to $P(0)$." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "02d74789", + "metadata": {}, + "outputs": [], + "source": [ + "# Set up the Riccatti ODE\n", + "def Pdot_reverse(t, x):\n", + " # Get the P matrix from the state by resizing\n", + " P = np.reshape(x, (sys.nstates, sys.nstates))\n", + " \n", + " # Compute the right hand side of Riccati ODE\n", + " Prhs = P @ sys.A + sys.A.T @ P + Qx - \\\n", + " P @ sys.B @ np.linalg.inv(Qu) @ sys.B.T @ P\n", + " \n", + " # Return P as a vector, *backwards* in time (no minus sign)\n", + " return Prhs.reshape((-1))\n", + "\n", + "# Solve the Riccati ODE (converting from matrix to vector and back)\n", + "P0 = np.reshape(Pf, (-1))\n", + "Psol = sp.integrate.solve_ivp(Pdot_reverse, (0, Tf), P0)\n", + "Pfwd = np.reshape(Psol.y, (sys.nstates, sys.nstates, -1))\n", + "\n", + "# Reorder the solution in time\n", + "Prev = Pfwd[:, :, ::-1] \n", + "trev = Tf - Psol.t[::-1]\n", + "\n", + "print(\"Trange = \", trev[0], \"to\", trev[-1])\n", + "print(\"P[Tf] =\", Prev[:,:,-1])\n", + "print(\"P[0] =\", Prev[:,:,0])\n", + "\n", + "# Internal comparison: show that initial value is close to algebraic solution\n", + "_, P_lqr, _ = ct.lqr(sys.A, sys.B, Qx, Qu)\n", + "print(\"P_lqr =\", P_lqr)" + ] + }, + { + "cell_type": "markdown", + "id": "f4fb1166", + "metadata": {}, + "source": [ + "For solving the $x$ dynamics, we need a function to evaluate $P(t)$ at an arbitrary time (used by the integrator). We can do this with the SciPy `interp1d` function:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "728f675b", + "metadata": {}, + "outputs": [], + "source": [ + "# Define an interpolation function for P\n", + "P = sp.interpolate.interp1d(trev, Prev)\n", + "\n", + "print(\"P(0) =\", P(0))\n", + "print(\"P(3.5) =\", P(3.5))\n", + "print(\"P(4) =\", P(4))" + ] + }, + { + "cell_type": "markdown", + "id": "eb30c3fa", + "metadata": {}, + "source": [ + "We now solve the $\\dot x$ equations *forward* in time, using $P(t)$:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "84092dcd", + "metadata": {}, + "outputs": [], + "source": [ + "# Now solve the state forward in time\n", + "def xdot_forward(t, x):\n", + " u = -np.linalg.inv(Qu) @ sys.B.T @ P(t) @ x\n", + " return sys.A @ x + sys.B @ u\n", + "\n", + "# Now simulate from a shifted initial condition\n", + "xsol = sp.integrate.solve_ivp(xdot_forward, (0, Tf), x0)\n", + "tvec = xsol.t\n", + "x = xsol.y\n", + "print(\"x[0] =\", x[:, 0])\n", + "print(\"x[Tf] =\", x[:, -1])" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "8488acad", + "metadata": {}, + "outputs": [], + "source": [ + "# Finally compute the \"desired\" state and input values\n", + "xd = x\n", + "ud = np.zeros((sys.ninputs, tvec.size))\n", + "for i, t in enumerate(tvec):\n", + " ud[:, i] = -np.linalg.inv(Qu) @ sys.B.T @ P(t) @ x[:, i]\n", + "\n", + "plot_lanechange(tvec, xd, ud)" + ] + }, + { + "cell_type": "markdown", + "id": "89483f4b", + "metadata": {}, + "source": [ + "Note here that we are stabilizing the system to the origin (compared to some of other examples where we change langes and so the final $y$ position is $y_\\text{f} = 2$." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "7ed4c5eb", + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/examples/cds112-L3b_optimal.ipynb b/examples/cds112-L3b_optimal.ipynb new file mode 100644 index 000000000..1c7e0e1c2 --- /dev/null +++ b/examples/cds112-L3b_optimal.ipynb @@ -0,0 +1,461 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "edb7e2c6", + "metadata": {}, + "source": [ + "## Optimal Control\n", + "\n", + "Richard M. Murray, 31 Dec 2021 (updated 7 Jul 2024)\n", + "\n", + "This notebook contains an example of using optimal control for a vehicle steering system. It illustrates different methods of setting up optimal control problems and solving them using python-control." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "7066eb69", + "metadata": {}, + "outputs": [], + "source": [ + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "import control as ct\n", + "import control.optimal as opt\n", + "import control.flatsys as fs\n", + "import time" + ] + }, + { + "cell_type": "markdown", + "id": "4afb09dd", + "metadata": {}, + "source": [ + "## Vehicle steering dynamics\n", + "\n", + "\n", + "\n", + " \n", + " \n", + "\n", + "
\n", + "$$\n", + "\\begin{aligned}\n", + " \\dot x &= \\cos\\theta\\, v \\\\\n", + " \\dot y &= \\sin\\theta\\, v \\\\\n", + " \\dot\\theta &= \\frac{v}{l} \\tan \\delta, \\qquad |\\delta| \\leq \\delta_\\text{max}\n", + "\\end{aligned}\n", + "$$\n", + "
\n", + "\n", + "The vehicle dynamics are given by a simple bicycle model. We take the state of the system as $(x, y, \\theta)$ where $(x, y)$ is the position of the vehicle in the plane and $\\theta$ is the angle of the vehicle with respect to horizontal. The vehicle input is given by $(v, \\delta)$ where $v$ is the forward velocity of the vehicle and $\\delta$ is the angle of the steering wheel. The model includes saturation of the vehicle steering angle." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "a6143a8a", + "metadata": {}, + "outputs": [], + "source": [ + "# Vehicle dynamics (bicycle model)\n", + "\n", + "# Function to take states, inputs and return the flat flag\n", + "def _kincar_flat_forward(x, u, params={}):\n", + " # Get the parameter values\n", + " b = params.get('wheelbase', 3.)\n", + " #! TODO: add dir processing\n", + "\n", + " # Create a list of arrays to store the flat output and its derivatives\n", + " zflag = [np.zeros(3), np.zeros(3)]\n", + "\n", + " # Flat output is the x, y position of the rear wheels\n", + " zflag[0][0] = x[0]\n", + " zflag[1][0] = x[1]\n", + "\n", + " # First derivatives of the flat output\n", + " zflag[0][1] = u[0] * np.cos(x[2]) # dx/dt\n", + " zflag[1][1] = u[0] * np.sin(x[2]) # dy/dt\n", + "\n", + " # First derivative of the angle\n", + " thdot = (u[0]/b) * np.tan(u[1])\n", + "\n", + " # Second derivatives of the flat output (setting vdot = 0)\n", + " zflag[0][2] = -u[0] * thdot * np.sin(x[2])\n", + " zflag[1][2] = u[0] * thdot * np.cos(x[2])\n", + "\n", + " return zflag\n", + "\n", + "# Function to take the flat flag and return states, inputs\n", + "def _kincar_flat_reverse(zflag, params={}):\n", + " # Get the parameter values\n", + " b = params.get('wheelbase', 3.)\n", + " dir = params.get('dir', 'f')\n", + "\n", + " # Create a vector to store the state and inputs\n", + " x = np.zeros(3)\n", + " u = np.zeros(2)\n", + "\n", + " # Given the flat variables, solve for the state\n", + " x[0] = zflag[0][0] # x position\n", + " x[1] = zflag[1][0] # y position\n", + " if dir == 'f':\n", + " x[2] = np.arctan2(zflag[1][1], zflag[0][1]) # tan(theta) = ydot/xdot\n", + " elif dir == 'r':\n", + " # Angle is flipped by 180 degrees (since v < 0)\n", + " x[2] = np.arctan2(-zflag[1][1], -zflag[0][1])\n", + " else:\n", + " raise ValueError(\"unknown direction:\", dir)\n", + "\n", + " # And next solve for the inputs\n", + " u[0] = zflag[0][1] * np.cos(x[2]) + zflag[1][1] * np.sin(x[2])\n", + " thdot_v = zflag[1][2] * np.cos(x[2]) - zflag[0][2] * np.sin(x[2])\n", + " u[1] = np.arctan2(thdot_v, u[0]**2 / b)\n", + "\n", + " return x, u\n", + "\n", + "# Function to compute the RHS of the system dynamics\n", + "def _kincar_update(t, x, u, params):\n", + " b = params.get('wheelbase', 3.) # get parameter values\n", + " #! TODO: add dir processing\n", + " dx = np.array([\n", + " np.cos(x[2]) * u[0],\n", + " np.sin(x[2]) * u[0],\n", + " (u[0]/b) * np.tan(u[1])\n", + " ])\n", + " return dx\n", + "\n", + "def _kincar_output(t, x, u, params):\n", + " return x # return x, y, theta (full state)\n", + "\n", + "# Create differentially flat input/output system\n", + "kincar = fs.FlatSystem(\n", + " _kincar_flat_forward, _kincar_flat_reverse, name=\"kincar\",\n", + " updfcn=_kincar_update, outfcn=_kincar_output,\n", + " inputs=('v', 'delta'), outputs=('x', 'y', 'theta'),\n", + " states=('x', 'y', 'theta'))" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "43377b51-35db-4e8f-9101-b22af1de1cb2", + "metadata": {}, + "outputs": [], + "source": [ + "# Utility function to plot lane change manuever\n", + "def plot_lanechange(t, y, u, figure=None, yf=None):\n", + " # Plot the xy trajectory\n", + " plt.subplot(3, 1, 1, label='xy')\n", + " plt.plot(y[0], y[1])\n", + " plt.xlabel(\"x [m]\")\n", + " plt.ylabel(\"y [m]\")\n", + " if yf is not None:\n", + " plt.plot(yf[0], yf[1], 'ro')\n", + "\n", + " # Plot the inputs as a function of time\n", + " plt.subplot(3, 1, 2, label='v')\n", + " plt.plot(t, u[0])\n", + " plt.xlabel(\"Time $t$ [sec]\")\n", + " plt.ylabel(\"$v$ [m/s]\")\n", + "\n", + " plt.subplot(3, 1, 3, label='delta')\n", + " plt.plot(t, u[1])\n", + " plt.xlabel(\"Time $t$ [sec]\")\n", + " plt.ylabel(\"$\\\\delta$ [rad]\")\n", + "\n", + " plt.suptitle(\"Lane change manuever\")\n", + " plt.tight_layout()" + ] + }, + { + "cell_type": "markdown", + "id": "64bd3c3b", + "metadata": {}, + "source": [ + "## Optimal trajectory generation\n", + "\n", + "We consider the problem of changing from one lane to another over a perod of 10 seconds while driving at a forward speed of 10 m/s." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "42dcbd79", + "metadata": {}, + "outputs": [], + "source": [ + "# Initial and final conditions\n", + "x0 = np.array([ 0., -2., 0.]); u0 = np.array([10., 0.])\n", + "xf = np.array([100., 2., 0.]); uf = np.array([10., 0.])\n", + "Tf = 10" + ] + }, + { + "cell_type": "markdown", + "id": "5ff2e044", + "metadata": {}, + "source": [ + "An important part of the optimization procedure is to give a good initial guess. Here are some possibilities:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "650d321a", + "metadata": {}, + "outputs": [], + "source": [ + "# Define the time horizon (and spacing) for the optimization\n", + "# timepts = np.linspace(0, Tf, 5, endpoint=True)\n", + "# timepts = np.linspace(0, Tf, 10, endpoint=True)\n", + "timepts = np.linspace(0, Tf, 20, endpoint=True)\n", + "\n", + "# Compute some initial guesses to use\n", + "bend_left = [10, 0.01] # slight left veer (will extend over all timepts)\n", + "straight_line = ( # straight line from start to end with nominal input\n", + " np.array([x0 + (xf - x0) * t/Tf for t in timepts]).transpose(), \n", + " u0\n", + ")" + ] + }, + { + "cell_type": "markdown", + "id": "4e75a2c4", + "metadata": {}, + "source": [ + "### Approach 1: standard quadratic cost\n", + "\n", + "We can set up the optimal control problem as trying to minimize the distance form the desired final point while at the same time as not exerting too much control effort to achieve our goal.\n", + "\n", + "(The optimization module solves optimal control problems by choosing the values of the input at each point in the time horizon to try to minimize the cost. This means that each input generates a parameter value at each point in the time horizon, so the more refined your time horizon, the more parameters the optimizer has to search over.)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "984c2f0b", + "metadata": {}, + "outputs": [], + "source": [ + "# Set up the cost functions\n", + "Qx = np.diag([.1, 10, .1]) # keep lateral error low\n", + "Qu = np.diag([.1, 1]) # minimize applied inputs\n", + "quad_cost = opt.quadratic_cost(kincar, Qx, Qu, x0=xf, u0=uf)\n", + "\n", + "# Compute the optimal control, setting step size for gradient calculation (eps)\n", + "start_time = time.process_time()\n", + "result1 = opt.solve_ocp(\n", + " kincar, timepts, x0, quad_cost, \n", + " initial_guess=straight_line,\n", + " # initial_guess= bend_left,\n", + " # initial_guess=u0,\n", + " # minimize_method='trust-constr',\n", + " # minimize_options={'finite_diff_rel_step': 0.01},\n", + " # trajectory_method='shooting'\n", + " # solve_ivp_method='LSODA'\n", + ")\n", + "print(\"* Total time = %5g seconds\\n\" % (time.process_time() - start_time))\n", + "\n", + "# Plot the results from the optimization\n", + "plot_lanechange(timepts, result1.states, result1.inputs, xf)\n", + "print(\"Final computed state: \", result1.states[:,-1])\n", + "\n", + "# Simulate the system and see what happens\n", + "t1, u1 = result1.time, result1.inputs\n", + "t1, y1 = ct.input_output_response(kincar, timepts, u1, x0)\n", + "plot_lanechange(t1, y1, u1, yf=xf[0:2])\n", + "print(\"Final simulated state:\", y1[:,-1])" + ] + }, + { + "cell_type": "markdown", + "id": "b7cade52", + "metadata": {}, + "source": [ + "Note the amount of time required to solve the problem and also any warning messages about to being able to solve the optimization (mainly in earlier versions of python-control). You can try to adjust a number of factors to try to get a better solution:\n", + "* Try changing the number of points in the time horizon\n", + "* Try using a different initial guess\n", + "* Try changing the optimization method (see commented out code)" + ] + }, + { + "cell_type": "markdown", + "id": "6a9f9d9b", + "metadata": {}, + "source": [ + "### Approach 2: input cost, input constraints, terminal cost\n", + "\n", + "The previous solution integrates the position error for the entire horizon, and so the car changes lanes very quickly (at the cost of larger inputs). Instead, we can penalize the final state and impose a higher cost on the inputs, resuling in a more gradual lane change.\n", + "\n", + "We can also try using a different solver for this example. You can pass the solver using the `minimize_method` keyword and send options to the solver using the `minimize_options` keyword (which should be set to a dictionary of options)." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "a201e33c", + "metadata": {}, + "outputs": [], + "source": [ + "# Add input constraint, input cost, terminal cost\n", + "constraints = [ opt.input_range_constraint(kincar, [8, -0.1], [12, 0.1]) ]\n", + "traj_cost = opt.quadratic_cost(kincar, None, np.diag([0.1, 1]), u0=uf)\n", + "term_cost = opt.quadratic_cost(kincar, np.diag([1, 10, 100]), None, x0=xf)\n", + "\n", + "# Compute the optimal control\n", + "start_time = time.process_time()\n", + "result2 = opt.solve_ocp(\n", + " kincar, timepts, x0, traj_cost, constraints, terminal_cost=term_cost,\n", + " initial_guess=straight_line, \n", + " # minimize_method='trust-constr',\n", + " # minimize_options={'finite_diff_rel_step': 0.01},\n", + " # minimize_method='SLSQP', minimize_options={'eps': 0.01},\n", + " # log=True,\n", + ")\n", + "print(\"* Total time = %5g seconds\\n\" % (time.process_time() - start_time))\n", + "\n", + "# Plot the results from the optimization\n", + "plot_lanechange(timepts, result2.states, result2.inputs, xf)\n", + "print(\"Final computed state: \", result2.states[:,-1])\n", + "\n", + "# Simulate the system and see what happens\n", + "t2, u2 = result2.time, result2.inputs\n", + "t2, y2 = ct.input_output_response(kincar, timepts, u2, x0)\n", + "plot_lanechange(t2, y2, u2, yf=xf[0:2])\n", + "print(\"Final simulated state:\", y2[:,-1])" + ] + }, + { + "cell_type": "markdown", + "id": "3d2ccf97", + "metadata": {}, + "source": [ + "### Approach 3: terminal constraints\n", + "\n", + "We can also remove the cost function on the state and replace it with a terminal *constraint* on the state. If a solution is found, it guarantees we get to exactly the final state. Note however, that terminal constraints can be very difficult to satisfy for a general optimization (compare the solution times here with what we saw last week when we used differential flatness)." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "dc77a856", + "metadata": {}, + "outputs": [], + "source": [ + "# Input cost and terminal constraints\n", + "R = np.diag([1, 1]) # minimize applied inputs\n", + "cost3 = opt.quadratic_cost(kincar, np.zeros((3,3)), R, u0=uf)\n", + "constraints = [\n", + " opt.input_range_constraint(kincar, [8, -0.1], [12, 0.1]) ]\n", + "terminal = [ opt.state_range_constraint(kincar, xf, xf) ]\n", + "\n", + "# Compute the optimal control\n", + "start_time = time.process_time()\n", + "result3 = opt.solve_ocp(\n", + " kincar, timepts, x0, cost3, constraints,\n", + " terminal_constraints=terminal, initial_guess=straight_line,\n", + "# solve_ivp_kwargs={'atol': 1e-3, 'rtol': 1e-2},\n", + "# minimize_method='trust-constr',\n", + "# minimize_options={'finite_diff_rel_step': 0.01},\n", + ")\n", + "print(\"* Total time = %5g seconds\\n\" % (time.process_time() - start_time))\n", + "\n", + "# Plot the results from the optimization\n", + "plot_lanechange(timepts, result3.states, result3.inputs, xf)\n", + "print(\"Final computed state: \", result3.states[:,-1])\n", + "\n", + "# Simulate the system and see what happens\n", + "t3, u3 = result3.time, result3.inputs\n", + "t3, y3 = ct.input_output_response(kincar, timepts, u3, x0)\n", + "plot_lanechange(t3, y3, u3, yf=xf[0:2])\n", + "print(\"Final state: \", y3[:,-1])" + ] + }, + { + "cell_type": "markdown", + "id": "9e744463", + "metadata": {}, + "source": [ + "### Approach 4: terminal constraints w/ basis functions\n", + "\n", + "As a final example, we can use a basis function to reduce the size\n", + "of the problem and get faster answers with more temporal resolution.\n", + "\n", + "Here we parameterize the input by a set of 4 Bezier curves but solve for a much more time resolved set of inputs. Note that while we are using the `control.flatsys` module to define the basis functions, we are not exploiting the fact that the system is differentially flat." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "ee82aa25", + "metadata": {}, + "outputs": [], + "source": [ + "# Get basis functions for flat systems module\n", + "import control.flatsys as flat\n", + "\n", + "# Compute the optimal control\n", + "start_time = time.process_time()\n", + "result4 = opt.solve_ocp(\n", + " kincar, timepts, x0, quad_cost, constraints,\n", + " terminal_constraints=terminal,\n", + " initial_guess=straight_line,\n", + " basis=flat.PolyFamily(4, T=Tf),\n", + " # solve_ivp_kwargs={'method': 'RK45', 'atol': 1e-2, 'rtol': 1e-2},\n", + " # solve_ivp_kwargs={'atol': 1e-3, 'rtol': 1e-2},\n", + " # minimize_method='trust-constr', minimize_options={'disp': True},\n", + " log=False\n", + ")\n", + "print(\"* Total time = %5g seconds\\n\" % (time.process_time() - start_time))\n", + "\n", + "# Plot the results from the optimization\n", + "plot_lanechange(timepts, result4.states, result4.inputs, xf)\n", + "print(\"Final computed state: \", result3.states[:,-1])\n", + "\n", + "# Simulate the system and see what happens\n", + "t4, u4 = result4.time, result4.inputs\n", + "t4, y4 = ct.input_output_response(kincar, timepts, u4, x0)\n", + "plot_lanechange(t4, y4, u4, yf=xf[0:2])\n", + "plt.legend(['optimal', 'simulation'])\n", + "print(\"Final simulated state: \", y4[:,-1])" + ] + }, + { + "cell_type": "markdown", + "id": "2a74388e", + "metadata": {}, + "source": [ + "Note how much smoother the inputs look, although the solver can still have a hard time satisfying the final constraints, resulting in longer computation times." + ] + }, + { + "cell_type": "markdown", + "id": "1465d149", + "metadata": {}, + "source": [ + "### Additional things to try\n", + "\n", + "* Compare the results here with what we go last week exploiting the property of differential flatness (computation time, in particular)\n", + "* Try using different weights, solvers, initial guess and other properties and see how things change.\n", + "* Try using different values for `initial_guess` to get faster convergence and/or different classes of solutions." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "02bad3d5", + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/examples/cds112-L4a_lqr-tracking.ipynb b/examples/cds112-L4a_lqr-tracking.ipynb new file mode 100644 index 000000000..0687f4cc5 --- /dev/null +++ b/examples/cds112-L4a_lqr-tracking.ipynb @@ -0,0 +1,279 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "af1717f2", + "metadata": {}, + "source": [ + "# LQR Tracking Example\n", + "\n", + "Richard M. Murray, 25 Jan 2022\n", + "\n", + "This example uses a linear system to show how to implement LQR based tracking and some of the tradeoffs between feedfoward and feedback. Integral action is also implemented." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "50d5c4d3", + "metadata": {}, + "outputs": [], + "source": [ + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "import control as ct" + ] + }, + { + "cell_type": "markdown", + "id": "a23d6f89", + "metadata": {}, + "source": [ + "## System definition\n", + "\n", + "We use a simple linear system to illustrate the concepts. This system corresponds to the linearized lateral dynamics of a vehicle driving down a road at 10 m/s." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "b5923c88", + "metadata": {}, + "outputs": [], + "source": [ + "# Define a simple linear system that we want to control\n", + "sys = ct.ss([[0, 10], [-1, 0]], [[0], [1]], np.eye(2), 0, name='sys')\n", + "print(sys)" + ] + }, + { + "cell_type": "markdown", + "id": "dba5ea2b", + "metadata": {}, + "source": [ + "## Controller design\n", + "\n", + "We start by defining the equilibrium point that we plan to stabilize." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "874c1479", + "metadata": {}, + "outputs": [], + "source": [ + "# Define the desired equilibrium point for the system\n", + "x0 = np.array([2, 0])\n", + "u0 = np.array([2])\n", + "Tf = 4" + ] + }, + { + "cell_type": "markdown", + "id": "99f036ea", + "metadata": {}, + "source": [ + "Then construct a simple LQR controller (gain matrix) and create the controller + closed loop system models:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "3ce6a230", + "metadata": {}, + "outputs": [], + "source": [ + "# Construct an LQR controller for the system\n", + "K, _, _ = ct.lqr(sys, np.eye(sys.nstates), np.eye(sys.ninputs))\n", + "ctrl, clsys = ct.create_statefbk_iosystem(sys, K)\n", + "print(ctrl)\n", + "print(clsys)" + ] + }, + { + "cell_type": "markdown", + "id": "5c711b56", + "metadata": {}, + "source": [ + "Note that the name of the second system is `u[0]`. This is a bug in control-0.9.3 that will be fixed in a [future release](https://github.com/python-control/python-control/pull/849)." + ] + }, + { + "cell_type": "markdown", + "id": "84422c3f", + "metadata": {}, + "source": [ + "## System simulations\n", + "\n", + "### Baseline controller\n", + "\n", + "To see how the baseline controller performs, we ask it to track a step change in (xd, ud):" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "b763b91b", + "metadata": {}, + "outputs": [], + "source": [ + "# Plot the step response with respect to the reference input\n", + "tvec = np.linspace(0, Tf, 100)\n", + "xd = x0\n", + "ud = u0\n", + "\n", + "# U = np.hstack([xd, ud])\n", + "U = np.outer(np.hstack([xd, ud]), np.ones_like(tvec))\n", + "time, output = ct.input_output_response(clsys, tvec, U)\n", + "plt.plot(time, output[0], time, output[1])\n", + "plt.plot([time[0], time[-1]], [xd[0], xd[0]], '--');\n", + "plt.legend(['x[0]', 'x[1]']);" + ] + }, + { + "cell_type": "markdown", + "id": "84ee7635", + "metadata": {}, + "source": [ + "### Disturbance rejection\n", + "\n", + "We add a disturbance to the system by modifying ud (since this enters directly at the system input u)." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "1ecbb3a0", + "metadata": {}, + "outputs": [], + "source": [ + "# Resimulate with a disturbance input\n", + "delta = 0.5\n", + "U = np.outer(np.hstack([xd, ud + delta]), np.ones_like(tvec))\n", + "time, output = ct.input_output_response(clsys, tvec, U)\n", + "plt.plot(time, output[0], time, output[1])\n", + "plt.plot([time[0], time[-1]], [xd[0], xd[0]], '--')\n", + "plt.legend(['x[0]', 'x[1]']);" + ] + }, + { + "cell_type": "markdown", + "id": "ea2d1c59", + "metadata": {}, + "source": [ + "We see that this leads to steady state error, since some amount of system error is required to generate the force to offset the disturbance." + ] + }, + { + "cell_type": "markdown", + "id": "84a9e61c", + "metadata": {}, + "source": [ + "### Integral feedback\n", + "\n", + "A standard approach to compensate for constant disturbances is to use integral feedback. To do this, we have to decide what output we want to track and create a new controller with integral feedback.\n", + "\n", + "We do this by creating an \"augmented\" system that includes the dynamics of the process along with the dynamics of the controller (= integrators for the errors that we choose):" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "ee2ecc51", + "metadata": {}, + "outputs": [], + "source": [ + "# Create a controller with integral feedback\n", + "C = np.array([[1, 0]])\n", + "\n", + "# Define an augmented state space for use with LQR\n", + "A_aug = np.block([\n", + " [sys.A, np.zeros((sys.nstates, 1))], \n", + " [C, 0]\n", + "])\n", + "B_aug = np.vstack([sys.B, 0])\n", + "print(\"A =\", A_aug, \"\\nB =\", B_aug)" + ] + }, + { + "cell_type": "markdown", + "id": "463d9b85", + "metadata": {}, + "source": [ + "Now generate an LQR controller for the augmented system:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "3dd3479f", + "metadata": {}, + "outputs": [], + "source": [ + "# Create an LQR controller for the augmented system\n", + "K_aug, _, _ = ct.lqr(\n", + " A_aug, B_aug, np.diag([1, 1, 1]), np.eye(sys.ninputs))\n", + "print(K_aug)" + ] + }, + { + "cell_type": "markdown", + "id": "19bb6592", + "metadata": {}, + "source": [ + "We can think about this gain as `K_aug = [K, ki]` and the resulting contoller becomes\n", + "\n", + "$$\n", + "u = u_\\text{d} - K(x - x_\\text{d}) - k_\\text{i} \\int_0^t (y - y_\\text{d})\\, d\\tau.\n", + "$$" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "e183a822", + "metadata": {}, + "outputs": [], + "source": [ + "# Construct an LQR controller for the system\n", + "integral_ctrl, sys_integral = ct.create_statefbk_iosystem(sys, K_aug, integral_action=C)\n", + "print(integral_ctrl)\n", + "print(sys_integral)\n", + "\n", + "# Resimulate with a disturbance input\n", + "delta = 0.5\n", + "U = np.outer(np.hstack([xd, ud + delta]), np.ones_like(tvec))\n", + "time, output = ct.input_output_response(sys_integral, tvec, U)\n", + "plt.plot(time, output[0], time, output[1])\n", + "plt.plot([time[0], time[-1]], [xd[0], xd[0]], '--')\n", + "plt.legend(['x[0]', 'x[1]']);" + ] + }, + { + "cell_type": "markdown", + "id": "437487da", + "metadata": {}, + "source": [ + "## Things to try\n", + "* Play around with the gains and see whether you can reduce the overshoot (50%!)\n", + "* Try following more complicated trajectories (hint: linear systems are differentially flat...)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "99394ace", + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/examples/cds112-L4b_pvtol-lqr.ipynb b/examples/cds112-L4b_pvtol-lqr.ipynb new file mode 100644 index 000000000..b472429e2 --- /dev/null +++ b/examples/cds112-L4b_pvtol-lqr.ipynb @@ -0,0 +1,355 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "f8bfc15c", + "metadata": {}, + "source": [ + "# PVTOL Linear Quadratic Regulator Example\n", + "\n", + "Richard M. Murray, 25 Jan 2022\n", + "\n", + "This notebook contains an example of LQR control applied to the PVTOL system. It demonstrates how to construct an LQR controller and also the importance of the feedforward component of the controller. A gain scheduled design is also demonstrated." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "c120d65c", + "metadata": {}, + "outputs": [], + "source": [ + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "import control as ct" + ] + }, + { + "cell_type": "markdown", + "id": "77e2ed47", + "metadata": {}, + "source": [ + "## System description\n", + "\n", + "We use the PVTOL dynamics from the textbook, which are contained in the `pvtol` module. The vehicle model is both an I/O system model and a flat system model (for the case when the viscous damping coefficient $c$ is zero).\n", + "\n", + "\n", + "\n", + " \n", + " \n", + "\n", + "
\n", + "$$\n", + "\\begin{aligned}\n", + " m \\ddot x &= F_1 \\cos\\theta - F_2 \\sin\\theta - c \\dot x, \\\\\n", + " m \\ddot y &= F_1 \\sin\\theta + F_2 \\cos\\theta - m g - c \\dot y, \\\\\n", + " J \\ddot \\theta &= r F_1.\n", + "\\end{aligned}\n", + "$$\n", + "
" + ] + }, + { + "cell_type": "markdown", + "id": "0a12fc3d", + "metadata": {}, + "source": [ + "The parameter values for the PVTOL system come from the Caltech ducted fan experiment, shown in the video below (the wing forces are not included in the PVTOL model):" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "7adc6cf1", + "metadata": {}, + "outputs": [], + "source": [ + "from IPython.display import YouTubeVideo\n", + "display(YouTubeVideo('ZFb5kFpgCm4', width=640, height=480))\n", + "\n", + "from pvtol import pvtol, plot_results\n", + "print(pvtol)" + ] + }, + { + "cell_type": "markdown", + "id": "45259984", + "metadata": {}, + "source": [ + "Since we will be creating a linear controller, we need a linear system model. We obtain that model by linearizing the dynamics around an equilibrium point. This can be done in python-control using the `find_eqpt` function. We fix the output of the system to be zero and find the state and inputs that hold us there." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "ea50d7cd", + "metadata": {}, + "outputs": [], + "source": [ + "# Find the equilibrium point corresponding to hover\n", + "xeq, ueq = ct.find_eqpt(pvtol, np.zeros(6), np.zeros(2), y0=np.zeros(6), iy=[0, 1])\n", + "\n", + "print(\"xeq = \", xeq)\n", + "print(\"ueq = \", ueq)\n", + "\n", + "# Get the linearized dynamics\n", + "linsys = pvtol.linearize(xeq, ueq)\n", + "print(linsys)" + ] + }, + { + "cell_type": "markdown", + "id": "7cb8840b", + "metadata": {}, + "source": [ + "## Linear quadratic regulator (LQR) design\n", + "\n", + "Now that we have a linearized model of the system, we can compute a controller using linear quadratic regulator theory. We seek to find the control law that minimizes the function\n", + "\n", + "$$\n", + "J(x(\\cdot), u(\\cdot)) = \\int_0^\\infty x^T(\\tau) Q_x x(\\tau) + u^T(\\tau) Q_u u(\\tau)\\, d\\tau\n", + "$$\n", + "\n", + "The weighting matrices $Q_x \\in \\mathbb{R}^{n \\times n}$ and $Q_u \\in \\mathbb{R}^{m \\times m}$ should be chosen based on the desired performance of the system (tradeoffs in state errors and input magnitudes). See Example 3.5 in OBC for a discussion of how to choose these weights. For now, we just choose identity weights for all states and inputs." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "5cfa1ba7", + "metadata": {}, + "outputs": [], + "source": [ + "# Start with a diagonal weighting\n", + "Qx1 = np.diag([1, 1, 1, 1, 1, 1])\n", + "Qu1 = np.diag([1, 1])\n", + "K, X, E = ct.lqr(linsys, Qx1, Qu1)" + ] + }, + { + "cell_type": "markdown", + "id": "863d07de", + "metadata": {}, + "source": [ + "To create a controller for the system, we need to create an I/O system that takes in the desired trajectory $(x_\\text{d}, u_\\text{d})$ and the current state $x$ and generates the control law\n", + "\n", + "$$\n", + "u = u_\\text{d} - K (x - x_\\text{d})\n", + "$$\n", + "\n", + "The function `create_statefbk_iosystem()` does this (see [documentation](https://python-control.readthedocs.io/en/0.9.3.post2/generated/control.create_statefbk_iosystem.html) for details)." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "5db704e6", + "metadata": {}, + "outputs": [], + "source": [ + "control, pvtol_closed = ct.create_statefbk_iosystem(pvtol, K)\n", + "print(control, \"\\n\")\n", + "print(pvtol_closed)" + ] + }, + { + "cell_type": "markdown", + "id": "bedcb0c0", + "metadata": {}, + "source": [ + "## Closed loop system simulation\n", + "\n", + "We now generate a trajectory for the system and track that trajectory.\n", + "\n", + "For this simple example, we take the system input to be a \"step\" input that moves the system 1 meter to the right. More complex trajectories (eg, using the results from HW #3) could also be used." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "a497aa2c", + "metadata": {}, + "outputs": [], + "source": [ + "# Generate a step response by setting xd, ud\n", + "Tf = 15\n", + "T = np.linspace(0, Tf, 100)\n", + "xd = np.outer(np.array([1, 0, 0, 0, 0, 0]), np.ones_like(T))\n", + "ud = np.outer(ueq, np.ones_like(T))\n", + "ref = np.vstack([xd, ud])\n", + "\n", + "response = ct.input_output_response(pvtol_closed, T, ref, xeq)\n", + "plot_results(response.time, response.states, response.outputs[6:])" + ] + }, + { + "cell_type": "markdown", + "id": "f014e660", + "metadata": {}, + "source": [ + "The limitations of the linear controlller can be seen if we take a larger step, say 10 meters." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "a141f100", + "metadata": {}, + "outputs": [], + "source": [ + "xd = np.outer(np.array([10, 0, 0, 0, 0, 0]), np.ones_like(T))\n", + "ref = np.vstack([xd, ud])\n", + "response = ct.input_output_response(pvtol_closed, T, ref, xeq)\n", + "plot_results(response.time, response.states, response.outputs[6:])" + ] + }, + { + "cell_type": "markdown", + "id": "8adb6ff4", + "metadata": {}, + "source": [ + "We see that the large initial error causes the vehicle to rotate to a very high role angle (almost 1 radian $\\approx 60^\\circ$), at which point the linear model is not very accurate and the controller errors in the $y$ direction get very large.\n", + "\n", + "One way to fix this problem is to change the gains on the controller so that we penalize the $y$ error more and try to keep that error from building up. However, given the fact that we are trying to stabilize a point that is fairly far from our initial condition, it can be difficult to manage the tradesoffs to get good performance.\n", + "\n", + "An alterntaive approach is is to stabilize the system around a trajectory that moves from the initial to final condition. As a very simple approach, we start by using a _nonfeasible_ trajectory that goes from 0 to 10 in 10 seconds." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "a075a0a7", + "metadata": {}, + "outputs": [], + "source": [ + "timepts = np.linspace(0, 15, 100)\n", + "xf = np.array([10, 0, 0, 0, 0, 0])\n", + "xd = np.array([xf/10 * t if t < 10 else xf for t in timepts]).T\n", + "ud = np.outer(ueq, np.ones_like(timepts))\n", + "ref = np.vstack([xd, ud])\n", + "response = ct.input_output_response(pvtol_closed, timepts, ref, xeq)\n", + "plot_results(response.time, response.states, response.outputs[6:])" + ] + }, + { + "cell_type": "markdown", + "id": "73d74c23", + "metadata": {}, + "source": [ + "Note that even though the trajectory was not feasible (it asked the system to move sideways while remaining pointed in the vertical ($\\theta = 0$) direction, the controller has very good performance." + ] + }, + { + "cell_type": "markdown", + "id": "b7539806", + "metadata": {}, + "source": [ + "## Gain scheduled controller design" + ] + }, + { + "cell_type": "markdown", + "id": "23d7e21c", + "metadata": {}, + "source": [ + "Another challenge in using linearized models is that they are only accurate near the point in which they were computed. For the PVTOL system, this can be a problem if the roll angle $\\theta$ gets large, since in this case the linearization changes significantly (the forces $F_1$ and $F_2$ are no longer aligned with the horizontal and vertical axes).\n", + "\n", + "One approach to solving this problem is to compute different gains at different points in the operating envelope of the system. The code below illustrates the use of gain scheduling by modifying the system drag to a very high value (so that the vehicle must roll to a large angle in order to move sideways against the high drag) and then demonstrates the difficulty in obtaining good performance while trying to track the (still infeasible) trajectory." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "4590b138", + "metadata": {}, + "outputs": [], + "source": [ + "# Increase the viscous drag to force larger angles\n", + "linsys = pvtol.linearize(xeq, ueq, params={'c': 20})\n", + "\n", + "# Change to physically motivated gains\n", + "Qx3 = np.diag([10, 100, (180/np.pi) / 5, 0, 0, 0])\n", + "Qu3 = np.diag([10, 1])\n", + "\n", + "# Compute a single gain around hover\n", + "K, X, E = ct.lqr(linsys, Qx3, Qu3)\n", + "control, pvtol_closed = ct.create_statefbk_iosystem(pvtol, K)\n", + "\n", + "# Simulate the response trying to track horizontal trajectory\n", + "response = ct.input_output_response(pvtol_closed, T, ref, xeq, params={'c': 20})\n", + "plot_results(response.time, response.states, response.outputs[6:])" + ] + }, + { + "cell_type": "markdown", + "id": "9e01104a", + "metadata": {}, + "source": [ + "Note that the angle $\\theta$ is quite large (-0.5 rad) during the initla portion of the trajectory, and at this angle (~30$^\\circ$) it is difficult to maintain our altitude while moving sideways. This happens in large part becuase the system model that we used was linearized about the $\\theta = 0$ configuration.\n", + "\n", + "This problem can be addressed by designing a gain scheduled controller in which we compute different system gains at different roll angles. We carry out those computations below, using the `create_statefbk_iosystem` function, but now passing a set of gains and points instead of just a single gain.\n", + "\n", + "(Note: there is a bug in control-0.9.3 that requires gain scheduling to be done on two or more variables, so we also schedule on the horizontal velocity $\\dot x$, even though that doesn't matter that much here.)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "e427459f", + "metadata": {}, + "outputs": [], + "source": [ + "import itertools\n", + "import math\n", + "\n", + "# Set up points around which to linearize (control-0.9.3: must be 2D or greater)\n", + "angles = np.linspace(-math.pi/3, math.pi/3, 10)\n", + "speeds = np.linspace(-10, 10, 3)\n", + "points = list(itertools.product(angles, speeds))\n", + "\n", + "# Compute the gains at each design point\n", + "gains = []\n", + "for point in points:\n", + " # Compute the state that we want to linearize about\n", + " xgs = xeq.copy()\n", + " xgs[2], xgs[3] = point[0], point[1]\n", + " \n", + " # Linearize the system and compute the LQR gains\n", + " linsys = pvtol.linearize(xgs, ueq, params={'c': 20})\n", + " K, X, E = ct.lqr(linsys, Qx3, Qu3)\n", + " gains.append(K)\n", + " \n", + "# Create a gain scheduled controller off of the current state\n", + "control, pvtol_closed = ct.create_statefbk_iosystem(\n", + " pvtol, (gains, points), gainsched_indices=['x2', 'x3'])\n", + "\n", + "# Simulate the response\n", + "response = ct.input_output_response(pvtol_closed, T, ref, xeq, params={'c': 20})\n", + "plot_results(response.time, response.states, response.outputs[6:])" + ] + }, + { + "cell_type": "markdown", + "id": "7399db70", + "metadata": {}, + "source": [ + "We see that the response is much better, with about 10X less error in the $y$ coordinate." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "c8021347", + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/examples/cds112-L5_rhc-doubleint.ipynb b/examples/cds112-L5_rhc-doubleint.ipynb new file mode 100644 index 000000000..2a311fc46 --- /dev/null +++ b/examples/cds112-L5_rhc-doubleint.ipynb @@ -0,0 +1,616 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "9d41c333", + "metadata": {}, + "source": [ + "# RHC Example: Double integrator with bounded input\n", + "\n", + "Richard M. Murray, 3 Feb 2022 (updated 29 Jan 2023)\n", + "\n", + "To illustrate the implementation of a receding horizon controller, we\n", + "consider a linear system corresponding to a double integrator with\n", + "bounded input:\n", + "\n", + "$$\n", + " \\dot x = \\begin{bmatrix} 0 & 1 \\\\ 0 & 0 \\end{bmatrix} x + \\begin{bmatrix} 0 \\\\ 1 \\end{bmatrix} \\text{clip}(u)\n", + " \\qquad\\text{where}\\qquad\n", + " \\text{clip}(u) = \\begin{cases}\n", + " -1 & u < -1, \\\\\n", + " u & -1 \\leq u \\leq 1, \\\\\n", + " 1 & u > 1.\n", + " \\end{cases}\n", + "$$\n", + "\n", + "We implement a model predictive controller by choosing\n", + "\n", + "$$\n", + " Q_x = \\begin{bmatrix} 1 & 0 \\\\ 0 & 0 \\end{bmatrix}, \\qquad\n", + " Q_u = \\begin{bmatrix} 1 \\end{bmatrix}, \\qquad\n", + " P_1 = \\begin{bmatrix} 0.1 & 0 \\\\ 0 & 0.1 \\end{bmatrix}.\n", + "$$" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "4fe0af7f", + "metadata": {}, + "outputs": [], + "source": [ + "import numpy as np\n", + "import scipy as sp\n", + "import matplotlib.pyplot as plt\n", + "import control as ct\n", + "import control.optimal as opt\n", + "import control.flatsys as fs\n", + "import time" + ] + }, + { + "cell_type": "markdown", + "id": "4c695f81", + "metadata": {}, + "source": [ + "## System definition\n", + "\n", + "The system is defined as a double integrator with bounded input." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "5c01f571", + "metadata": {}, + "outputs": [], + "source": [ + "def doubleint_update(t, x, u, params):\n", + " # Get the parameters\n", + " lb = params.get('lb', -1)\n", + " ub = params.get('ub', 1)\n", + " assert lb < ub\n", + "\n", + " # bound the input\n", + " u_clip = np.clip(u, lb, ub)\n", + "\n", + " return np.array([x[1], u_clip[0]])\n", + "\n", + "proc = ct.NonlinearIOSystem(\n", + " doubleint_update, None, name=\"double integrator\",\n", + " inputs = ['u'], outputs=['x[0]', 'x[1]'], states=2)" + ] + }, + { + "cell_type": "markdown", + "id": "6c2f0d00", + "metadata": {}, + "source": [ + "## Receding horizon controller\n", + "\n", + "To define a receding horizon controller, we create an optimal control problem (using the `OptimalControlProblem` class) and then use the `compute_trajectory` method to solve for the trajectory from the current state.\n", + "\n", + "We start by defining the cost functions, which consists of a trajectory cost and a terminal cost:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "a501efef", + "metadata": {}, + "outputs": [], + "source": [ + "Qx = np.diag([1, 0]) # state cost\n", + "Qu = np.diag([1]) # input cost\n", + "traj_cost=opt.quadratic_cost(proc, Qx, Qu)\n", + "\n", + "P1 = np.diag([0.1, 0.1]) # terminal cost\n", + "term_cost = opt.quadratic_cost(proc, P1, None)" + ] + }, + { + "cell_type": "markdown", + "id": "c5470629", + "metadata": {}, + "source": [ + "We also set up a set of constraints the correspond to the fact that the input should have magnitude 1. This can be done using either the [`input_range_constraint`](https://python-control.readthedocs.io/en/0.9.3.post2/generated/control.optimal.input_range_constraint.html) function or the [`input_poly_constraint`](https://python-control.readthedocs.io/en/0.9.3.post2/generated/control.optimal.input_poly_constraint.html) function." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "cb4c511a", + "metadata": {}, + "outputs": [], + "source": [ + "traj_constraints = opt.input_range_constraint(proc, -1, 1)\n", + "# traj_constraints = opt.input_poly_constraint(\n", + "# proc, np.array([[1], [-1]]), np.array([1, 1]))" + ] + }, + { + "cell_type": "markdown", + "id": "a5568374", + "metadata": {}, + "source": [ + "We define the horizon for evaluating finite-time, optimal control by setting up a set of time points across the designed horizon. The input will be computed at each time point." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "9edec673", + "metadata": {}, + "outputs": [], + "source": [ + "Th = 5\n", + "timepts = np.linspace(0, Th, 11, endpoint=True)\n", + "print(timepts)" + ] + }, + { + "cell_type": "markdown", + "id": "cb8fcecc", + "metadata": {}, + "source": [ + "Finally, we define the optimal control problem that we want to solve (without actually solving it)." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "e9f31be6", + "metadata": {}, + "outputs": [], + "source": [ + "# Set up the optimal control problem\n", + "ocp = opt.OptimalControlProblem(\n", + " proc, timepts, traj_cost,\n", + " terminal_cost=term_cost,\n", + " trajectory_constraints=traj_constraints,\n", + " # terminal_constraints=term_constraints,\n", + ")" + ] + }, + { + "cell_type": "markdown", + "id": "ee9a39dd", + "metadata": {}, + "source": [ + "To make sure that the problem is properly defined, we solve the problem for a specific initial condition. We also compare the amount of time required to solve the problem from a \"cold start\" (no initial guess) versus a \"warm start\" (use the previous solution, shifted forward on point in time)." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "887295eb", + "metadata": {}, + "outputs": [], + "source": [ + "X0 = np.array([1, 1])\n", + "\n", + "start_time = time.process_time()\n", + "res = ocp.compute_trajectory(X0, initial_guess=0, return_states=True)\n", + "stop_time = time.process_time()\n", + "print(f'* Cold start: {stop_time-start_time:.3} sec')\n", + "\n", + "# Resolve using previous solution (shifted forward) as initial guess to compare timing\n", + "start_time = time.process_time()\n", + "u = res.inputs\n", + "u_shift = np.hstack([u[:, 1:], u[:, -1:]])\n", + "ocp.compute_trajectory(X0, initial_guess=u_shift, print_summary=False)\n", + "stop_time = time.process_time()\n", + "print(f'* Warm start: {stop_time-start_time:.3} sec')" + ] + }, + { + "cell_type": "markdown", + "id": "115dec26", + "metadata": {}, + "source": [ + "(In this case the timing is not that different since the system is very simple.)\n", + "\n", + "Plotting the result, we see that the solution is properly computed." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "4b98e773", + "metadata": {}, + "outputs": [], + "source": [ + "plt.plot(res.time, res.states[0], 'k-', label='$x_1$')\n", + "plt.plot(res.time, res.inputs[0], 'b-', label='u')\n", + "plt.xlabel('Time [s]')\n", + "plt.ylabel('$x_1$, $u$')\n", + "plt.legend();" + ] + }, + { + "cell_type": "markdown", + "id": "0e85981a", + "metadata": {}, + "source": [ + "We implement the receding horicon controller using a function that we can with different versions of the problem." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "eb2e8126", + "metadata": {}, + "outputs": [], + "source": [ + "# Create a figure to use for plotting\n", + "def run_rhc_and_plot(\n", + " proc, ocp, X0, Tf, print_summary=False, verbose=False, ax=None, plot=True): \n", + " # Start at the initial point\n", + " x = X0\n", + " \n", + " # Initialize the axes\n", + " if plot and ax is None:\n", + " ax = plt.axes()\n", + " \n", + " # Initialize arrays to store the final trajectory\n", + " time_, inputs_, outputs_, states_ = [], [], [], []\n", + " \n", + " # Generate the individual traces for the receding horizon control\n", + " for t in ocp.timepts:\n", + " # Compute the optimal trajectory over the horizon\n", + " start_time = time.process_time()\n", + " res = ocp.compute_trajectory(x, print_summary=print_summary)\n", + " if verbose:\n", + " print(f\"{t=}: comp time = {time.process_time() - start_time:0.3}\")\n", + "\n", + " # Simulate the system for the update time, with higher res for plotting\n", + " tvec = np.linspace(0, res.time[1], 20)\n", + " inputs = res.inputs[:, 0] + np.outer(\n", + " (res.inputs[:, 1] - res.inputs[:, 0]) / (tvec[-1] - tvec[0]), tvec)\n", + " soln = ct.input_output_response(proc, tvec, inputs, x)\n", + " \n", + " # Save this segment for later use (final point will appear in next segment)\n", + " time_.append(t + soln.time[:-1])\n", + " inputs_.append(soln.inputs[:, :-1])\n", + " outputs_.append(soln.outputs[:, :-1])\n", + " states_.append(soln.states[:, :-1])\n", + "\n", + " if plot:\n", + " # Plot the results over the full horizon\n", + " h3, = ax.plot(t + res.time, res.states[0], 'k--', linewidth=0.5)\n", + " ax.plot(t + res.time, res.inputs[0], 'b--', linewidth=0.5)\n", + "\n", + " # Plot the results for this time segment\n", + " h1, = ax.plot(t + soln.time, soln.states[0], 'k-')\n", + " h2, = ax.plot(t + soln.time, soln.inputs[0], 'b-')\n", + " \n", + " # Update the state to use for the next time point\n", + " x = soln.states[:, -1]\n", + " \n", + " # Append the final point to the response\n", + " time_.append(t + soln.time[-1:])\n", + " inputs_.append(soln.inputs[:, -1:])\n", + " outputs_.append(soln.outputs[:, -1:])\n", + " states_.append(soln.states[:, -1:])\n", + "\n", + " # Label the plot\n", + " if plot:\n", + " # Adjust the limits for consistency\n", + " ax.set_ylim([-4, 3.5])\n", + "\n", + " # Add reference line for input lower bound\n", + " ax.plot([0, 7], [-1, -1], 'k--', linewidth=0.666)\n", + "\n", + " # Label the results\n", + " ax.set_xlabel(\"Time $t$ [sec]\")\n", + " ax.set_ylabel(\"State $x_1$, input $u$\")\n", + " ax.legend(\n", + " [h1, h2, h3], ['$x_1$', '$u$', 'prediction'],\n", + " loc='lower right', labelspacing=0)\n", + " plt.tight_layout()\n", + " \n", + " # Append\n", + " return ct.TimeResponseData(\n", + " np.hstack(time_), np.hstack(outputs_), np.hstack(states_), np.hstack(inputs_))" + ] + }, + { + "cell_type": "markdown", + "id": "be13e00a", + "metadata": {}, + "source": [ + "Finally, we call the controller and plot the response. The solid lines show the portions of the trajectory that we follow. The dashed lines are the trajectory over the full horizon, but which are not followed since we update the computation at each time step. (To get rid of the statistics of each optimization call, use `print_summary=False`.)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "305a1127", + "metadata": {}, + "outputs": [], + "source": [ + "Tf = 10\n", + "rhc_resp = run_rhc_and_plot(proc, ocp, X0, Tf, verbose=True, print_summary=False)\n", + "print(f\"xf = {rhc_resp.states[:, -1]}\")" + ] + }, + { + "cell_type": "markdown", + "id": "6005bfb3", + "metadata": {}, + "source": [ + "## RHC vs LQR vs LQR terminal cost\n", + "\n", + "In the example above, we used a receding horizon controller with the terminal cost as $P_1 = \\text{diag}(0.1, 0.1)$. An alternative is to set the terminal cost to be the LQR terminal cost that goes along with the trajectory cost, which then provides a \"cost to go\" that matches the LQR \"cost to go\" (but keeping in mind that the LQR controller does not necessarily respect the constraints).\n", + "\n", + "The following code compares the original RHC formulation with a receding horizon controller using an LQR terminal cost versus an LQR controller." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "ea2de1f3", + "metadata": {}, + "outputs": [], + "source": [ + "# Get the LQR solution\n", + "K, P_lqr, E = ct.lqr(proc.linearize(0, 0), Qx, Qu)\n", + "print(f\"P_lqr = \\n{P_lqr}\")\n", + "\n", + "# Create an LQR controller (and run it)\n", + "lqr_ctrl, lqr_clsys = ct.create_statefbk_iosystem(proc, K)\n", + "lqr_resp = ct.input_output_response(lqr_clsys, rhc_resp.time, 0, X0)\n", + "\n", + "# Create a new optimal control problem using the LQR terminal cost\n", + "# (need use more refined time grid as well, to approximate LQR rate)\n", + "lqr_timepts = np.linspace(0, Th, 25, endpoint=True)\n", + "lqr_term_cost=opt.quadratic_cost(proc, P_lqr, None)\n", + "ocp_lqr = opt.OptimalControlProblem(\n", + " proc, lqr_timepts, traj_cost, terminal_cost=lqr_term_cost,\n", + " trajectory_constraints=traj_constraints,\n", + ")\n", + "\n", + "# Create the response for the new controller\n", + "rhc_lqr_resp = run_rhc_and_plot(\n", + " proc, ocp_lqr, X0, 10, plot=False, print_summary=False)\n", + "\n", + "# Plot the different responses to compare them\n", + "fig, ax = plt.subplots(2, 1)\n", + "ax[0].plot(rhc_resp.time, rhc_resp.states[0], label='RHC + P_1')\n", + "ax[0].plot(rhc_lqr_resp.time, rhc_lqr_resp.states[0], '--', label='RHC + P_lqr')\n", + "ax[0].plot(lqr_resp.time, lqr_resp.outputs[0], ':', label='LQR')\n", + "ax[0].legend()\n", + "\n", + "ax[1].plot(rhc_resp.time, rhc_resp.inputs[0], label='RHC + P_1')\n", + "ax[1].plot(rhc_lqr_resp.time, rhc_lqr_resp.inputs[0], '--', label='RHC + P_lqr')\n", + "ax[1].plot(lqr_resp.time, lqr_resp.outputs[2], ':', label='LQR')" + ] + }, + { + "cell_type": "markdown", + "id": "9497530b", + "metadata": {}, + "source": [ + "## Discrete time RHC\n", + "\n", + "Many receding horizon control problems are solved based on a discrete time model. We show here how to implement this for a \"double integrator\" system, which in discrete time has the form\n", + "\n", + "$$\n", + " x[k+1] = \\begin{bmatrix} 1 & 1 \\\\ 0 & 1 \\end{bmatrix} x[k] + \\begin{bmatrix} 0 \\\\ 1 \\end{bmatrix} \\text{clip}(u[k])\n", + "$$\n" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "ae7cefa5", + "metadata": {}, + "outputs": [], + "source": [ + "#\n", + "# System definition\n", + "#\n", + "\n", + "def doubleint_update(t, x, u, params):\n", + " # Get the parameters\n", + " lb = params.get('lb', -1)\n", + " ub = params.get('ub', 1)\n", + " assert lb < ub\n", + "\n", + " # Get the sampling time\n", + " dt = params.get('dt', 1)\n", + "\n", + " # bound the input\n", + " u_clip = np.clip(u, lb, ub)\n", + "\n", + " return np.array([x[0] + dt * x[1], x[1] + dt * u_clip[0]])\n", + "\n", + "proc = ct.NonlinearIOSystem(\n", + " doubleint_update, None, name=\"double integrator\",\n", + " inputs = ['u'], outputs=['x[0]', 'x[1]'], states=2,\n", + " params={'dt': 1}, dt=1)\n", + "\n", + "#\n", + "# Linear quadratic regulator\n", + "#\n", + "\n", + "# Define the cost functions to use\n", + "Qx = np.diag([1, 0]) # state cost\n", + "Qu = np.diag([1]) # input cost\n", + "P1 = np.diag([0.1, 0.1]) # terminal cost\n", + "\n", + "# Get the LQR solution\n", + "K, P, E = ct.dlqr(proc.linearize(0, 0), Qx, Qu)\n", + "\n", + "# Test out the LQR controller, with no constraints\n", + "linsys = proc.linearize(0, 0)\n", + "clsys_lin = ct.ss(linsys.A - linsys.B @ K, linsys.B, linsys.C, 0, dt=proc.dt)\n", + "\n", + "X0 = np.array([2, 1]) # initial conditions\n", + "Tf = 10 # simulation time\n", + "res = ct.initial_response(clsys_lin, Tf, X0=X0)\n", + "\n", + "# Plot the results\n", + "plt.figure(1); plt.clf(); ax = plt.axes()\n", + "ax.plot(res.time, res.states[0], 'k-', label='$x_1$')\n", + "ax.plot(res.time, (-K @ res.states)[0], 'b-', label='$u$')\n", + "\n", + "# Test out the LQR controller with constraints\n", + "clsys_lqr = ct.feedback(proc, -K, 1)\n", + "tvec = np.arange(0, Tf, proc.dt)\n", + "res_lqr_const = ct.input_output_response(clsys_lqr, tvec, 0, X0)\n", + "\n", + "# Plot the results\n", + "ax.plot(res_lqr_const.time, res_lqr_const.states[0], 'k--', label='constrained')\n", + "ax.plot(res_lqr_const.time, (-K @ res_lqr_const.states)[0], 'b--')\n", + "ax.plot([0, 7], [-1, -1], 'k--', linewidth=0.75)\n", + "\n", + "# Adjust the limits for consistency\n", + "ax.set_ylim([-4, 3.5])\n", + "\n", + "# Label the results\n", + "ax.set_xlabel(\"Time $t$ [sec]\")\n", + "ax.set_ylabel(\"State $x_1$, input $u$\")\n", + "ax.legend(loc='lower right', labelspacing=0)\n", + "plt.title(\"Linearized LQR response from x0\")" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "13cfc5d8", + "metadata": {}, + "outputs": [], + "source": [ + "#\n", + "# Receding horizon controller\n", + "#\n", + "\n", + "# Create the constraints\n", + "traj_constraints = opt.input_range_constraint(proc, -1, 1)\n", + "term_constraints = opt.state_range_constraint(proc, [0, 0], [0, 0])\n", + "\n", + "# Define the optimal control problem we want to solve\n", + "T = 5\n", + "timepts = np.arange(0, T * proc.dt, proc.dt)\n", + "\n", + "# Set up the optimal control problems\n", + "ocp_orig = opt.OptimalControlProblem(\n", + " proc, timepts,\n", + " opt.quadratic_cost(proc, Qx, Qu),\n", + " trajectory_constraints=traj_constraints,\n", + " terminal_cost=opt.quadratic_cost(proc, P1, None),\n", + ")\n", + "\n", + "ocp_lqr = opt.OptimalControlProblem(\n", + " proc, timepts,\n", + " opt.quadratic_cost(proc, Qx, Qu),\n", + " trajectory_constraints=traj_constraints,\n", + " terminal_cost=opt.quadratic_cost(proc, P, None),\n", + ")\n", + "\n", + "ocp_low = opt.OptimalControlProblem(\n", + " proc, timepts,\n", + " opt.quadratic_cost(proc, Qx, Qu),\n", + " trajectory_constraints=traj_constraints,\n", + " terminal_cost=opt.quadratic_cost(proc, P/10, None),\n", + ")\n", + "\n", + "ocp_high = opt.OptimalControlProblem(\n", + " proc, timepts,\n", + " opt.quadratic_cost(proc, Qx, Qu),\n", + " trajectory_constraints=traj_constraints,\n", + " terminal_cost=opt.quadratic_cost(proc, P*10, None),\n", + ")\n", + "weight_list = [P1, P, P/10, P*10]\n", + "ocp_list = [ocp_orig, ocp_lqr, ocp_low, ocp_high]\n", + "\n", + "# Do a test run to figure out how long computation takes\n", + "start_time = time.process_time()\n", + "ocp_lqr.compute_trajectory(X0)\n", + "stop_time = time.process_time()\n", + "print(\"* Process time: %0.2g s\\n\" % (stop_time - start_time))\n", + "\n", + "# Create a figure to use for plotting\n", + "fig, [[ax_orig, ax_lqr], [ax_low, ax_high]] = plt.subplots(2, 2)\n", + "ax_list = [ax_orig, ax_lqr, ax_low, ax_high]\n", + "ax_name = ['orig', 'lqr', 'low', 'high']\n", + "\n", + "# Generate the individual traces for the receding horizon control\n", + "for ocp, ax, name, Pf in zip(ocp_list, ax_list, ax_name, weight_list):\n", + " x, t = X0, 0\n", + " for i in np.arange(0, Tf, proc.dt):\n", + " # Calculate the optimal trajectory\n", + " res = ocp.compute_trajectory(x, print_summary=False)\n", + " soln = ct.input_output_response(proc, res.time, res.inputs, x)\n", + "\n", + " # Plot the results for this time instant\n", + " ax.plot(res.time[:2] + t, res.inputs[0, :2], 'b-', linewidth=1)\n", + " ax.plot(res.time[:2] + t, soln.outputs[0, :2], 'k-', linewidth=1)\n", + " \n", + " # Plot the results projected forward\n", + " ax.plot(res.time[1:] + t, res.inputs[0, 1:], 'b--', linewidth=0.75)\n", + " ax.plot(res.time[1:] + t, soln.outputs[0, 1:], 'k--', linewidth=0.75)\n", + " \n", + " # Update the state to use for the next time point\n", + " x = soln.states[:, 1]\n", + " t += proc.dt\n", + "\n", + " # Adjust the limits for consistency\n", + " ax.set_ylim([-1.5, 3.5])\n", + "\n", + " # Label the results\n", + " ax.set_xlabel(\"Time $t$ [sec]\")\n", + " ax.set_ylabel(\"State $x_1$, input $u$\")\n", + " ax.set_title(f\"MPC response for {name}\")\n", + " plt.tight_layout()" + ] + }, + { + "cell_type": "markdown", + "id": "015dc953", + "metadata": {}, + "source": [ + "We can also implement a receding horizon controller for a discrete time system using `opt.create_mpc_iosystem`. This creates a controller that accepts the current state as the input and generates the control to apply from that state." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "4f8bb594", + "metadata": {}, + "outputs": [], + "source": [ + "# Construct using create_mpc_iosystem\n", + "clsys = opt.create_mpc_iosystem(\n", + " proc, timepts, opt.quadratic_cost(proc, Qx, Qu), traj_constraints,\n", + " terminal_cost=opt.quadratic_cost(proc, P1, None), \n", + ")\n", + "print(clsys)" + ] + }, + { + "cell_type": "markdown", + "id": "f1b08fb4", + "metadata": {}, + "source": [ + "(This function needs some work to be more user-friendly, e.g. renaming of the inputs and outputs.)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "d2afd287", + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/examples/cds112-L6_stochastic-linsys.ipynb b/examples/cds112-L6_stochastic-linsys.ipynb new file mode 100644 index 000000000..3efc158cb --- /dev/null +++ b/examples/cds112-L6_stochastic-linsys.ipynb @@ -0,0 +1,328 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "03aa22e7", + "metadata": {}, + "source": [ + "# Stochastic Response\n", + "Richard M. Murray, 6 Feb 2022 (updated 9 Feb 2023)\n", + "\n", + "This notebook illustrates the implementation of random processes and stochastic response. We focus on a system of the form\n", + "$$\n", + " \\dot X = A X + F V \\qquad X \\in {\\mathbb R}^n\n", + "$$\n", + "\n", + "where $V$ is a white noise process and the system is a first order linear system." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "902af902", + "metadata": {}, + "outputs": [], + "source": [ + "import numpy as np\n", + "import scipy as sp\n", + "import matplotlib.pyplot as plt\n", + "import control as ct\n", + "from math import sqrt, exp" + ] + }, + { + "cell_type": "markdown", + "id": "77d58303", + "metadata": {}, + "source": [ + "## First order linear system\n", + "\n", + "We start by looking at the stochastic response for a first order linear system\n", + "\n", + "$$\n", + "\\begin{gathered}\n", + " \\dot X = -a X + V, \\qquad Y = C X \\\\\n", + " \\mathbb{E}(V) = 0, \\quad \\mathbb{E}(V^\\mathsf{T}(t_1) V(t_2)) = 0.1\\, \\delta(t_1 - t_2)\n", + "\\end{gathered}\n", + "$$" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "60192a8c", + "metadata": {}, + "outputs": [], + "source": [ + "# First order system\n", + "a = 1\n", + "c = 1\n", + "sys = ct.tf(c, [1, a])\n", + "\n", + "# Create the time vector that we want to use\n", + "Tf = 5\n", + "T = np.linspace(0, Tf, 1000)\n", + "dt = T[1] - T[0]\n", + "\n", + "# Create the basis for a white noise signal\n", + "# Note: use sqrt(Q/dt) for desired covariance\n", + "Q = np.array([[0.1]])\n", + "# V = np.random.normal(0, sqrt(Q[0,0]/dt), T.shape)\n", + "V = ct.white_noise(T, Q)\n", + "\n", + "plt.plot(T, V[0])\n", + "plt.xlabel('Time [s]')\n", + "plt.ylabel('$V$');" + ] + }, + { + "cell_type": "markdown", + "id": "b4629e2c", + "metadata": {}, + "source": [ + "Note that the magnitude of the signal seems to be much larger than $Q$. This is because we have a Guassian process $\\implies$ the signal consists of a sequence of \"impulse-like\" functions that have magnitude that increases with the time step $dt$ as $1/\\sqrt{dt}$ (this gives covariance $\\mathbb{E}(V(t_1) V^T(t_2)) = Q \\delta(t_2 - t_1)$." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "23319dc6", + "metadata": {}, + "outputs": [], + "source": [ + "# Calculate the sample properties and make sure they match\n", + "print(\"mean(V) [0.0] = \", np.mean(V))\n", + "print(\"cov(V) * dt [%0.3g] = \" % Q, np.round(np.cov(V), decimals=3) * dt)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "2bdaaccf", + "metadata": {}, + "outputs": [], + "source": [ + "# Response of the first order system\n", + "# Scale white noise by sqrt(dt) to account for impulse\n", + "T, Y = ct.forced_response(sys, T, V)\n", + "plt.plot(T, Y)\n", + "plt.xlabel('Time [s]')\n", + "plt.ylabel('$Y$');" + ] + }, + { + "cell_type": "markdown", + "id": "ead0232e", + "metadata": {}, + "source": [ + "This is a first order system, and so we can use the calculation from the course\n", + "notes to compute the analytical correlation function and compare this to the \n", + "sampled data:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "d31ce324", + "metadata": {}, + "outputs": [], + "source": [ + "# Compare static properties to what we expect analytically\n", + "def r(tau):\n", + " return c**2 * Q / (2 * a) * exp(-a * abs(tau))\n", + " \n", + "print(\"* mean(Y) [%0.3g] = %0.3g\" % (0, np.mean(Y).item()))\n", + "print(\"* cov(Y) [%0.3g] = %0.3g\" % (r(0).item(), np.cov(Y).item()))" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "1cf5a4b1", + "metadata": {}, + "outputs": [], + "source": [ + "# Correlation function for the input\n", + "# Scale by dt to take time step into account\n", + "# r_V = sp.signal.correlate(V, V) * dt / Tf\n", + "# tau = sp.signal.correlation_lags(len(V), len(V)) * dt\n", + "tau, r_V = ct.correlation(T, V)\n", + "\n", + "plt.plot(tau, r_V, 'r-')\n", + "plt.xlabel(r'$\\tau$')\n", + "plt.ylabel(r'$r_V(\\tau)$');" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "62af90a4", + "metadata": {}, + "outputs": [], + "source": [ + "# Correlation function for the output\n", + "# r_Y = sp.signal.correlate(Y, Y) * dt / Tf\n", + "# tau = sp.signal.correlation_lags(len(Y), len(Y)) * dt\n", + "tau, r_Y = ct.correlation(T, Y)\n", + "plt.plot(tau, r_Y)\n", + "plt.xlabel(r'$\\tau$')\n", + "plt.ylabel(r'$r_Y(\\tau)$')\n", + "\n", + "# Compare to the analytical answer\n", + "plt.plot(tau, [r(t)[0, 0] for t in tau], 'k--');" + ] + }, + { + "cell_type": "markdown", + "id": "2a2785e9", + "metadata": {}, + "source": [ + "The analytical curve may or may not line up that well with the correlation function based on the sample. Try running the code again from the top to see how things change based on the specific random sequence chosen at the start.\n", + "\n", + "Note: the _right_ way to compute the correlation function would be to run a lot of different samples of white noise filtered through the system dynamics and compute $R(t_1, t_2)$ across those samples." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "bd5dfc75", + "metadata": {}, + "outputs": [], + "source": [ + "# As a crude approximation, compute the average correlation\n", + "r_avg = np.zeros_like(r_Y)\n", + "for i in range(100):\n", + " V = ct.white_noise(T, Q)\n", + " _, Y = ct.forced_response(sys, T, V)\n", + " tau, r_Y = ct.correlation(T, Y)\n", + " r_avg = r_avg + r_Y\n", + "r_avg = r_avg / i\n", + "plt.plot(tau, r_avg)\n", + "plt.xlabel(r'$\\tau$')\n", + "plt.ylabel(r'$r_Y(\\tau)$')\n", + "\n", + "# Compare to the analytical answer\n", + "plt.plot(tau, [r(t)[0, 0] for t in tau], 'k--');" + ] + }, + { + "cell_type": "markdown", + "id": "f07ec584", + "metadata": {}, + "source": [ + "## Dryden gust model\n", + "\n", + "Friedland, _Control Systems Design_, Example 10B\n", + "\n", + "Based on experimental data, the power spectral density for the vertical component of random wind velocity in turbulent air can be modeled as\n", + "$$\n", + "S(\\omega) = \\sigma_\\text{z}^2 T \\frac{1 + 3 (\\omega T)^2}{[1 + (\\omega T)^2]^2},\n", + "$$\n", + "where $\\sigma_\\text{z}$ and $T$ are parameters that depend on the wind characteristics.\n", + "\n", + "This power spectral density can be modeled using white noise by running it through a linear system with transfer fucntion\n", + "$$\n", + "H(s) = \\frac{1 + \\sqrt{3} T}{(1 + T s)^2}.\n", + "$$\n", + "A state space realization for this transfer function is given by\n", + "$$\n", + "\\begin{aligned}\n", + " \\dot X &= \\begin{bmatrix} 0 & 1 \\\\ -\\frac{1}{T^2} & -\\frac{2}{T} \\end{bmatrix} X \n", + " + \\begin{bmatrix} 0 \\\\ 1 \\end{bmatrix} V \\\\\n", + " Y &= \\begin{bmatrix} \\frac{1}{T^2} & \\frac{\\sqrt{3}}{T} \\end{bmatrix}\n", + " \\end{aligned}\n", + "$$" + ] + }, + { + "cell_type": "markdown", + "id": "d09fc03a", + "metadata": {}, + "source": [ + "To create a disturbance signal with the characteristics of the Dryden gust model, we create a linear system with the given parameters and computing the input/output response to white noise:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "8df16a23", + "metadata": {}, + "outputs": [], + "source": [ + "sigma_z = 1\n", + "T = 1\n", + "filter = ct.ss([[0, 1], [-1/T**2, -2/T]], [[0], [1]], [[1/T**2, sqrt(3)/T]], 0)\n", + "\n", + "timepts = np.linspace(0, 10, 1000)\n", + "V = ct.white_noise(timepts, sigma_z**2)\n", + "resp = ct.input_output_response(filter, timepts, V)\n", + "\n", + "plt.plot(resp.time, resp.outputs);" + ] + }, + { + "cell_type": "markdown", + "id": "4d6604ee", + "metadata": {}, + "source": [ + "We can compute the correlation function and power spectral density to confirm that we match the desired characteristics:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "febc8b80", + "metadata": {}, + "outputs": [], + "source": [ + "# Compute the correlation function\n", + "tau, R = ct.correlation(resp.time, resp.outputs)\n", + "\n", + "# Analytical expression for the correlation function (see Friedland)\n", + "def dryden_corrfcn(tau, sigma_z=1, T=1):\n", + " return sigma_z**2 * np.exp(-np.abs(tau)/T) * (1- np.abs(tau)/(2*T))\n", + "\n", + "# Plot the correlation function\n", + "fig, axs = plt.subplots(1, 2)\n", + "axs[0].plot(tau, R)\n", + "axs[0].plot(tau, dryden_corrfcn(tau))\n", + "axs[0].set_xlabel(r\"$\\tau$\")\n", + "axs[0].set_ylabel(r\"$r(\\tau)$\")\n", + "axs[0].set_title(\"Correlation function\")\n", + "\n", + "# Compute the power spectral density\n", + "dt = timepts[1] - timepts[0]\n", + "S = sp.fft.rfft(R) * dt * 2 # rfft returns omega >= 0 => muliple mag by 2\n", + "omega = sp.fft.rfftfreq(R.size, dt)\n", + "\n", + "# Analytical expression for the correlation function (see Friedland)\n", + "def dryden_psd(omega, sigma_z=1., T=1.):\n", + " return sigma_z**2 * T * (1 + 3 * (omega * T)**2) / (1 + (omega * T)**2)**2\n", + "\n", + "# Plot the power spectral density\n", + "axs[1].loglog(omega[1:], np.abs(S[1:]))\n", + "axs[1].loglog(omega[1:], dryden_psd(omega[1:]))\n", + "axs[1].set_xlabel(r\"$\\omega$ [rad/sec]\")\n", + "axs[1].set_ylabel(r\"$S(\\omega)$\")\n", + "axs[1].set_title(\"Power spectral density\")\n", + "\n", + "plt.tight_layout()" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "1516ff6a", + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/examples/cds112-L7_kalman-pvtol.ipynb b/examples/cds112-L7_kalman-pvtol.ipynb new file mode 100644 index 000000000..435c7fce6 --- /dev/null +++ b/examples/cds112-L7_kalman-pvtol.ipynb @@ -0,0 +1,425 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "c017196f", + "metadata": {}, + "source": [ + "# PVTOL LQR + EQF example\n", + "RMM, 14 Feb 2022\n", + "\n", + "This notebook illustrates the implementation of an extended Kalman filter and the use of the estimated state for LQR feedback." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "544525ab", + "metadata": {}, + "outputs": [], + "source": [ + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "import matplotlib.patches as patches\n", + "import control as ct" + ] + }, + { + "cell_type": "markdown", + "id": "859834cf", + "metadata": {}, + "source": [ + "## System definition\n", + "The dynamics of the system\n", + "with disturbances on the $x$ and $y$ variables is given by\n", + "$$\n", + " \\begin{aligned}\n", + " m \\ddot x &= F_1 \\cos\\theta - F_2 \\sin\\theta - c \\dot x + d_x, \\\\\n", + " m \\ddot y &= F_1 \\sin\\theta + F_2 \\cos\\theta - c \\dot y - m g + d_y, \\\\\n", + " J \\ddot \\theta &= r F_1.\n", + " \\end{aligned}\n", + "$$\n", + "The measured values of the system are the position and orientation,\n", + "with added noise $n_x$, $n_y$, and $n_\\theta$:\n", + "$$\n", + " \\vec y = \\begin{bmatrix} x \\\\ y \\\\ \\theta \\end{bmatrix} + \n", + " \\begin{bmatrix} n_x \\\\ n_y \\\\ n_z \\end{bmatrix}.\n", + "$$\n" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "ffafed74", + "metadata": {}, + "outputs": [], + "source": [ + "# pvtol = nominal system (no disturbances or noise)\n", + "# noisy_pvtol = pvtol w/ process disturbances and sensor noise\n", + "from pvtol import pvtol, pvtol_noisy, plot_results\n", + "\n", + "# Find the equilibrium point corresponding to the origin\n", + "xe, ue = ct.find_eqpt(\n", + " pvtol, np.zeros(pvtol.nstates),\n", + " np.zeros(pvtol.ninputs), [0, 0, 0, 0, 0, 0],\n", + " iu=range(2, pvtol.ninputs), iy=[0, 1])\n", + "\n", + "x0, u0 = ct.find_eqpt(\n", + " pvtol, np.zeros(pvtol.nstates),\n", + " np.zeros(pvtol.ninputs), np.array([2, 1, 0, 0, 0, 0]),\n", + " iu=range(2, pvtol.ninputs), iy=[0, 1])\n", + "\n", + "# Extract the linearization for use in LQR design\n", + "pvtol_lin = pvtol.linearize(xe, ue)\n", + "A, B = pvtol_lin.A, pvtol_lin.B\n", + "\n", + "print(pvtol, \"\\n\")\n", + "print(pvtol_noisy)" + ] + }, + { + "cell_type": "markdown", + "id": "2b63bf5b", + "metadata": {}, + "source": [ + "We now define the properties of the noise and disturbances. To make things (a bit more) interesting, we include some cross terms between the noise in $\\theta$ and the noise in $x$ and $y$:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "1e1ee7c9", + "metadata": {}, + "outputs": [], + "source": [ + "# Disturbance and noise intensities\n", + "Qv = np.diag([1e-2, 1e-2])\n", + "Qw = np.array([[2e-4, 0, 1e-5], [0, 2e-4, 1e-5], [1e-5, 1e-5, 1e-4]])\n", + "Qwinv = np.linalg.inv(Qw)\n", + "\n", + "# Initial state covariance\n", + "P0 = np.eye(pvtol.nstates)" + ] + }, + { + "cell_type": "markdown", + "id": "e4c52c73", + "metadata": {}, + "source": [ + "## Control system design\n", + "\n", + "To design the control system, we first construct an estimator for the state (given the commanded inputs and measured outputs. Since this is a nonlinear system, we use the update law for the nominal system to compute the state update. We also make use of the linearization around the current state for the covariance update (using the function `pvtol.A(x, u)`, which is defined in `pvtol.py`, making this an extended Kalman filter)." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "3647bf15", + "metadata": {}, + "outputs": [], + "source": [ + "# Define the disturbance input and measured output matrices\n", + "F = np.array([[0, 0], [0, 0], [0, 0], [1/pvtol.params['m'], 0], [0, 1/pvtol.params['m']], [0, 0]])\n", + "C = np.eye(3, 6)\n", + "\n", + "# Estimator update law\n", + "def estimator_update(t, x, u, params):\n", + " # Extract the states of the estimator\n", + " xhat = x[0:pvtol.nstates]\n", + " P = x[pvtol.nstates:].reshape(pvtol.nstates, pvtol.nstates)\n", + "\n", + " # Extract the inputs to the estimator\n", + " y = u[0:3] # just grab the first three outputs\n", + " u = u[6:8] # get the inputs that were applied as well\n", + "\n", + " # Compute the linearization at the current state\n", + " A = pvtol.A(xhat, u) # A matrix depends on current state\n", + " # A = pvtol.A(xe, ue) # Fixed A matrix (for testing/comparison)\n", + " \n", + " # Compute the optimal again\n", + " L = P @ C.T @ Qwinv\n", + "\n", + " # Update the state estimate\n", + " xhatdot = pvtol.updfcn(t, xhat, u, params) - L @ (C @ xhat - y)\n", + "\n", + " # Update the covariance\n", + " Pdot = A @ P + P @ A.T - P @ C.T @ Qwinv @ C @ P + F @ Qv @ F.T\n", + "\n", + " # Return the derivative\n", + " return np.hstack([xhatdot, Pdot.reshape(-1)])\n", + "\n", + "def estimator_output(t, x, u, params):\n", + " # Return the estimator states\n", + " return x[0:pvtol.nstates]\n", + "\n", + "estimator = ct.NonlinearIOSystem(\n", + " estimator_update, estimator_output,\n", + " states=pvtol.nstates + pvtol.nstates**2,\n", + " inputs= pvtol_noisy.output_labels \\\n", + " + pvtol_noisy.input_labels[0:pvtol.ninputs],\n", + " outputs=[f'xh{i}' for i in range(pvtol.nstates)],\n", + ")\n", + "print(estimator)" + ] + }, + { + "cell_type": "markdown", + "id": "ba3d2640", + "metadata": {}, + "source": [ + "For the controller, we will use an LQR feedback with physically motivated weights (see OBC, Example 3.5):" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "9787db61", + "metadata": {}, + "outputs": [], + "source": [ + "#\n", + "# LQR design w/ physically motivated weighting\n", + "#\n", + "# Shoot for 1 cm error in x, 10 cm error in y. Try to keep the angle\n", + "# less than 5 degrees in making the adjustments. Penalize side forces\n", + "# due to loss in efficiency.\n", + "#\n", + "\n", + "Qx = np.diag([100, 10, (180/np.pi) / 5, 0, 0, 0])\n", + "Qu = np.diag([10, 1])\n", + "K, _, _ = ct.lqr(A, B, Qx, Qu)\n", + "\n", + "#\n", + "# Control system construction: combine LQR w/ EKF\n", + "#\n", + "# Use the linearization around the origin to design the optimal gains\n", + "# to see how they compare to the final value of P for the EKF\n", + "#\n", + "\n", + "# Construct the state feedback controller with estimated state as input\n", + "statefbk, _ = ct.create_statefbk_iosystem(pvtol, K, estimator=estimator)\n", + "print(statefbk, \"\\n\")\n", + "\n", + "# Reconstruct the control system with the noisy version of the process\n", + "# Create a closed loop system around the controller\n", + "clsys = ct.interconnect(\n", + " [pvtol_noisy, statefbk, estimator],\n", + " inplist = statefbk.input_labels[0:pvtol.ninputs + pvtol.nstates] + \\\n", + " pvtol_noisy.input_labels[pvtol.ninputs:],\n", + " inputs = statefbk.input_labels[0:pvtol.ninputs + pvtol.nstates] + \\\n", + " pvtol_noisy.input_labels[pvtol.ninputs:],\n", + " outlist = pvtol.output_labels + statefbk.output_labels + estimator.output_labels,\n", + " outputs = pvtol.output_labels + statefbk.output_labels + estimator.output_labels\n", + ")\n", + "print(clsys)" + ] + }, + { + "cell_type": "markdown", + "id": "5f527f16", + "metadata": {}, + "source": [ + "Note that we have to construct the closed loop system manually since we need to allow the disturbance and noise inputs to be sent to the closed loop system and `create_statefbk_iosystem` does not support this (to be fixed in an upcoming release)." + ] + }, + { + "cell_type": "markdown", + "id": "7bf558a0", + "metadata": {}, + "source": [ + "## Simulations\n", + "\n", + "Finally, we can simulate the system to see how it all works. We start by creating the noise for the system:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "c2583a0e", + "metadata": {}, + "outputs": [], + "source": [ + "# Create the time vector for the simulation\n", + "Tf = 10\n", + "timepts = np.linspace(0, Tf, 1000)\n", + "\n", + "# Create representative process disturbance and sensor noise vectors\n", + "np.random.seed(117) # avoid figures changing from run to run\n", + "V = ct.white_noise(timepts, Qv) # smaller disturbances and noise then design\n", + "W = ct.white_noise(timepts, Qw)\n", + "plt.plot(timepts, V[0], label=\"V[0]\")\n", + "plt.plot(timepts, W[0], label=\"W[0]\")\n", + "plt.legend();" + ] + }, + { + "cell_type": "markdown", + "id": "4d944709", + "metadata": {}, + "source": [ + "### LQR with EKF\n", + "\n", + "We can now feed the desired trajectory plus the noise and disturbances into the system and see how well the controller with a state estimator does in holding the system at an equilibrium point:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "ad7a9750", + "metadata": {}, + "outputs": [], + "source": [ + "# Put together the input for the system\n", + "U = [xe, ue, V, W]\n", + "X0 = [x0, xe, P0.reshape(-1)]\n", + "\n", + "# Initial condition response\n", + "resp = ct.input_output_response(clsys, timepts, U, X0)\n", + "\n", + "# Plot the response\n", + "plot_results(timepts, resp.states, resp.outputs[pvtol.nstates:])" + ] + }, + { + "cell_type": "markdown", + "id": "86f10064", + "metadata": {}, + "source": [ + "To see how well the estimtator did, we can compare the estimated position with the actual position:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "c5f24119", + "metadata": {}, + "outputs": [], + "source": [ + "# Response of the first two states, including internal estimates\n", + "h1, = plt.plot(resp.time, resp.outputs[0], 'b-', linewidth=0.75)\n", + "h2, = plt.plot(resp.time, resp.outputs[1], 'r-', linewidth=0.75)\n", + "\n", + "# Add on the internal estimator states\n", + "xh0 = clsys.find_output('xh0')\n", + "xh1 = clsys.find_output('xh1')\n", + "h3, = plt.plot(resp.time, resp.outputs[xh0], 'k--')\n", + "h4, = plt.plot(resp.time, resp.outputs[xh1], 'k--')\n", + "\n", + "plt.plot([0, 10], [0, 0], 'k--', linewidth=0.5)\n", + "plt.ylabel(r\"Position $x$, $y$ [m]\")\n", + "plt.xlabel(r\"Time $t$ [s]\")\n", + "plt.legend(\n", + " [h1, h2, h3, h4], ['$x$', '$y$', r'$\\hat{x}$', r'$\\hat{y}$'], \n", + " loc='upper right', frameon=False, ncol=2);" + ] + }, + { + "cell_type": "markdown", + "id": "7139202f", + "metadata": {}, + "source": [ + "Note the rapid convergence of the estimate to the proper value, since we are directly measuring the position variables. If we look at the full set of states, we see that other variables have different convergence properties:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "78a61e74", + "metadata": {}, + "outputs": [], + "source": [ + "fig, axs = plt.subplots(2, 3)\n", + "var = ['x', 'y', r'\\theta', r'\\dot x', r'\\dot y', r'\\dot \\theta']\n", + "for i in [0, 1]:\n", + " for j in [0, 1, 2]:\n", + " k = i * 3 + j\n", + " axs[i, j].plot(resp.time, resp.outputs[k], label=f'${var[k]}$')\n", + " axs[i, j].plot(resp.time, resp.outputs[xh0+k], label=f'$\\\\hat {var[k]}$')\n", + " axs[i, j].legend()\n", + " if i == 1:\n", + " axs[i, j].set_xlabel(\"Time $t$ [s]\")\n", + " if j == 0:\n", + " axs[i, j].set_ylabel(\"State\")\n", + "plt.tight_layout()" + ] + }, + { + "cell_type": "markdown", + "id": "2039578e", + "metadata": {}, + "source": [ + "Note the lag in tracking changes in the $\\dot x$ and $\\dot y$ states (varies from simulation to simulation, depending on the specific noise signal)." + ] + }, + { + "cell_type": "markdown", + "id": "0c0d5c99", + "metadata": {}, + "source": [ + "### Full state feedback\n", + "\n", + "To see how the inclusion of the estimator affects the system performance, we compare it with the case where we are able to directly measure the state of the system." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "3b6a1f1c", + "metadata": {}, + "outputs": [], + "source": [ + "# Compute the full state feedback solution\n", + "lqr_ctrl, _ = ct.create_statefbk_iosystem(pvtol, K)\n", + "\n", + "lqr_clsys = ct.interconnect(\n", + " [pvtol_noisy, lqr_ctrl],\n", + " inplist = lqr_ctrl.input_labels[0:pvtol.ninputs + pvtol.nstates] + \\\n", + " pvtol_noisy.input_labels[pvtol.ninputs:],\n", + " inputs = lqr_ctrl.input_labels[0:pvtol.ninputs + pvtol.nstates] + \\\n", + " pvtol_noisy.input_labels[pvtol.ninputs:],\n", + " outlist = pvtol.output_labels + lqr_ctrl.output_labels,\n", + " outputs = pvtol.output_labels + lqr_ctrl.output_labels\n", + ")\n", + "\n", + "# Put together the input for the system (turn off sensor noise)\n", + "U = [xe, ue, V, W*0]\n", + "\n", + "# Run a simulation with full state feedback\n", + "lqr_resp = ct.input_output_response(lqr_clsys, timepts, U, x0)\n", + "\n", + "# Compare the results\n", + "plt.plot(resp.states[0], resp.states[1], 'b-', label=\"Extended KF\")\n", + "plt.plot(lqr_resp.states[0], lqr_resp.states[1], 'r-', label=\"Full state\")\n", + "\n", + "plt.xlabel('$x$ [m]')\n", + "plt.ylabel('$y$ [m]')\n", + "plt.axis('equal')\n", + "plt.legend(frameon=False);" + ] + }, + { + "cell_type": "markdown", + "id": "8c0083cb", + "metadata": {}, + "source": [ + "Things to try:\n", + "* Compute a feasable trajectory and stabilize around that instead of the origin" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "777053a4", + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/examples/cds112-L8_fusion-kincar.ipynb b/examples/cds112-L8_fusion-kincar.ipynb new file mode 100644 index 000000000..20bc26c93 --- /dev/null +++ b/examples/cds112-L8_fusion-kincar.ipynb @@ -0,0 +1,476 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "eec23018", + "metadata": {}, + "source": [ + "# Kinematic car sensor fusion example\n", + "RMM, 24 Feb 2022 (updated 23 Feb 2023)\n", + "\n", + "In this example we work through estimation of the state of a car changing\n", + "lanes with two different sensors available: one with good longitudinal accuracy\n", + "and the other with good lateral accuracy.\n", + "\n", + "All calculations are done in discrete time, using both the form of the Kalman\n", + "filter in Theorem 7.2 and the predictor corrector form." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "107a6613", + "metadata": {}, + "outputs": [], + "source": [ + "import numpy as np\n", + "import scipy as sp\n", + "import matplotlib.pyplot as plt\n", + "import control as ct\n", + "import control.optimal as opt\n", + "import control.flatsys as fs\n", + "\n", + "# Define some line styles for later use\n", + "ebarstyle = {'elinewidth': 0.5, 'capsize': 2}\n", + "xdstyle = {'color': 'k', 'linestyle': '--', 'linewidth': 0.5, \n", + " 'marker': '+', 'markersize': 4}" + ] + }, + { + "cell_type": "markdown", + "id": "ea8807a4", + "metadata": {}, + "source": [ + "## System definition\n", + "\n", + "We make use of a simple model for a vehicle navigating in the plane, known as the \"bicycle model\". The kinematics of this vehicle can be written in terms of the contact point $(x, y)$ and the angle $\\theta$ of the vehicle with respect to the horizontal axis:\n", + "\n", + "\n", + "\n", + " \n", + " \n", + "\n", + "
\n", + "$$\n", + "\\begin{aligned}\n", + " \\dot x &= \\cos\\theta\\, v \\\\\n", + " \\dot y &= \\sin\\theta\\, v \\\\\n", + " \\dot\\theta &= \\frac{v}{l} \\tan \\delta\n", + "\\end{aligned}\n", + "$$\n", + "
\n", + "\n", + "The input $v$ represents the velocity of the vehicle and the input $\\delta$ represents the turning rate. The parameter $l$ is the wheelbase." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "a04106f8", + "metadata": {}, + "outputs": [], + "source": [ + "# Vehicle steering dynamics\n", + "#\n", + "# System state: x, y, theta\n", + "# System input: v, phi\n", + "# System output: x, y\n", + "# System parameters: wheelbase, maxsteer\n", + "#\n", + "from kincar import kincar, plot_lanechange\n", + "print(kincar)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "69c048ed", + "metadata": {}, + "outputs": [], + "source": [ + "# Generate a trajectory for the vehicle\n", + "# Define the endpoints of the trajectory\n", + "x0 = [0., -2., 0.]; u0 = [10., 0.]\n", + "xf = [40., 2., 0.]; uf = [10., 0.]\n", + "Tf = 4\n", + "\n", + "# Find a trajectory between the initial condition and the final condition\n", + "traj = fs.point_to_point(kincar, Tf, x0, u0, xf, uf, basis=fs.PolyFamily(6))\n", + "\n", + "# Create the desired trajectory between the initial and final condition\n", + "Ts = 0.1\n", + "# Ts = 0.5\n", + "timepts = np.arange(0, Tf + Ts, Ts)\n", + "xd, ud = traj.eval(timepts)\n", + "\n", + "plot_lanechange(timepts, xd, ud)" + ] + }, + { + "cell_type": "markdown", + "id": "aeeaa39e", + "metadata": {}, + "source": [ + "### Discrete time system model\n", + "\n", + "For the model that we use for the Kalman filter, we take a simple discretization using the approximation that $\\dot x = (x[k+1] - x[k])/T_s$ where $T_s$ is the sampling time." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "2469c60e", + "metadata": {}, + "outputs": [], + "source": [ + "#\n", + "# Create a discrete time, linear model\n", + "#\n", + "\n", + "# Linearize about the starting point\n", + "linsys = ct.linearize(kincar, x0, u0)\n", + "\n", + "# Create a discrete time model by hand\n", + "Ad = np.eye(linsys.nstates) + linsys.A * Ts\n", + "Bd = linsys.B * Ts\n", + "discsys = ct.ss(Ad, Bd, np.eye(linsys.nstates), 0, dt=Ts)\n", + "print(discsys);" + ] + }, + { + "cell_type": "markdown", + "id": "084c5ae8", + "metadata": {}, + "source": [ + "### Sensor model\n", + "\n", + "We assume that we have two sensors: one with good longitudinal accuracy and the other with good lateral accuracy. For each sensor we define the map from the state space to the sensor outputs, the covariance matrix for the measurements, and a white noise signal (now in discrete time).\n", + "\n", + "Note: we pass the keyword `dt` to the `white_noise` function so that the white noise is consistent with a discrete time model (so the covariance is _not_ rescaled by $\\sqrt{dt}$)." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "0a19d109", + "metadata": {}, + "outputs": [], + "source": [ + "# Sensor #1: longitudinal\n", + "C_lon = np.eye(2, discsys.nstates)\n", + "Rw_lon = np.diag([0.1 ** 2, 1 ** 2])\n", + "W_lon = ct.white_noise(timepts, Rw_lon, dt=Ts)\n", + "\n", + "# Sensor #2: lateral\n", + "C_lat = np.eye(2, discsys.nstates)\n", + "Rw_lat = np.diag([1 ** 2, 0.1 ** 2])\n", + "W_lat = ct.white_noise(timepts, Rw_lat, dt=Ts)\n", + "\n", + "# Plot the noisy signals\n", + "plt.subplot(2, 1, 1)\n", + "Y = xd[0:2] + W_lon\n", + "plt.plot(Y[0], Y[1])\n", + "plt.plot(xd[0], xd[1], **xdstyle)\n", + "plt.xlabel(\"$x$ position [m]\")\n", + "plt.ylabel(\"$y$ position [m]\")\n", + "plt.title(\"Sensor #1 (longitudinal)\")\n", + " \n", + "plt.subplot(2, 1, 2)\n", + "Y = xd[0:2] + W_lat\n", + "plt.plot(Y[0], Y[1])\n", + "plt.plot(xd[0], xd[1], **xdstyle)\n", + "plt.xlabel(\"$x$ position [m]\")\n", + "plt.ylabel(\"$y$ position [m]\")\n", + "plt.title(\"Sensor #2 (lateral)\")\n", + "plt.tight_layout()" + ] + }, + { + "cell_type": "markdown", + "id": "c3fa1a3d", + "metadata": {}, + "source": [ + "## Linear Quadratic Estimator\n", + "\n", + "We now construct a linear quadratic estimator for the system usign the Kalman filter form. This is idone using the [`create_estimator_iosystem`](https://github.com/python-control/python-control/blob/main/control/stochsys.py#L310-L517) function in python-control." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "993601a2", + "metadata": {}, + "outputs": [], + "source": [ + "# Disturbance and initial condition model\n", + "# Note: multiple by sampling time since we discretized the dynamics\n", + "Rv = np.diag([0.1, 0.01]) * Ts\n", + "# Rv = np.diag([10, 1]) * Ts # Variant: no input information\n", + "P0 = np.diag([1, 1, 0.1])\n", + "\n", + "# Combine the sensors\n", + "# Note: no sampling time here because we are doing discrete-time KF\n", + "C = np.vstack([C_lon, C_lat])\n", + "Rw = sp.linalg.block_diag(Rw_lon, Rw_lat)\n", + "\n", + "estim = ct.create_estimator_iosystem(discsys, Rv, Rw, C=C, P0=P0)\n", + "print(estim)" + ] + }, + { + "cell_type": "markdown", + "id": "0c2e8ab0", + "metadata": {}, + "source": [ + "We can now run the estimator on the noisy signals to see how well it works." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "3d02ec33", + "metadata": {}, + "outputs": [], + "source": [ + "# Compute the inputs to the estimator\n", + "Y = np.vstack([xd[0:2] + W_lon, xd[0:2] + W_lat])\n", + "U = np.vstack([Y, ud]) # add input to the Kalman filter\n", + "# U = np.vstack([Y, ud * 0]) # variant: no input information\n", + "X0 = np.hstack([xd[:, 0], P0.reshape(-1)])\n", + "\n", + "# Run the estimator on the trajectory\n", + "estim_resp = ct.input_output_response(estim, timepts, U, X0)\n", + "\n", + "# Run a prediction to see what happens next\n", + "T_predict = np.arange(timepts[-1], timepts[-1] + 4 + Ts, Ts)\n", + "U_predict = np.outer(U[:, -1], np.ones_like(T_predict))\n", + "predict_resp = ct.input_output_response(\n", + " estim, T_predict, U_predict, estim_resp.states[:, -1],\n", + " params={'correct': False})\n", + "\n", + "# Plot the estimated trajectory versus the actual trajectory\n", + "plt.subplot(2, 1, 1)\n", + "plt.errorbar(\n", + " estim_resp.time, estim_resp.outputs[0], \n", + " estim_resp.states[estim.find_state('P[0,0]')], fmt='b-', **ebarstyle)\n", + "plt.errorbar(\n", + " predict_resp.time, predict_resp.outputs[0], \n", + " predict_resp.states[estim.find_state('P[0,0]')], fmt='r-', **ebarstyle)\n", + "plt.plot(timepts, xd[0], 'k--')\n", + "plt.ylabel(\"$x$ position [m]\")\n", + "\n", + "plt.subplot(2, 1, 2)\n", + "plt.errorbar(\n", + " estim_resp.time, estim_resp.outputs[1], \n", + " estim_resp.states[estim.find_state('P[1,1]')], fmt='b-', **ebarstyle)\n", + "plt.errorbar(\n", + " predict_resp.time, predict_resp.outputs[1], \n", + " predict_resp.states[estim.find_state('P[1,1]')], fmt='r-', **ebarstyle)\n", + "# lims = plt.axis(); plt.axis([lims[0], lims[1], -5, 5])\n", + "plt.plot(timepts, xd[1], 'k--');\n", + "plt.ylabel(\"$y$ position [m]\")\n", + "plt.xlabel(\"Time $t$ [s]\");" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "44f69f79", + "metadata": {}, + "outputs": [], + "source": [ + "# Plot the estimated errors\n", + "plt.subplot(2, 1, 1)\n", + "plt.errorbar(\n", + " estim_resp.time, estim_resp.outputs[0] - xd[0], \n", + " estim_resp.states[estim.find_state('P[0,0]')], fmt='b-', **ebarstyle)\n", + "plt.errorbar(\n", + " predict_resp.time, predict_resp.outputs[0] - (xd[0] + xd[0, -1]), \n", + " predict_resp.states[estim.find_state('P[0,0]')], fmt='r-', **ebarstyle)\n", + "lims = plt.axis(); plt.axis([lims[0], lims[1], -0.2, 0.2])\n", + "# lims = plt.axis(); plt.axis([lims[0], lims[1], -2, 0.2])\n", + "\n", + "plt.subplot(2, 1, 2)\n", + "plt.errorbar(\n", + " estim_resp.time, estim_resp.outputs[1] - xd[1], \n", + " estim_resp.states[estim.find_state('P[1,1]')], fmt='b-', **ebarstyle)\n", + "plt.errorbar(\n", + " predict_resp.time, predict_resp.outputs[1] - xd[1, -1], \n", + " predict_resp.states[estim.find_state('P[1,1]')], fmt='r-', **ebarstyle)\n", + "lims = plt.axis(); plt.axis([lims[0], lims[1], -0.2, 0.2]);" + ] + }, + { + "cell_type": "markdown", + "id": "6f6c1b6f", + "metadata": {}, + "source": [ + "## Things to try\n", + "* Remove the input (and update P0 and Rv)\n", + "* Change the sampling rate" + ] + }, + { + "cell_type": "markdown", + "id": "8f680b92", + "metadata": {}, + "source": [ + "## Predictor-corrector form\n", + "\n", + "Instead of using create_estimator_iosystem, we can also compute out the estimate in a more manual fashion, done here using the predictor-corrector form." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "fa488d51", + "metadata": {}, + "outputs": [], + "source": [ + "# System matrices\n", + "A, B, F = discsys.A, discsys.B, discsys.B\n", + "\n", + "# Create an array to store the results\n", + "xhat = np.zeros((discsys.nstates, timepts.size))\n", + "P = np.zeros((discsys.nstates, discsys.nstates, timepts.size))\n", + "\n", + "# Update the estimates at each time\n", + "for i, t in enumerate(timepts):\n", + " # Prediction step\n", + " if i == 0:\n", + " # Use the initial condition\n", + " xkkm1 = xd[:, 0]\n", + " Pkkm1 = P0\n", + " else:\n", + " xkkm1 = A @ xkk + B @ ud[:, i-1]\n", + " Pkkm1 = A @ Pkk @ A.T + F @ Rv @ F.T\n", + " \n", + " # Correction step (variant: apply only when sensor data is available)\n", + " L = Pkkm1 @ C.T @ np.linalg.inv(Rw + C @ Pkkm1 @ C.T)\n", + " xkk = xkkm1 - L @ (C @ xkkm1 - Y[:, i])\n", + " Pkk = Pkkm1 - L @ C @ Pkkm1\n", + "\n", + " # Save the state estimate and covariance for later plotting\n", + " xhat[:, i], P[:, :, i] = xkkm1, Pkkm1 # For comparison to Kalman form\n", + " # xhat[:, i], P[:, :, i] = xkk, Pkk # variant: \n", + " \n", + "plt.subplot(2, 1, 1)\n", + "plt.errorbar(timepts, xhat[0], P[0, 0], fmt='b-', **ebarstyle)\n", + "plt.plot(timepts, xd[0], 'k--')\n", + "plt.ylabel(\"$x$ position [m]\")\n", + "\n", + "plt.subplot(2, 1, 2)\n", + "plt.errorbar(timepts, xhat[1], P[1, 1], fmt='b-', **ebarstyle)\n", + "plt.plot(timepts, xd[1], 'k--')\n", + "plt.ylabel(\"$x$ position [m]\")\n", + "plt.xlabel(\"Time $t$ [s]\");" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "4eda4729", + "metadata": {}, + "outputs": [], + "source": [ + "# Plot the estimated errors (and compare to Kalman form)\n", + "plt.subplot(2, 1, 1)\n", + "plt.errorbar(timepts, xhat[0] - xd[0], P[0, 0], fmt='b-', **ebarstyle)\n", + "plt.plot(estim_resp.time, estim_resp.outputs[0] - xd[0], 'r--', linewidth=3)\n", + "lims = plt.axis(); plt.axis([lims[0], lims[1], -0.2, 0.2])\n", + "plt.ylabel(\"x error [m]\")\n", + "\n", + "plt.subplot(2, 1, 2)\n", + "plt.errorbar(timepts, xhat[1] - xd[1], P[1, 1], fmt='b-', **ebarstyle,\n", + " label='predictor/corrector')\n", + "plt.plot(estim_resp.time, estim_resp.outputs[1] - xd[1], 'r--', linewidth=3,\n", + " label='Kalman form')\n", + "lims = plt.axis(); plt.axis([lims[0], lims[1], -0.2, 0.2])\n", + "plt.ylabel(\"y error [m]\")\n", + "plt.xlabel(\"Time $t$ [s]\")\n", + "plt.legend(loc='lower right');" + ] + }, + { + "cell_type": "markdown", + "id": "19a673a1", + "metadata": {}, + "source": [ + "## Information filter\n", + "\n", + "An alternative way to implement the computation is using the information filter formulation." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "36111bc2", + "metadata": {}, + "outputs": [], + "source": [ + "from numpy.linalg import inv\n", + "\n", + "# Update the estimates at each time\n", + "for i, t in enumerate(timepts):\n", + " # Prediction step\n", + " if i == 0:\n", + " # Use the initial condition\n", + " xkkm1 = xd[:, 0]\n", + " Pkkm1 = P0\n", + " else:\n", + " xkkm1 = A @ xkk + B @ ud[:, i-1]\n", + " Pkkm1 = A @ Pkk @ A.T + F @ Rv @ F.T\n", + " \n", + " # Correction step (variant: apply only when sensor data is available)\n", + " Ikk, Zkk = inv(Pkkm1), inv(Pkkm1) @ xkkm1\n", + " \n", + " # Longitudinal sensor update\n", + " Ikk += C_lon.T @ inv(Rw_lon) @ C_lon # Omega_lon\n", + " Zkk += C_lon.T @ inv(Rw_lon) @ Y[:2, i] # Psi_lon\n", + "\n", + " # Lateral sensor update\n", + " Ikk += C_lat.T @ inv(Rw_lat) @ C_lat # Omega_lat\n", + " Zkk += C_lat.T @ inv(Rw_lat) @ Y[2:, i] # Psi_lat\n", + " \n", + " # Compute the updated state and covariance \n", + " Pkk = inv(Ikk)\n", + " xkk = Pkk @ Zkk\n", + "\n", + " # Save the state estimate and covariance for later plotting\n", + " xhat[:, i], P[:, :, i] = xkkm1, Pkkm1\n", + "\n", + "# Plot the estimated errors (and compare to Kalman form)\n", + "plt.subplot(2, 1, 1)\n", + "plt.errorbar(timepts, xhat[0] - xd[0], P[0, 0], fmt='b-', **ebarstyle)\n", + "plt.plot(estim_resp.time, estim_resp.outputs[0] - xd[0], 'r--', linewidth=3)\n", + "lims = plt.axis(); plt.axis([lims[0], lims[1], -0.2, 0.2])\n", + "plt.ylabel(\"x error [m]\")\n", + "\n", + "plt.subplot(2, 1, 2)\n", + "plt.errorbar(timepts, xhat[1] - xd[1], P[1, 1], fmt='b-', **ebarstyle,\n", + " label='information filter')\n", + "plt.plot(estim_resp.time, estim_resp.outputs[1] - xd[1], 'r--', linewidth=3,\n", + " label='Kalman form')\n", + "lims = plt.axis(); plt.axis([lims[0], lims[1], -0.2, 0.2])\n", + "plt.ylabel(\"y error [m]\")\n", + "plt.xlabel(\"Time $t$ [s]\")\n", + "plt.legend(loc='lower right');" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "ad5cf57f", + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/examples/cds112-L9_mhe-pvtol.ipynb b/examples/cds112-L9_mhe-pvtol.ipynb new file mode 100644 index 000000000..12793df7b --- /dev/null +++ b/examples/cds112-L9_mhe-pvtol.ipynb @@ -0,0 +1,758 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "baba5fab", + "metadata": {}, + "source": [ + "# Moving Horizon Estimation\n", + "\n", + "Richard M. Murray, 24 Feb 2023\n", + "\n", + "In this notebook we illustrate the implementation of moving horizon estimation (MHE)." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "36715c5f", + "metadata": {}, + "outputs": [], + "source": [ + "import numpy as np\n", + "import scipy as sp\n", + "import matplotlib.pyplot as plt\n", + "import control as ct\n", + "\n", + "import control.optimal as opt\n", + "import control.flatsys as fs" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "1a4e4084", + "metadata": {}, + "outputs": [], + "source": [ + "# Import the new MHE routines (to be moved to python-control)\n", + "# import ctrlutil as opt_" + ] + }, + { + "cell_type": "markdown", + "id": "d72a155b", + "metadata": {}, + "source": [ + "## System Description\n", + "\n", + "We use the PVTOL dynamics from the textbook, which are contained in the `pvtol` module:\n", + "\n", + "\n", + "\n", + " \n", + " \n", + " \n", + "\n", + "
\n", + "$$\n", + "\\begin{aligned}\n", + " m \\ddot x &= F_1 \\cos\\theta - F_2 \\sin\\theta - c \\dot x, \\\\\n", + " m \\ddot y &= F_1 \\sin\\theta + F_2 \\cos\\theta - m g - c \\dot y, \\\\\n", + " J \\ddot \\theta &= r F_1.\n", + "\\end{aligned}\n", + "$$\n", + "
\n", + "\n", + "The measured values of the system are the position and orientation,\n", + "with added noise $n_x$, $n_y$, and $n_\\theta$:\n", + "\n", + "$$\n", + " \\vec y = \\begin{bmatrix} x \\\\ y \\\\ \\theta \\end{bmatrix} + \n", + " \\begin{bmatrix} n_x \\\\ n_y \\\\ n_z \\end{bmatrix}.\n", + "$$\n", + "\n", + "The parameter values for the PVTOL system come from the Caltech ducted fan experiment, described in more detail in [Lecture 4b](cds112-L4b_pvtol-lqr.ipynb)." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "08919988", + "metadata": {}, + "outputs": [], + "source": [ + "# pvtol = nominal system (no disturbances or noise)\n", + "# noisy_pvtol = pvtol w/ process disturbances and sensor noise\n", + "from pvtol import pvtol, pvtol_noisy, plot_results\n", + "import pvtol as pvt\n", + "\n", + "# Find the equiblirum point corresponding to the origin\n", + "xe, ue = ct.find_eqpt(\n", + " pvtol, np.zeros(pvtol.nstates),\n", + " np.zeros(pvtol.ninputs), [0, 0, 0, 0, 0, 0],\n", + " iu=range(2, pvtol.ninputs), iy=[0, 1])\n", + "\n", + "# Initial condition = 2 meters right, 1 meter up\n", + "x0, u0 = ct.find_eqpt(\n", + " pvtol, np.zeros(pvtol.nstates),\n", + " np.zeros(pvtol.ninputs), np.array([2, 1, 0, 0, 0, 0]),\n", + " iu=range(2, pvtol.ninputs), iy=[0, 1])\n", + "\n", + "# Extract the linearization for use in LQR design\n", + "pvtol_lin = pvtol.linearize(xe, ue)\n", + "A, B = pvtol_lin.A, pvtol_lin.B\n", + "\n", + "print(pvtol, \"\\n\")\n", + "print(pvtol_noisy)" + ] + }, + { + "cell_type": "markdown", + "id": "5771ab93", + "metadata": {}, + "source": [ + "### Control Design\n", + "\n", + "We begin by designing an LQR conroller than can be used for trajectory tracking, which is described in more detail in [Lecture 4b](cds112-L4b_pvtol-lqr.ipynb):" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "d2e88938", + "metadata": {}, + "outputs": [], + "source": [ + "#\n", + "# LQR design w/ physically motivated weighting\n", + "#\n", + "# Shoot for 10 cm error in x, 10 cm error in y. Try to keep the angle\n", + "# less than 5 degrees in making the adjustments. Penalize side forces\n", + "# due to loss in efficiency.\n", + "#\n", + "\n", + "Qx = np.diag([100, 10, (180/np.pi) / 5, 0, 0, 0])\n", + "Qu = np.diag([10, 1])\n", + "K, _, _ = ct.lqr(A, B, Qx, Qu)\n", + "\n", + "# Compute the full state feedback solution\n", + "lqr_ctrl, _ = ct.create_statefbk_iosystem(pvtol, K)\n", + "\n", + "# Define the closed loop system that will be used to generate trajectories\n", + "lqr_clsys = ct.interconnect(\n", + " [pvtol_noisy, lqr_ctrl],\n", + " inplist = lqr_ctrl.input_labels[0:pvtol.ninputs + pvtol.nstates] + \\\n", + " pvtol_noisy.input_labels[pvtol.ninputs:],\n", + " inputs = lqr_ctrl.input_labels[0:pvtol.ninputs + pvtol.nstates] + \\\n", + " pvtol_noisy.input_labels[pvtol.ninputs:],\n", + " outlist = pvtol.output_labels + lqr_ctrl.output_labels,\n", + " outputs = pvtol.output_labels + lqr_ctrl.output_labels\n", + ")\n", + "print(lqr_clsys)" + ] + }, + { + "cell_type": "markdown", + "id": "29f55c0a-8c17-4347-aa46-b1944e700b32", + "metadata": {}, + "source": [ + "(The warning message can be ignored; it is generated because we implement this system as a differentially flat system and hence we require that an output function be explicitly given, rather than using `None`.)" + ] + }, + { + "cell_type": "markdown", + "id": "e9bc481f-7b2f-4b40-89b7-1ef5a35251b7", + "metadata": {}, + "source": [ + "We next define the characteristics of the uncertainty in the system: the disturbance and noise covariances (intensities) as well as the initial condition covariance:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "78853391", + "metadata": {}, + "outputs": [], + "source": [ + "# Disturbance and noise intensities\n", + "Qv = np.diag([1e-2, 1e-2])\n", + "Qw = np.array([[1e-4, 0, 1e-5], [0, 1e-4, 1e-5], [1e-5, 1e-5, 1e-4]])\n", + "\n", + "# Initial state covariance\n", + "P0 = np.eye(pvtol.nstates)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "c590fd88", + "metadata": {}, + "outputs": [], + "source": [ + "# Create the time vector for the simulation\n", + "Tf = 6\n", + "timepts = np.linspace(0, Tf, 20)\n", + "\n", + "# Create representative process disturbance and sensor noise vectors\n", + "# np.random.seed(117) # uncomment to avoid figures changing from run to run\n", + "V = ct.white_noise(timepts, Qv)\n", + "W = ct.white_noise(timepts, Qw)\n", + "plt.plot(timepts, V[0], label=\"V[0]\")\n", + "plt.plot(timepts, W[0], label=\"W[0]\")\n", + "plt.legend();" + ] + }, + { + "cell_type": "markdown", + "id": "7db5188e-03c7-439c-8cf2-47681d3feccf", + "metadata": {}, + "source": [ + "To get a better sense of the size of the disturbances and noise, we simulate the noise-free system with the applied disturbances, and then add in the noise. Note that in this simulation we are still assuming that the controller has access to the noise-free state (not realistic, but used here just to show that the disturbances and noise do not cause large perturbations)." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "c35fd695", + "metadata": {}, + "outputs": [], + "source": [ + "# Desired trajectory\n", + "xd, ud = xe, ue\n", + "# xd = np.vstack([\n", + "# np.sin(2 * np.pi * timepts / timepts[-1]), \n", + "# np.zeros((5, timepts.size))])\n", + "# ud = np.outer(ue, np.ones_like(timepts))\n", + "\n", + "# Run a simulation with full state feedback (no noise) to generate a trajectory\n", + "uvec = [xd, ud, V, W*0]\n", + "lqr_resp = ct.input_output_response(lqr_clsys, timepts, uvec, x0)\n", + "U = lqr_resp.outputs[6:8] # controller input signals\n", + "Y = lqr_resp.outputs[0:3] + W # noisy output signals (noise in pvtol_noisy)\n", + "\n", + "# Compare to the no noise case\n", + "uvec = [xd, ud, V*0, W*0]\n", + "lqr0_resp = ct.input_output_response(lqr_clsys, timepts, uvec, x0)\n", + "lqr0_fine = ct.input_output_response(lqr_clsys, timepts, uvec, x0, \n", + " t_eval=np.linspace(timepts[0], timepts[-1], 100))\n", + "U0 = lqr0_resp.outputs[6:8]\n", + "Y0 = lqr0_resp.outputs[0:3]\n", + "\n", + "# Compare the results\n", + "# plt.plot(Y0[0], Y0[1], 'k--', linewidth=2, label=\"No disturbances\")\n", + "plt.plot(lqr0_fine.states[0], lqr0_fine.states[1], 'r-', label=\"Actual\")\n", + "plt.plot(Y[0], Y[1], 'b-', label=\"Noisy\")\n", + "\n", + "plt.xlabel('$x$ [m]')\n", + "plt.ylabel('$y$ [m]')\n", + "plt.axis('equal')\n", + "plt.legend(frameon=False)\n", + "\n", + "plt.figure()\n", + "plot_results(timepts, lqr_resp.states, lqr_resp.outputs[6:8])" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "a7f1dec6", + "metadata": {}, + "outputs": [], + "source": [ + "# Utility functions for making plots\n", + "def plot_state_comparison(\n", + " timepts, est_states, act_states=None, estimated_label='$\\\\hat x_{i}$', actual_label='$x_{i}$',\n", + " start=0):\n", + " for i in range(sys.nstates):\n", + " plt.subplot(2, 3, i+1)\n", + " if act_states is not None:\n", + " plt.plot(timepts[start:], act_states[i, start:], 'r--', \n", + " label=actual_label.format(i=i))\n", + " plt.plot(timepts[start:], est_states[i, start:], 'b', \n", + " label=estimated_label.format(i=i))\n", + " plt.legend()\n", + " plt.tight_layout()\n", + " \n", + "# Define a function to plot out all of the relevant signals\n", + "def plot_estimator_response(timepts, estimated, U, V, Y, W, start=0):\n", + " # Plot the input signal and disturbance\n", + " for i in [0, 1]:\n", + " # Input signal (the same across all)\n", + " plt.subplot(4, 3, i+1)\n", + " plt.plot(timepts[start:], U[i, start:], 'k')\n", + " plt.ylabel(f'U[{i}]')\n", + "\n", + " # Plot the estimated disturbance signal\n", + " plt.subplot(4, 3, 4+i)\n", + " plt.plot(timepts[start:], estimated.inputs[i, start:], 'b-', label=\"est\")\n", + " plt.plot(timepts[start:], V[i, start:], 'k', label=\"actual\")\n", + " plt.ylabel(f'V[{i}]')\n", + "\n", + " plt.subplot(4, 3, 6)\n", + " plt.plot(0, 0, 'b', label=\"estimated\")\n", + " plt.plot(0, 0, 'k', label=\"actual\")\n", + " plt.plot(0, 0, 'r', label=\"measured\")\n", + " plt.legend(frameon=False)\n", + " plt.grid(False)\n", + " plt.axis('off')\n", + " \n", + " # Plot the output (measured and estimated) \n", + " for i in [0, 1, 2]:\n", + " plt.subplot(4, 3, 7+i)\n", + " plt.plot(timepts[start:], Y[i, start:], 'r', label=\"measured\")\n", + " plt.plot(timepts[start:], estimated.states[i, start:], 'b', label=\"measured\")\n", + " plt.plot(timepts[start:], Y[i, start:] - W[i, start:], 'k', label=\"actual\")\n", + " plt.ylabel(f'Y[{i}]')\n", + " \n", + " for i in [0, 1, 2]:\n", + " plt.subplot(4, 3, 10+i)\n", + " plt.plot(timepts[start:], estimated.outputs[i, start:], 'b', label=\"estimated\")\n", + " plt.plot(timepts[start:], W[i, start:], 'k', label=\"actual\")\n", + " plt.ylabel(f'W[{i}]')\n", + " plt.xlabel('Time [s]')\n", + "\n", + " plt.tight_layout()" + ] + }, + { + "cell_type": "markdown", + "id": "73dd9be3", + "metadata": {}, + "source": [ + "## State Estimation\n", + "\n", + "We next consider the problem of only measuring the (noisy) outputs of the system and designing a controller that uses the estimated state as the input to the LQR controller that we designed previously.\n", + "\n", + "We start by using a standard Kalman filter." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "5a1f32da", + "metadata": {}, + "outputs": [], + "source": [ + "# Create a new system with only x, y, theta as outputs\n", + "sys = ct.nlsys(\n", + " pvt._noisy_update, lambda t, x, u, params: x[0:3], name=\"pvtol_noisy\",\n", + " states = [f'x{i}' for i in range(6)],\n", + " inputs = ['F1', 'F2'] + ['Dx', 'Dy'],\n", + " outputs = ['x', 'y', 'theta']\n", + ")\n", + "print(sys)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "3a0679f4", + "metadata": {}, + "outputs": [], + "source": [ + "# Standard Kalman filter\n", + "linsys = sys.linearize(xe, [ue, V[:, 0] * 0])\n", + "# print(linsys)\n", + "B = linsys.B[:, 0:2]\n", + "G = linsys.B[:, 2:4]\n", + "linsys = ct.ss(\n", + " linsys.A, B, linsys.C, 0,\n", + " states=sys.state_labels, inputs=sys.input_labels[0:2], outputs=sys.output_labels)\n", + "# print(linsys)\n", + "\n", + "estim = ct.create_estimator_iosystem(linsys, Qv, Qw, G=G, P0=P0)\n", + "print(estim)\n", + "print(f'{xe=}, {P0=}')\n", + "\n", + "kf_resp = ct.input_output_response(\n", + " estim, timepts, [Y, U], X0 = [xe, P0.reshape(-1)])\n", + "plot_state_comparison(timepts, kf_resp.outputs, lqr_resp.states)" + ] + }, + { + "cell_type": "markdown", + "id": "654dde1b", + "metadata": {}, + "source": [ + "### Extended Kalman filter\n", + "\n", + "We see that the standard Kalman filter does not do a good job in estimating the $y$ position (state $x_2$) nor the $y$ velocity (state $x_4$).\n", + "\n", + "A better estimate can be obtained using an extended Kalman filter, which uses the linearization of the system around the current state, rather than a fixed linearization." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "1f83a335", + "metadata": {}, + "outputs": [], + "source": [ + "# Define the disturbance input and measured output matrices\n", + "F = np.array([[0, 0], [0, 0], [0, 0], [1/pvtol.params['m'], 0], [0, 1/pvtol.params['m']], [0, 0]])\n", + "C = np.eye(3, 6)\n", + "\n", + "Qwinv = np.linalg.inv(Qw)\n", + "\n", + "# Estimator update law\n", + "def estimator_update(t, x, u, params):\n", + " # Extract the states of the estimator\n", + " xhat = x[0:pvtol.nstates]\n", + " P = x[pvtol.nstates:].reshape(pvtol.nstates, pvtol.nstates)\n", + "\n", + " # Extract the inputs to the estimator\n", + " y = u[0:3] # just grab the first three outputs\n", + " u = u[6:8] # get the inputs that were applied as well\n", + "\n", + " # Compute the linearization at the current state\n", + " A = pvtol.A(xhat, u) # A matrix depends on current state\n", + " # A = pvtol.A(xe, ue) # Fixed A matrix (for testing/comparison)\n", + " \n", + " # Compute the optimal \"gain\n", + " L = P @ C.T @ Qwinv\n", + "\n", + " # Update the state estimate\n", + " xhatdot = pvtol.updfcn(t, xhat, u, params) - L @ (C @ xhat - y)\n", + "\n", + " # Update the covariance\n", + " Pdot = A @ P + P @ A.T - P @ C.T @ Qwinv @ C @ P + F @ Qv @ F.T\n", + "\n", + " # Return the derivative\n", + " return np.hstack([xhatdot, Pdot.reshape(-1)])\n", + "\n", + "def estimator_output(t, x, u, params):\n", + " # Return the estimator states\n", + " return x[0:pvtol.nstates]\n", + "\n", + "ekf = ct.NonlinearIOSystem(\n", + " estimator_update, estimator_output,\n", + " states=pvtol.nstates + pvtol.nstates**2,\n", + " inputs= pvtol_noisy.output_labels \\\n", + " + pvtol_noisy.input_labels[0:pvtol.ninputs],\n", + " outputs=[f'xh{i}' for i in range(pvtol.nstates)]\n", + ")\n", + "print(ekf)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "a4caf69b", + "metadata": {}, + "outputs": [], + "source": [ + "ekf_resp = ct.input_output_response(\n", + " ekf, timepts, [lqr_resp.states, lqr_resp.outputs[6:8]],\n", + " X0=[xe, P0.reshape(-1)])\n", + "plot_state_comparison(timepts, ekf_resp.outputs, lqr_resp.states)" + ] + }, + { + "cell_type": "markdown", + "id": "10163c6c-5634-4dbb-ba11-e20fb1e065ed", + "metadata": {}, + "source": [ + "## Maximum Likelihood Estimation\n", + "\n", + "Finally, we illustrate how to set up the problem as maximum likelihood problem, which is described in more detail in the [Optimization-Based Control](https://fbswiki.org/wiki/index.php/Supplement:_Optimization-Based_Control) (OBC) course notes, in Section 7.6.\n", + "\n", + "The basic idea in maximum likelihood estimation is to set up the estimation problem as an optimization problem where we define the likelihood of a given estimate (and the resulting noise and disturbances predicted by the\n", + "model) as a cost function." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "1074908c", + "metadata": {}, + "outputs": [], + "source": [ + "# Define the optimal estimation problem\n", + "traj_cost = opt.gaussian_likelihood_cost(sys, Qv, Qw)\n", + "init_cost = lambda xhat, x: (xhat - x) @ P0 @ (xhat - x)\n", + "oep = opt.OptimalEstimationProblem(\n", + " sys, timepts, traj_cost, terminal_cost=init_cost)\n", + "\n", + "# Compute the estimate from the noisy signals\n", + "est = oep.compute_estimate(Y, U, X0=lqr_resp.states[:, 0])\n", + "plot_state_comparison(timepts, est.states, lqr_resp.states)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "0c6981b9", + "metadata": {}, + "outputs": [], + "source": [ + "# Plot the response of the estimator\n", + "plot_estimator_response(timepts, est, U, V, Y, W)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "25b8aa85", + "metadata": {}, + "outputs": [], + "source": [ + "# Noise free and disturbance free => estimation should be near perfect\n", + "noisefree_cost = opt.gaussian_likelihood_cost(sys, Qv, Qw*1e-6)\n", + "oep0 = opt.OptimalEstimationProblem(\n", + " sys, timepts, noisefree_cost, terminal_cost=init_cost)\n", + "est0 = oep0.compute_estimate(Y0, U0, X0=lqr0_resp.states[:, 0],\n", + " initial_guess=(lqr0_resp.states, V * 0))\n", + "plot_state_comparison(\n", + " timepts, est0.states, lqr0_resp.states, estimated_label='$\\\\bar x_{i}$')" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "7a76821f", + "metadata": {}, + "outputs": [], + "source": [ + "plot_estimator_response(timepts, est0, U0, V*0, Y0, W*0)" + ] + }, + { + "cell_type": "markdown", + "id": "6b9031cf", + "metadata": {}, + "source": [ + "### Bounded disturbances\n", + "\n", + "Another situation that the maximum likelihood framework can handle is when input distributions that are bounded. We implement that here by carrying out the optimal estimation problem with constraints." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "93482470", + "metadata": {}, + "outputs": [], + "source": [ + "V_clipped = np.clip(V, -0.05, 0.05) \n", + "\n", + "plt.plot(timepts, V[0], label=\"V[0]\")\n", + "plt.plot(timepts, V_clipped[0], label=\"V[0] clipped\")\n", + "plt.plot(timepts, W[0], label=\"W[0]\")\n", + "plt.legend();" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "56e186f1", + "metadata": {}, + "outputs": [], + "source": [ + "uvec = [xe, ue, V_clipped, W]\n", + "clipped_resp = ct.input_output_response(lqr_clsys, timepts, uvec, x0)\n", + "U_clipped = clipped_resp.outputs[6:8] # controller input signals\n", + "Y_clipped = clipped_resp.outputs[0:3] + W # noisy output signals\n", + "\n", + "traj_constraint = opt.disturbance_range_constraint(\n", + " sys, [-0.05, -0.05], [0.05, 0.05])\n", + "oep_clipped = opt.OptimalEstimationProblem(\n", + " sys, timepts, traj_cost, terminal_cost=init_cost,\n", + " trajectory_constraints=traj_constraint)\n", + "\n", + "est_clipped = oep_clipped.compute_estimate(\n", + " Y_clipped, U_clipped, X0=lqr0_resp.states[:, 0])\n", + "plot_state_comparison(timepts, est_clipped.states, lqr_resp.states)\n", + "plt.suptitle(\"MHE with constraints\")\n", + "plt.tight_layout()\n", + "\n", + "plt.figure()\n", + "ekf_unclipped = ct.input_output_response(\n", + " ekf, timepts, [clipped_resp.states, clipped_resp.outputs[6:8]],\n", + " X0=[xe, P0.reshape(-1)])\n", + "\n", + "plot_state_comparison(timepts, ekf_unclipped.outputs, lqr_resp.states)\n", + "plt.suptitle(\"EKF w/out constraints\")\n", + "plt.tight_layout()" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "108c341a", + "metadata": {}, + "outputs": [], + "source": [ + "plot_estimator_response(timepts, est_clipped, U, V_clipped, Y, W)" + ] + }, + { + "cell_type": "markdown", + "id": "430117ce", + "metadata": {}, + "source": [ + "## Moving Horizon Estimation (MHE)\n", + "\n", + "Finally, we can now move to the implementation of a moving horizon estimator, using our fixed horizon, maximum likelihood, optimal estimator. The details of this implementation are described in more detail in the [Optimization-Based Control](https://fbswiki.org/wiki/index.php/Supplement:_Optimization-Based_Control) (OBC) course notes, in Section 7.6." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "121d67ba", + "metadata": {}, + "outputs": [], + "source": [ + "# Use a shorter horizon\n", + "mhe_timepts = timepts[0:5]\n", + "oep = opt.OptimalEstimationProblem(\n", + " sys, mhe_timepts, traj_cost, terminal_cost=init_cost)\n", + "\n", + "try:\n", + " mhe = oep.create_mhe_iosystem(2)\n", + " \n", + " est_mhe = ct.input_output_response(\n", + " mhe, timepts, [Y, U], X0=resp.states[:, 0], \n", + " params={'verbose': True}\n", + " )\n", + " plot_state_comparison(timepts, est_mhe.states, lqr_resp.states)\n", + "except:\n", + " print(\"MHE for continuous time systems not implemented\")" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "1914ad96", + "metadata": {}, + "outputs": [], + "source": [ + "# Create discrete time version of PVTOL\n", + "Ts = 0.1\n", + "print(f\"Sample time: {Ts=}\")\n", + "dsys = ct.nlsys(\n", + " lambda t, x, u, params: x + Ts * sys.updfcn(t, x, u, params),\n", + " sys.outfcn, dt=Ts, states=sys.state_labels,\n", + " inputs=sys.input_labels, outputs=sys.output_labels,\n", + ")\n", + "print(dsys)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "11162130", + "metadata": {}, + "outputs": [], + "source": [ + "# Create a new list of time points\n", + "timepts = np.arange(0, Tf, Ts)\n", + "\n", + "# Create representative process disturbance and sensor noise vectors\n", + "# np.random.seed(117) # avoid figures changing from run to run\n", + "V = ct.white_noise(timepts, Qv)\n", + "# V = np.clip(V0, -0.1, 0.1) # Hold for later\n", + "W = ct.white_noise(timepts, Qw, dt=Ts)\n", + "# plt.plot(timepts, V0[0], 'b--', label=\"V[0]\")\n", + "plt.plot(timepts, V[0], label=\"V[0]\")\n", + "plt.plot(timepts, W[0], label=\"W[0]\")\n", + "plt.legend();" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "c8a6a693", + "metadata": {}, + "outputs": [], + "source": [ + "# Generate a new trajectory over the longer time vector\n", + "uvec = [xd, ud, V, W*0]\n", + "lqr_resp = ct.input_output_response(lqr_clsys, timepts, uvec, x0)\n", + "U = lqr_resp.outputs[6:8] # controller input signals\n", + "Y = lqr_resp.outputs[0:3] + W # noisy output signals" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "d683767f", + "metadata": {}, + "outputs": [], + "source": [ + "mhe_timepts = timepts[0:10]\n", + "oep = opt.OptimalEstimationProblem(\n", + " dsys, mhe_timepts, traj_cost, terminal_cost=init_cost,\n", + " disturbance_indices=[2, 3])\n", + "mhe = oep.create_mhe_iosystem()\n", + " \n", + "mhe_resp = ct.input_output_response(\n", + " mhe, timepts, [Y, U], X0=x0, \n", + " params={'verbose': True}\n", + ")\n", + "plot_state_comparison(timepts, mhe_resp.states, lqr_resp.states)" + ] + }, + { + "cell_type": "markdown", + "id": "ad6aac39-5b55-4ffd-ab21-44385dc11ff5", + "metadata": {}, + "source": [ + "Although this estimator eventually converges to the underlying tate of the system, the initial transient response is quite poor.\n", + "\n", + "One possible explanation is that we are not starting the system at the origin, even though we are penalizing the initial state if it is away from the origin.\n", + "\n", + "To see if this matters, we shift the problem to one in which the system's initial condition is at the origin:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "bfc68072", + "metadata": {}, + "outputs": [], + "source": [ + "# Resimulate starting at the origin and moving to the \"initial\" condition\n", + "uvec = [x0, ue, V, W*0]\n", + "lqr_resp = ct.input_output_response(lqr_clsys, timepts, uvec, xe)\n", + "U = lqr_resp.outputs[6:8] # controller input signals\n", + "Y = lqr_resp.outputs[0:3] + W # noisy output signals" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "49213d04", + "metadata": {}, + "outputs": [], + "source": [ + "mhe_timepts = timepts[0:8]\n", + "oep = opt.OptimalEstimationProblem(\n", + " dsys, mhe_timepts, traj_cost, terminal_cost=init_cost,\n", + " disturbance_indices=[2, 3])\n", + "mhe = oep.create_mhe_iosystem()\n", + " \n", + "mhe_resp = ct.input_output_response(\n", + " mhe, timepts, [Y, U],\n", + " params={'verbose': True}\n", + ")\n", + "plot_state_comparison(timepts, mhe_resp.outputs, lqr_resp.states)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "650a559a", + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/examples/describing_functions.ipynb b/examples/describing_functions.ipynb index fc7185901..5d433c4c6 100644 --- a/examples/describing_functions.ipynb +++ b/examples/describing_functions.ipynb @@ -232,7 +232,7 @@ "$$\n", "H(j\\omega) N(a) = -1$$\n", "\n", - "The `describing_function_plot` function plots $H(j\\omega)$ and $-1/N(a)$ and prints out the the amplitudes and frequencies corresponding to intersections of these curves. " + "The `describing_function_plot` function plots $H(j\\omega)$ and $-1/N(a)$ and prints out the amplitudes and frequencies corresponding to intersections of these curves. " ] }, { diff --git a/examples/kincar.py b/examples/kincar.py new file mode 100644 index 000000000..a12cdc774 --- /dev/null +++ b/examples/kincar.py @@ -0,0 +1,113 @@ +# kincar.py - planar vehicle model (with flatness) +# RMM, 16 Jan 2022 + +import numpy as np +import matplotlib.pyplot as plt +import control as ct +import control.flatsys as fs + +# +# Vehicle dynamics (bicycle model) +# + +# Function to take states, inputs and return the flat flag +def _kincar_flat_forward(x, u, params={}): + # Get the parameter values + b = params.get('wheelbase', 3.) + #! TODO: add dir processing + + # Create a list of arrays to store the flat output and its derivatives + zflag = [np.zeros(3), np.zeros(3)] + + # Flat output is the x, y position of the rear wheels + zflag[0][0] = x[0] + zflag[1][0] = x[1] + + # First derivatives of the flat output + zflag[0][1] = u[0] * np.cos(x[2]) # dx/dt + zflag[1][1] = u[0] * np.sin(x[2]) # dy/dt + + # First derivative of the angle + thdot = (u[0]/b) * np.tan(u[1]) + + # Second derivatives of the flat output (setting vdot = 0) + zflag[0][2] = -u[0] * thdot * np.sin(x[2]) + zflag[1][2] = u[0] * thdot * np.cos(x[2]) + + return zflag + +# Function to take the flat flag and return states, inputs +def _kincar_flat_reverse(zflag, params={}): + # Get the parameter values + b = params.get('wheelbase', 3.) + dir = params.get('dir', 'f') + + # Create a vector to store the state and inputs + x = np.zeros(3) + u = np.zeros(2) + + # Given the flat variables, solve for the state + x[0] = zflag[0][0] # x position + x[1] = zflag[1][0] # y position + if dir == 'f': + x[2] = np.arctan2(zflag[1][1], zflag[0][1]) # tan(theta) = ydot/xdot + elif dir == 'r': + # Angle is flipped by 180 degrees (since v < 0) + x[2] = np.arctan2(-zflag[1][1], -zflag[0][1]) + else: + raise ValueError("unknown direction:", dir) + + # And next solve for the inputs + u[0] = zflag[0][1] * np.cos(x[2]) + zflag[1][1] * np.sin(x[2]) + thdot_v = zflag[1][2] * np.cos(x[2]) - zflag[0][2] * np.sin(x[2]) + u[1] = np.arctan2(thdot_v, u[0]**2 / b) + + return x, u + +# Function to compute the RHS of the system dynamics +def _kincar_update(t, x, u, params): + b = params.get('wheelbase', 3.) # get parameter values + #! TODO: add dir processing + dx = np.array([ + np.cos(x[2]) * u[0], + np.sin(x[2]) * u[0], + (u[0]/b) * np.tan(u[1]) + ]) + return dx + +def _kincar_output(t, x, u, params): + return x # return x, y, theta (full state) + +# Create differentially flat input/output system +kincar = fs.FlatSystem( + _kincar_flat_forward, _kincar_flat_reverse, name="kincar", + updfcn=_kincar_update, outfcn=_kincar_output, + inputs=('v', 'delta'), outputs=('x', 'y', 'theta'), + states=('x', 'y', 'theta')) + +# +# Utility function to plot lane change maneuver +# + +def plot_lanechange(t, y, u, figure=None, yf=None): + # Plot the xy trajectory + plt.subplot(3, 1, 1, label='xy') + plt.plot(y[0], y[1]) + plt.xlabel("x [m]") + plt.ylabel("y [m]") + if yf is not None: + plt.plot(yf[0], yf[1], 'ro') + + # Plot the inputs as a function of time + plt.subplot(3, 1, 2, label='v') + plt.plot(t, u[0]) + plt.xlabel("Time $t$ [sec]") + plt.ylabel("$v$ [m/s]") + + plt.subplot(3, 1, 3, label='delta') + plt.plot(t, u[1]) + plt.xlabel("Time $t$ [sec]") + plt.ylabel("$\\delta$ [rad]") + + plt.suptitle("Lane change maneuver") + plt.tight_layout() diff --git a/examples/steering-optimal.py b/examples/steering-optimal.py index d9bad608e..80ad671f6 100644 --- a/examples/steering-optimal.py +++ b/examples/steering-optimal.py @@ -79,14 +79,14 @@ def plot_lanechange(t, y, u, yf=None, figure=None): plt.xlabel("t [sec]") plt.ylabel("steering [rad/s]") - plt.suptitle("Lane change manuever") + plt.suptitle("Lane change maneuver") plt.tight_layout() plt.show(block=False) # # Optimal control problem # -# Perform a "lane change" manuever over the course of 10 seconds. +# Perform a "lane change" maneuver over the course of 10 seconds. # # Initial and final conditions diff --git a/examples/vehicle-steering.png b/examples/vehicle-steering.png deleted file mode 100644 index f10aab853..000000000 Binary files a/examples/vehicle-steering.png and /dev/null differ diff --git a/examples/vehicle.py b/examples/vehicle.py index b316ceced..07af35c9f 100644 --- a/examples/vehicle.py +++ b/examples/vehicle.py @@ -84,7 +84,7 @@ def _vehicle_output(t, x, u, params): states=('x', 'y', 'theta')) # -# Utility function to plot lane change manuever +# Utility function to plot lane change maneuver # def plot_lanechange(t, y, u, figure=None, yf=None): @@ -107,5 +107,5 @@ def plot_lanechange(t, y, u, figure=None, yf=None): plt.xlabel("t [sec]") plt.ylabel("steering [rad/s]") - plt.suptitle("Lane change manuever") + plt.suptitle("Lane change maneuver") plt.tight_layout()