{"nbformat":4,"nbformat_minor":0,"metadata":{"celltoolbar":"Tags","kernelspec":{"display_name":"Python 3","language":"python","name":"python3"},"language_info":{"codemirror_mode":{"name":"ipython","version":3},"file_extension":".py","mimetype":"text/x-python","name":"python","nbconvert_exporter":"python","pygments_lexer":"ipython3","version":"3.6.10"},"colab":{"name":"ilqr_driving.ipynb","provenance":[{"file_id":"https://github.com/RussTedrake/underactuated/blob/master/exercises/trajopt/ilqr_driving/ilqr_driving.ipynb","timestamp":1619128834651}],"collapsed_sections":[]}},"cells":[{"cell_type":"markdown","metadata":{"id":"23NQsXwOl-VJ"},"source":["# Iterative Linear Quadratic Regulator"]},{"cell_type":"markdown","metadata":{"id":"hlsjBjfOl-VR"},"source":["## Notebook Setup \n","The following cell will install Drake, checkout the underactuated repository, and set up the path (only if necessary).\n","- On Google's Colaboratory, this **will take approximately two minutes** on the first time it runs (to provision the machine), but should only need to reinstall once every 12 hours. Colab will ask you to \"Reset all runtimes\"; say no to save yourself the reinstall.\n","- On Binder, the machines should already be provisioned by the time you can run this; it should return (almost) instantly.\n","\n","More details are available [here](http://underactuated.mit.edu/drake.html)."]},{"cell_type":"code","metadata":{"id":"lVM6NYSil-VS","colab":{"base_uri":"https://localhost:8080/"},"executionInfo":{"status":"ok","timestamp":1619218256235,"user_tz":240,"elapsed":146912,"user":{"displayName":"Manmeet Bhabra","photoUrl":"","userId":"11686790358753401934"}},"outputId":"239f6180-ffad-4a94-bfe1-728e9c432882"},"source":["try:\n"," import pydrake\n"," import underactuated\n","except ImportError:\n"," !curl -s https://raw.githubusercontent.com/RussTedrake/underactuated/master/scripts/setup/jupyter_setup.py > jupyter_setup.py\n"," from jupyter_setup import setup_underactuated\n"," setup_underactuated()\n","\n","# Setup matplotlib backend (to notebook, if possible, or inline). \n","from underactuated.jupyter import setup_matplotlib_backend\n","plt_is_interactive = setup_matplotlib_backend()"],"execution_count":1,"outputs":[{"output_type":"stream","text":["/content/jupyter_setup.py:13: UserWarning: jupyter_setup.py is deprecated. Please use setup_underactuated_colab.py instead.\n"," warnings.warn(\"jupyter_setup.py is deprecated. Please use\"\n"],"name":"stderr"},{"output_type":"stream","text":["Cloning into '/opt/underactuated'...\n","\n","HEAD is now at 2a15bde minor reword on exercise 7.2 (#428)\n","\n","ERROR: torchtext 0.9.1 has requirement torch==1.8.1, but you'll have torch 1.7.1 which is incompatible.\n","ERROR: bokeh 2.3.1 has requirement pillow>=7.1.0, but you'll have pillow 7.0.0 which is incompatible.\n","ERROR: albumentations 0.1.12 has requirement imgaug<0.2.7,>=0.2.5, but you'll have imgaug 0.2.9 which is incompatible.\n","\n","\n","WARNING: apt does not have a stable CLI interface. Use with caution in scripts.\n","\n","\n"],"name":"stdout"}]},{"cell_type":"code","metadata":{"id":"ZbGv-S7ql-VT","executionInfo":{"status":"ok","timestamp":1619218256236,"user_tz":240,"elapsed":146907,"user":{"displayName":"Manmeet Bhabra","photoUrl":"","userId":"11686790358753401934"}}},"source":["# python libraries\n","import numpy as np\n","import matplotlib.pyplot as plt\n","import matplotlib as mpl\n","\n","# pydrake imports\n","from pydrake.all import (Variable, SymbolicVectorSystem, DiagramBuilder,\n"," LogOutput, Simulator, ConstantVectorSource,\n"," MathematicalProgram, Solve, SnoptSolver, PiecewisePolynomial)\n","import pydrake.symbolic as sym"],"execution_count":2,"outputs":[]},{"cell_type":"markdown","metadata":{"id":"kbZo-Vjcl-VT"},"source":["## Iterative Linear Quadratic Regulator Derivation\n","\n","In this exercise we will derive the iterative Linear Quadratic Regulator (iLQR) solving the following optimization problem.\n","\n","\\begin{align*} \\min_{\\mathbf{u}[\\cdot]} \\quad & \\ell_f(\\mathbf{x}[N]) +\n"," \\sum_{n=0}^{N-1} \\ell(\\mathbf{x}[n],\\mathbf{u}[n]) \\\\ \\text{subject to} \\quad & \\mathbf{x}[n+1] = {\\bf\n"," f}(\\mathbf{x}[n], \\mathbf{u}[n]), \\quad \\forall n\\in[0, N-1] \\\\ & \\mathbf{x}[0] = \\mathbf{x}_0\n","\\end{align*}\n","\n","After completing this exercise you will be able to write your own MPC solver from scratch without any proprietary or third-party software (with the exception of auto-differentiation). You will derive all necessary equations yourself.\n","While the iLQR algorithm will be capable of solving general model predictive control problems in the form described above, we will apply it to the control of a vehicle. \n","\n","### Vehicle Control Problem\n","Before we start the actual derivation of iLQR we will take a look at the vehicle dynamics and cost functions. The vehicle has the following continuous time dynamics and is controlled by longitudinal acceleration and steering velocity."]},{"cell_type":"code","metadata":{"id":"a6mJKOvZl-VU","executionInfo":{"status":"ok","timestamp":1619218256237,"user_tz":240,"elapsed":146903,"user":{"displayName":"Manmeet Bhabra","photoUrl":"","userId":"11686790358753401934"}}},"source":["n_x = 5\n","n_u = 2\n","def car_continuous_dynamics(x, u):\n"," # x = [x position, y position, heading, speed, steering angle] \n"," # u = [acceleration, steering velocity]\n"," m = sym if x.dtype == object else np # Check type for autodiff\n"," heading = x[2]\n"," v = x[3]\n"," steer = x[4]\n"," x_d = np.array([\n"," v*m.cos(heading),\n"," v*m.sin(heading),\n"," v*m.tan(steer),\n"," u[0],\n"," u[1] \n"," ])\n"," return x_d"],"execution_count":3,"outputs":[]},{"cell_type":"markdown","metadata":{"id":"fLCctl1Ql-VU"},"source":["Note that while the vehicle dynamics are in continuous time, our problem formulation is in discrete time. Define the general discrete time dynamics $\\bf f$ with a simple [Euler integrator](https://en.wikipedia.org/wiki/Euler_method) in the next cell."]},{"cell_type":"code","metadata":{"id":"vfFjPCXjl-VV","executionInfo":{"status":"ok","timestamp":1619218256237,"user_tz":240,"elapsed":146714,"user":{"displayName":"Manmeet Bhabra","photoUrl":"","userId":"11686790358753401934"}}},"source":["def discrete_dynamics(x, u):\n"," dt = 0.1\n"," # TODO: Fill in the Euler integrator below and return the next state\n"," x_next = x + dt*car_continuous_dynamics(x,u)\n"," return x_next"],"execution_count":4,"outputs":[]},{"cell_type":"markdown","metadata":{"id":"I44cEXHkl-VV"},"source":["Given an initial state $\\mathbf{x}_0$ and a guess of a control trajectory $\\mathbf{u}[0:N-1]$ we roll out the state trajectory $x[0:N]$ until the time horizon $N$. Please complete the rollout function."]},{"cell_type":"code","metadata":{"id":"xljtEAHQl-VV","executionInfo":{"status":"ok","timestamp":1619218256238,"user_tz":240,"elapsed":146235,"user":{"displayName":"Manmeet Bhabra","photoUrl":"","userId":"11686790358753401934"}}},"source":["def rollout(x0, u_trj):\n"," x_trj = np.zeros((u_trj.shape[0]+1, x0.shape[0]))\n"," \n"," # TODO: Define the rollout here and return the state trajectory x_trj: [N, number of states]\n","\n"," # Set the initial condition\n"," x_trj[0,:] = x0\n"," \n"," # Loop over the states from n = 0 to n = N-1 and \n"," # get the resulting trajectory (get the next state using\n"," # the discretized dynamics)\n"," N = u_trj.shape[0] + 1\n"," for i in range(0,N-1):\n"," x_trj[i+1,:] = discrete_dynamics(x_trj[i,:], u_trj[i,:])\n"," \n"," return x_trj\n","\n","# Debug your implementation with this example code\n","N = 10\n","x0 = np.array([1, 0, 0, 1, 0])\n","u_trj = np.zeros((N-1, n_u))\n","x_trj = rollout(x0, u_trj)"],"execution_count":5,"outputs":[]},{"cell_type":"markdown","metadata":{"id":"VYAWJ1gjl-VW"},"source":["We define the stage cost function $\\ell$ and final cost function $\\ell_f$. The goal of these cost functions is to drive the vehicle along a circle with radius $r$ around the origin with a desired speed."]},{"cell_type":"code","metadata":{"id":"4G8ds6Qol-VW","executionInfo":{"status":"ok","timestamp":1619218256238,"user_tz":240,"elapsed":145831,"user":{"displayName":"Manmeet Bhabra","photoUrl":"","userId":"11686790358753401934"}}},"source":["r = 2.0\n","v_target = 2.0\n","eps = 1e-6 # The derivative of sqrt(x) at x=0 is undefined. Avoid by subtle smoothing\n","def cost_stage(x, u):\n"," m = sym if x.dtype == object else np # Check type for autodiff\n"," c_circle = (m.sqrt(x[0]**2 + x[1]**2 + eps) - r)**2\n"," c_speed = (x[3]-v_target)**2\n"," c_control= (u[0]**2 + u[1]**2)*0.1\n"," return c_circle + c_speed + c_control\n","\n","def cost_final(x):\n"," m = sym if x.dtype == object else np # Check type for autodiff\n"," c_circle = (m.sqrt(x[0]**2 + x[1]**2 + eps) - r)**2\n"," c_speed = (x[3]-v_target)**2\n"," return c_circle + c_speed"],"execution_count":6,"outputs":[]},{"cell_type":"markdown","metadata":{"id":"o7RNi0sOl-VX"},"source":["Your next task is to write the total cost function of the state and control trajectory. This is simply the sum of all stages over the control horizon and the objective from general problem formulation above."]},{"cell_type":"code","metadata":{"id":"7X0KT5VQl-VX","colab":{"base_uri":"https://localhost:8080/"},"executionInfo":{"status":"ok","timestamp":1619218256239,"user_tz":240,"elapsed":145503,"user":{"displayName":"Manmeet Bhabra","photoUrl":"","userId":"11686790358753401934"}},"outputId":"2deb0b9c-64b1-41dd-896e-1e9e6af91a31"},"source":["def cost_trj(x_trj, u_trj):\n"," total = 0.0\n","\n"," # TODO: Sum up all costs\n","\n"," # Look to find the cost associated with this trajectory\n"," # (1) Additive Cost\n"," for i in range(x_trj.shape[0]-1):\n"," total += cost_stage(x_trj[i,:], u_trj[i,:])\n"," \n"," # (2) Terminal Cost\n"," total += cost_final(x_trj[-1,:])\n","\n"," return total\n"," \n","# Debug your code\n","cost_trj(x_trj, u_trj)"],"execution_count":7,"outputs":[{"output_type":"execute_result","data":{"text/plain":["13.84999562457404"]},"metadata":{"tags":[]},"execution_count":7}]},{"cell_type":"markdown","metadata":{"id":"btxf7eUrl-VY"},"source":["### Bellman Recursion\n","\n","Now that we are warmed up, let's derive the actual algorithm. We start with the Bellman equation known from lecture defining optimality in a recursively backwards in time.\n","\\begin{align*} V(\\mathbf{x}[n]) = & \\min_{\\mathbf{u}[n]} \\quad \\ell(\\mathbf{x}[n], \\mathbf{u}[n]) + V(\\mathbf{x}[n+1]) \\\\\n","\\end{align*}\n","\n","You may have noticed that we neglected a couple of constraints of the original problem formulation. The fully equivalent formulation is \n","\\begin{align*} \\min_{\\mathbf{u}[n]} \\quad & Q(\\mathbf{x}[n], \\mathbf{u}[n]), \\quad \\forall n\\in[0, N-1]\n","\\\\ \\text{subject to} \\quad \n","& Q(\\mathbf{x}[n], \\mathbf{u}[n]) = \\ell(\\mathbf{x}[n], \\mathbf{u}[n]) + V(\\mathbf{x}[n+1]) \\\\\n","& V(\\mathbf{x}[N]) = \\ell_f(\\mathbf{x}[N]) \\\\\n","& \\mathbf{x}[n+1] = {\\bf f}(\\mathbf{x}[n], \\mathbf{u}[n]), \\quad \\\\ \n","& \\mathbf{x}[0] = \\mathbf{x}_0.\n","\\end{align*}\n","The definition of a Q-function will become handy during the derivation of the algorithm.\n","\n","The key idea of iLQR is simple: Approximate the dynamics linearly and the costs quadratically around a nominal trajectory. We will expand all terms of the Q-function accordingly and optimize the resulting quadratic equation for an optimal linear control law in closed form. We will see that by applying the Bellman equation recursively backwards in time, the value function remains a quadratic.\n","The linear and quadratic approximations are computed around the nominal state $\\bf \\bar{x} = \\bf x - \\delta \\bf x$ and the nominal control $\\bf \\bar{u} = \\bf u - \\delta \\bf u$. After applying the Bellman equation backwards in time from time $N$ to $0$ (the backward pass), we will update the nominal controls $\\bf \\bar{u}$ and states $\\bf \\bar{x}$ by applying the computed linear feedback law from the backward pass and rolling out the dynamics from the initial state $\\bf x_0$ to the final horizon $N$. Iterating between backwards and forwards pass optimizes the control problem.\n","\n","### Q-function Expansion\n","\n","Let's start by expanding all terms in the Q-function of the Bellman equation. The quadaratic cost function is\n","\\begin{align*} \n","\\ell(\\mathbf{x}[n], \\mathbf{u}[n]) \\approx \\ell_n \n","+ \\begin{bmatrix}\\ell_{\\mathbf{x},n} \\\\ \\ell_{\\mathbf{u},n} \\end{bmatrix} ^T \\begin{bmatrix} \\delta \\mathbf{x}[n] \\\\ \\delta \\mathbf{u}[n] \\end{bmatrix}\n","+ \\frac{1}{2}\\begin{bmatrix} \\delta \\mathbf{x}[n] \\\\ \\delta \\mathbf{u}[n] \\end{bmatrix} ^T \n","\\begin{bmatrix}\\ell_{\\mathbf{xx},n} & \\ell_{\\mathbf{ux},n}^T\\\\ \n","\\ell_{\\mathbf{ux},n} & \\ell_{\\mathbf{uu},n}\\end{bmatrix}\n"," \\begin{bmatrix} \\delta \\mathbf{x}[n] \\\\ \\delta \\mathbf{u}[n] \\end{bmatrix},\n","\\end{align*}\n","and the dynamics function is\n","\\begin{align*} x[n+1]=\n","\\mathbf{f}(\\mathbf{x}[n], \\mathbf{u}[n]) \\approx \\mathbf{f}_n\n","+ \\begin{bmatrix}\\mathbf{f}_{\\mathbf{x},n} & \\mathbf{f}_{\\mathbf{u},n} \\end{bmatrix} \\begin{bmatrix} \\delta \\mathbf{x}[n] \\\\ \\delta \\mathbf{u}[n] \\end{bmatrix}.\n","\\end{align*}\n","Here, $\\ell = \\ell(\\bar{\\mathbf{x}}, \\bar{\\mathbf{u}})$ and $\\mathbf{f} = \\mathbf{f}(\\bar{\\mathbf{x}}, \\bar{\\mathbf{u}})$. $\\ell_\\mathbf{x}, \\ell_\\mathbf{u}, \\mathbf{f}_\\mathbf{x}, \\mathbf{f}_\\mathbf{u}$ are the gradients and Jacobians evaluated at $\\bar{\\mathbf{x}}$ and $\\bar{\\mathbf{u}}$. $\\ell_\\mathbf{xx}, \\ell_\\mathbf{ux}, \\ell_\\mathbf{uu}$ are the Hessians at $\\bar{\\mathbf{x}}$ and $\\bar{\\mathbf{u}}$. The expansion of the final cost follows analogously.\n","The code to evaluate all the derivative terms is:"]},{"cell_type":"code","metadata":{"id":"CAzIKONql-VY","executionInfo":{"status":"ok","timestamp":1619218256392,"user_tz":240,"elapsed":145364,"user":{"displayName":"Manmeet Bhabra","photoUrl":"","userId":"11686790358753401934"}}},"source":["class derivatives():\n"," def __init__(self, discrete_dynamics, cost_stage, cost_final, n_x, n_u):\n"," self.x_sym = np.array([sym.Variable(\"x_{}\".format(i)) for i in range(n_x)])\n"," self.u_sym = np.array([sym.Variable(\"u_{}\".format(i)) for i in range(n_u)])\n"," x = self.x_sym\n"," u = self.u_sym\n"," \n"," l = cost_stage(x, u)\n"," self.l_x = sym.Jacobian([l], x).ravel()\n"," self.l_u = sym.Jacobian([l], u).ravel()\n"," self.l_xx = sym.Jacobian(self.l_x, x)\n"," self.l_ux = sym.Jacobian(self.l_u, x)\n"," self.l_uu = sym.Jacobian(self.l_u, u)\n"," \n"," l_final = cost_final(x)\n"," self.l_final_x = sym.Jacobian([l_final], x).ravel()\n"," self.l_final_xx = sym.Jacobian(self.l_final_x, x)\n"," \n"," f = discrete_dynamics(x, u)\n"," self.f_x = sym.Jacobian(f, x)\n"," self.f_u = sym.Jacobian(f, u)\n"," \n"," def stage(self, x, u):\n"," env = {self.x_sym[i]: x[i] for i in range(x.shape[0])}\n"," env.update({self.u_sym[i]: u[i] for i in range(u.shape[0])})\n"," \n"," l_x = sym.Evaluate(self.l_x, env).ravel()\n"," l_u = sym.Evaluate(self.l_u, env).ravel()\n"," l_xx = sym.Evaluate(self.l_xx, env)\n"," l_ux = sym.Evaluate(self.l_ux, env)\n"," l_uu = sym.Evaluate(self.l_uu, env)\n"," \n"," f_x = sym.Evaluate(self.f_x, env)\n"," f_u = sym.Evaluate(self.f_u, env)\n","\n"," return l_x, l_u, l_xx, l_ux, l_uu, f_x, f_u\n"," \n"," def final(self, x):\n"," env = {self.x_sym[i]: x[i] for i in range(x.shape[0])}\n"," \n"," l_final_x = sym.Evaluate(self.l_final_x, env).ravel()\n"," l_final_xx = sym.Evaluate(self.l_final_xx, env)\n"," \n"," return l_final_x, l_final_xx\n"," \n","derivs = derivatives(discrete_dynamics, cost_stage, cost_final, n_x, n_u)\n","# Test the output:\n","# x = np.array([0, 0, 0, 0, 0])\n","# u = np.array([0, 0])\n","# print(derivs.stage(x, u))\n","# print(derivs.final(x))"],"execution_count":8,"outputs":[]},{"cell_type":"markdown","metadata":{"id":"CRiMokHHl-VZ"},"source":["Expanding the second term of the Q-function of the Bellman equation, i.e. the value function at the next state $\\mathbf{x}[n+1]$, to second order yields \\begin{align*} \n","V(\\mathbf{x}[n+1]) \\approx V_{n+1} + \n","V_{\\mathbf{x},n+1}^T \\delta \\mathbf{x}[n+1] + \\frac{1}{2}\\delta \\mathbf{x}[n+1]^T \n","V_{\\mathbf{xx},n+1} \\delta \\mathbf{x}[n+1],\n","\\end{align*}\n","where $\\delta \\mathbf{x}[n+1]$ is given by\n","\\begin{align*} \n","\\delta \\mathbf{x}[n+1] \n","& = \\mathbf{x}[n+1] - \\bar{\\mathbf{x}}[n+1] \\\\\n","& = \\mathbf{f}_n + \\begin{bmatrix}\\mathbf{f}_{\\mathbf{x},n} & \\mathbf{f}_{\\mathbf{u},n} \\end{bmatrix} \\begin{bmatrix} \\delta \\mathbf{x}[n] \\\\ \\delta \\mathbf{u}[n] \\end{bmatrix} - \\bar{\\mathbf{x}}[n+1] \\\\\n","& = \\mathbf{f}_n + \\begin{bmatrix}\\mathbf{f}_{\\mathbf{x},n} & \\mathbf{f}_{\\mathbf{u},n} \\end{bmatrix} \\begin{bmatrix} \\delta \\mathbf{x}[n] \\\\ \\delta \\mathbf{u}[n] \\end{bmatrix} - \\mathbf{f}(\\bar{\\mathbf{x}}[n], \\bar{\\mathbf{u}}[n]) \\\\\n","& = \\begin{bmatrix}\\mathbf{f}_{\\mathbf{x},n} & \\mathbf{f}_{\\mathbf{u},n} \\end{bmatrix} \\begin{bmatrix} \\delta \\mathbf{x}[n] \\\\ \\delta \\mathbf{u}[n] \\end{bmatrix}.\n","\\end{align*}\n","\n","We have now expanded all terms of the Bellman equation and can regroup them in the form of\n","\\begin{align*} \n","Q(\\mathbf{x}[n], \\mathbf{u}[n]) & \n","\\approx \\ell_n \n","+ \\begin{bmatrix}\\ell_{\\mathbf{x},n} \\\\ \\ell_{\\mathbf{u},n} \\end{bmatrix} ^T \\begin{bmatrix} \\delta \\mathbf{x}[n] \\\\ \\delta \\mathbf{u}[n] \\end{bmatrix}\n","+ \\frac{1}{2}\\begin{bmatrix} \\delta \\mathbf{x}[n] \\\\ \\delta \\mathbf{u}[n] \\end{bmatrix} ^T \n","\\begin{bmatrix}\\ell_{\\mathbf{xx},n} & \\ell_{\\mathbf{ux},n}^T\\\\ \n","\\ell_{\\mathbf{ux},n} & \\ell_{\\mathbf{uu},n}\\end{bmatrix}\n"," \\begin{bmatrix} \\delta \\mathbf{x}[n] \\\\ \\delta \\mathbf{u}[n] \\end{bmatrix}, \\\\\n"," & \\quad + V_{n+1} + \n","V_{\\mathbf{x},n+1}^T \\delta \\mathbf{x}[n+1] + \\frac{1}{2}\\delta \\mathbf{x}[n+1]^T \n","V_{\\mathbf{xx},n+1} \\delta \\mathbf{x}[n+1], \\\\\n","& = Q_n \n","+ \\begin{bmatrix} Q_{\\mathbf{x},n} \\\\ Q_{\\mathbf{u},n} \\end{bmatrix} ^T \\begin{bmatrix} \\delta \\mathbf{x}[n] \\\\ \\delta \\mathbf{u}[n] \\end{bmatrix}\n","+ \\frac{1}{2}\\begin{bmatrix} \\delta \\mathbf{x}[n] \\\\ \\delta \\mathbf{u}[n] \\end{bmatrix} ^T \n","\\begin{bmatrix} Q_{\\mathbf{xx},n} & Q_{\\mathbf{ux},n}^T\\\\ \n","Q_{\\mathbf{ux},n} & Q_{\\mathbf{uu},n}\\end{bmatrix}\n"," \\begin{bmatrix} \\delta \\mathbf{x}[n] \\\\ \\delta \\mathbf{u}[n] \\end{bmatrix}.\n","\\end{align*}\n","Find $Q_{\\mathbf{x},n}$, $Q_{\\mathbf{u},n}$, $Q_{\\mathbf{xx},n}$, $Q_{\\mathbf{ux},n}$, $Q_{\\mathbf{uu},n}$ in terms of $\\ell$ and $\\textbf{f}$ and their expansions by collecitng coefficients in $(\\cdot)\\delta \\mathbf{x}[n]$, $(\\cdot)\\delta \\mathbf{u}[n]$, $1/2 \\delta \\mathbf{x}[n]^T (\\cdot) \\delta \\mathbf{x}[n]$, and similar. Write your results in the corresponding function below."]},{"cell_type":"code","metadata":{"id":"ycO2vBUbl-Va","executionInfo":{"status":"ok","timestamp":1619218256392,"user_tz":240,"elapsed":144847,"user":{"displayName":"Manmeet Bhabra","photoUrl":"","userId":"11686790358753401934"}}},"source":["def Q_terms(l_x, l_u, l_xx, l_ux, l_uu, f_x, f_u, V_x, V_xx):\n"," # TODO: Define the Q-terms here\n","\n"," # Q_x = np.zeros(l_x.shape)\n"," # Q_u = np.zeros(l_u.shape)\n"," # Q_xx = np.zeros(l_xx.shape)\n"," # Q_ux = np.zeros(l_ux.shape)\n"," # Q_uu = np.zeros(l_uu.shape)\n","\n"," Q_x = l_x + (f_x.T).dot(V_x)\n"," Q_u = l_u + (f_u.T).dot(V_x)\n","\n"," Q_xx = l_xx + (f_x.T).dot(V_xx).dot(f_x)\n"," Q_ux = l_ux + (f_u.T).dot(V_xx).dot(f_x)\n"," Q_uu = l_uu + (f_u.T).dot(V_xx).dot(f_u)\n","\n"," return Q_x, Q_u, Q_xx, Q_ux, Q_uu"],"execution_count":9,"outputs":[]},{"cell_type":"markdown","metadata":{"id":"9BHwTV2Nl-Va"},"source":["### Q-function Optimization and Optimal Linear Control Law\n","Amazing! Now that we have the Q-function in quadratic form, we can optimize for the optimal control gains in closed form.\n","The original formulation, i.e. optimizing over $\\mathbf{u}[n]$,\n","\\begin{align*} \\min_{\\mathbf{u}[n]} \\quad & Q(\\mathbf{x}[n], \\mathbf{u}[n]),\n","\\end{align*} is equivalent to optimzing over $\\delta \\mathbf{u}[n]$.\n","\n","\\begin{align*} \n","\\delta \\mathbf{u}[n]^* = {\\arg\\!\\min}_{\\delta \\mathbf{u}[n]} \\quad Q_n \n","+ \\begin{bmatrix} Q_{\\mathbf{x},n} \\\\ Q_{\\mathbf{u},n} \\end{bmatrix} ^T \\begin{bmatrix} \\delta \\mathbf{x}[n] \\\\ \\delta \\mathbf{u}[n] \\end{bmatrix} + \\frac{1}{2}\\begin{bmatrix} \\delta \\mathbf{x}[n] \\\\ \\delta \\mathbf{u}[n] \\end{bmatrix} ^T \n","\\begin{bmatrix} Q_{\\mathbf{xx},n} & Q_{\\mathbf{ux},n}^T\\\\ \n","Q_{\\mathbf{ux},n} & Q_{\\mathbf{uu},n}\\end{bmatrix}\n"," \\begin{bmatrix} \\delta \\mathbf{x}[n] \\\\ \\delta \\mathbf{u}[n] \\end{bmatrix}\n"," = k + K \\delta \\mathbf{x}[n]\n","\\end{align*} It turns out that the optimal control is linear in $\\delta \\mathbf{x}[n]$.\n","Solve the quadratic optimization analytically and derive equations for the feedforward gains $k$ and feedback gains $K$. Implement the function below. Hint: You do not need to compute $Q_\\mathbf{uu}^{-1}$ by hand."]},{"cell_type":"code","metadata":{"id":"qaB5ogXVl-Va","executionInfo":{"status":"ok","timestamp":1619218256393,"user_tz":240,"elapsed":144374,"user":{"displayName":"Manmeet Bhabra","photoUrl":"","userId":"11686790358753401934"}}},"source":["def gains(Q_uu, Q_u, Q_ux):\n"," Q_uu_inv = np.linalg.inv(Q_uu)\n"," # TODO: Implement the feedforward gain k and feedback gain K.\n"," # k = np.zeros(Q_u.shape)\n"," # K = np.zeros(Q_ux.shape)\n","\n"," k = - Q_uu_inv.dot(Q_u)\n"," K = - Q_uu_inv.dot(Q_ux)\n","\n"," return k, K"],"execution_count":10,"outputs":[]},{"cell_type":"markdown","metadata":{"id":"3EGsoOSFl-Vb"},"source":["### Value Function Backward Update\n","We are almost done! We need to derive the backwards update equation for the value function. We simply plugin the optimal control $\\delta \\mathbf{u}[n]^* = k + K \\delta \\mathbf{x}[n]$ back into the Q-function which yields the value function\n","\\begin{align*} \n","V(\\mathbf{x}[n]) \\approx V_{n} + \n","V_{\\mathbf{x},n}^T \\delta \\mathbf{x}[n] + \\frac{1}{2}\\delta \\mathbf{x}[n]^T \n","V_{\\mathbf{xx},n} \\delta \\mathbf{x}[n] = Q_n \n","+ \\begin{bmatrix} Q_{\\mathbf{x},n} \\\\ Q_{\\mathbf{u},n} \\end{bmatrix}^T \n","\\begin{bmatrix} \\delta \\mathbf{x}[n] \\\\ \\delta \\mathbf{u}[n]^* \\end{bmatrix} \n","+ \\frac{1}{2}\\begin{bmatrix} \\delta \\mathbf{x}[n] \\\\ \\delta \\mathbf{u}[n]^* \\end{bmatrix}^T \n","\\begin{bmatrix} Q_{\\mathbf{xx},n} & Q_{\\mathbf{ux},n}^T\\\\ \n","Q_{\\mathbf{ux},n} & Q_{\\mathbf{uu},n}\\end{bmatrix}\n"," \\begin{bmatrix} \\delta \\mathbf{x}[n] \\\\ \\delta \\mathbf{u}[n]^* \\end{bmatrix}.\n","\\end{align*}\n","Compare terms in $(\\cdot) \\delta \\mathbf{x}[n]$ and $ 1/2 \\delta \\mathbf{x}[n]^T (\\cdot) \\delta \\mathbf{x}[n]$, find $V_{\\mathbf{x},n}$, and $V_{\\mathbf{xx},n}$ and implement the corresponding function below."]},{"cell_type":"code","metadata":{"id":"y4emy6itl-Vb","executionInfo":{"status":"ok","timestamp":1619218256394,"user_tz":240,"elapsed":143697,"user":{"displayName":"Manmeet Bhabra","photoUrl":"","userId":"11686790358753401934"}}},"source":["def V_terms(Q_x, Q_u, Q_xx, Q_ux, Q_uu, K, k):\n"," # TODO: Implement V_x and V_xx, hint: use the A.dot(B) function for matrix multiplcation.\n"," # V_x = np.zeros(Q_x.shape)\n"," # V_xx = np.zeros(Q_xx.shape)\n","\n"," V_x = ((Q_u.T).dot(K)).T + Q_x + ((k.T).dot(Q_ux) + (k.T).dot(Q_uu).dot(K)).T\n"," V_xx = Q_xx + 2*(K.T).dot(Q_ux) + (K.T).dot(Q_uu).dot(K)\n"," return V_x, V_xx"],"execution_count":11,"outputs":[]},{"cell_type":"markdown","metadata":{"id":"d6z0vab-l-Vb"},"source":["### Expected Cost Reduction\n","We can also estimate by how much we expect to reduce the cost by applying the optimal controls. Simply subtract the previous nominal Q-value ($\\delta \\mathbf{x}[n] = 0$ and $\\delta \\mathbf{u}[n]=0$) from the value function. The result is implemented below and is a useful aid in checking how accurate the quadratic approximation is during convergence of iLQR and adapting stepsize and regularization."]},{"cell_type":"code","metadata":{"id":"Hk3pXFKil-Vb","executionInfo":{"status":"ok","timestamp":1619218256394,"user_tz":240,"elapsed":143003,"user":{"displayName":"Manmeet Bhabra","photoUrl":"","userId":"11686790358753401934"}}},"source":["def expected_cost_reduction(Q_u, Q_uu, k):\n"," return -Q_u.T.dot(k) - 0.5 * k.T.dot(Q_uu.dot(k))"],"execution_count":12,"outputs":[]},{"cell_type":"markdown","metadata":{"id":"AxdqBTESl-Vc"},"source":["### Forward Pass\n","We have now have all the ingredients to implement the forward pass and the backward pass of iLQR. In the forward pass, at each timestep the new updated control $\\mathbf{u}' = \\bar{\\mathbf{u}} + k + K (x' - \\bar{\\mathbf{x}})$ is applied and the dynamis propagated based on the updated control. The nominal control and state trajectory $\\bar{\\mathbf{u}}, \\bar{\\mathbf{x}}$ with which we computed $k$ and $K$ are then updated and we receive a new set of state and control trajectories."]},{"cell_type":"code","metadata":{"id":"tMx1oq13l-Vc","executionInfo":{"status":"ok","timestamp":1619218256395,"user_tz":240,"elapsed":142384,"user":{"displayName":"Manmeet Bhabra","photoUrl":"","userId":"11686790358753401934"}}},"source":["def forward_pass(x_trj, u_trj, k_trj, K_trj):\n"," x_trj_new = np.zeros(x_trj.shape)\n"," x_trj_new[0,:] = x_trj[0,:]\n"," u_trj_new = np.zeros(u_trj.shape)\n"," \n"," # TODO: Implement the forward pass here\n"," for n in range(u_trj.shape[0]):\n"," u_trj_new[n,:] = u_trj[n,:] + k_trj[n,:] + K_trj[n,:].dot(x_trj_new[n,:] - x_trj[n,:]) # Apply feedback law\n"," x_trj_new[n+1,:] = discrete_dynamics(x_trj_new[n,:], u_trj_new[n,:]) # Apply dynamics\n"," \n"," return x_trj_new, u_trj_new"],"execution_count":13,"outputs":[]},{"cell_type":"markdown","metadata":{"id":"vYmRNoiCl-Vc"},"source":["### Backward Pass\n","The backward pass starts from the terminal boundary condition $V(\\mathbf{x}[N]) = \\ell_f(\\mathbf{x}[N])$, such that $V_{\\mathbf{x},N} = \\ell_{\\mathbf{x},f}$ and $V_{\\mathbf{xx},N} = \\ell_{\\mathbf{xx},f}$. In the backwards loop terms for the Q-function at $n$ are computed based on the quadratic value function approximation at $n+1$ and the derivatives and hessians of dynamics and cost functions at $n$. To solve for the gains $k$ and $K$ an inversion of the matrix $Q_\\mathbf{uu}$ is necessary. To ensure invertability and to improve conditioning we add a diagonal matrix to $Q_\\mathbf{uu}$. This is equivalent to adding a quadratic penalty on the distance of the new control trajectory from the control trajectory of the previous iteration. The result is a smaller stepsize and more conservative convergence properties."]},{"cell_type":"code","metadata":{"id":"u7FzdzUUl-Vc","executionInfo":{"status":"ok","timestamp":1619218256528,"user_tz":240,"elapsed":141720,"user":{"displayName":"Manmeet Bhabra","photoUrl":"","userId":"11686790358753401934"}}},"source":["def backward_pass(x_trj, u_trj, regu):\n"," k_trj = np.zeros([u_trj.shape[0], u_trj.shape[1]])\n"," K_trj = np.zeros([u_trj.shape[0], u_trj.shape[1], x_trj.shape[1]])\n"," expected_cost_redu = 0\n"," # TODO: Set terminal boundary condition here (V_x, V_xx)\n"," # V_x = np.zeros((x_trj.shape[1],))\n"," # V_xx = np.zeros((x_trj.shape[1],x_trj.shape[1]))\n","\n"," V_x = derivs.final(x_trj[-1,:])[0]\n"," V_xx = derivs.final(x_trj[-1,:])[1]\n","\n"," for n in range(u_trj.shape[0]-1, -1, -1):\n"," # TODO: First compute derivatives, then the Q-terms \n"," # l_x, l_u, l_xx, l_ux, l_uu, f_x, f_u = \n"," # Q_x, Q_u, Q_xx, Q_ux, Q_uu =\n","\n"," l_x, l_u, l_xx, l_ux, l_uu, f_x, f_u = derivs.stage(x_trj[n,:], u_trj[n,:])\n"," Q_x, Q_u, Q_xx, Q_ux, Q_uu = Q_terms(l_x, l_u, l_xx, l_ux, l_uu, f_x, f_u, V_x, V_xx)\n","\n"," # Q_x = np.zeros((x_trj.shape[1],))\n"," # Q_u = np.zeros((u_trj.shape[1],))\n"," # Q_xx = np.zeros((x_trj.shape[1], x_trj.shape[1]))\n"," # Q_ux = np.zeros((u_trj.shape[1], x_trj.shape[1]))\n"," # Q_uu = np.zeros((u_trj.shape[1], u_trj.shape[1]))\n","\n"," # We add regularization to ensure that Q_uu is invertible and nicely conditioned\n"," Q_uu_regu = Q_uu + np.eye(Q_uu.shape[0])*regu\n"," k, K = gains(Q_uu_regu, Q_u, Q_ux)\n"," k_trj[n,:] = k\n"," K_trj[n,:,:] = K\n"," V_x, V_xx = V_terms(Q_x, Q_u, Q_xx, Q_ux, Q_uu, K, k)\n"," expected_cost_redu += expected_cost_reduction(Q_u, Q_uu, k)\n","\n"," return k_trj, K_trj, expected_cost_redu"],"execution_count":14,"outputs":[]},{"cell_type":"markdown","metadata":{"id":"WDb7lZ7Cl-Vd"},"source":["### Main Loop\n","\n","The main iLQR loop consists of iteratively applying the forward and backward pass. The regularization is adapted based on whether the new control and state trajectories improved the cost. We lower the regularization if the total cost was reduced and accept the new trajectory pair. If the total cost did not decrease, the trajectory pair is rejected and the regularization is increased. You may want to test the algorithm with deactivated regularization and observe the changed behavior.\n","The main loop stops if the maximum number of iterations is reached or the expected reduction is below a certain threshold.\n","\n","If you have correctly implemented all subparts of the iLQR you should see that the car plans to drive around the circle."]},{"cell_type":"code","metadata":{"id":"UhWlFwGol-Vd","colab":{"base_uri":"https://localhost:8080/","height":0},"executionInfo":{"status":"ok","timestamp":1619218257968,"user_tz":240,"elapsed":142453,"user":{"displayName":"Manmeet Bhabra","photoUrl":"","userId":"11686790358753401934"}},"outputId":"c736df22-20e7-43d1-dcf0-0c0bd90d4ecd"},"source":["def run_ilqr(x0, N, max_iter=50, regu_init=100):\n"," # First forward rollout\n"," u_trj = np.random.randn(N-1, n_u)*0.0001\n"," x_trj = rollout(x0, u_trj)\n"," total_cost = cost_trj(x_trj, u_trj)\n"," regu = regu_init\n"," max_regu = 10000\n"," min_regu = 0.01\n"," \n"," # Setup traces\n"," cost_trace = [total_cost]\n"," expected_cost_redu_trace = []\n"," redu_ratio_trace = [1]\n"," redu_trace = []\n"," regu_trace = [regu]\n"," \n"," # Run main loop\n"," for it in range(max_iter):\n"," # Backward and forward pass\n"," k_trj, K_trj, expected_cost_redu = backward_pass(x_trj, u_trj, regu)\n"," x_trj_new, u_trj_new = forward_pass(x_trj, u_trj, k_trj, K_trj)\n"," # Evaluate new trajectory\n"," total_cost = cost_trj(x_trj_new, u_trj_new)\n"," cost_redu = cost_trace[-1] - total_cost\n"," redu_ratio = cost_redu / abs(expected_cost_redu)\n"," # Accept or reject iteration\n"," if cost_redu > 0:\n"," # Improvement! Accept new trajectories and lower regularization\n"," redu_ratio_trace.append(redu_ratio)\n"," cost_trace.append(total_cost)\n"," x_trj = x_trj_new\n"," u_trj = u_trj_new\n"," regu *= 0.7\n"," else:\n"," # Reject new trajectories and increase regularization\n"," regu *= 2.0\n"," cost_trace.append(cost_trace[-1])\n"," redu_ratio_trace.append(0)\n"," regu = min(max(regu, min_regu), max_regu)\n"," regu_trace.append(regu)\n"," redu_trace.append(cost_redu)\n","\n"," # Early termination if expected improvement is small\n"," if expected_cost_redu <= 1e-6:\n"," break\n"," \n"," return x_trj, u_trj, cost_trace, regu_trace, redu_ratio_trace, redu_trace\n","\n","# Setup problem and call iLQR\n","x0 = np.array([-3.0, 1.0, -0.2, 0.0, 0.0])\n","N = 50\n","max_iter=50\n","regu_init=100\n","x_trj, u_trj, cost_trace, regu_trace, redu_ratio_trace, redu_trace = run_ilqr(x0, N, max_iter, regu_init)\n","\n","\n","plt.figure(figsize=(9.5,8))\n","# Plot circle\n","theta = np.linspace(0, 2*np.pi, 100)\n","plt.plot(r*np.cos(theta), r*np.sin(theta), linewidth=5)\n","ax = plt.gca()\n","\n","# Plot resulting trajecotry of car\n","plt.plot(x_trj[:,0], x_trj[:,1], linewidth=5)\n","w = 2.0\n","h = 1.0\n","\n","# Plot rectangles\n","for n in range(x_trj.shape[0]):\n"," rect = mpl.patches.Rectangle((-w/2,-h/2), w, h, fill=False)\n"," t = mpl.transforms.Affine2D().rotate_deg_around(0, 0, \n"," np.rad2deg(x_trj[n,2])).translate(x_trj[n,0], x_trj[n,1]) + ax.transData\n"," rect.set_transform(t)\n"," ax.add_patch(rect)\n","ax.set_aspect(1)\n","plt.ylim((-3,3))\n","plt.xlim((-4.5,3))\n","plt.tight_layout()"],"execution_count":15,"outputs":[{"output_type":"display_data","data":{"image/png":"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\n","text/plain":["
"]},"metadata":{"tags":[],"needs_background":"light"}}]},{"cell_type":"code","metadata":{"id":"qGSJ5PvYl-Vd","colab":{"base_uri":"https://localhost:8080/","height":441},"executionInfo":{"status":"ok","timestamp":1619218258928,"user_tz":240,"elapsed":143058,"user":{"displayName":"Manmeet Bhabra","photoUrl":"","userId":"11686790358753401934"}},"outputId":"20d5a135-2a9b-4147-853f-7fc22e2f985c"},"source":["plt.subplots(figsize=(10,6))\n","# Plot results\n","plt.subplot(2, 2, 1)\n","plt.plot(cost_trace)\n","plt.xlabel('# Iteration')\n","plt.ylabel('Total cost')\n","plt.title('Cost trace')\n","\n","plt.subplot(2, 2, 2)\n","delta_opt = (np.array(cost_trace) - cost_trace[-1])\n","plt.plot(delta_opt)\n","plt.yscale('log')\n","plt.xlabel('# Iteration')\n","plt.ylabel('Optimality gap')\n","plt.title('Convergence plot')\n","\n","plt.subplot(2, 2, 3)\n","plt.plot(redu_ratio_trace)\n","plt.title('Ratio of actual reduction and expected reduction')\n","plt.ylabel('Reduction ratio')\n","plt.xlabel('# Iteration')\n","\n","plt.subplot(2, 2, 4)\n","plt.plot(regu_trace)\n","plt.title('Regularization trace')\n","plt.ylabel('Regularization')\n","plt.xlabel('# Iteration')\n","plt.tight_layout()"],"execution_count":16,"outputs":[{"output_type":"display_data","data":{"image/png":"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\n","text/plain":["
"]},"metadata":{"tags":[],"needs_background":"light"}}]},{"cell_type":"markdown","metadata":{"id":"d-Ne7z9nl-Vd"},"source":["### Convergence Analysis\n","You can find some plots of the convergence traces captured throughout the iLQR solve process above. The convergence plot indicates that we have achieved superlinear convergence. In fact, iLQR achieves nearly second order convergence. In the case of linear convergence (e.g. gradient descent), the [graph would show a line](https://en.wikipedia.org/wiki/Rate_of_convergence). While the integrated regularization improves robustness it damps convergence in the early iteration steps. \n","\n","In the ideal case, the expected reduction and the actual reduction should be the same, i.e. the reduction ratio remains around 1. If that is the case, the quadratic approximation of costs and linear approximation of the dynamics are very accurate. If the ratio becomes significantly lower than 1, the regularization needs to be increased and thus the stepsize reduced."]},{"cell_type":"markdown","metadata":{"id":"KU0NN2tTl-Ve"},"source":["## Autograding\n","You can check your work by running the following cell."]},{"cell_type":"code","metadata":{"id":"jAsruo3xl-Ve","colab":{"base_uri":"https://localhost:8080/"},"executionInfo":{"status":"ok","timestamp":1619218259247,"user_tz":240,"elapsed":141915,"user":{"displayName":"Manmeet Bhabra","photoUrl":"","userId":"11686790358753401934"}},"outputId":"52d16892-0336-447e-a1cf-f8c3469e7112"},"source":["from underactuated.exercises.trajopt.ilqr_driving.test_ilqr_driving import TestIlqrDriving\n","from underactuated.exercises.grader import Grader\n","Grader.grade_output([TestIlqrDriving], [locals()], 'results.json')\n","Grader.print_test_results('results.json')"],"execution_count":17,"outputs":[{"output_type":"stream","text":["Total score is 18/18.\n","\n","Score for Test discrete_dynamics is 1/1.\n","\n","Score for Test rollout is 1/1.\n","\n","Score for Test cost_trj is 1/1.\n","\n","Score for Test Q_terms is 5/5.\n","\n","Score for Test gains is 3/3.\n","\n","Score for Test V_terms is 3/3.\n","\n","Score for Test forward_pass is 2/2.\n","\n","Score for Test backward_pass is 2/2.\n"],"name":"stdout"}]},{"cell_type":"code","metadata":{"id":"YBNhsBNb2cMf"},"source":[""],"execution_count":null,"outputs":[]}]}