From 1ed9537fdc7866ce6c9469b776b96768227f6417 Mon Sep 17 00:00:00 2001 From: mcarfagno Date: Tue, 13 Apr 2021 11:30:08 +0100 Subject: [PATCH] reorganizing my jupyter notebooks --- notebooks/1.0-lti-system-modelling.ipynb | 466 ++++ notebooks/1.1-symbolic-system-equations.ipynb | 344 +++ ...n.ipynb => 1.1.1-numerical-jacobian.ipynb} | 0 ...ynb => 1.2-parametrized-path-curves.ipynb} | 453 +-- notebooks/2.0-MPC-base.ipynb | 730 +++++ ...2.1-MPC-with-iterative-linearization.ipynb | 454 +++ .../2.2-MPC-v2-car-reference-frame.ipynb | 450 +++ notebooks/3.0-MPC-with-track-constrains.ipynb | 1125 ++++++++ notebooks/MPC_racecar_tracking.ipynb | 2450 ----------------- .../MPC_racecar_crosstrack.ipynb | 9 - .../MPC_cte_cvxpy.ipynb | 0 .../MPC_tracking_cvxpy.ipynb | 0 12 files changed, 3572 insertions(+), 2909 deletions(-) create mode 100644 notebooks/1.0-lti-system-modelling.ipynb create mode 100644 notebooks/1.1-symbolic-system-equations.ipynb rename notebooks/{numericalJacobian.ipynb => 1.1.1-numerical-jacobian.ipynb} (100%) rename notebooks/{equations.ipynb => 1.2-parametrized-path-curves.ipynb} (70%) create mode 100644 notebooks/2.0-MPC-base.ipynb create mode 100644 notebooks/2.1-MPC-with-iterative-linearization.ipynb create mode 100644 notebooks/2.2-MPC-v2-car-reference-frame.ipynb create mode 100644 notebooks/3.0-MPC-with-track-constrains.ipynb delete mode 100644 notebooks/MPC_racecar_tracking.ipynb rename notebooks/{ => cte_based_formulation}/MPC_racecar_crosstrack.ipynb (99%) rename notebooks/{diff_drive_kinematics => old_scipy_implementation}/MPC_cte_cvxpy.ipynb (100%) rename notebooks/{diff_drive_kinematics => old_scipy_implementation}/MPC_tracking_cvxpy.ipynb (100%) diff --git a/notebooks/1.0-lti-system-modelling.ipynb b/notebooks/1.0-lti-system-modelling.ipynb new file mode 100644 index 0000000..49a503a --- /dev/null +++ b/notebooks/1.0-lti-system-modelling.ipynb @@ -0,0 +1,466 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# 1 System Modelling\n", + "\n", + "This notebook contains the theory on using the vehicle Kinematics Equations to derive the linearized state space model" + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [], + "source": [ + "import numpy as np\n", + "from scipy.integrate import odeint\n", + "from scipy.interpolate import interp1d\n", + "import cvxpy as cp\n", + "\n", + "import matplotlib.pyplot as plt\n", + "plt.style.use(\"ggplot\")\n", + "\n", + "import time" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## kinematics model equations\n", + "\n", + "The variables of the model are:\n", + "\n", + "* $x$ coordinate of the robot\n", + "* $y$ coordinate of the robot\n", + "* $v$ velocity of the robot\n", + "* $\\theta$ heading of the robot\n", + "\n", + "The inputs of the model are:\n", + "\n", + "* $a$ acceleration of the robot\n", + "* $\\delta$ steering of the robot\n", + "\n", + "These are the differential equations f(x,u) of the model:\n", + "\n", + "$\\dot{x} = f(x,u)$\n", + "\n", + "* $\\dot{x} = v\\cos{\\theta}$ \n", + "* $\\dot{y} = v\\sin{\\theta}$\n", + "* $\\dot{v} = a$\n", + "* $\\dot{\\theta} = \\frac{v\\tan{\\delta}}{L}$\n", + "\n", + "Discretize with forward Euler Integration for time step dt:\n", + "\n", + "${x_{t+1}} = x_{t} + f(x,u)dt$\n", + "\n", + "* ${x_{t+1}} = x_{t} + v_t\\cos{\\theta}dt$\n", + "* ${y_{t+1}} = y_{t} + v_t\\sin{\\theta}dt$\n", + "* ${v_{t+1}} = v_{t} + a_tdt$\n", + "* ${\\theta_{t+1}} = \\theta_{t} + \\frac{v\\tan{\\delta}}{L} dt$\n", + "\n", + "----------------------\n", + "\n", + "The Model is **non-linear** and **time variant**, but the Numerical Optimizer requires a Linear sets of equations. To approximate the equivalent **LTI** State space model, the **Taylor's series expansion** is used around $\\bar{x}$ and $\\bar{u}$ (at each time step):\n", + "\n", + "$ f(x,u) \\approx f(\\bar{x},\\bar{u}) + \\frac{\\partial f(x,u)}{\\partial x}|_{x=\\bar{x},u=\\bar{u}}(x-\\bar{x}) + \\frac{\\partial f(x,u)}{\\partial u}|_{x=\\bar{x},u=\\bar{u}}(u-\\bar{u})$\n", + "\n", + "This can be rewritten usibg the State Space model form Ax+Bu :\n", + "\n", + "$ f(\\bar{x},\\bar{u}) + A|_{x=\\bar{x},u=\\bar{u}}(x-\\bar{x}) + B|_{x=\\bar{x},u=\\bar{u}}(u-\\bar{u})$\n", + "\n", + "Where:\n", + "\n", + "$\n", + "A =\n", + "\\quad\n", + "\\begin{bmatrix}\n", + "\\frac{\\partial f(x,u)}{\\partial x} & \\frac{\\partial f(x,u)}{\\partial y} & \\frac{\\partial f(x,u)}{\\partial v} & \\frac{\\partial f(x,u)}{\\partial \\theta} \\\\\n", + "\\end{bmatrix}\n", + "\\quad\n", + "=\n", + "\\displaystyle \\left[\\begin{matrix}0 & 0 & \\cos{\\left(\\theta \\right)} & - v \\sin{\\left(\\theta \\right)}\\\\0 & 0 & \\sin{\\left(\\theta \\right)} & v \\cos{\\left(\\theta \\right)}\\\\0 & 0 & 0 & 0\\\\0 & 0 & \\frac{\\tan{\\left(\\delta \\right)}}{L} & 0\\end{matrix}\\right]\n", + "$\n", + "\n", + "and\n", + "\n", + "$\n", + "B = \n", + "\\quad\n", + "\\begin{bmatrix}\n", + "\\frac{\\partial f(x,u)}{\\partial a} & \\frac{\\partial f(x,u)}{\\partial \\delta} \\\\\n", + "\\end{bmatrix}\n", + "\\quad\n", + "= \n", + "\\displaystyle \\left[\\begin{matrix}0 & 0\\\\0 & 0\\\\1 & 0\\\\0 & \\frac{v \\left(\\tan^{2}{\\left(\\delta \\right)} + 1\\right)}{L}\\end{matrix}\\right]\n", + "$\n", + "\n", + "are the *Jacobians*.\n", + "\n", + "\n", + "\n", + "So the discretized model is given by:\n", + "\n", + "$ x_{t+1} = x_t + (f(\\bar{x},\\bar{u}) + A|_{x=\\bar{x}}(x_t-\\bar{x}) + B|_{u=\\bar{u}}(u_t-\\bar{u}) )dt $\n", + "\n", + "$ x_{t+1} = (I+dtA)x_t + dtBu_t +dt(f(\\bar{x},\\bar{u}) - A\\bar{x} - B\\bar{u}))$\n", + "\n", + "The LTI-equivalent kinematics model is:\n", + "\n", + "$ x_{t+1} = A'x_t + B' u_t + C' $\n", + "\n", + "with:\n", + "\n", + "$ A' = I+dtA|_{x=\\bar{x},u=\\bar{u}} $\n", + "\n", + "$ B' = dtB|_{x=\\bar{x},u=\\bar{u}} $\n", + "\n", + "$ C' = dt(f(\\bar{x},\\bar{u}) - A|_{x=\\bar{x},u=\\bar{u}}\\bar{x} - B|_{x=\\bar{x},u=\\bar{u}}\\bar{u}) $" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "-----------------\n", + "[About Taylor Series Expansion](https://courses.engr.illinois.edu/ece486/fa2017/documents/lecture_notes/state_space_p2.pdf):\n", + "\n", + "In order to linearize general nonlinear systems, we will use the Taylor Series expansion of functions.\n", + "\n", + "Typically it is possible to assume that the system is operating about some nominal\n", + "state solution $\\bar{x}$ (possibly requires a nominal input $\\bar{u}$) called **equilibrium point**.\n", + "\n", + "Recall that the Taylor Series expansion of f(x) around the\n", + "point $\\bar{x}$ is given by:\n", + "\n", + "$f(x)=f(\\bar{x}) + \\frac{df(x)}{dx}|_{x=\\bar{x}}(x-\\bar{x})$ + higher order terms...\n", + "\n", + "For x sufficiently close to $\\bar{x}$, these higher order terms will be very close to zero, and so we can drop them.\n", + "\n", + "The extension to functions of multiple states and inputs is very similar to the above procedure.Suppose the evolution of state x\n", + "is given by:\n", + "\n", + "$\\dot{x} = f(x1, x2, . . . , xn, u1, u2, . . . , um) = Ax+Bu$\n", + "\n", + "Where:\n", + "\n", + "$ A =\n", + "\\quad\n", + "\\begin{bmatrix}\n", + "\\frac{\\partial f(x,u)}{\\partial x1} & ... & \\frac{\\partial f(x,u)}{\\partial xn} \\\\\n", + "\\end{bmatrix}\n", + "\\quad\n", + "$ and $ B = \\quad\n", + "\\begin{bmatrix}\n", + "\\frac{\\partial f(x,u)}{\\partial u1} & ... & \\frac{\\partial f(x,u)}{\\partial um} \\\\\n", + "\\end{bmatrix}\n", + "\\quad $\n", + "\n", + "Then:\n", + "\n", + "$f(x,u)=f(\\bar{x},\\bar{u}) + \\frac{df(x,u)}{dx}|_{x=\\bar{x}}(x-\\bar{x}) + \\frac{df(x,u)}{du}|_{u=\\bar{u}}(u-\\bar{u}) = f(\\bar{x},\\bar{u}) + A_{x=\\bar{x}}(x-\\bar{x}) + B_{u=\\bar{u}}(u-\\bar{u})$\n", + "\n", + "-----------------" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## ODE Model\n", + "Motion Prediction: using scipy intergration" + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [], + "source": [ + "# Define process model\n", + "# This uses the continuous model \n", + "def kinematics_model(x,t,u):\n", + " \"\"\"\n", + " Returns the set of ODE of the vehicle model.\n", + " \"\"\"\n", + " \n", + " L=0.3 #vehicle wheelbase\n", + " dxdt = x[2]*np.cos(x[3])\n", + " dydt = x[2]*np.sin(x[3])\n", + " dvdt = u[0]\n", + " dthetadt = x[2]*np.tan(u[1])/L\n", + "\n", + " dqdt = [dxdt,\n", + " dydt,\n", + " dvdt,\n", + " dthetadt]\n", + "\n", + " return dqdt\n", + "\n", + "def predict(x0,u):\n", + " \"\"\"\n", + " \"\"\"\n", + " \n", + " x_ = np.zeros((N,T+1))\n", + " \n", + " x_[:,0] = x0\n", + " \n", + " # solve ODE\n", + " for t in range(1,T+1):\n", + "\n", + " tspan = [0,DT]\n", + " x_next = odeint(kinematics_model,\n", + " x0,\n", + " tspan,\n", + " args=(u[:,t-1],))\n", + "\n", + " x0 = x_next[1]\n", + " x_[:,t]=x_next[1]\n", + " \n", + " return x_" + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "CPU times: user 3.39 ms, sys: 0 ns, total: 3.39 ms\n", + "Wall time: 2.79 ms\n" + ] + } + ], + "source": [ + "%%time\n", + "\n", + "u_bar = np.zeros((M,T))\n", + "u_bar[0,:] = 0.2 #m/ss\n", + "u_bar[1,:] = np.radians(-np.pi/4) #rad\n", + "\n", + "x0 = np.zeros(N)\n", + "x0[0] = 0\n", + "x0[1] = 1\n", + "x0[2] = 0\n", + "x0[3] = np.radians(0)\n", + "\n", + "x_bar=predict(x0,u_bar)" + ] + }, + { + "cell_type": "code", + "execution_count": 6, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "#plot trajectory\n", + "plt.subplot(2, 2, 1)\n", + "plt.plot(x_bar[0,:],x_bar[1,:])\n", + "plt.plot(np.linspace(0,10,T+1),np.zeros(T+1),\"b-\")\n", + "plt.axis('equal')\n", + "plt.ylabel('y')\n", + "plt.xlabel('x')\n", + "\n", + "plt.subplot(2, 2, 2)\n", + "plt.plot(np.degrees(x_bar[2,:]))\n", + "plt.ylabel('theta(t) [deg]')\n", + "#plt.xlabel('time')\n", + "\n", + "\n", + "plt.tight_layout()\n", + "plt.show()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## State Space Linearized Model" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [], + "source": [ + "\"\"\"\n", + "Control problem statement.\n", + "\"\"\"\n", + "\n", + "N = 4 #number of state variables\n", + "M = 2 #number of control variables\n", + "T = 20 #Prediction Horizon\n", + "DT = 0.2 #discretization step" + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [], + "source": [ + "def get_linear_model(x_bar,u_bar):\n", + " \"\"\"\n", + " Computes the LTI approximated state space model x' = Ax + Bu + C\n", + " \"\"\"\n", + " \n", + " L=0.3 #vehicle wheelbase\n", + " \n", + " x = x_bar[0]\n", + " y = x_bar[1]\n", + " v = x_bar[2]\n", + " theta = x_bar[3]\n", + " \n", + " a = u_bar[0]\n", + " delta = u_bar[1]\n", + " \n", + " A = np.zeros((N,N))\n", + " A[0,2]=np.cos(theta)\n", + " A[0,3]=-v*np.sin(theta)\n", + " A[1,2]=np.sin(theta)\n", + " A[1,3]=v*np.cos(theta)\n", + " A[3,2]=v*np.tan(delta)/L\n", + " A_lin=np.eye(N)+DT*A\n", + " \n", + " B = np.zeros((N,M))\n", + " B[2,0]=1\n", + " B[3,1]=v/(L*np.cos(delta)**2)\n", + " B_lin=DT*B\n", + " \n", + " f_xu=np.array([v*np.cos(theta), v*np.sin(theta), a,v*np.tan(delta)/L]).reshape(N,1)\n", + " C_lin = DT*(f_xu - np.dot(A,x_bar.reshape(N,1)) - np.dot(B,u_bar.reshape(M,1)))\n", + " \n", + " return np.round(A_lin,4), np.round(B_lin,4), np.round(C_lin,4)" + ] + }, + { + "cell_type": "code", + "execution_count": 7, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "CPU times: user 2.71 ms, sys: 0 ns, total: 2.71 ms\n", + "Wall time: 1.82 ms\n" + ] + } + ], + "source": [ + "%%time\n", + "\n", + "u_bar = np.zeros((M,T))\n", + "u_bar[0,:] = 0.2 #m/s\n", + "u_bar[1,:] = np.radians(-np.pi/4) #rad\n", + "\n", + "x0 = np.zeros(N)\n", + "x0[0] = 0\n", + "x0[1] = 1\n", + "x0[2] = 0\n", + "x0[3] = np.radians(0)\n", + "\n", + "x_bar=np.zeros((N,T+1))\n", + "x_bar[:,0]=x0\n", + "\n", + "for t in range (1,T+1):\n", + " xt=x_bar[:,t-1].reshape(N,1)\n", + " ut=u_bar[:,t-1].reshape(M,1)\n", + " \n", + " A,B,C=get_linear_model(xt,ut)\n", + " \n", + " xt_plus_one = np.dot(A,xt)+np.dot(B,ut)+C\n", + " \n", + " x_bar[:,t]= np.squeeze(xt_plus_one)" + ] + }, + { + "cell_type": "code", + "execution_count": 8, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "#plot trajectory\n", + "plt.subplot(2, 2, 1)\n", + "plt.plot(x_bar[0,:],x_bar[1,:])\n", + "plt.plot(np.linspace(0,10,T+1),np.zeros(T+1),\"b-\")\n", + "plt.axis('equal')\n", + "plt.ylabel('y')\n", + "plt.xlabel('x')\n", + "\n", + "plt.subplot(2, 2, 2)\n", + "plt.plot(np.degrees(x_bar[2,:]))\n", + "plt.ylabel('theta(t)')\n", + "#plt.xlabel('time')\n", + "\n", + "\n", + "plt.tight_layout()\n", + "plt.show()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "The results are the same as expected, so the linearized model is equivalent as expected." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python [conda env:.conda-jupyter] *", + "language": "python", + "name": "conda-env-.conda-jupyter-py" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.8.5" + } + }, + "nbformat": 4, + "nbformat_minor": 4 +} diff --git a/notebooks/1.1-symbolic-system-equations.ipynb b/notebooks/1.1-symbolic-system-equations.ipynb new file mode 100644 index 0000000..7cb4feb --- /dev/null +++ b/notebooks/1.1-symbolic-system-equations.ipynb @@ -0,0 +1,344 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# STATE SPACE MODEL MATRICES\n", + "\n", + "### Diff drive" + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [ + { + "data": { + "text/latex": [ + "$\\displaystyle \\left[\\begin{matrix}0 & 0 & - v \\sin{\\left(\\theta \\right)} & 0 & 0\\\\0 & 0 & v \\cos{\\left(\\theta \\right)} & 0 & 0\\\\0 & 0 & 0 & 0 & 0\\\\0 & 0 & 0 & 0 & 0\\\\0 & 0 & 0 & v \\cos{\\left(\\psi \\right)} & 0\\end{matrix}\\right]$" + ], + "text/plain": [ + "Matrix([\n", + "[0, 0, -v*sin(theta), 0, 0],\n", + "[0, 0, v*cos(theta), 0, 0],\n", + "[0, 0, 0, 0, 0],\n", + "[0, 0, 0, 0, 0],\n", + "[0, 0, 0, v*cos(psi), 0]])" + ] + }, + "execution_count": 1, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "import sympy as sp\n", + "\n", + "x,y,theta,psi,cte,v,w = sp.symbols(\"x y theta psi cte v w\")\n", + "\n", + "gs = sp.Matrix([[ sp.cos(theta)*v],\n", + " [ sp.sin(theta)*v],\n", + " [w],\n", + " [-w],\n", + " [ v*sp.sin(psi)]])\n", + "\n", + "state = sp.Matrix([x,y,theta,psi,cte])\n", + "\n", + "#A\n", + "gs.jacobian(state)" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [ + { + "data": { + "text/latex": [ + "$\\displaystyle \\left[\\begin{matrix}\\cos{\\left(\\theta \\right)} & 0\\\\\\sin{\\left(\\theta \\right)} & 0\\\\0 & 1\\\\0 & -1\\\\\\sin{\\left(\\psi \\right)} & 0\\end{matrix}\\right]$" + ], + "text/plain": [ + "Matrix([\n", + "[cos(theta), 0],\n", + "[sin(theta), 0],\n", + "[ 0, 1],\n", + "[ 0, -1],\n", + "[ sin(psi), 0]])" + ] + }, + "execution_count": 2, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "state = sp.Matrix([v,w])\n", + "\n", + "#B\n", + "gs.jacobian(state)" + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [ + { + "data": { + "text/latex": [ + "$\\displaystyle \\left[\\begin{matrix}1 & 0 & - dt v \\sin{\\left(\\theta \\right)}\\\\0 & 1 & dt v \\cos{\\left(\\theta \\right)}\\\\0 & 0 & 1\\end{matrix}\\right]$" + ], + "text/plain": [ + "Matrix([\n", + "[1, 0, -dt*v*sin(theta)],\n", + "[0, 1, dt*v*cos(theta)],\n", + "[0, 0, 1]])" + ] + }, + "execution_count": 3, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "import sympy as sp\n", + "\n", + "x,y,theta,psi,cte,v,w ,dt= sp.symbols(\"x y theta psi cte v w dt\")\n", + "\n", + "gs = sp.Matrix([[x + sp.cos(theta)*v*dt],\n", + " [y+ sp.sin(theta)*v*dt],\n", + " [theta + w*dt]])\n", + "\n", + "state = sp.Matrix([x,y,theta])\n", + "\n", + "#A\n", + "gs.jacobian(state)#.subs({x:0,y:0,theta:0})" + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [ + { + "data": { + "text/latex": [ + "$\\displaystyle \\left[\\begin{matrix}dt \\cos{\\left(\\theta \\right)} & 0\\\\dt \\sin{\\left(\\theta \\right)} & 0\\\\0 & dt\\end{matrix}\\right]$" + ], + "text/plain": [ + "Matrix([\n", + "[dt*cos(theta), 0],\n", + "[dt*sin(theta), 0],\n", + "[ 0, dt]])" + ] + }, + "execution_count": 4, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "state = sp.Matrix([v,w])\n", + "\n", + "#B\n", + "gs.jacobian(state)#.subs({x:0,y:0,theta:0})" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "### Ackermann" + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "metadata": {}, + "outputs": [], + "source": [ + "x,y,theta,v,delta,L,a = sp.symbols(\"x y theta v delta L a\")\n", + "\n", + "gs = sp.Matrix([[ sp.cos(theta)*v],\n", + " [ sp.sin(theta)*v],\n", + " [a],\n", + " [ v*sp.tan(delta)/L]])\n", + "\n", + "X = sp.Matrix([x,y,v,theta])\n", + "\n", + "#A\n", + "A=gs.jacobian(X)\n", + "\n", + "U = sp.Matrix([a,delta])\n", + "\n", + "#B\n", + "B=gs.jacobian(U)#.subs({x:0,y:0,theta:0})B=" + ] + }, + { + "cell_type": "code", + "execution_count": 6, + "metadata": {}, + "outputs": [ + { + "data": { + "text/latex": [ + "$\\displaystyle \\left[\\begin{matrix}0 & 0\\\\0 & 0\\\\1 & 0\\\\0 & \\frac{v \\left(\\tan^{2}{\\left(\\delta \\right)} + 1\\right)}{L}\\end{matrix}\\right]$" + ], + "text/plain": [ + "Matrix([\n", + "[0, 0],\n", + "[0, 0],\n", + "[1, 0],\n", + "[0, v*(tan(delta)**2 + 1)/L]])" + ] + }, + "execution_count": 6, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "B" + ] + }, + { + "cell_type": "code", + "execution_count": 7, + "metadata": {}, + "outputs": [ + { + "data": { + "text/latex": [ + "$\\displaystyle \\left[\\begin{matrix}1 & 0 & dt \\cos{\\left(\\theta \\right)} & - dt v \\sin{\\left(\\theta \\right)}\\\\0 & 1 & dt \\sin{\\left(\\theta \\right)} & dt v \\cos{\\left(\\theta \\right)}\\\\0 & 0 & 1 & 0\\\\0 & 0 & \\frac{dt \\tan{\\left(\\delta \\right)}}{L} & 1\\end{matrix}\\right]$" + ], + "text/plain": [ + "Matrix([\n", + "[1, 0, dt*cos(theta), -dt*v*sin(theta)],\n", + "[0, 1, dt*sin(theta), dt*v*cos(theta)],\n", + "[0, 0, 1, 0],\n", + "[0, 0, dt*tan(delta)/L, 1]])" + ] + }, + "execution_count": 7, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "#A LIN\n", + "DT = sp.symbols(\"dt\")\n", + "sp.eye(4)+A*DT" + ] + }, + { + "cell_type": "code", + "execution_count": 8, + "metadata": {}, + "outputs": [ + { + "data": { + "text/latex": [ + "$\\displaystyle \\left[\\begin{matrix}0 & 0\\\\0 & 0\\\\dt & 0\\\\0 & \\frac{dt v \\left(\\tan^{2}{\\left(\\delta \\right)} + 1\\right)}{L}\\end{matrix}\\right]$" + ], + "text/plain": [ + "Matrix([\n", + "[ 0, 0],\n", + "[ 0, 0],\n", + "[dt, 0],\n", + "[ 0, dt*v*(tan(delta)**2 + 1)/L]])" + ] + }, + "execution_count": 8, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "B*DT" + ] + }, + { + "cell_type": "code", + "execution_count": 9, + "metadata": {}, + "outputs": [ + { + "data": { + "text/latex": [ + "$\\displaystyle \\left[\\begin{matrix}dt \\theta v \\sin{\\left(\\theta \\right)}\\\\- dt \\theta v \\cos{\\left(\\theta \\right)}\\\\0\\\\- \\frac{\\delta dt v \\left(\\tan^{2}{\\left(\\delta \\right)} + 1\\right)}{L}\\end{matrix}\\right]$" + ], + "text/plain": [ + "Matrix([\n", + "[ dt*theta*v*sin(theta)],\n", + "[ -dt*theta*v*cos(theta)],\n", + "[ 0],\n", + "[-delta*dt*v*(tan(delta)**2 + 1)/L]])" + ] + }, + "execution_count": 9, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "DT*(gs - A*X - B*U)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# ADD DELAY (for real time implementation)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "It is necessary to take *actuation latency* into account: so instead of using the actual state as estimated, the delay factored in using the kinematic model\n", + "\n", + "Starting State is :\n", + "\n", + "* $x_{delay} = 0.0 + v * dt$\n", + "* $y_{delay} = 0.0$\n", + "* $psi_{delay} = 0.0 + w * dt$\n", + "* $cte_{delay} = cte + v * sin(epsi) * dt$\n", + "* $epsi_{delay} = epsi - w * dt$\n", + "\n", + "Note that the starting position and heading is always 0; this is becouse the path is parametrized to **vehicle reference frame**" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.8.5" + } + }, + "nbformat": 4, + "nbformat_minor": 4 +} diff --git a/notebooks/numericalJacobian.ipynb b/notebooks/1.1.1-numerical-jacobian.ipynb similarity index 100% rename from notebooks/numericalJacobian.ipynb rename to notebooks/1.1.1-numerical-jacobian.ipynb diff --git a/notebooks/equations.ipynb b/notebooks/1.2-parametrized-path-curves.ipynb similarity index 70% rename from notebooks/equations.ipynb rename to notebooks/1.2-parametrized-path-curves.ipynb index 865bbcb..f7ec4c1 100644 --- a/notebooks/equations.ipynb +++ b/notebooks/1.2-parametrized-path-curves.ipynb @@ -1,293 +1,5 @@ { "cells": [ - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "# STATE SPACE MODEL MATRICES\n", - "\n", - "### Diff drive" - ] - }, - { - "cell_type": "code", - "execution_count": 1, - "metadata": {}, - "outputs": [ - { - "data": { - "text/latex": [ - "$\\displaystyle \\left[\\begin{matrix}0 & 0 & - v \\sin{\\left(\\theta \\right)} & 0 & 0\\\\0 & 0 & v \\cos{\\left(\\theta \\right)} & 0 & 0\\\\0 & 0 & 0 & 0 & 0\\\\0 & 0 & 0 & 0 & 0\\\\0 & 0 & 0 & v \\cos{\\left(\\psi \\right)} & 0\\end{matrix}\\right]$" - ], - "text/plain": [ - "Matrix([\n", - "[0, 0, -v*sin(theta), 0, 0],\n", - "[0, 0, v*cos(theta), 0, 0],\n", - "[0, 0, 0, 0, 0],\n", - "[0, 0, 0, 0, 0],\n", - "[0, 0, 0, v*cos(psi), 0]])" - ] - }, - "execution_count": 1, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "import sympy as sp\n", - "\n", - "x,y,theta,psi,cte,v,w = sp.symbols(\"x y theta psi cte v w\")\n", - "\n", - "gs = sp.Matrix([[ sp.cos(theta)*v],\n", - " [ sp.sin(theta)*v],\n", - " [w],\n", - " [-w],\n", - " [ v*sp.sin(psi)]])\n", - "\n", - "state = sp.Matrix([x,y,theta,psi,cte])\n", - "\n", - "#A\n", - "gs.jacobian(state)" - ] - }, - { - "cell_type": "code", - "execution_count": 2, - "metadata": {}, - "outputs": [ - { - "data": { - "text/latex": [ - "$\\displaystyle \\left[\\begin{matrix}\\cos{\\left(\\theta \\right)} & 0\\\\\\sin{\\left(\\theta \\right)} & 0\\\\0 & 1\\\\0 & -1\\\\\\sin{\\left(\\psi \\right)} & 0\\end{matrix}\\right]$" - ], - "text/plain": [ - "Matrix([\n", - "[cos(theta), 0],\n", - "[sin(theta), 0],\n", - "[ 0, 1],\n", - "[ 0, -1],\n", - "[ sin(psi), 0]])" - ] - }, - "execution_count": 2, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "state = sp.Matrix([v,w])\n", - "\n", - "#B\n", - "gs.jacobian(state)" - ] - }, - { - "cell_type": "code", - "execution_count": 3, - "metadata": {}, - "outputs": [ - { - "data": { - "text/latex": [ - "$\\displaystyle \\left[\\begin{matrix}1 & 0 & - dt v \\sin{\\left(\\theta \\right)}\\\\0 & 1 & dt v \\cos{\\left(\\theta \\right)}\\\\0 & 0 & 1\\end{matrix}\\right]$" - ], - "text/plain": [ - "Matrix([\n", - "[1, 0, -dt*v*sin(theta)],\n", - "[0, 1, dt*v*cos(theta)],\n", - "[0, 0, 1]])" - ] - }, - "execution_count": 3, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "import sympy as sp\n", - "\n", - "x,y,theta,psi,cte,v,w ,dt= sp.symbols(\"x y theta psi cte v w dt\")\n", - "\n", - "gs = sp.Matrix([[x + sp.cos(theta)*v*dt],\n", - " [y+ sp.sin(theta)*v*dt],\n", - " [theta + w*dt]])\n", - "\n", - "state = sp.Matrix([x,y,theta])\n", - "\n", - "#A\n", - "gs.jacobian(state)#.subs({x:0,y:0,theta:0})" - ] - }, - { - "cell_type": "code", - "execution_count": 4, - "metadata": {}, - "outputs": [ - { - "data": { - "text/latex": [ - "$\\displaystyle \\left[\\begin{matrix}dt \\cos{\\left(\\theta \\right)} & 0\\\\dt \\sin{\\left(\\theta \\right)} & 0\\\\0 & dt\\end{matrix}\\right]$" - ], - "text/plain": [ - "Matrix([\n", - "[dt*cos(theta), 0],\n", - "[dt*sin(theta), 0],\n", - "[ 0, dt]])" - ] - }, - "execution_count": 4, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "state = sp.Matrix([v,w])\n", - "\n", - "#B\n", - "gs.jacobian(state)#.subs({x:0,y:0,theta:0})" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Ackermann" - ] - }, - { - "cell_type": "code", - "execution_count": 5, - "metadata": {}, - "outputs": [], - "source": [ - "x,y,theta,v,delta,L,a = sp.symbols(\"x y theta v delta L a\")\n", - "\n", - "gs = sp.Matrix([[ sp.cos(theta)*v],\n", - " [ sp.sin(theta)*v],\n", - " [a],\n", - " [ v*sp.tan(delta)/L]])\n", - "\n", - "X = sp.Matrix([x,y,v,theta])\n", - "\n", - "#A\n", - "A=gs.jacobian(X)\n", - "\n", - "U = sp.Matrix([a,delta])\n", - "\n", - "#B\n", - "B=gs.jacobian(U)#.subs({x:0,y:0,theta:0})B=" - ] - }, - { - "cell_type": "code", - "execution_count": 6, - "metadata": {}, - "outputs": [ - { - "data": { - "text/latex": [ - "$\\displaystyle \\left[\\begin{matrix}0 & 0\\\\0 & 0\\\\1 & 0\\\\0 & \\frac{v \\left(\\tan^{2}{\\left(\\delta \\right)} + 1\\right)}{L}\\end{matrix}\\right]$" - ], - "text/plain": [ - "Matrix([\n", - "[0, 0],\n", - "[0, 0],\n", - "[1, 0],\n", - "[0, v*(tan(delta)**2 + 1)/L]])" - ] - }, - "execution_count": 6, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "B" - ] - }, - { - "cell_type": "code", - "execution_count": 7, - "metadata": {}, - "outputs": [ - { - "data": { - "text/latex": [ - "$\\displaystyle \\left[\\begin{matrix}1 & 0 & dt \\cos{\\left(\\theta \\right)} & - dt v \\sin{\\left(\\theta \\right)}\\\\0 & 1 & dt \\sin{\\left(\\theta \\right)} & dt v \\cos{\\left(\\theta \\right)}\\\\0 & 0 & 1 & 0\\\\0 & 0 & \\frac{dt \\tan{\\left(\\delta \\right)}}{L} & 1\\end{matrix}\\right]$" - ], - "text/plain": [ - "Matrix([\n", - "[1, 0, dt*cos(theta), -dt*v*sin(theta)],\n", - "[0, 1, dt*sin(theta), dt*v*cos(theta)],\n", - "[0, 0, 1, 0],\n", - "[0, 0, dt*tan(delta)/L, 1]])" - ] - }, - "execution_count": 7, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "#A LIN\n", - "DT = sp.symbols(\"dt\")\n", - "sp.eye(4)+A*DT" - ] - }, - { - "cell_type": "code", - "execution_count": 8, - "metadata": {}, - "outputs": [ - { - "data": { - "text/latex": [ - "$\\displaystyle \\left[\\begin{matrix}0 & 0\\\\0 & 0\\\\dt & 0\\\\0 & \\frac{dt v \\left(\\tan^{2}{\\left(\\delta \\right)} + 1\\right)}{L}\\end{matrix}\\right]$" - ], - "text/plain": [ - "Matrix([\n", - "[ 0, 0],\n", - "[ 0, 0],\n", - "[dt, 0],\n", - "[ 0, dt*v*(tan(delta)**2 + 1)/L]])" - ] - }, - "execution_count": 8, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "B*DT" - ] - }, - { - "cell_type": "code", - "execution_count": 9, - "metadata": {}, - "outputs": [ - { - "data": { - "text/latex": [ - "$\\displaystyle \\left[\\begin{matrix}dt \\theta v \\sin{\\left(\\theta \\right)}\\\\- dt \\theta v \\cos{\\left(\\theta \\right)}\\\\0\\\\- \\frac{\\delta dt v \\left(\\tan^{2}{\\left(\\delta \\right)} + 1\\right)}{L}\\end{matrix}\\right]$" - ], - "text/plain": [ - "Matrix([\n", - "[ dt*theta*v*sin(theta)],\n", - "[ -dt*theta*v*cos(theta)],\n", - "[ 0],\n", - "[-delta*dt*v*(tan(delta)**2 + 1)/L]])" - ] - }, - "execution_count": 9, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "DT*(gs - A*X - B*U)" - ] - }, { "cell_type": "markdown", "metadata": {}, @@ -471,70 +183,6 @@ "#plt.savefig(\"fitted_poly\")" ] }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## With SPLINES" - ] - }, - { - "cell_type": "code", - "execution_count": 17, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "(array([-0.39433757, -0.39433757, -0.39433757, -0.39433757, 0.56791288,\n", - " 1.04903811, 1.67104657, 1.67104657, 1.67104657, 1.67104657]), array([-0.34967937, 0.15467936, -2.19173016, 1.11089663, -8. ,\n", - " -0.7723291 , 0. , 0. , 0. , 0. ]), 3)\n", - "[[ 4.64353595 4.64353595 4.64353595 4.64353595 -23.21767974\n", - " 65.74806776 65.74806776 65.74806776 65.74806776]\n", - " [ -6.70236682 -6.70236682 -6.70236682 -6.70236682 6.70236682\n", - " -26.8094673 95.8780974 95.8780974 95.8780974 ]\n", - " [ 1.57243489 1.57243489 1.57243489 1.57243489 1.57243489\n", - " -8.10159833 34.85967446 34.85967446 34.85967446]\n", - " [ -0.34967937 -0.34967937 -0.34967937 -0.34967937 -0.90523492\n", - " -1.1830127 -0.7723291 -0.7723291 -0.7723291 ]]\n" - ] - } - ], - "source": [ - "#define track\n", - "wp=np.array([0,5,6,10,11,15, 0,0,2,2,0,4]).reshape(2,-1)\n", - "track = compute_path_from_wp(wp[0,:],wp[1,:],step=0.5)\n", - "\n", - "#vehicle state\n", - "state=[3.5,0.5,np.radians(30)]\n", - "\n", - "#given vehicle pos find lookahead waypoints\n", - "nn_idx=get_nn_idx(state,track)-1 #index ox closest wp, take the previous to have a straighter line\n", - "LOOKAHED=6\n", - "lk_wp=track[:,nn_idx:nn_idx+LOOKAHED]\n", - "\n", - "#trasform lookahead waypoints to vehicle ref frame\n", - "dx = lk_wp[0,:] - state[0]\n", - "dy = lk_wp[1,:] - state[1]\n", - "\n", - "wp_vehicle_frame = np.vstack(( dx * np.cos(-state[2]) - dy * np.sin(-state[2]),\n", - " dy * np.cos(-state[2]) + dx * np.sin(-state[2]) ))\n", - "\n", - "#fit poly\n", - "import scipy\n", - "from scipy.interpolate import CubicSpline\n", - "from scipy.interpolate import PPoly,splrep\n", - "spl=splrep(wp_vehicle_frame[0,:], wp_vehicle_frame[1,:])\n", - "print( spl)\n", - "print(PPoly.from_spline(spl).c)\n", - "#coeff=np.polyfit(wp_vehicle_frame[0,:], wp_vehicle_frame[1,:], 5, rcond=None, full=False, w=None, cov=False)\n", - "\n", - "#def f(x,coeff):\n", - "# return coeff[0]*x**3+coeff[1]*x**2+coeff[2]*x**1+coeff[3]*x**0\n", - "\n" - ] - }, { "cell_type": "code", "execution_count": null, @@ -558,108 +206,13 @@ " a = np.linalg.lstsq(C,bc)[0]\n", " return a" ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "# COMPUTE ERRORS" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "* **crosstrack error** cte -> desired y-position - y-position of vehicle: this is the value of the fitted polynomial (road curve)\n", - " \n", - "$\n", - "f = K_0 * x^3 + K_1 * x^2 + K_2 * x + K_3\n", - "$\n", - "\n", - "Then for the origin cte = K_3\n", - " \n", - "* **heading error** epsi -> desired heading - heading of vehicle : is the inclination of tangent to the fitted polynomial (road curve)\n", - "\n", - "The derivative of the fitted poly has the form\n", - "\n", - "$\n", - "f' = 3.0 * K_0 * x^2 + 2.0 * K_1 * x + K_2\n", - "$\n", - "\n", - "Then for the origin the equation of the tangent in the origin is $y=k2$ \n", - "\n", - "epsi = -atan(K_2)\n", - "\n", - "in general:\n", - "\n", - "$\n", - "y_{desired} = f(px) \\\\\n", - "heading_{desired} = -atan(f`(px))\n", - "$" - ] - }, - { - "cell_type": "code", - "execution_count": 15, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "-0.5808399313875324\n", - "28.307545725691345\n" - ] - } - ], - "source": [ - "#for 0\n", - "\n", - "# cte=coeff[3]\n", - "# epsi=-np.arctan(coeff[2])\n", - "cte=f(0,coeff)\n", - "epsi=-np.arctan(df(0,coeff))\n", - "print(cte)\n", - "print(np.degrees(epsi))" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "# ADD DELAY (for real time implementation)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "It is necessary to take *actuation latency* into account: so instead of using the actual state as estimated, the delay factored in using the kinematic model\n", - "\n", - "Starting State is :\n", - "\n", - "* $x_{delay} = 0.0 + v * dt$\n", - "* $y_{delay} = 0.0$\n", - "* $psi_{delay} = 0.0 + w * dt$\n", - "* $cte_{delay} = cte + v * sin(epsi) * dt$\n", - "* $epsi_{delay} = epsi - w * dt$\n", - "\n", - "Note that the starting position and heading is always 0; this is becouse the path is parametrized to **vehicle reference frame**" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] } ], "metadata": { "kernelspec": { - "display_name": "Python 3", + "display_name": "Python [conda env:.conda-jupyter] *", "language": "python", - "name": "python3" + "name": "conda-env-.conda-jupyter-py" }, "language_info": { "codemirror_mode": { @@ -671,7 +224,7 @@ "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython3", - "version": "3.7.6" + "version": "3.8.5" } }, "nbformat": 4, diff --git a/notebooks/2.0-MPC-base.ipynb b/notebooks/2.0-MPC-base.ipynb new file mode 100644 index 0000000..780f67d --- /dev/null +++ b/notebooks/2.0-MPC-base.ipynb @@ -0,0 +1,730 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# 2 MPC\n", + "This notebook contains the CVXPY implementation of a MPC\n", + "This is the simplest one" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "### MPC Problem formulation\n", + "\n", + "**Model Predictive Control** refers to the control approach of **numerically** solving a optimization problem at each time step. \n", + "\n", + "The controller generates a control signal over a fixed lenght T (Horizon) at each time step." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "![mpc](img/mpc_block_diagram.png)\n", + "\n", + "![mpc](img/mpc_t.png)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "#### Linear MPC Formulation\n", + "\n", + "Linear MPC makes use of the **LTI** (Linear time invariant) discrete state space model, wich represents a motion model used for Prediction.\n", + "\n", + "$x_{t+1} = Ax_t + Bu_t$\n", + "\n", + "The LTI formulation means that **future states** are linearly related to the current state and actuator signal. Hence, the MPC seeks to find a **control policy** U over a finite lenght horizon.\n", + "\n", + "$U={u_{t|t}, u_{t+1|t}, ...,u_{t+T|t}}$\n", + "\n", + "The objective function used minimize (drive the state to 0) is:\n", + "\n", + "$\n", + "\\begin{equation}\n", + "\\begin{aligned}\n", + "\\min_{} \\quad & \\sum^{t+T-1}_{j=t} x^T_{j|t}Qx_{j|t} + u^T_{j|t}Ru_{j|t}\\\\\n", + "\\textrm{s.t.} \\quad & x(0) = x0\\\\\n", + " & x_{j+1|t} = Ax_{j|t}+Bu_{j|t}) \\quad \\textrm{for} \\quad t 0:\n", + " target_idx = nn_idx\n", + " else:\n", + " target_idx = nn_idx+1\n", + "\n", + " except IndexError as e:\n", + " target_idx = nn_idx\n", + "\n", + " return target_idx\n", + "\n", + "def get_ref_trajectory(state, path, target_v):\n", + " \"\"\"\n", + " Adapted from pythonrobotics\n", + " \"\"\"\n", + " xref = np.zeros((N, T + 1))\n", + " dref = np.zeros((1, T + 1))\n", + " \n", + " #sp = np.ones((1,T +1))*target_v #speed profile\n", + " \n", + " ncourse = path.shape[1]\n", + "\n", + " ind = get_nn_idx(state, path)\n", + "\n", + " xref[0, 0] = path[0,ind] #X\n", + " xref[1, 0] = path[1,ind] #Y\n", + " xref[2, 0] = target_v #sp[ind] #V\n", + " xref[3, 0] = path[2,ind] #Theta\n", + " dref[0, 0] = 0.0 # steer operational point should be 0\n", + " \n", + " dl = 0.05 # Waypoints spacing [m]\n", + " travel = 0.0\n", + "\n", + " for i in range(T + 1):\n", + " travel += abs(target_v) * DT #current V or target V?\n", + " dind = int(round(travel / dl))\n", + "\n", + " if (ind + dind) < ncourse:\n", + " xref[0, i] = path[0,ind + dind]\n", + " xref[1, i] = path[1,ind + dind]\n", + " xref[2, i] = target_v #sp[ind + dind]\n", + " xref[3, i] = path[2,ind + dind]\n", + " dref[0, i] = 0.0\n", + " else:\n", + " xref[0, i] = path[0,ncourse - 1]\n", + " xref[1, i] = path[1,ncourse - 1]\n", + " xref[2, i] = 0.0 #stop? #sp[ncourse - 1]\n", + " xref[3, i] = path[2,ncourse - 1]\n", + " dref[0, i] = 0.0\n", + "\n", + " return xref, dref" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## MPC \n", + "\n", + "test single iteration" + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "-----------------------------------------------------------------\n", + " OSQP v0.6.0 - Operator Splitting QP Solver\n", + " (c) Bartolomeo Stellato, Goran Banjac\n", + " University of Oxford - Stanford University 2019\n", + "-----------------------------------------------------------------\n", + "problem: variables n = 326, constraints m = 408\n", + " nnz(P) + nnz(A) = 1063\n", + "settings: linear system solver = qdldl,\n", + " eps_abs = 1.0e-05, eps_rel = 1.0e-05,\n", + " eps_prim_inf = 1.0e-04, eps_dual_inf = 1.0e-04,\n", + " rho = 1.00e-01 (adaptive),\n", + " sigma = 1.00e-06, alpha = 1.60, max_iter = 10000\n", + " check_termination: on (interval 25),\n", + " scaling: on, scaled_termination: off\n", + " warm start: on, polish: on, time_limit: off\n", + "\n", + "iter objective pri res dua res rho time\n", + " 1 0.0000e+00 4.27e+00 4.67e+02 1.00e-01 4.07e-04s\n", + " 175 1.6965e+02 2.63e-05 3.49e-05 7.14e+00 1.86e-03s\n", + "\n", + "status: solved\n", + "solution polish: unsuccessful\n", + "number of iterations: 175\n", + "optimal objective: 169.6454\n", + "run time: 2.50e-03s\n", + "optimal rho estimate: 6.34e+00\n", + "\n", + "CPU times: user 122 ms, sys: 75 µs, total: 122 ms\n", + "Wall time: 119 ms\n" + ] + } + ], + "source": [ + "%%time\n", + "\n", + "MAX_SPEED = 1.5 #m/s\n", + "MAX_STEER = np.radians(30) #rad\n", + "MAX_ACC = 1.0\n", + "REF_VEL=1.0\n", + "\n", + "track = compute_path_from_wp([0,3,6],\n", + " [0,0,0],0.05)\n", + "\n", + "# Starting Condition\n", + "x0 = np.zeros(N)\n", + "x0[0] = 0 #x\n", + "x0[1] = -0.25 #y\n", + "x0[2] = 0.0 #v\n", + "x0[3] = np.radians(-0) #yaw\n", + " \n", + "#starting guess\n", + "u_bar = np.zeros((M,T))\n", + "u_bar[0,:] = MAX_ACC/2 #a\n", + "u_bar[1,:] = 0.1 #delta\n", + "\n", + "# dynamics starting state w.r.t world frame\n", + "x_bar = np.zeros((N,T+1))\n", + "x_bar[:,0] = x0\n", + "\n", + "#prediction for linearization of costrains\n", + "for t in range (1,T+1):\n", + " xt = x_bar[:,t-1].reshape(N,1)\n", + " ut = u_bar[:,t-1].reshape(M,1)\n", + " A, B, C = get_linear_model(xt,ut)\n", + " xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n", + " x_bar[:,t] = xt_plus_one\n", + "\n", + "#CVXPY Linear MPC problem statement\n", + "x = cp.Variable((N, T+1))\n", + "u = cp.Variable((M, T))\n", + "cost = 0\n", + "constr = []\n", + "\n", + "# Cost Matrices\n", + "Q = np.diag([10,10,10,10]) #state error cost\n", + "Qf = np.diag([10,10,10,10]) #state final error cost\n", + "R = np.diag([10,10]) #input cost\n", + "R_ = np.diag([10,10]) #input rate of change cost\n", + "\n", + "#Get Reference_traj\n", + "x_ref, d_ref = get_ref_trajectory(x_bar[:,0], track, REF_VEL)\n", + "\n", + "#Prediction Horizon\n", + "for t in range(T):\n", + " \n", + " # Tracking Error\n", + " cost += cp.quad_form(x[:,t] - x_ref[:,t], Q)\n", + "\n", + " # Actuation effort\n", + " cost += cp.quad_form(u[:,t], R)\n", + " \n", + " # Actuation rate of change\n", + " if t < (T - 1):\n", + " cost += cp.quad_form(u[:, t + 1] - u[:, t], R_)\n", + "\n", + " # Kinrmatics Constrains (Linearized model)\n", + " A,B,C = get_linear_model(x_bar[:,t], u_bar[:,t])\n", + " constr += [x[:,t+1] == A@x[:,t] + B@u[:,t] + C.flatten()]\n", + "\n", + "#Final Point tracking\n", + "cost += cp.quad_form(x[:, T] - x_ref[:, T], Qf)\n", + "\n", + "# sums problem objectives and concatenates constraints.\n", + "constr += [x[:,0] == x_bar[:,0]] #starting condition\n", + "constr += [x[2,:] <= MAX_SPEED] #max speed\n", + "constr += [x[2,:] >= 0.0] #min_speed (not really needed)\n", + "constr += [cp.abs(u[0,:]) <= MAX_ACC] #max acc\n", + "constr += [cp.abs(u[1,:]) <= MAX_STEER] #max steer\n", + "# for t in range(T):\n", + "# if t < (T - 1):\n", + "# constr += [cp.abs(u[0,t] - u[0,t-1])/DT <= MAX_ACC] #max acc\n", + "# constr += [cp.abs(u[1,t] - u[1,t-1])/DT <= MAX_STEER] #max steer\n", + "\n", + "prob = cp.Problem(cp.Minimize(cost), constr)\n", + "solution = prob.solve(solver=cp.OSQP, verbose=True)" + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "x_mpc=np.array(x.value[0, :]).flatten()\n", + "y_mpc=np.array(x.value[1, :]).flatten()\n", + "v_mpc=np.array(x.value[2, :]).flatten()\n", + "theta_mpc=np.array(x.value[3, :]).flatten()\n", + "a_mpc=np.array(u.value[0, :]).flatten()\n", + "delta_mpc=np.array(u.value[1, :]).flatten()\n", + "\n", + "#simulate robot state trajectory for optimized U\n", + "x_traj=predict(x0, np.vstack((a_mpc,delta_mpc)))\n", + "\n", + "#plt.figure(figsize=(15,10))\n", + "#plot trajectory\n", + "plt.subplot(2, 2, 1)\n", + "plt.plot(track[0,:],track[1,:],\"b\")\n", + "plt.plot(x_ref[0,:],x_ref[1,:],\"g+\")\n", + "plt.plot(x_traj[0,:],x_traj[1,:])\n", + "plt.axis(\"equal\")\n", + "plt.ylabel('y')\n", + "plt.xlabel('x')\n", + "\n", + "#plot v(t)\n", + "plt.subplot(2, 2, 3)\n", + "plt.plot(a_mpc)\n", + "plt.ylabel('a_in(t)')\n", + "#plt.xlabel('time')\n", + "\n", + "\n", + "plt.subplot(2, 2, 2)\n", + "plt.plot(theta_mpc)\n", + "plt.ylabel('theta(t)')\n", + "\n", + "plt.subplot(2, 2, 4)\n", + "plt.plot(delta_mpc)\n", + "plt.ylabel('d_in(t)')\n", + "\n", + "plt.tight_layout()\n", + "plt.show()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## full track demo" + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "metadata": {}, + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "/home/marcello/.conda/envs/jupyter/lib/python3.8/site-packages/cvxpy/problems/problem.py:1054: UserWarning: Solution may be inaccurate. Try another solver, adjusting the solver settings, or solve with verbose=True for more information.\n", + " warnings.warn(\n" + ] + }, + { + "name": "stdout", + "output_type": "stream", + "text": [ + "CVXPY Optimization Time: Avrg: 0.1677s Max: 0.2731s Min: 0.1438s\n" + ] + } + ], + "source": [ + "track = compute_path_from_wp([0,3,4,6,10,12,14,6,1,0],\n", + " [0,0,2,4,3,3,-2,-6,-2,-2],0.05)\n", + "\n", + "# track = compute_path_from_wp([0,10,10,0],\n", + "# [0,0,1,1],0.05)\n", + "\n", + "sim_duration = 200 #time steps\n", + "opt_time=[]\n", + "\n", + "x_sim = np.zeros((N,sim_duration))\n", + "u_sim = np.zeros((M,sim_duration-1))\n", + "\n", + "MAX_SPEED = 1.5 #m/s\n", + "MAX_ACC = 1.0 #m/ss\n", + "MAX_D_ACC = 1.0 #m/sss\n", + "MAX_STEER = np.radians(30) #rad\n", + "MAX_D_STEER = np.radians(30) #rad/s\n", + "\n", + "REF_VEL = 1.0 #m/s\n", + "\n", + "# Starting Condition\n", + "x0 = np.zeros(N)\n", + "x0[0] = 0 #x\n", + "x0[1] = -0.25 #y\n", + "x0[2] = 0.0 #v\n", + "x0[3] = np.radians(-0) #yaw\n", + " \n", + "#starting guess\n", + "u_bar = np.zeros((M,T))\n", + "u_bar[0,:] = MAX_ACC/2 #a\n", + "u_bar[1,:] = 0.0 #delta\n", + "\n", + "for sim_time in range(sim_duration-1):\n", + " \n", + " iter_start = time.time()\n", + " \n", + " # dynamics starting state\n", + " x_bar = np.zeros((N,T+1))\n", + " x_bar[:,0] = x_sim[:,sim_time]\n", + " \n", + " #prediction for linearization of costrains\n", + " for t in range (1,T+1):\n", + " xt = x_bar[:,t-1].reshape(N,1)\n", + " ut = u_bar[:,t-1].reshape(M,1)\n", + " A,B,C = get_linear_model(xt,ut)\n", + " xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n", + " x_bar[:,t] = xt_plus_one\n", + " \n", + " #CVXPY Linear MPC problem statement\n", + " x = cp.Variable((N, T+1))\n", + " u = cp.Variable((M, T))\n", + " cost = 0\n", + " constr = []\n", + "\n", + " # Cost Matrices\n", + " Q = np.diag([20,20,10,0]) #state error cost\n", + " Qf = np.diag([30,30,30,0]) #state final error cost\n", + " R = np.diag([10,10]) #input cost\n", + " R_ = np.diag([10,10]) #input rate of change cost\n", + "\n", + " #Get Reference_traj\n", + " x_ref, d_ref = get_ref_trajectory(x_bar[:,0] ,track, REF_VEL)\n", + " \n", + " #Prediction Horizon\n", + " for t in range(T):\n", + "\n", + " # Tracking Error\n", + " cost += cp.quad_form(x[:,t] - x_ref[:,t], Q)\n", + "\n", + " # Actuation effort\n", + " cost += cp.quad_form(u[:,t], R)\n", + "\n", + " # Actuation rate of change\n", + " if t < (T - 1):\n", + " cost += cp.quad_form(u[:,t+1] - u[:,t], R_)\n", + " constr+= [cp.abs(u[0, t + 1] - u[0, t])/DT <= MAX_D_ACC] #max acc rate of change\n", + " constr += [cp.abs(u[1, t + 1] - u[1, t])/DT <= MAX_D_STEER] #max steer rate of change\n", + "\n", + " # Kinrmatics Constrains (Linearized model)\n", + " A,B,C = get_linear_model(x_bar[:,t], u_bar[:,t])\n", + " constr += [x[:,t+1] == A@x[:,t] + B@u[:,t] + C.flatten()]\n", + " \n", + " #Final Point tracking\n", + " cost += cp.quad_form(x[:, T] - x_ref[:, T], Qf)\n", + "\n", + " # sums problem objectives and concatenates constraints.\n", + " constr += [x[:,0] == x_bar[:,0]] #starting condition\n", + " constr += [x[2,:] <= MAX_SPEED] #max speed\n", + " constr += [x[2,:] >= 0.0] #min_speed (not really needed)\n", + " constr += [cp.abs(u[0,:]) <= MAX_ACC] #max acc\n", + " constr += [cp.abs(u[1,:]) <= MAX_STEER] #max steer\n", + " \n", + " # Solve\n", + " prob = cp.Problem(cp.Minimize(cost), constr)\n", + " solution = prob.solve(solver=cp.OSQP, verbose=False)\n", + " \n", + " #retrieved optimized U and assign to u_bar to linearize in next step\n", + " u_bar = np.vstack((np.array(u.value[0,:]).flatten(),\n", + " (np.array(u.value[1,:]).flatten())))\n", + " \n", + " u_sim[:,sim_time] = u_bar[:,0]\n", + " \n", + " # Measure elpased time to get results from cvxpy\n", + " opt_time.append(time.time()-iter_start)\n", + " \n", + " # move simulation to t+1\n", + " tspan = [0,DT]\n", + " x_sim[:,sim_time+1] = odeint(kinematics_model,\n", + " x_sim[:,sim_time],\n", + " tspan,\n", + " args=(u_bar[:,0],))[1]\n", + " \n", + "print(\"CVXPY Optimization Time: Avrg: {:.4f}s Max: {:.4f}s Min: {:.4f}s\".format(np.mean(opt_time),\n", + " np.max(opt_time),\n", + " np.min(opt_time))) " + ] + }, + { + "cell_type": "code", + "execution_count": 6, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "#plot trajectory\n", + "grid = plt.GridSpec(4, 5)\n", + "\n", + "plt.figure(figsize=(15,10))\n", + "\n", + "plt.subplot(grid[0:4, 0:4])\n", + "plt.plot(track[0,:],track[1,:],\"b+\")\n", + "plt.plot(x_sim[0,:],x_sim[1,:])\n", + "plt.axis(\"equal\")\n", + "plt.ylabel('y')\n", + "plt.xlabel('x')\n", + "\n", + "plt.subplot(grid[0, 4])\n", + "plt.plot(u_sim[0,:])\n", + "plt.ylabel('a(t) [m/ss]')\n", + "\n", + "plt.subplot(grid[1, 4])\n", + "plt.plot(x_sim[2,:])\n", + "plt.ylabel('v(t) [m/s]')\n", + "\n", + "plt.subplot(grid[2, 4])\n", + "plt.plot(np.degrees(u_sim[1,:]))\n", + "plt.ylabel('delta(t) [rad]')\n", + "\n", + "plt.subplot(grid[3, 4])\n", + "plt.plot(x_sim[3,:])\n", + "plt.ylabel('theta(t) [rad]')\n", + "\n", + "plt.tight_layout()\n", + "plt.show()" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python [conda env:.conda-jupyter] *", + "language": "python", + "name": "conda-env-.conda-jupyter-py" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.8.5" + } + }, + "nbformat": 4, + "nbformat_minor": 4 +} diff --git a/notebooks/2.1-MPC-with-iterative-linearization.ipynb b/notebooks/2.1-MPC-with-iterative-linearization.ipynb new file mode 100644 index 0000000..6267a48 --- /dev/null +++ b/notebooks/2.1-MPC-with-iterative-linearization.ipynb @@ -0,0 +1,454 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Iterative Linearization" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "The goal is to have a more accurate linearization of the diff equations. For every time step the optimization is iterativelly repeated using he previous optimization results **u_bar** to approximate the vehicle dynamics, instead of a random starting guess and/or the rsult at time t-1.\n", + "\n", + "In previous case the results at t-1 wer used to approimate the dynamics art time t!\n", + "\n", + "This maks the results less correlated but makes the controller slower!" + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [], + "source": [ + "import numpy as np\n", + "from scipy.integrate import odeint\n", + "from scipy.interpolate import interp1d\n", + "import cvxpy as cp\n", + "\n", + "import matplotlib.pyplot as plt\n", + "plt.style.use(\"ggplot\")\n", + "\n", + "import time" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [], + "source": [ + "\"\"\"\n", + "Control problem statement.\n", + "\"\"\"\n", + "\n", + "N = 4 #number of state variables\n", + "M = 2 #number of control variables\n", + "T = 20 #Prediction Horizon\n", + "DT = 0.2 #discretization step\n", + "\n", + "def get_linear_model(x_bar,u_bar):\n", + " \"\"\"\n", + " Computes the LTI approximated state space model x' = Ax + Bu + C\n", + " \"\"\"\n", + " \n", + " L=0.3 #vehicle wheelbase\n", + " \n", + " x = x_bar[0]\n", + " y = x_bar[1]\n", + " v = x_bar[2]\n", + " theta = x_bar[3]\n", + " \n", + " a = u_bar[0]\n", + " delta = u_bar[1]\n", + " \n", + " A = np.zeros((N,N))\n", + " A[0,2]=np.cos(theta)\n", + " A[0,3]=-v*np.sin(theta)\n", + " A[1,2]=np.sin(theta)\n", + " A[1,3]=v*np.cos(theta)\n", + " A[3,2]=v*np.tan(delta)/L\n", + " A_lin=np.eye(N)+DT*A\n", + " \n", + " B = np.zeros((N,M))\n", + " B[2,0]=1\n", + " B[3,1]=v/(L*np.cos(delta)**2)\n", + " B_lin=DT*B\n", + " \n", + " f_xu=np.array([v*np.cos(theta), v*np.sin(theta), a,v*np.tan(delta)/L]).reshape(N,1)\n", + " C_lin = DT*(f_xu - np.dot(A,x_bar.reshape(N,1)) - np.dot(B,u_bar.reshape(M,1)))\n", + " \n", + " return np.round(A_lin,4), np.round(B_lin,4), np.round(C_lin,4)\n", + "\n", + "\"\"\"\n", + "the ODE is used to update the simulation given the mpc results\n", + "I use this insted of using the LTI twice\n", + "\"\"\"\n", + "def kinematics_model(x,t,u):\n", + " \"\"\"\n", + " Returns the set of ODE of the vehicle model.\n", + " \"\"\"\n", + " \n", + " L=0.3 #vehicle wheelbase\n", + " dxdt = x[2]*np.cos(x[3])\n", + " dydt = x[2]*np.sin(x[3])\n", + " dvdt = u[0]\n", + " dthetadt = x[2]*np.tan(u[1])/L\n", + "\n", + " dqdt = [dxdt,\n", + " dydt,\n", + " dvdt,\n", + " dthetadt]\n", + "\n", + " return dqdt\n", + "\n", + "def predict(x0,u):\n", + " \"\"\"\n", + " \"\"\"\n", + " \n", + " x_ = np.zeros((N,T+1))\n", + " \n", + " x_[:,0] = x0\n", + " \n", + " # solve ODE\n", + " for t in range(1,T+1):\n", + "\n", + " tspan = [0,DT]\n", + " x_next = odeint(kinematics_model,\n", + " x0,\n", + " tspan,\n", + " args=(u[:,t-1],))\n", + "\n", + " x0 = x_next[1]\n", + " x_[:,t]=x_next[1]\n", + " \n", + " return x_\n", + "\n", + "def compute_path_from_wp(start_xp, start_yp, step = 0.1):\n", + " \"\"\"\n", + " Computes a reference path given a set of waypoints\n", + " \"\"\"\n", + " \n", + " final_xp=[]\n", + " final_yp=[]\n", + " delta = step #[m]\n", + "\n", + " for idx in range(len(start_xp)-1):\n", + " section_len = np.sum(np.sqrt(np.power(np.diff(start_xp[idx:idx+2]),2)+np.power(np.diff(start_yp[idx:idx+2]),2)))\n", + "\n", + " interp_range = np.linspace(0,1,np.floor(section_len/delta).astype(int))\n", + " \n", + " fx=interp1d(np.linspace(0,1,2),start_xp[idx:idx+2],kind=1)\n", + " fy=interp1d(np.linspace(0,1,2),start_yp[idx:idx+2],kind=1)\n", + " \n", + " final_xp=np.append(final_xp,fx(interp_range))\n", + " final_yp=np.append(final_yp,fy(interp_range))\n", + " \n", + " dx = np.append(0, np.diff(final_xp))\n", + " dy = np.append(0, np.diff(final_yp))\n", + " theta = np.arctan2(dy, dx)\n", + "\n", + " return np.vstack((final_xp,final_yp,theta))\n", + "\n", + "\n", + "def get_nn_idx(state,path):\n", + " \"\"\"\n", + " Computes the index of the waypoint closest to vehicle\n", + " \"\"\"\n", + "\n", + " dx = state[0]-path[0,:]\n", + " dy = state[1]-path[1,:]\n", + " dist = np.hypot(dx,dy)\n", + " nn_idx = np.argmin(dist)\n", + "\n", + " try:\n", + " v = [path[0,nn_idx+1] - path[0,nn_idx],\n", + " path[1,nn_idx+1] - path[1,nn_idx]] \n", + " v /= np.linalg.norm(v)\n", + "\n", + " d = [path[0,nn_idx] - state[0],\n", + " path[1,nn_idx] - state[1]]\n", + "\n", + " if np.dot(d,v) > 0:\n", + " target_idx = nn_idx\n", + " else:\n", + " target_idx = nn_idx+1\n", + "\n", + " except IndexError as e:\n", + " target_idx = nn_idx\n", + "\n", + " return target_idx\n", + "\n", + "def get_ref_trajectory(state, path, target_v):\n", + " \"\"\"\n", + " Adapted from pythonrobotics\n", + " \"\"\"\n", + " xref = np.zeros((N, T + 1))\n", + " dref = np.zeros((1, T + 1))\n", + " \n", + " #sp = np.ones((1,T +1))*target_v #speed profile\n", + " \n", + " ncourse = path.shape[1]\n", + "\n", + " ind = get_nn_idx(state, path)\n", + "\n", + " xref[0, 0] = path[0,ind] #X\n", + " xref[1, 0] = path[1,ind] #Y\n", + " xref[2, 0] = target_v #sp[ind] #V\n", + " xref[3, 0] = path[2,ind] #Theta\n", + " dref[0, 0] = 0.0 # steer operational point should be 0\n", + " \n", + " dl = 0.05 # Waypoints spacing [m]\n", + " travel = 0.0\n", + "\n", + " for i in range(T + 1):\n", + " travel += abs(target_v) * DT #current V or target V?\n", + " dind = int(round(travel / dl))\n", + "\n", + " if (ind + dind) < ncourse:\n", + " xref[0, i] = path[0,ind + dind]\n", + " xref[1, i] = path[1,ind + dind]\n", + " xref[2, i] = target_v #sp[ind + dind]\n", + " xref[3, i] = path[2,ind + dind]\n", + " dref[0, i] = 0.0\n", + " else:\n", + " xref[0, i] = path[0,ncourse - 1]\n", + " xref[1, i] = path[1,ncourse - 1]\n", + " xref[2, i] = 0.0 #stop? #sp[ncourse - 1]\n", + " xref[3, i] = path[2,ncourse - 1]\n", + " dref[0, i] = 0.0\n", + "\n", + " return xref, dref" + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + ":127: RuntimeWarning: invalid value encountered in true_divide\n", + " v /= np.linalg.norm(v)\n" + ] + }, + { + "name": "stdout", + "output_type": "stream", + "text": [ + "CVXPY Optimization Time: Avrg: 0.5979s Max: 0.8275s Min: 0.2939s\n" + ] + } + ], + "source": [ + "track = compute_path_from_wp([0,3,4,6,10,12,14,6,1,0],\n", + " [0,0,2,4,3,3,-2,-6,-2,-2],0.05)\n", + "\n", + "# track = compute_path_from_wp([0,10,10,0],\n", + "# [0,0,1,1],0.05)\n", + "\n", + "sim_duration = 200 #time steps\n", + "opt_time=[]\n", + "\n", + "x_sim = np.zeros((N,sim_duration))\n", + "u_sim = np.zeros((M,sim_duration-1))\n", + "\n", + "MAX_SPEED = 1.5 #m/s\n", + "MAX_ACC = 1.0 #m/ss\n", + "MAX_D_ACC = 1.0 #m/sss\n", + "MAX_STEER = np.radians(30) #rad\n", + "MAX_D_STEER = np.radians(30) #rad/s\n", + "\n", + "REF_VEL = 1.0 #m/s\n", + "\n", + "# Starting Condition\n", + "x0 = np.zeros(N)\n", + "x0[0] = 0 #x\n", + "x0[1] = -0.25 #y\n", + "x0[2] = 0.0 #v\n", + "x0[3] = np.radians(-0) #yaw\n", + "\n", + "for sim_time in range(sim_duration-1):\n", + " \n", + " iter_start = time.time()\n", + " \n", + " #starting guess for ctrl\n", + " u_bar = np.zeros((M,T))\n", + " u_bar[0,:] = MAX_ACC/2 #a\n", + " u_bar[1,:] = 0.0 #delta \n", + " \n", + " for _ in range(5):\n", + " u_prev = u_bar\n", + " \n", + " # dynamics starting state\n", + " x_bar = np.zeros((N,T+1))\n", + " x_bar[:,0] = x_sim[:,sim_time]\n", + "\n", + " #prediction for linearization of costrains\n", + " for t in range (1,T+1):\n", + " xt = x_bar[:,t-1].reshape(N,1)\n", + " ut = u_bar[:,t-1].reshape(M,1)\n", + " A,B,C = get_linear_model(xt,ut)\n", + " xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n", + " x_bar[:,t] = xt_plus_one\n", + "\n", + " #CVXPY Linear MPC problem statement\n", + " x = cp.Variable((N, T+1))\n", + " u = cp.Variable((M, T))\n", + " cost = 0\n", + " constr = []\n", + "\n", + " # Cost Matrices\n", + " Q = np.diag([20,20,10,0]) #state error cost\n", + " Qf = np.diag([30,30,30,0]) #state final error cost\n", + " R = np.diag([10,10]) #input cost\n", + " R_ = np.diag([10,10]) #input rate of change cost\n", + "\n", + " #Get Reference_traj\n", + " x_ref, d_ref = get_ref_trajectory(x_bar[:,0] ,track, REF_VEL)\n", + "\n", + " #Prediction Horizon\n", + " for t in range(T):\n", + "\n", + " # Tracking Error\n", + " cost += cp.quad_form(x[:,t] - x_ref[:,t], Q)\n", + "\n", + " # Actuation effort\n", + " cost += cp.quad_form(u[:,t], R)\n", + "\n", + " # Actuation rate of change\n", + " if t < (T - 1):\n", + " cost += cp.quad_form(u[:,t+1] - u[:,t], R_)\n", + " constr+= [cp.abs(u[0, t + 1] - u[0, t])/DT <= MAX_D_ACC] #max acc rate of change\n", + " constr += [cp.abs(u[1, t + 1] - u[1, t])/DT <= MAX_D_STEER] #max steer rate of change\n", + "\n", + " # Kinrmatics Constrains (Linearized model)\n", + " A,B,C = get_linear_model(x_bar[:,t], u_bar[:,t])\n", + " constr += [x[:,t+1] == A@x[:,t] + B@u[:,t] + C.flatten()]\n", + "\n", + " #Final Point tracking\n", + " cost += cp.quad_form(x[:, T] - x_ref[:, T], Qf)\n", + "\n", + " # sums problem objectives and concatenates constraints.\n", + " constr += [x[:,0] == x_bar[:,0]] #starting condition\n", + " constr += [x[2,:] <= MAX_SPEED] #max speed\n", + " constr += [x[2,:] >= 0.0] #min_speed (not really needed)\n", + " constr += [cp.abs(u[0,:]) <= MAX_ACC] #max acc\n", + " constr += [cp.abs(u[1,:]) <= MAX_STEER] #max steer\n", + "\n", + " # Solve\n", + " prob = cp.Problem(cp.Minimize(cost), constr)\n", + " solution = prob.solve(solver=cp.OSQP, verbose=False)\n", + "\n", + " #retrieved optimized U and assign to u_bar to linearize in next step\n", + " u_bar = np.vstack((np.array(u.value[0,:]).flatten(),\n", + " (np.array(u.value[1,:]).flatten())))\n", + " \n", + " #check how this solution differs from previous\n", + " #if the solutions are very\n", + " delta_u = np.sum(np.sum(np.abs(u_bar - u_prev),axis=0),axis=0)\n", + " if delta_u < 0.05:\n", + " break\n", + " \n", + " \n", + " # select u from best iteration\n", + " u_sim[:,sim_time] = u_bar[:,0]\n", + " \n", + " \n", + " # Measure elpased time to get results from cvxpy\n", + " opt_time.append(time.time()-iter_start)\n", + " \n", + " # move simulation to t+1\n", + " tspan = [0,DT]\n", + " x_sim[:,sim_time+1] = odeint(kinematics_model,\n", + " x_sim[:,sim_time],\n", + " tspan,\n", + " args=(u_bar[:,0],))[1]\n", + " \n", + " #reset u_bar? -> this simulates that we don use previous solution!\n", + " u_bar[0,:] = MAX_ACC/2 #a\n", + " u_bar[1,:] = 0.0 #delta\n", + " \n", + " \n", + "print(\"CVXPY Optimization Time: Avrg: {:.4f}s Max: {:.4f}s Min: {:.4f}s\".format(np.mean(opt_time),\n", + " np.max(opt_time),\n", + " np.min(opt_time))) " + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "#plot trajectory\n", + "grid = plt.GridSpec(4, 5)\n", + "\n", + "plt.figure(figsize=(15,10))\n", + "\n", + "plt.subplot(grid[0:4, 0:4])\n", + "plt.plot(track[0,:],track[1,:],\"b+\")\n", + "plt.plot(x_sim[0,:],x_sim[1,:])\n", + "plt.axis(\"equal\")\n", + "plt.ylabel('y')\n", + "plt.xlabel('x')\n", + "\n", + "plt.subplot(grid[0, 4])\n", + "plt.plot(u_sim[0,:])\n", + "plt.ylabel('a(t) [m/ss]')\n", + "\n", + "plt.subplot(grid[1, 4])\n", + "plt.plot(x_sim[2,:])\n", + "plt.ylabel('v(t) [m/s]')\n", + "\n", + "plt.subplot(grid[2, 4])\n", + "plt.plot(np.degrees(u_sim[1,:]))\n", + "plt.ylabel('delta(t) [rad]')\n", + "\n", + "plt.subplot(grid[3, 4])\n", + "plt.plot(x_sim[3,:])\n", + "plt.ylabel('theta(t) [rad]')\n", + "\n", + "plt.tight_layout()\n", + "plt.show()" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python [conda env:.conda-jupyter] *", + "language": "python", + "name": "conda-env-.conda-jupyter-py" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.8.5" + } + }, + "nbformat": 4, + "nbformat_minor": 4 +} diff --git a/notebooks/2.2-MPC-v2-car-reference-frame.ipynb b/notebooks/2.2-MPC-v2-car-reference-frame.ipynb new file mode 100644 index 0000000..b418f8f --- /dev/null +++ b/notebooks/2.2-MPC-v2-car-reference-frame.ipynb @@ -0,0 +1,450 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [], + "source": [ + "import numpy as np\n", + "from scipy.integrate import odeint\n", + "from scipy.interpolate import interp1d\n", + "import cvxpy as cp\n", + "\n", + "import matplotlib.pyplot as plt\n", + "plt.style.use(\"ggplot\")\n", + "\n", + "import time" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## V2 Use Dynamics w.r.t Robot Frame\n", + "\n", + "explanation here...\n", + "\n", + "benefits:\n", + "* slightly faster mpc convergence time -> more variables are 0, this helps the computation?\n", + "* no issues when vehicle heading ~PI in world" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [], + "source": [ + "\"\"\"\n", + "Control problem statement.\n", + "\"\"\"\n", + "\n", + "N = 4 #number of state variables\n", + "M = 2 #number of control variables\n", + "T = 20 #Prediction Horizon\n", + "DT = 0.2 #discretization step\n", + "\n", + "def get_linear_model(x_bar,u_bar):\n", + " \"\"\"\n", + " Computes the LTI approximated state space model x' = Ax + Bu + C\n", + " \"\"\"\n", + " \n", + " L=0.3 #vehicle wheelbase\n", + " \n", + " x = x_bar[0]\n", + " y = x_bar[1]\n", + " v = x_bar[2]\n", + " theta = x_bar[3]\n", + " \n", + " a = u_bar[0]\n", + " delta = u_bar[1]\n", + " \n", + " A = np.zeros((N,N))\n", + " A[0,2]=np.cos(theta)\n", + " A[0,3]=-v*np.sin(theta)\n", + " A[1,2]=np.sin(theta)\n", + " A[1,3]=v*np.cos(theta)\n", + " A[3,2]=v*np.tan(delta)/L\n", + " A_lin=np.eye(N)+DT*A\n", + " \n", + " B = np.zeros((N,M))\n", + " B[2,0]=1\n", + " B[3,1]=v/(L*np.cos(delta)**2)\n", + " B_lin=DT*B\n", + " \n", + " f_xu=np.array([v*np.cos(theta), v*np.sin(theta), a,v*np.tan(delta)/L]).reshape(N,1)\n", + " C_lin = DT*(f_xu - np.dot(A,x_bar.reshape(N,1)) - np.dot(B,u_bar.reshape(M,1)))\n", + " \n", + " return np.round(A_lin,4), np.round(B_lin,4), np.round(C_lin,4)\n", + "\n", + "\"\"\"\n", + "the ODE is used to update the simulation given the mpc results\n", + "I use this insted of using the LTI twice\n", + "\"\"\"\n", + "def kinematics_model(x,t,u):\n", + " \"\"\"\n", + " Returns the set of ODE of the vehicle model.\n", + " \"\"\"\n", + " \n", + " L=0.3 #vehicle wheelbase\n", + " dxdt = x[2]*np.cos(x[3])\n", + " dydt = x[2]*np.sin(x[3])\n", + " dvdt = u[0]\n", + " dthetadt = x[2]*np.tan(u[1])/L\n", + "\n", + " dqdt = [dxdt,\n", + " dydt,\n", + " dvdt,\n", + " dthetadt]\n", + "\n", + " return dqdt\n", + "\n", + "def predict(x0,u):\n", + " \"\"\"\n", + " \"\"\"\n", + " \n", + " x_ = np.zeros((N,T+1))\n", + " \n", + " x_[:,0] = x0\n", + " \n", + " # solve ODE\n", + " for t in range(1,T+1):\n", + "\n", + " tspan = [0,DT]\n", + " x_next = odeint(kinematics_model,\n", + " x0,\n", + " tspan,\n", + " args=(u[:,t-1],))\n", + "\n", + " x0 = x_next[1]\n", + " x_[:,t]=x_next[1]\n", + " \n", + " return x_\n", + "\n", + "\n", + "\"\"\"\n", + "MODIFIED TO INCLUDE FRAME TRANSFORMATION\n", + "\"\"\"\n", + "def compute_path_from_wp(start_xp, start_yp, step = 0.1):\n", + " \"\"\"\n", + " Computes a reference path given a set of waypoints\n", + " \"\"\"\n", + " \n", + " final_xp=[]\n", + " final_yp=[]\n", + " delta = step #[m]\n", + "\n", + " for idx in range(len(start_xp)-1):\n", + " section_len = np.sum(np.sqrt(np.power(np.diff(start_xp[idx:idx+2]),2)+np.power(np.diff(start_yp[idx:idx+2]),2)))\n", + "\n", + " interp_range = np.linspace(0,1,np.floor(section_len/delta).astype(int))\n", + " \n", + " fx=interp1d(np.linspace(0,1,2),start_xp[idx:idx+2],kind=1)\n", + " fy=interp1d(np.linspace(0,1,2),start_yp[idx:idx+2],kind=1)\n", + " \n", + " # watch out to duplicate points!\n", + " final_xp=np.append(final_xp,fx(interp_range)[1:])\n", + " final_yp=np.append(final_yp,fy(interp_range)[1:])\n", + " \n", + " dx = np.append(0, np.diff(final_xp))\n", + " dy = np.append(0, np.diff(final_yp))\n", + " theta = np.arctan2(dy, dx)\n", + "\n", + " return np.vstack((final_xp,final_yp,theta))\n", + "\n", + "\n", + "def get_nn_idx(state,path):\n", + " \"\"\"\n", + " Computes the index of the waypoint closest to vehicle\n", + " \"\"\"\n", + "\n", + " dx = state[0]-path[0,:]\n", + " dy = state[1]-path[1,:]\n", + " dist = np.hypot(dx,dy)\n", + " nn_idx = np.argmin(dist)\n", + "\n", + " try:\n", + " v = [path[0,nn_idx+1] - path[0,nn_idx],\n", + " path[1,nn_idx+1] - path[1,nn_idx]] \n", + " v /= np.linalg.norm(v)\n", + "\n", + " d = [path[0,nn_idx] - state[0],\n", + " path[1,nn_idx] - state[1]]\n", + "\n", + " if np.dot(d,v) > 0:\n", + " target_idx = nn_idx\n", + " else:\n", + " target_idx = nn_idx+1\n", + "\n", + " except IndexError as e:\n", + " target_idx = nn_idx\n", + "\n", + " return target_idx\n", + "\n", + "def normalize_angle(angle):\n", + " \"\"\"\n", + " Normalize an angle to [-pi, pi]\n", + " \"\"\"\n", + " while angle > np.pi:\n", + " angle -= 2.0 * np.pi\n", + "\n", + " while angle < -np.pi:\n", + " angle += 2.0 * np.pi\n", + "\n", + " return angle\n", + "\n", + "def get_ref_trajectory(state, path, target_v):\n", + " \"\"\"\n", + " modified reference in robot frame\n", + " \"\"\"\n", + " xref = np.zeros((N, T + 1))\n", + " dref = np.zeros((1, T + 1))\n", + " \n", + " #sp = np.ones((1,T +1))*target_v #speed profile\n", + " \n", + " ncourse = path.shape[1]\n", + "\n", + " ind = get_nn_idx(state, path)\n", + " dx=path[0,ind] - state[0]\n", + " dy=path[1,ind] - state[1]\n", + " \n", + " xref[0, 0] = dx * np.cos(-state[3]) - dy * np.sin(-state[3]) #X\n", + " xref[1, 0] = dy * np.cos(-state[3]) + dx * np.sin(-state[3]) #Y\n", + " xref[2, 0] = target_v #V\n", + " xref[3, 0] = normalize_angle(path[2,ind]- state[3]) #Theta\n", + " dref[0, 0] = 0.0 # steer operational point should be 0\n", + " \n", + " dl = 0.05 # Waypoints spacing [m]\n", + " travel = 0.0\n", + " \n", + " for i in range(T + 1):\n", + " travel += abs(target_v) * DT #current V or target V?\n", + " dind = int(round(travel / dl))\n", + " \n", + " if (ind + dind) < ncourse:\n", + " dx=path[0,ind + dind] - state[0]\n", + " dy=path[1,ind + dind] - state[1]\n", + " \n", + " xref[0, i] = dx * np.cos(-state[3]) - dy * np.sin(-state[3])\n", + " xref[1, i] = dy * np.cos(-state[3]) + dx * np.sin(-state[3])\n", + " xref[2, i] = target_v #sp[ind + dind]\n", + " xref[3, i] = normalize_angle(path[2,ind + dind] - state[3])\n", + " dref[0, i] = 0.0\n", + " else:\n", + " dx=path[0,ncourse - 1] - state[0]\n", + " dy=path[1,ncourse - 1] - state[1]\n", + " \n", + " xref[0, i] = dx * np.cos(-state[3]) - dy * np.sin(-state[3])\n", + " xref[1, i] = dy * np.cos(-state[3]) + dx * np.sin(-state[3])\n", + " xref[2, i] = 0.0 #stop? #sp[ncourse - 1]\n", + " xref[3, i] = normalize_angle(path[2,ncourse - 1] - state[3])\n", + " dref[0, i] = 0.0\n", + "\n", + " return xref, dref" + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "CVXPY Optimization Time: Avrg: 0.1655s Max: 0.1952s Min: 0.1495s\n" + ] + } + ], + "source": [ + "track = compute_path_from_wp([0,3,4,6,10,12,14,6,1,0],\n", + " [0,0,2,4,3,3,-2,-6,-2,-2],0.05)\n", + "\n", + "# track = compute_path_from_wp([0,10,10,0],\n", + "# [0,0,1,1],0.05)\n", + "\n", + "sim_duration = 200 #time steps\n", + "opt_time=[]\n", + "\n", + "x_sim = np.zeros((N,sim_duration))\n", + "u_sim = np.zeros((M,sim_duration-1))\n", + "\n", + "MAX_SPEED = 1.5 #m/s\n", + "MAX_ACC = 1.0 #m/ss\n", + "MAX_D_ACC = 1.0 #m/sss\n", + "MAX_STEER = np.radians(30) #rad\n", + "MAX_D_STEER = np.radians(30) #rad/s\n", + "\n", + "REF_VEL = 1.0 #m/s\n", + "\n", + "# Starting Condition\n", + "x0 = np.zeros(N)\n", + "x0[0] = 0 #x\n", + "x0[1] = -0.25 #y\n", + "x0[2] = 0.0 #v\n", + "x0[3] = np.radians(-0) #yaw\n", + " \n", + "#starting guess\n", + "u_bar = np.zeros((M,T))\n", + "u_bar[0,:] = MAX_ACC/2 #a\n", + "u_bar[1,:] = 0.0 #delta\n", + " \n", + "for sim_time in range(sim_duration-1):\n", + " \n", + " iter_start = time.time()\n", + " \n", + " # dynamics starting state w.r.t. robot are always null except vel \n", + " x_bar = np.zeros((N,T+1))\n", + " x_bar[2,0] = x_sim[2,sim_time]\n", + " \n", + " #prediction for linearization of costrains\n", + " for t in range (1,T+1):\n", + " xt = x_bar[:,t-1].reshape(N,1)\n", + " ut = u_bar[:,t-1].reshape(M,1)\n", + " A,B,C = get_linear_model(xt,ut)\n", + " xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n", + " x_bar[:,t] = xt_plus_one\n", + " \n", + " #CVXPY Linear MPC problem statement\n", + " x = cp.Variable((N, T+1))\n", + " u = cp.Variable((M, T))\n", + " cost = 0\n", + " constr = []\n", + "\n", + " # Cost Matrices\n", + " Q = np.diag([20,20,10,20]) #state error cost\n", + " Qf = np.diag([30,30,30,30]) #state final error cost\n", + " R = np.diag([10,10]) #input cost\n", + " R_ = np.diag([10,10]) #input rate of change cost\n", + "\n", + " #Get Reference_traj\n", + " #dont use x0 in this case\n", + " x_ref, d_ref = get_ref_trajectory(x_sim[:,sim_time] ,track, REF_VEL)\n", + " \n", + " #Prediction Horizon\n", + " for t in range(T):\n", + "\n", + " # Tracking Error\n", + " cost += cp.quad_form(x[:,t] - x_ref[:,t], Q)\n", + "\n", + " # Actuation effort\n", + " cost += cp.quad_form(u[:,t], R)\n", + "\n", + " # Actuation rate of change\n", + " if t < (T - 1):\n", + " cost += cp.quad_form(u[:,t+1] - u[:,t], R_)\n", + " constr+= [cp.abs(u[0, t + 1] - u[0, t])/DT <= MAX_D_ACC] #max acc rate of change\n", + " constr += [cp.abs(u[1, t + 1] - u[1, t])/DT <= MAX_D_STEER] #max steer rate of change\n", + "\n", + " # Kinrmatics Constrains (Linearized model)\n", + " A,B,C = get_linear_model(x_bar[:,t], u_bar[:,t])\n", + " constr += [x[:,t+1] == A@x[:,t] + B@u[:,t] + C.flatten()]\n", + " \n", + " #Final Point tracking\n", + " cost += cp.quad_form(x[:, T] - x_ref[:, T], Qf)\n", + "\n", + " # sums problem objectives and concatenates constraints.\n", + " constr += [x[:,0] == x_bar[:,0]] #starting condition\n", + " constr += [x[2,:] <= MAX_SPEED] #max speed\n", + " constr += [x[2,:] >= 0.0] #min_speed (not really needed)\n", + " constr += [cp.abs(u[0,:]) <= MAX_ACC] #max acc\n", + " constr += [cp.abs(u[1,:]) <= MAX_STEER] #max steer\n", + " \n", + " # Solve\n", + " prob = cp.Problem(cp.Minimize(cost), constr)\n", + " solution = prob.solve(solver=cp.OSQP, verbose=False)\n", + " \n", + " #retrieved optimized U and assign to u_bar to linearize in next step\n", + " u_bar = np.vstack((np.array(u.value[0,:]).flatten(),\n", + " (np.array(u.value[1,:]).flatten())))\n", + " \n", + " u_sim[:,sim_time] = u_bar[:,0]\n", + " \n", + " # Measure elpased time to get results from cvxpy\n", + " opt_time.append(time.time()-iter_start)\n", + " \n", + " # move simulation to t+1\n", + " tspan = [0,DT]\n", + " x_sim[:,sim_time+1] = odeint(kinematics_model,\n", + " x_sim[:,sim_time],\n", + " tspan,\n", + " args=(u_bar[:,0],))[1]\n", + " \n", + "print(\"CVXPY Optimization Time: Avrg: {:.4f}s Max: {:.4f}s Min: {:.4f}s\".format(np.mean(opt_time),\n", + " np.max(opt_time),\n", + " np.min(opt_time))) " + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "#plot trajectory\n", + "grid = plt.GridSpec(4, 5)\n", + "\n", + "plt.figure(figsize=(15,10))\n", + "\n", + "plt.subplot(grid[0:4, 0:4])\n", + "plt.plot(track[0,:],track[1,:],\"b+\")\n", + "plt.plot(x_sim[0,:],x_sim[1,:])\n", + "plt.axis(\"equal\")\n", + "plt.ylabel('y')\n", + "plt.xlabel('x')\n", + "\n", + "plt.subplot(grid[0, 4])\n", + "plt.plot(u_sim[0,:])\n", + "plt.ylabel('a(t) [m/ss]')\n", + "\n", + "plt.subplot(grid[1, 4])\n", + "plt.plot(x_sim[2,:])\n", + "plt.ylabel('v(t) [m/s]')\n", + "\n", + "plt.subplot(grid[2, 4])\n", + "plt.plot(np.degrees(u_sim[1,:]))\n", + "plt.ylabel('delta(t) [rad]')\n", + "\n", + "plt.subplot(grid[3, 4])\n", + "plt.plot(x_sim[3,:])\n", + "plt.ylabel('theta(t) [rad]')\n", + "\n", + "plt.tight_layout()\n", + "plt.show()" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python [conda env:.conda-jupyter] *", + "language": "python", + "name": "conda-env-.conda-jupyter-py" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.8.5" + } + }, + "nbformat": 4, + "nbformat_minor": 4 +} diff --git a/notebooks/3.0-MPC-with-track-constrains.ipynb b/notebooks/3.0-MPC-with-track-constrains.ipynb new file mode 100644 index 0000000..24470f9 --- /dev/null +++ b/notebooks/3.0-MPC-with-track-constrains.ipynb @@ -0,0 +1,1125 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "import numpy as np\n", + "from scipy.integrate import odeint\n", + "from scipy.interpolate import interp1d\n", + "import cvxpy as cp\n", + "\n", + "import matplotlib.pyplot as plt\n", + "plt.style.use(\"ggplot\")\n", + "\n", + "import time" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## V3 Add track constraints\n", + "inspried from -> https://arxiv.org/pdf/1711.07300.pdf\n", + "\n", + "explanation here...\n", + "\n", + "benefits:\n", + "* add a soft form of obstacle aoidance" + ] + }, + { + "cell_type": "code", + "execution_count": 19, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "[]" + ] + }, + "execution_count": 19, + "metadata": {}, + "output_type": "execute_result" + }, + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "def generate_track_bounds(track,width=0.5):\n", + " \"\"\"\n", + " in world frame\n", + " \"\"\"\n", + " bounds_low=np.zeros((2, track.shape[1]))\n", + " bounds_upp=np.zeros((2, track.shape[1]))\n", + " \n", + " for idx in range(track.shape[1]):\n", + " x = track[0,idx]\n", + " y = track [1,idx]\n", + " th = track [2,idx]\n", + " \n", + " \"\"\"\n", + " trasform the points\n", + " \"\"\"\n", + " bounds_upp[0, idx] = 0 * np.cos(th) - width * np.sin(th) + x #X\n", + " bounds_upp[1, idx] = 0 * np.sin(th) + width * np.cos(th) + y #Y\n", + " \n", + " bounds_low[0, idx] = 0 * np.cos(th) - (-width) * np.sin(th) + x #X\n", + " bounds_low[1, idx] = 0 * np.sin(th) + (-width) * np.cos(th) + y #Y\n", + " \n", + " return bounds_low, bounds_upp\n", + "\n", + "track = compute_path_from_wp([0,3,4,6,10,12,14,6,1,0],\n", + " [0,0,2,4,3,3,-2,-6,-2,-2],0.05)\n", + "\n", + "lower, upper = generate_track_bounds(track)\n", + "\n", + "plt.figure(figsize=(15,10))\n", + "\n", + "plt.plot(track[0,:],track[1,:],\"b-\")\n", + "plt.plot(lower[0,:],lower[1,:],\"g-\")\n", + "plt.plot(upper[0,:],upper[1,:],\"r-\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "the points can be used to generate the **halfplane constrains** for each reference point.\n", + "the issues (outliers points) should be gone after we are in vehicle frame...\n", + "\n", + "the halfplane constrains are defined given the line equation:\n", + "\n", + "**lower halfplane**\n", + "$$ a1x_1 + b1x_2 = c1 \\rightarrow a1x_1 + b1x_2 \\leq c1$$\n", + "\n", + "**upper halfplane**\n", + "$$ a2x_1 - b2x_2 = c2 \\rightarrow a2x_1 + b2x_2 \\leq c2$$\n", + "\n", + "we want to combine this in matrix form:\n", + "\n", + "$$\n", + "\\begin{bmatrix}\n", + "x_1 \\\\\n", + "x_2 \n", + "\\end{bmatrix}\n", + "\\begin{bmatrix}\n", + "a_1 & a_2\\\\\n", + "b_1 & b_2\n", + "\\end{bmatrix}\n", + "\\leq\n", + "\\begin{bmatrix}\n", + "c_1 \\\\\n", + "c_2 \n", + "\\end{bmatrix}\n", + "$$\n", + "\n", + "becouse our track points have known heading the coefficients can be computed from:\n", + "\n", + "$$ y - y' = \\frac{sin(\\theta)}{cos(\\theta)}(x - x') $$" + ] + }, + { + "cell_type": "code", + "execution_count": 57, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "(-2.0, 2.0)" + ] + }, + "execution_count": 57, + "metadata": {}, + "output_type": "execute_result" + }, + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "plt.style.use(\"ggplot\")\n", + "\n", + "def get_coeff(x,y,theta):\n", + " m = np.sin(theta)/np.cos(theta)\n", + " return(-m,1,y-m*x)\n", + "\n", + "#test -> assume point 10,1,pi/6\n", + "coeff = get_coeff(1,-1, np.pi/2)\n", + "y = []\n", + "pts = np.linspace(0,20,100)\n", + "\n", + "for x in pts:\n", + " y.append((-coeff[0]*x+coeff[2])/coeff[1])\n", + " \n", + "plt.figure(figsize=(5,5))\n", + "plt.plot(pts,y,\"b-\")\n", + "\n", + "plt.xlim((-2, 2))\n", + "plt.ylim((-2, 2))" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## WARN TANGENT BREAKS AROUND PI/2?\n", + "force the equation to x = val" + ] + }, + { + "cell_type": "code", + "execution_count": 56, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "(-2.0, 2.0)" + ] + }, + "execution_count": 56, + "metadata": {}, + "output_type": "execute_result" + }, + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "def get_coeff(x,y,theta):\n", + " \n", + " if (theta - np.pi/2) < 0.01:\n", + " #print (\"WARN -> theta is 90, tan is: \" + str(theta))\n", + " # eq is x = val\n", + " m = 0\n", + " return (1,1e-6,x)\n", + " else:\n", + " m = np.sin(theta)/np.cos(theta)\n", + " return(-m,1,y-m*x)\n", + " \n", + "#test -> assume point 10,1,pi/6\n", + "coeff = get_coeff(1,-1, np.pi/2)\n", + "y = []\n", + "pts = np.linspace(0,20,100)\n", + "\n", + "for x in pts:\n", + " y.append((-coeff[0]*x+coeff[2])/coeff[1])\n", + " \n", + "plt.figure(figsize=(5,5))\n", + "\n", + "plt.plot(pts,y,\"b-\")\n", + "plt.axis(\"equal\")\n", + "plt.xlim((-2, 2))\n", + "plt.ylim((-2, 2))" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "becouse the controller uses vhicle reference frame this rquire adapting -> the semiplane constraints must be gathetered from **x_ref points**\n", + "\n", + "*low and up are w.r.t vehicle y axis*" + ] + }, + { + "cell_type": "code", + "execution_count": 21, + "metadata": {}, + "outputs": [], + "source": [ + "def get_track_constrains(x_ref, width=0.5):\n", + " \"\"\"\n", + " x_ref has hape (4,T) -> [x,y,v,theta]_ref \n", + " \"\"\"\n", + " \n", + " #1-> get the upper and lower points\n", + " pts_low=np.zeros((3, x_ref.shape[1]))\n", + " pts_upp=np.zeros((3, x_ref.shape[1]))\n", + " \n", + " for idx in range(x_ref.shape[1]):\n", + " x = x_ref [0, idx]\n", + " y = x_ref [1, idx]\n", + " th = x_ref [3, idx]\n", + " \n", + " \"\"\"\n", + " trasform the points\n", + " \"\"\"\n", + " pts_upp[0, idx] = 0 * np.cos(th) - width * np.sin(th) + x #X\n", + " pts_upp[1, idx] = 0 * np.sin(th) + width * np.cos(th) + y #Y\n", + " pts_upp[2, idx] = th #heading\n", + " \n", + " pts_low[0, idx] = 0 * np.cos(th) - (-width) * np.sin(th) + x #X\n", + " pts_low[1, idx] = 0 * np.sin(th) + (-width) * np.cos(th) + y #Y\n", + " pts_low[2, idx] = th #heading\n", + " \n", + " #get coefficients ->(a,b,c)\n", + " coeff_low=np.zeros((3, x_ref.shape[1]))\n", + " coeff_upp=np.zeros((3, x_ref.shape[1]))\n", + " \n", + " for idx in range(pts_upp.shape[1]):\n", + " f = get_coeff(pts_low[0,idx],pts_low[1,idx],pts_low[2,idx])\n", + " coeff_low[0,idx]=f[0]\n", + " coeff_low[1,idx]=f[1]\n", + " coeff_low[2,idx]=f[2]\n", + " \n", + " f = get_coeff(pts_upp[0,idx],pts_upp[1,idx],pts_upp[2,idx])\n", + " coeff_upp[0,idx]=f[0]\n", + " coeff_upp[1,idx]=f[1]\n", + " coeff_upp[2,idx]=f[2]\n", + " \n", + " return coeff_low, coeff_upp\n", + " " + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## MPC INTEGRATION\n", + "\n", + "compare the results with and without" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [], + "source": [ + "\"\"\"\n", + "Control problem statement.\n", + "\"\"\"\n", + "\n", + "N = 4 #number of state variables\n", + "M = 2 #number of control variables\n", + "T = 20 #Prediction Horizon\n", + "DT = 0.2 #discretization step\n", + "\n", + "def get_linear_model(x_bar,u_bar):\n", + " \"\"\"\n", + " Computes the LTI approximated state space model x' = Ax + Bu + C\n", + " \"\"\"\n", + " \n", + " L=0.3 #vehicle wheelbase\n", + " \n", + " x = x_bar[0]\n", + " y = x_bar[1]\n", + " v = x_bar[2]\n", + " theta = x_bar[3]\n", + " \n", + " a = u_bar[0]\n", + " delta = u_bar[1]\n", + " \n", + " A = np.zeros((N,N))\n", + " A[0,2]=np.cos(theta)\n", + " A[0,3]=-v*np.sin(theta)\n", + " A[1,2]=np.sin(theta)\n", + " A[1,3]=v*np.cos(theta)\n", + " A[3,2]=v*np.tan(delta)/L\n", + " A_lin=np.eye(N)+DT*A\n", + " \n", + " B = np.zeros((N,M))\n", + " B[2,0]=1\n", + " B[3,1]=v/(L*np.cos(delta)**2)\n", + " B_lin=DT*B\n", + " \n", + " f_xu=np.array([v*np.cos(theta), v*np.sin(theta), a,v*np.tan(delta)/L]).reshape(N,1)\n", + " C_lin = DT*(f_xu - np.dot(A,x_bar.reshape(N,1)) - np.dot(B,u_bar.reshape(M,1)))\n", + " \n", + " return np.round(A_lin,4), np.round(B_lin,4), np.round(C_lin,4)\n", + "\n", + "\"\"\"\n", + "the ODE is used to update the simulation given the mpc results\n", + "I use this insted of using the LTI twice\n", + "\"\"\"\n", + "def kinematics_model(x,t,u):\n", + " \"\"\"\n", + " Returns the set of ODE of the vehicle model.\n", + " \"\"\"\n", + " \n", + " L=0.3 #vehicle wheelbase\n", + " dxdt = x[2]*np.cos(x[3])\n", + " dydt = x[2]*np.sin(x[3])\n", + " dvdt = u[0]\n", + " dthetadt = x[2]*np.tan(u[1])/L\n", + "\n", + " dqdt = [dxdt,\n", + " dydt,\n", + " dvdt,\n", + " dthetadt]\n", + "\n", + " return dqdt\n", + "\n", + "def predict(x0,u):\n", + " \"\"\"\n", + " \"\"\"\n", + " \n", + " x_ = np.zeros((N,T+1))\n", + " \n", + " x_[:,0] = x0\n", + " \n", + " # solve ODE\n", + " for t in range(1,T+1):\n", + "\n", + " tspan = [0,DT]\n", + " x_next = odeint(kinematics_model,\n", + " x0,\n", + " tspan,\n", + " args=(u[:,t-1],))\n", + "\n", + " x0 = x_next[1]\n", + " x_[:,t]=x_next[1]\n", + " \n", + " return x_\n", + "\n", + "\n", + "\"\"\"\n", + "MODIFIED TO INCLUDE FRAME TRANSFORMATION\n", + "\"\"\"\n", + "def compute_path_from_wp(start_xp, start_yp, step = 0.1):\n", + " \"\"\"\n", + " Computes a reference path given a set of waypoints\n", + " \"\"\"\n", + " \n", + " final_xp=[]\n", + " final_yp=[]\n", + " delta = step #[m]\n", + "\n", + " for idx in range(len(start_xp)-1):\n", + " section_len = np.sum(np.sqrt(np.power(np.diff(start_xp[idx:idx+2]),2)+np.power(np.diff(start_yp[idx:idx+2]),2)))\n", + "\n", + " interp_range = np.linspace(0,1,np.floor(section_len/delta).astype(int))\n", + " \n", + " fx=interp1d(np.linspace(0,1,2),start_xp[idx:idx+2],kind=1)\n", + " fy=interp1d(np.linspace(0,1,2),start_yp[idx:idx+2],kind=1)\n", + " \n", + " # watch out to duplicate points!\n", + " final_xp=np.append(final_xp,fx(interp_range)[1:])\n", + " final_yp=np.append(final_yp,fy(interp_range)[1:])\n", + " \n", + " dx = np.append(0, np.diff(final_xp))\n", + " dy = np.append(0, np.diff(final_yp))\n", + " theta = np.arctan2(dy, dx)\n", + "\n", + " return np.vstack((final_xp,final_yp,theta))\n", + "\n", + "\n", + "def get_nn_idx(state,path):\n", + " \"\"\"\n", + " Computes the index of the waypoint closest to vehicle\n", + " \"\"\"\n", + "\n", + " dx = state[0]-path[0,:]\n", + " dy = state[1]-path[1,:]\n", + " dist = np.hypot(dx,dy)\n", + " nn_idx = np.argmin(dist)\n", + "\n", + " try:\n", + " v = [path[0,nn_idx+1] - path[0,nn_idx],\n", + " path[1,nn_idx+1] - path[1,nn_idx]] \n", + " v /= np.linalg.norm(v)\n", + "\n", + " d = [path[0,nn_idx] - state[0],\n", + " path[1,nn_idx] - state[1]]\n", + "\n", + " if np.dot(d,v) > 0:\n", + " target_idx = nn_idx\n", + " else:\n", + " target_idx = nn_idx+1\n", + "\n", + " except IndexError as e:\n", + " target_idx = nn_idx\n", + "\n", + " return target_idx\n", + "\n", + "def normalize_angle(angle):\n", + " \"\"\"\n", + " Normalize an angle to [-pi, pi]\n", + " \"\"\"\n", + " while angle > np.pi:\n", + " angle -= 2.0 * np.pi\n", + "\n", + " while angle < -np.pi:\n", + " angle += 2.0 * np.pi\n", + "\n", + " return angle\n", + "\n", + "def get_ref_trajectory(state, path, target_v):\n", + " \"\"\"\n", + " modified reference in robot frame\n", + " \"\"\"\n", + " xref = np.zeros((N, T + 1))\n", + " dref = np.zeros((1, T + 1))\n", + " \n", + " #sp = np.ones((1,T +1))*target_v #speed profile\n", + " \n", + " ncourse = path.shape[1]\n", + "\n", + " ind = get_nn_idx(state, path)\n", + " dx=path[0,ind] - state[0]\n", + " dy=path[1,ind] - state[1]\n", + " \n", + " xref[0, 0] = dx * np.cos(-state[3]) - dy * np.sin(-state[3]) #X\n", + " xref[1, 0] = dy * np.cos(-state[3]) + dx * np.sin(-state[3]) #Y\n", + " xref[2, 0] = target_v #V\n", + " xref[3, 0] = normalize_angle(path[2,ind]- state[3]) #Theta\n", + " dref[0, 0] = 0.0 # steer operational point should be 0\n", + " \n", + " dl = 0.05 # Waypoints spacing [m]\n", + " travel = 0.0\n", + " \n", + " for i in range(T + 1):\n", + " travel += abs(target_v) * DT #current V or target V?\n", + " dind = int(round(travel / dl))\n", + " \n", + " if (ind + dind) < ncourse:\n", + " dx=path[0,ind + dind] - state[0]\n", + " dy=path[1,ind + dind] - state[1]\n", + " \n", + " xref[0, i] = dx * np.cos(-state[3]) - dy * np.sin(-state[3])\n", + " xref[1, i] = dy * np.cos(-state[3]) + dx * np.sin(-state[3])\n", + " xref[2, i] = target_v #sp[ind + dind]\n", + " xref[3, i] = normalize_angle(path[2,ind + dind] - state[3])\n", + " dref[0, i] = 0.0\n", + " else:\n", + " dx=path[0,ncourse - 1] - state[0]\n", + " dy=path[1,ncourse - 1] - state[1]\n", + " \n", + " xref[0, i] = dx * np.cos(-state[3]) - dy * np.sin(-state[3])\n", + " xref[1, i] = dy * np.cos(-state[3]) + dx * np.sin(-state[3])\n", + " xref[2, i] = 0.0 #stop? #sp[ncourse - 1]\n", + " xref[3, i] = normalize_angle(path[2,ncourse - 1] - state[3])\n", + " dref[0, i] = 0.0\n", + "\n", + " return xref, dref" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "simpe u-turn test\n", + "\n", + "## 1-> NO BOUNDS" + ] + }, + { + "cell_type": "code", + "execution_count": 22, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "CVXPY Optimization Time: Avrg: 0.1656s Max: 0.2061s Min: 0.1480s\n" + ] + } + ], + "source": [ + "track = compute_path_from_wp([0,3,3,0],\n", + " [0,0,1,1],0.05)\n", + "\n", + "track_lower, track_upper = generate_track_bounds(track,0.12)\n", + "\n", + "sim_duration = 50 #time steps\n", + "opt_time=[]\n", + "\n", + "x_sim = np.zeros((N,sim_duration))\n", + "u_sim = np.zeros((M,sim_duration-1))\n", + "\n", + "MAX_SPEED = 1.5 #m/s\n", + "MAX_ACC = 1.0 #m/ss\n", + "MAX_D_ACC = 1.0 #m/sss\n", + "MAX_STEER = np.radians(30) #rad\n", + "MAX_D_STEER = np.radians(30) #rad/s\n", + "\n", + "REF_VEL = 1.0 #m/s\n", + "\n", + "# Starting Condition\n", + "x0 = np.zeros(N)\n", + "x0[0] = 0 #x\n", + "x0[1] = -0.25 #y\n", + "x0[2] = 0.0 #v\n", + "x0[3] = np.radians(-0) #yaw\n", + " \n", + "#starting guess\n", + "u_bar = np.zeros((M,T))\n", + "u_bar[0,:] = MAX_ACC/2 #a\n", + "u_bar[1,:] = 0.0 #delta\n", + " \n", + "for sim_time in range(sim_duration-1):\n", + " \n", + " iter_start = time.time()\n", + " \n", + " # dynamics starting state w.r.t. robot are always null except vel \n", + " x_bar = np.zeros((N,T+1))\n", + " x_bar[2,0] = x_sim[2,sim_time]\n", + " \n", + " #prediction for linearization of costrains\n", + " for t in range (1,T+1):\n", + " xt = x_bar[:,t-1].reshape(N,1)\n", + " ut = u_bar[:,t-1].reshape(M,1)\n", + " A,B,C = get_linear_model(xt,ut)\n", + " xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n", + " x_bar[:,t] = xt_plus_one\n", + " \n", + " #CVXPY Linear MPC problem statement\n", + " x = cp.Variable((N, T+1))\n", + " u = cp.Variable((M, T))\n", + " cost = 0\n", + " constr = []\n", + "\n", + " # Cost Matrices\n", + " Q = np.diag([20,20,10,20]) #state error cost\n", + " Qf = np.diag([30,30,30,30]) #state final error cost\n", + " R = np.diag([10,10]) #input cost\n", + " R_ = np.diag([10,10]) #input rate of change cost\n", + "\n", + " #Get Reference_traj\n", + " #dont use x0 in this case\n", + " x_ref, d_ref = get_ref_trajectory(x_sim[:,sim_time] ,track, REF_VEL)\n", + " \n", + " #Prediction Horizon\n", + " for t in range(T):\n", + "\n", + " # Tracking Error\n", + " cost += cp.quad_form(x[:,t] - x_ref[:,t], Q)\n", + "\n", + " # Actuation effort\n", + " cost += cp.quad_form(u[:,t], R)\n", + "\n", + " # Actuation rate of change\n", + " if t < (T - 1):\n", + " cost += cp.quad_form(u[:,t+1] - u[:,t], R_)\n", + " constr+= [cp.abs(u[0, t + 1] - u[0, t])/DT <= MAX_D_ACC] #max acc rate of change\n", + " constr += [cp.abs(u[1, t + 1] - u[1, t])/DT <= MAX_D_STEER] #max steer rate of change\n", + "\n", + " # Kinrmatics Constrains (Linearized model)\n", + " A,B,C = get_linear_model(x_bar[:,t], u_bar[:,t])\n", + " constr += [x[:,t+1] == A@x[:,t] + B@u[:,t] + C.flatten()]\n", + " \n", + " #Final Point tracking\n", + " cost += cp.quad_form(x[:, T] - x_ref[:, T], Qf)\n", + "\n", + " # sums problem objectives and concatenates constraints.\n", + " constr += [x[:,0] == x_bar[:,0]] #starting condition\n", + " constr += [x[2,:] <= MAX_SPEED] #max speed\n", + " constr += [x[2,:] >= 0.0] #min_speed (not really needed)\n", + " constr += [cp.abs(u[0,:]) <= MAX_ACC] #max acc\n", + " constr += [cp.abs(u[1,:]) <= MAX_STEER] #max steer\n", + " \n", + " # Solve\n", + " prob = cp.Problem(cp.Minimize(cost), constr)\n", + " solution = prob.solve(solver=cp.OSQP, verbose=False)\n", + " \n", + " #retrieved optimized U and assign to u_bar to linearize in next step\n", + " u_bar = np.vstack((np.array(u.value[0,:]).flatten(),\n", + " (np.array(u.value[1,:]).flatten())))\n", + " \n", + " u_sim[:,sim_time] = u_bar[:,0]\n", + " \n", + " # Measure elpased time to get results from cvxpy\n", + " opt_time.append(time.time()-iter_start)\n", + " \n", + " # move simulation to t+1\n", + " tspan = [0,DT]\n", + " x_sim[:,sim_time+1] = odeint(kinematics_model,\n", + " x_sim[:,sim_time],\n", + " tspan,\n", + " args=(u_bar[:,0],))[1]\n", + " \n", + "print(\"CVXPY Optimization Time: Avrg: {:.4f}s Max: {:.4f}s Min: {:.4f}s\".format(np.mean(opt_time),\n", + " np.max(opt_time),\n", + " np.min(opt_time))) " + ] + }, + { + "cell_type": "code", + "execution_count": 23, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "#plot trajectory\n", + "grid = plt.GridSpec(4, 5)\n", + "\n", + "plt.figure(figsize=(15,10))\n", + "\n", + "plt.subplot(grid[0:4, 0:4])\n", + "plt.plot(track[0,:],track[1,:],\"b+\")\n", + "plt.plot(track_lower[0,:],track_lower[1,:],\"g-\")\n", + "plt.plot(track_upper[0,:],track_upper[1,:],\"r-\")\n", + "plt.plot(x_sim[0,:],x_sim[1,:])\n", + "plt.axis(\"equal\")\n", + "plt.ylabel('y')\n", + "plt.xlabel('x')\n", + "\n", + "plt.subplot(grid[0, 4])\n", + "plt.plot(u_sim[0,:])\n", + "plt.ylabel('a(t) [m/ss]')\n", + "\n", + "plt.subplot(grid[1, 4])\n", + "plt.plot(x_sim[2,:])\n", + "plt.ylabel('v(t) [m/s]')\n", + "\n", + "plt.subplot(grid[2, 4])\n", + "plt.plot(np.degrees(u_sim[1,:]))\n", + "plt.ylabel('delta(t) [rad]')\n", + "\n", + "plt.subplot(grid[3, 4])\n", + "plt.plot(x_sim[3,:])\n", + "plt.ylabel('theta(t) [rad]')\n", + "\n", + "plt.tight_layout()\n", + "plt.show()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## 2-> WITH BOUNDS\n", + "if there is 90 deg turn the optimization fails!\n", + "if speed is too high it also fails ..." + ] + }, + { + "cell_type": "code", + "execution_count": 24, + "metadata": {}, + "outputs": [], + "source": [ + "from scipy.signal import savgol_filter\n", + "def compute_path_from_wp(start_xp, start_yp, step = 0.1):\n", + " \"\"\"\n", + " Computes a reference path given a set of waypoints\n", + " \"\"\"\n", + " \n", + " final_xp=[]\n", + " final_yp=[]\n", + " delta = step #[m]\n", + "\n", + " for idx in range(len(start_xp)-1):\n", + " section_len = np.sum(np.sqrt(np.power(np.diff(start_xp[idx:idx+2]),2)+np.power(np.diff(start_yp[idx:idx+2]),2)))\n", + "\n", + " interp_range = np.linspace(0,1,np.floor(section_len/delta).astype(int))\n", + " \n", + " fx=interp1d(np.linspace(0,1,2),start_xp[idx:idx+2],kind=1)\n", + " fy=interp1d(np.linspace(0,1,2),start_yp[idx:idx+2],kind=1)\n", + " \n", + " # watch out to duplicate points!\n", + " final_xp=np.append(final_xp,fx(interp_range)[1:])\n", + " final_yp=np.append(final_yp,fy(interp_range)[1:])\n", + " \n", + " \"\"\"this smoothens up corners\"\"\"\n", + " window_size = 11 # Smoothening filter window\n", + " final_xp = savgol_filter(final_xp, window_size, 1)\n", + " final_yp = savgol_filter(final_yp, window_size, 1)\n", + " \n", + " dx = np.append(0, np.diff(final_xp))\n", + " dy = np.append(0, np.diff(final_yp))\n", + " theta = np.arctan2(dy, dx)\n", + "\n", + " return np.vstack((final_xp,final_yp,theta))\n" + ] + }, + { + "cell_type": "code", + "execution_count": 62, + "metadata": {}, + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "/home/marcello/.conda/envs/jupyter/lib/python3.8/site-packages/cvxpy/problems/problem.py:1054: UserWarning: Solution may be inaccurate. Try another solver, adjusting the solver settings, or solve with verbose=True for more information.\n", + " warnings.warn(\n" + ] + }, + { + "name": "stdout", + "output_type": "stream", + "text": [ + "CVXPY Optimization Time: Avrg: 0.1837s Max: 0.2651s Min: 0.1593s\n" + ] + } + ], + "source": [ + "WIDTH=0.12\n", + "computed_coeff = []\n", + "\n", + "track = compute_path_from_wp([0,3,3,0],\n", + " [0,0,1,1],0.05)\n", + "\n", + "track_lower, track_upper = generate_track_bounds(track,WIDTH)\n", + "\n", + "sim_duration = 200 #time steps\n", + "opt_time=[]\n", + "\n", + "x_sim = np.zeros((N,sim_duration))\n", + "u_sim = np.zeros((M,sim_duration-1))\n", + "\n", + "MAX_SPEED = 1.5 #m/s\n", + "MAX_ACC = 1.0 #m/ss\n", + "MAX_D_ACC = 1.0 #m/sss\n", + "MAX_STEER = np.radians(30) #rad\n", + "MAX_D_STEER = np.radians(30) #rad/s\n", + "\n", + "REF_VEL = 0.4 #m/s\n", + "\n", + "# Starting Condition\n", + "x0 = np.zeros(N)\n", + "x0[0] = 0 #x\n", + "x0[1] = -WIDTH/2 #y\n", + "x0[2] = 0.0 #v\n", + "x0[3] = np.radians(-0) #yaw\n", + " \n", + "#starting guess\n", + "u_bar = np.zeros((M,T))\n", + "u_bar[0,:] = MAX_ACC/2 #a\n", + "u_bar[1,:] = 0.0 #delta\n", + " \n", + "for sim_time in range(sim_duration-1):\n", + " \n", + " iter_start = time.time()\n", + " \n", + " # dynamics starting state w.r.t. robot are always null except vel \n", + " x_bar = np.zeros((N,T+1))\n", + " x_bar[2,0] = x_sim[2,sim_time]\n", + " \n", + " #prediction for linearization of costrains\n", + " for t in range (1,T+1):\n", + " xt = x_bar[:,t-1].reshape(N,1)\n", + " ut = u_bar[:,t-1].reshape(M,1)\n", + " A,B,C = get_linear_model(xt,ut)\n", + " xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n", + " x_bar[:,t] = xt_plus_one\n", + " \n", + " #CVXPY Linear MPC problem statement\n", + " x = cp.Variable((N, T+1))\n", + " u = cp.Variable((M, T))\n", + " cost = 0\n", + " constr = []\n", + "\n", + " # Cost Matrices\n", + " Q = np.diag([20,20,10,20]) #state error cost\n", + " Qf = np.diag([30,30,30,30]) #state final error cost\n", + " R = np.diag([10,10]) #input cost\n", + " R_ = np.diag([10,10]) #input rate of change cost\n", + "\n", + " #Get Reference_traj\n", + " #dont use x0 in this case\n", + " x_ref, d_ref = get_ref_trajectory(x_sim[:,sim_time] ,track, REF_VEL)\n", + " \n", + " #Prediction Horizon\n", + " for t in range(T):\n", + "\n", + " # Tracking Error\n", + " cost += cp.quad_form(x[:,t] - x_ref[:,t], Q)\n", + "\n", + " # Actuation effort\n", + " cost += cp.quad_form(u[:,t], R)\n", + "\n", + " # Actuation rate of change\n", + " if t < (T - 1):\n", + " cost += cp.quad_form(u[:,t+1] - u[:,t], R_)\n", + " constr+= [cp.abs(u[0, t + 1] - u[0, t])/DT <= MAX_D_ACC] #max acc rate of change\n", + " constr += [cp.abs(u[1, t + 1] - u[1, t])/DT <= MAX_D_STEER] #max steer rate of change\n", + "\n", + " # Kinrmatics Constrains (Linearized model)\n", + " A,B,C = get_linear_model(x_bar[:,t], u_bar[:,t])\n", + " constr += [x[:,t+1] == A@x[:,t] + B@u[:,t] + C.flatten()]\n", + " \n", + " #Final Point tracking\n", + " cost += cp.quad_form(x[:, T] - x_ref[:, T], Qf)\n", + "\n", + " # sums problem objectives and concatenates constraints.\n", + " constr += [x[:,0] == x_bar[:,0]] #starting condition\n", + " constr += [x[2,:] <= MAX_SPEED] #max speed\n", + " constr += [x[2,:] >= 0.0] #min_speed (not really needed)\n", + " constr += [cp.abs(u[0,:]) <= MAX_ACC] #max acc\n", + " constr += [cp.abs(u[1,:]) <= MAX_STEER] #max steer\n", + " \n", + " #Track constrains\n", + " low,upp = get_track_constrains(x_ref,WIDTH)\n", + " computed_coeff.append((low,upp))\n", + " for ii in range(low.shape[1]):\n", + " constr += [low[0,ii]*x[0,ii] + x[1,ii] >= low[2,ii]]\n", + " #constr += [upp[0,ii]*x[0,ii] + x[1,ii] <= upp[2,ii]]\n", + " \n", + " # Solve\n", + " prob = cp.Problem(cp.Minimize(cost), constr)\n", + " solution = prob.solve(solver=cp.OSQP, verbose=False)\n", + " \n", + " #retrieved optimized U and assign to u_bar to linearize in next step\n", + " u_bar = np.vstack((np.array(u.value[0,:]).flatten(),\n", + " (np.array(u.value[1,:]).flatten())))\n", + " \n", + " u_sim[:,sim_time] = u_bar[:,0]\n", + " \n", + " # Measure elpased time to get results from cvxpy\n", + " opt_time.append(time.time()-iter_start)\n", + " \n", + " # move simulation to t+1\n", + " tspan = [0,DT]\n", + " x_sim[:,sim_time+1] = odeint(kinematics_model,\n", + " x_sim[:,sim_time],\n", + " tspan,\n", + " args=(u_bar[:,0],))[1]\n", + " \n", + "print(\"CVXPY Optimization Time: Avrg: {:.4f}s Max: {:.4f}s Min: {:.4f}s\".format(np.mean(opt_time),\n", + " np.max(opt_time),\n", + " np.min(opt_time))) " + ] + }, + { + "cell_type": "code", + "execution_count": 63, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "#plot trajectory\n", + "grid = plt.GridSpec(4, 5)\n", + "\n", + "plt.figure(figsize=(15,10))\n", + "\n", + "plt.subplot(grid[0:4, 0:4])\n", + "plt.plot(track[0,:],track[1,:],\"b+\")\n", + "plt.plot(track_lower[0,:],track_lower[1,:],\"g.\")\n", + "plt.plot(track_upper[0,:],track_upper[1,:],\"r.\")\n", + "plt.plot(x_sim[0,:],x_sim[1,:])\n", + "plt.axis(\"equal\")\n", + "plt.ylabel('y')\n", + "plt.xlabel('x')\n", + "\n", + "plt.subplot(grid[0, 4])\n", + "plt.plot(u_sim[0,:])\n", + "plt.ylabel('a(t) [m/ss]')\n", + "\n", + "plt.subplot(grid[1, 4])\n", + "plt.plot(x_sim[2,:])\n", + "plt.ylabel('v(t) [m/s]')\n", + "\n", + "\n", + "plt.subplot(grid[2, 4])\n", + "plt.plot(np.degrees(u_sim[1,:]))\n", + "plt.ylabel('delta(t) [rad]')\n", + "\n", + "plt.subplot(grid[3, 4])\n", + "plt.plot(x_sim[3,:])\n", + "plt.ylabel('theta(t) [rad]')\n", + "\n", + "plt.tight_layout()\n", + "plt.show()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## VISUALIZE THE COMPUTED HALF-PLANES" + ] + }, + { + "cell_type": "code", + "execution_count": 66, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAWAAAAFgCAYAAACFYaNMAAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjMuMSwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy/d3fzzAAAACXBIWXMAAAsTAAALEwEAmpwYAABQXUlEQVR4nO3dd3hUZfbA8e+dkjKTntASQKQpoMGGCgorEOtaEBVBBDvSBASUZkBBMFIUC1UBIRSBVSxrj6yyP8UFQZIAgtIhEEJ6T2bm3t8fk4SEtAkpd4DzeR4eE+bOvSfJ8eTlrYqmaRpCCCEanEHvAIQQ4lIlBVgIIXQiBVgIIXQiBVgIIXQiBVgIIXQiBVgIIXRiqu0NkpOTWbBgAenp6SiKQkREBPfcc09dxCZEvZLcFXqrdQE2Go0MGjSI1q1bk5eXx8SJEwkPD6d58+Z1EZ8Q9UZyV+it1l0QgYGBtG7dGgBvb2/CwsJITU2tdWBC1DfJXaG3WreAS0tKSuLw4cO0bdu23GsxMTHExMQAEBUVVZePFaLWJHeFHpS6Woqcn5/PtGnT6Nu3LzfddFO11588ebIuHltrISEhJCcn6x2G28QB7hVLaGhovT/jQsxdd/oZSSzluZq3dTILwm63M2/ePLp37+5SAgvhLiR3hZ5qXYA1TWPx4sWEhYVx77331kVMQjQIyV2ht1r3Ae/fv58tW7bQsmVLXnrpJQAGDBjAddddV+vghKhPkrtCb7UuwFdeeSUbNmyoi1iEaFCSu0JvshJOCCF0IgVYCCF0IgVYCCF0IgVYCCF0IgVYCCF0IgVYCCF0IgVYCCF0IgVYCCF0IgVYCCF0IgVYCCF0IgVYCCF0IgVYCCF0IgVYCCF0IgVYCCF0IgVYCCF0IgVYCCF0IgVYCCF0IgVYCCF0IgVYCCF0IgVYCCF0IgVYCCF0IgVYCCF0IgVYCCF0IgVYCCF0IgVYCCF0IgVYCCF0IgVYCCF0YqqLmyxcuJCdO3fi7+/PvHnz6uKWQtQ7yVuhtzppAd92221Mnjy5Lm4lRIORvBV6q5MC3LFjR3x8fOriVkI0GMlbobc66YJwRUxMDDExMQBERUUREhLSUI+ukslkcotY3CUOcK9Y3IE75q47/YwklvPXYAU4IiKCiIiIks+Tk5Mb6tFVCgkJcYtY3CUOcK9YQkND9Q7BLXPXnX5GEkt5ruatzIIQQgidSAEWQgid1EkXxPz589m7dy9ZWVkMHTqUfv360atXr7q4tRD1RvJW6K1OCvCYMWPq4jZCNCjJW6E36YIQQgidSAEWQgidSAEWQgidSAEWQgidSAEWQgidSAEWQgidSAEWQgidSAEWQgidSAEWQgidSAEWQgidSAEWQgidSAEWQgidSAEWQgidSAEWQgidSAEWQgidSAEWQgidSAEWQgidSAEWQgidSAEWQgidSAEWQgidSAEWQgidSAEWQgidSAEWQgidSAEWQgidSAEWQgidKJqmaXo8WFMUPR4rLjCKPulZJcldUR1X81ZawEIIoRNTXdxk165drFixAlVV6d27N3369Kn2PacSEuri0bUWEhJCcnKy3mG4TRzgXrGE1vP9L9TcdaefkcRSnqt5W+sWsKqqLFu2jMmTJ/P222/zyy+/cOLEidreVoh6J7kr9FbrAnzgwAGaNm1KkyZNMJlMdOvWje3bt9dFbELUK8ldobdad0GkpqYSHBxc8nlwcDB///13uetiYmKIiYkBICoqipCQkNo+uk6YTCa3iMVd4gD3iqU+Xci5604/I4nl/NW6AFc0iUKpYJQ4IiKCiIiIks/doZ8G3KfPyF3iAPeKJTS0/nqBL+TcdaefkcRSnqt5W+suiODgYFJSUko+T0lJITAwsLa3FaLeSe4KvdW6BdymTRtOnTpFUlISQUFB/Prrr4waNara94WFNavto+uQu8TiLnGAu8RSn9OAL/zcdZc4QGIpy9W8rZOFGDt37mTlypWoqkrPnj3p27dv9Q9W3G+CvXA/mla/ix4kd0V9cDVvdVsJd/LkST0eW4679Bm5SxzgXrHUZx/w+XKH3HWnn5HEUl6D9QELIYQ4P1KAhRBCJ1KAhRBCJ1KAhRBCJ1KAhRBCJ1KAhRBCJ1KAhRBCJ1KAhRBCJ1KAhRBCJ1KAhRBCJ1KAhRBCJ1KAhRBCJ1KAhRBCJ1KAhRBCJ1KAhRBCJ1KAhRBCJ1KAhRBCJ1KAhRBCJ1KAhRBCJ1KAhRBCJ1KAhRBCJ1KAhRBCJ1KAhRBCJ1KAhRBCJ1KAhRBCJ1KAhRBCJ7UqwFu3bmXs2LE8+uijHDx4sK5iEqLeSe4Kd1CrAtyiRQvGjx9Phw4d6ioeIRqE5K5wB6bavLl58+Z1FYcQDUpyV7gD6QMWQgidVNsCnjFjBunp6eX+vn///nTp0sXlB8XExBATEwNAVFQUISEhrkdZj0wmk1vE4i5xgHvFUhsXc+66089IYjl/1RbgyMjIOnlQREQEERERJZ8nJyfXyX1rKyQkxC1icZc4wL1iCQ0NPe/3Xsy5604/I4mlPFfzVroghBBCJ7UqwNu2bWPo0KH89ddfREVFMXPmzLqKS4h6Jbkr3EGtZkHceOON3HjjjXUVixANRnJXuAPpghBCCJ1IARZCCJ1IARZCCJ1IARZCCJ1IARZCCJ1IARZCCJ1IARZCCJ1IARZCCJ1IARZCCJ1IARZCCJ1IARZCCJ1IARZCCJ1IARZCCJ1IARZCCJ1IARZCCJ1IARZCCJ1IARZCCJ1IARZCCJ1IARZCCJ1IARZCCJ1IARZCCJ1IARZCCJ1IARZCCJ1IARZCCJ1IARZCCJ1IARZCCJ1IARZCCJ2YavPm6OhoduzYgclkokmTJgwfPhyr1VpXsQlRbyR3hTuoVQs4PDycefPmMXfuXJo1a8amTZvqKi4h6pXkrnAHtSrAnTt3xmg0AtC+fXtSU1PrJCgh6pvkrnAHteqCKG3z5s1069at0tdjYmKIiYkBICoqitDQ0Lp6dK25SyzuEge4Vyz17ULNXXeJAySW86VomqZVdcGMGTNIT08v9/f9+/enS5cuAHz66accPHiQ8ePHoyhKtQ+dOHEiUVFR5xdxHXOXWNwlDrh4YrmYc9dd4gCJpTZxVNsCjoyMrPL1n376iR07djB16lSXEliIhiK5K9xdrfqAd+3axeeff86ECRPw9PSsq5iEqHeSu8Id1KoPeNmyZdjtdmbMmAFAu3btGDJkSLXvi4iIqM1j65S7xOIuccClEcuFnrvuEgdILBVxNY5q+4CFEELUD1kJJ4QQOpECLIQQOqmzecA15S5LQbdu3crGjRtJSEhg1qxZtGnTpsFj2LVrFytWrEBVVXr37k2fPn0aPAaAhQsXsnPnTvz9/Zk3b54uMQAkJyezYMEC0tPTURSFiIgI7rnnHt3iKc1d8hb0z113yVu4gHNX08muXbs0u92uaZqmRUdHa9HR0brEcfz4cS0hIUGbNm2aduDAgQZ/vsPh0EaOHKklJiZqNptNGz9+vHb8+PEGj0PTNG3Pnj3awYMHtbFjx+ry/GKpqanawYMHNU3TtNzcXG3UqFG6fU/O5S55q2n65q475a2mXbi5q1sXhLssBW3evLmuK2cOHDhA06ZNadKkCSaTiW7durF9+3ZdYunYsSM+Pj66PLu0wMBAWrduDYC3tzdhYWFus1TYXfIW9M1dd8pbuHBz1y36gDdv3sw111yjdxi6SE1NJTg4uOTz4OBgtyk27iApKYnDhw/Ttm1bvUMpR/JW8rYqruRuvfYBu7oU1Gg00r17d13j0ItWwSxAWZXllJ+fz7x583jyySexWCwN9lx3yVtXY9GD5G3VXM3dei3A7rIUtLo49BQcHExKSkrJ5ykpKQQGBuoYkXuw2+3MmzeP7t27c9NNNzXos90lb12JRS+St5WrSe7q1gUhS0Gd2rRpw6lTp0hKSsJut/Prr79yww036B2WrjRNY/HixYSFhXHvvffqHU4ZkrdOkrcVq2nu6rYS7oUXXsBut5d0nLu6FLSubdu2jeXLl5OZmYnVaqVVq1ZMmTKlQWPYuXMnK1euRFVVevbsSd++fRv0+cXmz5/P3r17ycrKwt/fn379+tGrV68Gj2Pfvn1MnTqVli1blrQwBwwYwHXXXdfgsZzLXfIW9M9dd8lbuHBzV5YiCyGETtxiFoQQQlyKpAALIYROpAALIYROpAALIYROpAALIYROpAALIYROpAALIYROpAALIYROpAALIYROpAALIYROpAALIYROpAALIYROar0fsDsfoChEVSR3hd5qXYCNRiODBg2idevW5OXlMXHiRMLDw2nevHldxCdEvZHcFXqrdReEOx+gKERVJHeF3ur0SKKqDqGLiYkhJiYGgKioqLp8rBC1Jrkr9FBnG7Ln5+czbdo0+vbt69IZXidPnqyLx9ZaSEgIycnJeofhNnGAe8XSEMeuX4i5604/owstFq/PPydo+HCSfv4ZewW/cB0OaNkylPHjM3nxxWwAgh99FCUzk+Rvvqnwntu3e9CnTwgrVqRwxx0FLudtncyC0PMARSFqQ3L3ElR8kKqqVviyoagqljRNNQ1zfDy28PBKbxkXZwYgPNxWo1BqXYDd+QBFIaoiuXuJKq6wlRTgs/XZ+YHx6FEMGRlVFuDYWDONGzto2rTie1am1n3A+/fvZ8uWLbRs2ZKXXnoJcJ8DFIWoiuTuJaqaAuy8RCt52RwXB1BlAY6PN3P11TVr/UIdFOArr7ySDRs21PY2QjQ4yd1LlEsF+OzLHnFxaB4e2K64osJrc3IUDhwwce+9+TUPpcbvEEKIC5hWVICVKuYfGAxn+4DNcXHYOnQAD48Kr92zx4yqKlx9dWGNY5ECLIS4tFQzCAelWsCahnn3bmxXX13ptec7AAdSgIUQlxoXuiAURUNVFYxHjjgH4Dp3rvTauLjzG4ADKcBCiEtNDfqAiwfgCquZgnY+rV+QAiyEuNTUoAB7xMWheXpib9++wuuKB+CkAAshhAu0oj5gVwbhqhuA273bjKYphIfXfAAOpAALIS41LvUBg+qgXgfgQAqwEOJS4+JCDC0jE0NmZrUDcE2aOGjSpOYDcCAFWAhxqXGxD5jkNAAKq2kBn2/rF6QACyEuNS4WYCU5xTkAV8kKuOxshYMHTefd/wtSgIUQlxhXB+FIScfWsSOYzRVes2dP8QCctICFEMI1Li7EIC29ygG42NhKBuAcDtdDcflKIYS4GLjSBaHa0WyOandAa9rUQePGZe/j/emnrofi8pVCCHExcKEAG+2FqBhcWAF3Tv9vYSG+8+a5HorLVwohxMWg3JEX5RkLC1AN5kpXwJ0dgCvb/WBZuxbT8eOuh+LylUIIcREoGYSroq/WYMvH7h9Q6QDc2RVwZwuwkpuL7/z5FHTt6nIsdXoqshBCuL3qWsCqirEgH3vToEpvUdEKOOuyZRjPnCH1ww9p5GooLl4nhBAXh2r6gI2HDmHQ7Nj9Ayu9RVycmWbNHDRq5LyHkp6Oz6JF5N9+O7YbbnA9FNejFkKIi0A1BdgjPh4DKg6/gEpvce4AnM+iRSiZmWS+/HLNQqnR1UIIcaGrpgvCHBuLQdFwWH0rfD0rS+HQobMDcIbTp7F++CF5Dz6IvWPHmoVSo6uFEOICVzIIV0kL2Bwfj+LpgYpS4evnDsD5vvMOit1O1rhxNY5FCrAQ4tJSVReEqjoLsMWz0mnCpQfgjEePYlmzhtwBA3C0alXzUGr8DiGEuJBVUYBNhw5hyMlBsXihqhW3gOPjzYSG2gkJUfGdOxfNZCJrzJjzC+W83iWEEBeqKgpw8RlwzgJc8dtjYz0ID7dh+vNPvDdtIvepp1CbNj2/UM7rXUIIcaGqYhDOHBeH5uWFYvGqcIyueADu6qtt+M6Zg+bjQ9bw4ecfynm/UwghLkBVDcKZ4+KwdeyIYlAqbAHv3u3s/73eshfv774je+hQtKDKF2xUp05Wwi1cuJCdO3fi7+/PvBpsRCGEniRvL1GVdUGoKubdu8l75BEMu8HhKN8HXLwF5S1fz8ARHEzOc8+Vu0ZJT4fQUNdCqVHglbjtttuYPHlyXdxKiAYjeXuJqqQAFw/AFYaHO8+Eq6ALIj7eTFhwDs23f0326NFoVmvZC1SVwNGjXQ+lprFXpGPHjvj4+NTFrYRoMJK3l6hKCrA5NhYAW3g4BkPFs9RiYz24wf4b9rAwch5/vNzrPgsW4BUT43oorkcthBAXgUoG4cxxcaheXtjbtUNRyo/RZWYqHD5sokvGZueiC0/PMq97/PILvrNnk31fH5dDabDd0GJiYogp+s0QFRVFSEhIQz26SiaTyS1icZc4wL1icQfumLvu9DO64GIpKsA+3t5YSl1r2rcPOncmpGlTPD1N2GyUudeeeGdFvq55Etahr2A1Gs/eMyEB88iR0K4dH98RzbOuxuvidbUWERFBREREyefJyckN9egqhYSEuEUs7hIHuFcsoS4OZtQnd8xdd/oZXWixKBkZNANysrLIKb7W4aDpzp3kPvoomcnJOBzBFBQoZe61dcEBoAdtXuxBclra2RvabAT374+WnU1C9AZee8aLZ0e6Fq/sByyEuLRU0AdsOnQIQ25uySGcBoNWdiVcQQF7Y1JpaT6Jz6O9ytzOb9YsPLdtI23BAlZuu4YTJ1wvq3VSgOfPn8/evXvJyspi6NCh9OvXj169elX/RiF0JHl7iaqgD7h4BZytc+eSS0r3AVtXr2Zn3qNc3cUBytmuB6+vvsJn6VJynnyS5Nsf5J1uPnTtWgCU7R+uTJ0U4DHnuQ5aCD1J3l6iigpw6YUY5thY5wBc27bO15SzDWQlJwfH28v5m0j69soAcgAwHjxIwNixFF57LRlTp7JsiZXkZCPLl6eCi2diyCwIIcQlpXglXOkuCHN8PParrgKTs01aehqa9cMPiU1rBUB4uB1wnv8WNGQImtlM2pIlpOV6sWiRD3fckcf115c9qLMqUoCFEJeWc/uAHQ7Mu3eXOYK+uA9YSUvDZ/Fifmv/GFB0Bpym4T9xIqb9+0lfsABHWBiLFvmQlaXw8stZNQulTr4gIYS4UJxTgE0HD5YZgCu+RFXBZ+FClKws/hd6P2FhdoKCVCyrV2P55BOyxo6l4B//IDHRwLJlVh58MI8OHew1C6XOvighhLgQnDMId+4AXPElWqEdn+XLyXvwQWKPBNO5sw1zbCz+U6eSf9ttZBeNIcyf74vdrjB+fM1avyAFWAhxqTlnNzRzXByqt3fJAFzJJckpYLdz4vkJHDliIrxtJoFDhuAICSH9vffAYODIESPr1lkYODCXyy5z1DgUKcBCiEuLojgH4koVYHunTlBqZZsxLwcyssgdOJBd6a0BuOXneRhPnyZt6VLUoi0o5871xWTSGD36bOv30KFSK+SqIQVYCHHpKe7kLR6AK9X9AODx1z5UxUjW6NHExzu3oOwau4yMV1/Fdu21AOzda+Kzz7x55pkcmjRxFvO8PIUhQ1zfH1hWwgkhLj1FBdh04ACGvLwyA3CmP//E40Qidv/2qE182P1jBq1IxfvBf5D+xBMl182e7Yevr8bw4dmAs0t50iR/9u1zvaxKC1gIcekpWupWMgBXagqa35tvopiNOPwCMJw8Sfz/7Fzrs5+M2bNL+o9//93MDz94MWxYNgEBzsG8tWstbNxo4cUnjrseRh1+SUIIcUHQFAVFVcsNwJl//x2vH35Abd8OVVMwPDueg2prOgy4As1icb5Xg6goP0JCHDzzjHNVXFycmchX/OjVaj9vrr3S5TikAAshLj1FXRAecXHYrrrKOQCnafhFReFo1AjHFe0gLZPdsc4SeXUvv5K3btniydatnowenY3VqpGWpvD8YAuNHYmsP3ILtjsjKntq+TDq/AsTQgh3ZzCA3Y5pz56S7gfPn3/Gc+tWskaPxpx4Ei0nl1+6OE88vuqqQqC49etL8+Z2Bg7MgaRkXopI4NQZM+saDUdZ/Q5pixe7Hkbdf2VCCOHmDAYMaWnOAbjwcNA0fKOisLdoQeHNN+O1bSuq2ZPtje+mRQs7QUHOft6vvvIiLs6DcWMzCfzXGlZ0/ZxvEm9g1j++4PL/m0dBz541CkNmQQghLj0GA4YzZwDnAJzXV1/hER9P+ptvEjhiBAbjROw+AcTvMTj3fwDsdpg925crLsvm+TV38+sOH6byPQ/2Ps2Ald2gePvgik7zrCyMuv66hBDC3WmKgiE5GdViwX7ZZfjOmYPtiivw2LoV019/Yet+Cw6MzhVwRQX4X2uMHDxoZtbxJzlzMIf+Pl/Spp3Km4tUFAWUrCwsH31EowjpAxZCiMoZDBiTk7F16oT3pk2YDxyg8PrrsXz2GVnjx6OFhVJY6GzShofb0L76kfmRdrqwjZ4PefFQq/+Rq3rxwQdp+B+Ox//ll2ly3XUETJmCZja7HkZ9fX1CCOG2DAYMqanYOnXCd948bO3bY9mwgfxevcgeNQqDQcNetLFZ9w+H8a8hv3PcEcaEaYVMCFjM77usvPPQt3R98S4a33kn3p98Qv5993Hmq69I/vZbl8OQPmAhxKVHVVEcDgyZmZhOnsQRHIyjaVPS3n3XWZzRsBdoXK4cxuf//sPrlsPcck0eaYYgPvjAh5EeS3g2eii2tm3JeO01ch9+GC0goMZhSAEWQlxylKLmreePP+IICMCQlUVydDRaYCDmP/7A8kUqdnUg1zY+yqz7fid5mQ/vpLzC0GkvczO/8frt35H85EYKu3YtWR1X7PBhI64e5i0FWAhx6bHb0RQFY0YGAOlRUdgvvxz/yZOxrFqFzWsZGgbaXZbHouWB3MuXzDr4OB7eBt7/1Jec8PfL3bKgABYu9OG993zJz3ctDCnAQohLjlJYCJqGBuQ99BCqry+N//EPDMnJ5N9+O0l/XA55cGh7Jln4YOt8DXvjmrM2OpVm4YHl7vfLLx5MmuTPwYNm7rsvD/B2KQ4ZhBNCXFrsdrAVze1t3hzD6dMEjRgBBgOORo3w/v57zqR5APCFxyNcc62d72JbMG5cFj16FJS5VXKygVGjAujXLwS7XWHN4qN8OOoXl0ORFrAQ4pLisWULCqABpsRETImJaAYDxsRECrp2JfPVV0mYfQMc1nCoCrt3m+nVK5/RQ85gPHgS48mTKCdOsub75rz6091k28xMCFxE5JlIrENTnA9xcTGGFGAhxCUl8IUXgKKFa3Y7qo8Puf36kX/nneDpieHkSZISnBuse2l5BCnprNvZg8btDwIQz1UMZTG/cgvdzb/yXvs5tG9dgCO0Dz8bbmD5nz1Y6WIsUoCFEBenzEw4cQKSkzEcPYrXL7/g9+23GIq6HzRA8/aGwkKsy5fjs3w5ACkEkc0wQKPAYWSD8jDBucfJ8Azidftk5jtG4U8GH5iG8AQryTvoxZq/H2GpOoTt3IiFHJcLsKJpNVi4XIe0c6ZuCFERRZ/0rFJBy5bgcKA4HM7+RFV1HvBotzv/6alpzs+LPi75Q6mvp/TXVcnXWJf/h1yK/7ed79e8iOcZjnNHs4UMYxiL+Yp7GMECjtKKp1nGbF7mDI1YzFBW8gTpBNKBvQxjEYOIJkBLdy1GKcDCnbljAT533ueFxA2/m7V27k/j3K9RKfX3yjmvV/T9uIwjnOAyAA7TnHHM51MepiN7eIeRJNOIJQzlJ3phppAH+ZTnWUwPtjhTQ1EwOlw7IblOCvCuXbtYsWIFqqrSu3dv+vTpU+17Tp48WdvH1omQkBCSk5P1DsNt4gD3iiXU1Rnt5+l8cletpABX+j9S8fVF/y3T+FAU5960ioJW9N+Sz41G50bhJlPJx5qXl3OllsWC3WxG8/RE8/JCtVhw+PmheXri8PHB1qgRBARAcLDzT/Pm4OdXPrY6cN75oqoYzpzBePIkxoQE53+LPz51CuPJkxiSksr9EnYEBqKGhuIo/hMW5vxv48YEJCTgWL8ez99+c34/NQ3NasXeti3mXbvQvL0x5OVhDw3F1rkzaR9+WObe33zjybPPBqMoGpqmYLGoqKrCU09loyiwcaOFM2eMtGhhZ+DAXPr3z6VRI7Xcl+Zq3ta6D1hVVZYtW8Yrr7xCcHAwkyZN4oYbbqB58+a1vbUQ9ep8czcxIaGBIqxcSEgI6W7yS7JCmoaSmVm+sBZ/fPIkxlOnUIr6Y4up3t4lRdXWsydqaCj2sLCzBTcszNlvW4rx+HEsa9bg99prGM+cQQkJQfX3x5CRQW6/fthbt8YvKgqA/F698P7qK+fxQmrZwllQAGPGBAIaJpOGzabQpo0dX1+NxYt9AOjdu4DBg9O57baC0qfYn7daF+ADBw7QtGlTmjRpAkC3bt3Yvn27FGDh9iR3ayEvr6SQGrKy8Nm/39lqLS6yCQkYcnLKvEUzmXA0bYojNJTC664723It9UcLDHSti8fhwHPzZqzR0Xhu3gyKQsEtt6C0bYtx61ZsbduSumwZmocHIX37ogYEoHl4oAYGovr4oHl5OfvpS3n22SCys51LI1TV2eqOj/egcWMHo0Zl89hjuTRv7lrXgqtqXYBTU1MJDg4u+Tw4OJi///673HUxMTHExMQAEBUVRUhISG0fXSdMJpNbxOIucYB7xVKfLuTcrdefkd0Op06hnDiBcuIEHDvm/Pj4cSj6O6VoM/NifoDWuDFaixbQoQPa7bdjb94cWrZEa9ECrXlzaNoUjEYUnIXnvIpPYiKGjz7CuGwZyrFjaE2bor78MprZjOc774DNhv2119DGjsUvIwPzzTdDUBCGpCTs77yD95o1cN11mLKzoeh7qGnw4otGNm82UtxT7HA4C/FHH9l4+GENs9kT8CwXjqpCYiKcOKFw4gQcP65w/LjCu++69uXUugBX1IWsVPAbLCIigohSGxW7Sx+ju/R3uksc4F6x1Gcf8IWcu+f9M9I0DKmpZ1uvJ09iSkgo81/j6dPOGR6lqD4+OJo3d7ZUO3Ys0/fq16kTyV5e4OVV9bPT0moeb1HMHlu3Yl21Cq9vvkGx2ym45RZypkzB0bQp/q+8gkd8PPm33YZh4UKS/f0hLY2gxx+HpCTsLVqgeHmRdPfdNJswgZzBg/HYtg21oICf/5POc88Fcvy4sz/BaNRwOJx9vitW+NCpUwpbtxpISDBy8mT5P6dOGbHZyuaMt7facAU4ODiYlJSUks9TUlIIDCy/VloId3Mx5q6Sk1PxoFapvlflnJ1iNA8PZ0Ft1ozCbt3KDmwVdw1UNYAXEgL18EtJSU/H8q9/YYmOxnzgAGpAADlPPUXO44+jNm6M7+zZWD/6CLVRI1IXLiT//vsJadQIkpPxffttvLZsIWfgQKxr1pD2zjuYjhxByc/H1rkzhT/tYO8BI3fd1YjiuREWi0ZgoEpKCnz5pbOfuUuXpmViMpk0mjVzEBrq4PrrCwkLc5R8Hhbm/OPvrwENNAjXpk0bTp06RVJSEkFBQfz666+MGjWqtrcVot5dcLlrs2FMTHT2r2ZmOvtdSxfYU6cwpKeXeYtmMKA2bowjNBRbx47kR0SULa5hYajBwWAwlKxbOH7c2VjN+Fshc4eJ7GwjOTlGcnMVcnMNZGcrFBQoFBYq2GwKqgqFhcE4HGCzKcVTo1FVBYfD+bGmOT+vYGo0mqacnQqtaVzP7wxjCf1Zj4U8fuNGFrGcDen9yP/Ai4c/+Bfv0B8LiSxgGFOSXidzuD84DzDmTnbxNfP5iEF0W/MbhXSi8+hhPMEqlgM3jejNR6wmFzg7SU0p+vqcn+fnl568dpbdDsePG0tazJVxdW5ZrQuw0Wjk6aefZubMmaiqSs+ePWnRokW17wsLa1bbR9chd4nFXeIAd4mlPqcBu1PuKqg0JomWHKMFx2nB8aKPT5R83JREDKUKgh+QSiDHaMkx2nKc2zhOC47RsugOLUhQw7AnmiER2Fl1BHqykMMA1jGMRVzPTrKxsprHWcQwdnEtAJdziAWM4G6+ZQfX8QCf8ztdytynJUdZwyDiuZpt3MyTRPMAn6Fi5np2kokvB2iHigEDxYNwpZPs3JnC9Uu3hRiKcjFOCRd1TdPcb9FDzXNXw5+MMsXVWVSPl/ncg7JTsnLxLlVMmxcV2rLvysVad19YUaz1fb/S3eyd2MPz2lIGEY0/meymE0sMz7PO8BiZij8AJtXGWO0tpqivY8PMK8xgISNwlGo/KoqG1ZTPT45/0E7bT98mP7HqzP2cIIybHFtRFPhNu5kcLMy95wsW7b2Dg0e9eb7td/z9t5n165Ox2xUGDgxm/fpk/vrLTGSkP/Hxp0qOpK+JBpsHfL4SEk7p9egy3GXAyV3iAPeKxdW+tIZULnfz88vOby1eSFCq79WQnV3mLaWnZDlCwykIvYvcc/petcBA/BSFTkCnc2I4+zPKrM8v1SU1yZfCQkg8akf57Fuaf/kRYQe3YjN48HOjvqzwGspXabeSkWmkuHHanS0sYhid2EtMwIOsvmE23m2bMi00h9DQs32vQUEqgVMmYV21nQ/uXkPXn38k1HGCUUEraGF1cOq4RmclltMPP82bU3M4cb0HXmYHyckGuncv4NZbC3nnHedc36uvtnHggLM0OhsA9ddYlM14hKghv6lTncW1uMCWGsgr5ggJwREWhr1NGwq6dy8331Vt0oQ6mcnvRlQVzpwxcPKksWTWQPF/T50yYjp+jIeSP+ApVtCYMxykNS/zJpt8B+MZEkxoqIM+ofmEhTlo7ZdExPdTuWzzOuzNW5AycyUdIyKYBZz7S8fhgEMzvqDHqlXMZRwzvr2Xo6Y2/BHSm8/Te+Ojaiwb9wue8wqw9riKwSMDmGYz0qxRAWlJRiZOTAUgPt5Mq1Z2/P21kla6Wn6RW52SAixEDVnWry9pqdrCw8vPGmjWrPopWRcYTYOMDKVk+lXpaVlnzpg4erRxhVOyrF42BgZ+ydT8JXRJ+wEUhUMd72LvfU9iuPNWnm8BY7xV4EzJg7w3bMBvxgwMWVlkjRhB9osvllv9BnD6tIF16yzsWHmIL5LGsdV8K5njXue7Xa8S8G0yzyVH0bdfHpGRmTT/bhsAS3d25eefvWh5uUrSUYV77snjmmucXT9xcWZuuKEQcK4GBynAQridxP379Q6hzuXlUeE819LFNien7AE6JpNG06YOLrsMrr++sKRLIDTUQSvPk3T4JZrgTWucpw43aULOi2PIeewxLKGhtAfO/ae96e+/8Z84Ec/ffqOgSxcyoqKwX3llmWs0zXn8z6pVVr77zgtvexa7vfuh+PngufZ9ji3KpOO3C/nO2odJK1vRtWs6AOa4OAq9fXllRTgPP5xLwW9GNLWQl17KAiAlxUBCgomnn3au3pMCLISoE3a7s7V48qSJkycN5VqwCQlGUlPLd4c0auQspm3b2unRo4CwMEeZItu4sYrRWNwHnO5cMPF//4c1Ohqv775DsdvJ79GDzOnTyY+IALO54gDz8vB95x18Fi9Gs1pJnzOH3P79z1ZBIC1NYeNGC9HRVg4dMhEQoPL0U9m8/vdAQv57iOj+nzGi/9W8njceHyWHqzaNRulUWPJ+bUc8v9mu54oOKqNHZ3HiEzOtgrLwae88HTkuzhnb1Vc7W8NSgIUQ1dI0SE01lGqxOltyZwusgdOnjTgcZbsGfH3VkgGszp1tZQa0QkOdiws8y6+8rVhqKtalS7FGR2M6dMi5YOKZZ8h5/HEcrVtX+VbP//wH/8mTMR07Ru4jj5AZGemcl1z0tf3xh5noaCtffOFNfr7C9dcXMn9+Gvfem0fI6g/w/+DfvN10JmNX3MvDNx/ghZ0Lye/7EEqn9iXPKMi2Yd67lz9MI1m6NJXFi30YiIHQpraS3uTyBVgriqF+Z+FIARbCjeXkKOWWwSYkOPtdjxxx9rueXTTg5OGhlRTRbt0Ky7VcQ0Md+PnVcmRf0zDv3Ik1Ohrzl1/ikZ9P4Q03kDZmDHn//Ge1feCGxET8p03D+9//xtamDckbN1LYrVvJ1/zZZ96sWmVh924PLBaVhx/OZfDgHDp1crZYbT//jvW11/mMB4hyvMzChakM/u80lB0qWePGlXnWivEnma4VcPWTzu6Mjz+28FJzFQ/T2eZtXJyZyy+3l3xfZBBOiItcYSEkJhornDVQ/Ccjo2y/q8Gg0bixymWXwVVX2bjjjvxyBTYkRK23PeOVnBy8N23CumoV5j17UK1W1EGDSOnXD3vHjtXfwOHAunIlvm++iWKzkTl+PNnDh4OnJ/v2mVi1ysonn3iTnW2gQwcbs2al07dvHr6+xS1SiFmbxR0Th3FUa8n3Axbw89QzBJ45gOWF9ajPP4+j1GKazz7zJuHLvQB0GnwlQ+b44eGh0aq1BillC3CXLme7LKQLQogLWOkpWecW2FOnnB8nJRnK/RM3IEAlLMxB8+YObryxbOs1LMxBkyYOzObiftfz3NzmPJj+/BPrqlV4f/ophuxsbB06kP7GG+T17Utwq1bYXZgHbI6Lw3/iRDxiY8nv0YOMWbPIDb2cr792tna3bfPE01Pjn//MY/DgHG64wVbmF8mxY0YiJ/sw8T+DCFRSOfDuV7zykHOert+Euc7N6CdOLLl+/34T48f7E934f6h5fsTmtOOLL7x54YUsPP5SSrajTE529o+Hh5/dPlMKsBBuStMgM1MpN5BVPN+1uMhWtEuWs5iq9OqVX6rVqpZ8bLG40QrR/Hy8v/4ay6pVeG7fjubpSd6995IzeDC26693+WgmJSsL3zlzsK5YgRocTOrChewLf5A1a618/LGF1FQjrVrZiYzMoF+/PIKCyla9wkJYssSH+fN9ec3xCr3ZTMrst2jzkLNLwbR7N95ffEHWqFF4NmkCyclkZys891wgPj4adzXajs3/Kt6c7U9AgMqwYdkwzlCyzr24/zc8/OxKRCnAQripK69sWrJxd7HiKVmhoQ6uu66wzIBW8Z/AQO2COE7OeOQI1tWr8V6/HmNqKvZWrciIjCS3Xz+0oCDXb6RpeH39Nf5Tp2I4fZrsgYP44uZX+XBDM34a7oXRqHHHHfkMHpzLrbcWlJ70UOJ///Ng4kR//vrLzLQbPuXl32eRM2AABY89WnKN35tvogYEkD10KJ7OxzJ+fACHD5tYv/oUlqf+5O+7n2PzZ15Mnpzp3K1MUUqqa3EBvuqqswW4eLm5DMIJ4WYefTS33KyB4ilZFyy7Ha+YGCyrVuH1889oRiP5d95JzqBBFN56KxVWxyoYjx3Df8oUvDZvJrf9VXzYey1RP/bg1GojTZs6GDcukwEDcmnWrOImZmqqgZkzffn4YyvNm9v5ZO5O+sx4GlunTmTMmFFyncf//ofX5s1kTpmC5u/cO2LFCitffunNpEmZ9AjejVJQwEdxN9GkiaNkni8GQ0kBjo8307q1vczApLSAhXBT06frv/9CXTEkJmJZuxbrmjUYExNxNG1K5vjx5A4YgNq0afU3OJfNhs+SJfi8/TYOzcgHHd5k5P4XKfzLzD/+kc/rr2cQEZGPqZLKo2mwYYM3M2b4kZVlYMSILF4clkyLx54CIPWDD6B4VZym4RsV5Vzk8ZTz9d9+U5g+3Y/bb89n+PBsPD6OA2DDoZsZPSsLb++iIluqAMfGenDTTQVlvy9SgIUQ9UJV8fy//3O2dr//HsXhIP+228iYNYv83r2ptDpWw2PbNnxemojXgf18a+nDc7nvkpMYyjPP5/H446m0alX1eWp//21i4kR/fvvNky5dCnjjjQw6dLDj/3IkHnFxpKxYgeOyy0qu99y8Gc9t20h/4w00b29SUgwMHGgiNNTB/PlpGAxgio0j0+CPvfllDBhw9hglzWBAUVXOnDFw6pSxZP5vMSnAQog6paSmYtmwwblg4sgRHEFBZD//PLkDB+Jo1eq876slp2B74mVCY9ZwjJaM4AtOd7qDlwfl8s9/nq52W4y8PHj3XV8WLfLBatWYMyed/v1zMRjAe+NGrGvWkDVyJAV33HH2TaqKX1QU9ssuI3fAABwOGDEikDNn4IsvUgkIcLZ0c7fEE69ez7jx2Xh4lHpo0ZH1xf2/nTtXXIDre7NeKcBCXMw0DfPvvzunkH31FUpBAQU33kjW+PHk3XMPri93Ky87C/565XO6bZpKmCON+ebx7Hn4JcY8Ax06lN8hriI//eTJ5Mn+HD1q4uGHc4mMzCQkxNnsNP35J/4TJ1LQtStZL71U5n1eX36Jee9e0t5/H8xm3prjy3//68nixXauuqposUZOIcHH9nIkaCR9+uSVfXDRIFxFA3DOl52VV1VlEE4IUUNKdjben3ziXKn255+oPj7kDhhAzqBB5Ta4qam9e03EvHecf/57HPeqPxNr6cqO52bzzxFt6Ge1u3SPxEQDr77qz5dfetOmjY0NG5K55ZazCyGUzEyCnn0Wzd+ftIULy3aL2Gz4zZ6NrUMH8h54gB9/9GT+fF8efTSXp54ylRxP99P7R3mCQto82rH8AGlRH3DxAFzxQo/SL4N0QQghasC0Z4+ztbtpE4acHAqvuor02bPJ69MHzXr+p2fk58O//+3N+o8M3P3HHKYzm0KzD7FD53Ll3BE0SkvFlY3LHQ5YtcrCm2/6UVioMH58JsOHZ5dtiGsaAePGYTx+nJSNG1EbNy5zD8v69ZiOHCHlo484nmBm1KhAOnSwMXNmOhACOLs14j/aB8CVAztQro4WFeDYWA+6di0491UpwEIIF+Xn4/3ll1hXrcJj5040Ly/y7r+fnEGDsF17rcsLJipy+LCR6Ggr69db6JIew1rTMC7jEOn3PkT+zKk0CglBMbo2RS0+3syECf7ExnrQo0c+s2ZlcPnl5QfmrEuX4v3112RERlJ4001lX8zLw/fttym8/noyu0fwfN9AHA744INUSm8ZvHKllbaZf1Bo9UdtdRnn0gwGVLtGYlL5ATiQAiyEqIbx0CGsq1djWb8eQ3o69tatyZg2jdxHHkELDDzv+9rt8P33XkRHW9iyxYvmxpN83vgpeqT/C1vL1iS/sd45N9hF2dkKs2f7smKFleBglQUL0njggbwKfy94bNuG38yZ5N1zDznPP1/udevKlRgTE0l7/32mvRpAbKwHy5allinkWVkK77/vw1af7WjXXF3xLyCDAXuhs7qWXgFX6mVAFmIIIUqz2fD64QdMa9fS5D//QTOZnAsmBg+m8JZbatXaPXnSwLp1VtautZCYaCSsaSGf9J7HA/97DUNqIZnjxpE9YoTLA3eaBl9/7cXUqf6cPm1g0KBcJk4sWolWAUNSEoFDh+Jo2ZL0efPKfS1KZia+771H/m23se5kL6KjrQwbls1dd+WXuW7JEh+y0xy0M+0mJ/zZioNTFByFGoqilRuAc75cPAjn0pd63qQAC3EBMCQkYF23DsvatRhPn0Zr0YLMl15yLpho0uS876uqsGWLJ6tWWfjhBy80DW67rYAlQ7dw52fj8PzxDwq6dyd91qxq9/Yt7fhxI1Om+PPjj1506mTjgw9Sue668oWuhN1O4PDhKBkZpKxZg+bnV+4SnyVLMKSnE9dvMi+P9efmmwuYOLHsopgzZ2DpUitDb/kNwy+F2K6+uuLnGQw4bFqFA3BFL5d8f+qTFGAh3JWq4vnzz1iio/H64QfQNAp69iQ9KgrfRx8lO+38d0NLTTWwfr030dFWjh41ERzsYNiwbAb1SaLT+iis05ejBgeTtmABeQ884HLL2maDpUt9eOstHwwGmDYtg6efzql2bYfvnDl4bt1K2vz52Dt0KPe6ITkZ69KlZN15LwPm9sTPT2PRorRy950920hensLIm3+FX8DWuXPFDzQYUO1qhd0PRS8DUoCFuOQYUlKwrF+PZfVqTEeP4ggOJnv4cOeCiZYtAfA9j40nNA22b/cgOtrCv//tTWGhwk03FfDyy1ncfVcu/pu/wX9QJIbTp8kdOJDMyZNL9ldwxbZtHkya5M++fWbuuiuP6dMzCAurvoJ5fv89vu+/T87AgeQ98kiF1/i89x5Kfj7j82Zw9KiRDRtSaNy47L0TEgwsWWLgkUfyCEvchRoQUPL9OlduvhGjJgVYCAHO89S2b8dSvGCisJCCm28mc8IE8u+6q1YLJrKyFD75xNna3bfPjK+vysCBOQwalMsVV9gxnjiB//NT8IqJwdahA6lLlzq3m3RRaiqMH+/PunVWwsLsrFiRwh13lJ/aVRHjkSMEjh5N4dVXkzF9esXXJCRgXbWKP8IfY+mWa4iMzODmmwvLXff2275oGowbl4X52Xhn90MlLfczqSZCqb4AyyCcEBcxJTMT708/dS6Y2LcP1deXnMcfJ3fQIOzt21d/gyrs3u08YWLTJm9ycw1cfXUhc+ak06dPnnPfYZsN66IP8S0a8MqIjCTnmWcqPzzzHJoG//qXNzNnmklNNTN0aDbjxmW5vqdxXh5BQ4aAopC2dGmlxxj5vPUWqgoPx7/OXXfl8fzzOeWuOXDAyIYNFoYNUwkLycX8559kDxlS6aOTU0w0R61wAA5kEE6Ii5o5Ph5LdLRzwURuLoXh4aTPmeNcMGGxnPd98/Lgyy+9WbXKyh9/eODlpfLAA/kMHpzDNdecLTbm7dsJmDgR87595N1xB5mvv44jLMzl5/z9t4lJk/zZutWTm29WWbs2mY4dXVsFV8w/MhLznj2krFxZaVeB6cABLBs28IHXSLTGYbz99pkKG7Vz5/rh6anx8ssOzHv2o9hslQ/AAaeTTRgVFR+fSmZkXAhdEFu3bmXjxo0kJCQwa9Ys2rRpU1dxCVGvdMndvDy8v/gCa3Q0Hn/8gerlRV6fPuQOGoTtmmtqdesDB4ysXm1l40YL6ekG2ra18eqrGTzySG7JxjQASloafm+8gXXNGuyhoaQuW+bs4nD9S+C993xZuNAHi0UjKiqd0aMtpKbWrPh6f/wx1nXryHrhBQoiIiq9zufN2eThzeuOySxbmlrhYaLx8Wa+/NKbMWOyaNLEk9x1zi0oKx2AA5KSTZgMlVfXC6IAt2jRgvHjx7N06dK6ikeIBtGQuWs8cMC5YGLDBgwZGdjatSPjtdfIffhhtICA876vzQbffefFqlVWfvnFE5NJ4+67na3drl0Ly7YUNQ3vTz7Bb/p0DOnpZD//PFnjxtVoefLPPzs3zjlyxETfvrlMnZpJo0YqBkPNWuym3bsJmDKFgltvLbfJTmnmuDgsX3/FdCJ58Q0POnXKq/C6N9/0JSBA5fnnswFPzHFxzgG4UodzlpaUZCArx4TReIEX4ObNm9dVHEI0qHrPXZsNr2+/xbpqFZ6//opmNpN/993OBRM331yrBRMJCUbef9/IsmVNSEoyEhZmZ8KETPr3zy03MwCcvwACJk3C89dfKbz2WlLWrcPeqZPLz0tKMvDqq358/rmFyy+38/HHyXTvXn4QzBVKRgZBQ4agBgSQtmABVR0jUvjSHFII4tjDQ5n+aMXF97ffPPjPf7yIjMwoaR2b4+KqHICLjTWjYsCgVFWAL7IjiWJiYoiJiQEgKiqKkJCQhnp0lUwmk1vE4i5xgHvF4g5qlLvHjmFcvhzDihUoiYlol12Gffp01CefxNikCeWXF7hGVeH77xWWLjXyzTcKmgZ33aUxZIiNO+/UMBq9gHMGsfLzMc6ejWHOHPD2xv7ee/DsswS4eLyQc48FA5GRRgoKIDLSzvjxKl5eZb8Kl/NF0zANHYqSkIA9JoagKnZlO/XxFi7bvZm3Qmfz1rKQCsfnNA3mzjURFqYxbpw33t7emBwOlH37UMeMqTSmgwcNeKKgaGql1wQFOQuvj48vISE+1X9t56naAjxjxgzS09PL/X3//v3p0qWLyw+KiIggolRfT7ILx1g3BOfx3vrH4i5xgHvFEhoaet7vbbDcdTjw/OknrNHReP74o3PBRO/e5Lz5JgU9e55t5Z3H9zQ52cD69RZWr7Zw7JiJRo0cjBiRw8iRnvj4OO9X0XoMjy1bCJg0CeORI+Q++CCZ06ahNmrknDPmgt27TUycGMAff5i49dYC3ngjndatHWRnQ3Z22WtdzRefhQvx+/JLMl59lZx27Sr9fuTnaWQMm4pZCeWWNY+QnZ1c7pkAP/zgydatwURFpZOTk0tODjQ6ehSzzUZG27bkV3L/334L4v4gIE2tNO6MDBPQmPT0LJKT8yu8piqu5m21BTgyMrLGDxfCHdR37hrOnMHy8cdY1qzBdPw4jpAQskeMIPfxx3HUootD05ynAa9aZeHrr72x2RS6di1g0qRM7rorHw8PCAnxrLB+GZKS8Js+HcumTdhbtSJ53ToKe/Rw+dnZ2Qpz5/qybJmVoCCV995L48EHK944pyY8tm7FNyqKvPvuI+fZSvZnKPLpM1sZn7uVXwfPpVV7jwqvUVV4800/WrWy079/bsnfKzt2AGALD6/0/nFxZp5tAkqq5vxmV/DFXRB9wEJcijy2bsW6ahVe33yDYrNR0LUrmZMmkX/33ZQ996ZmMjPPLpjYv9+Mn5/K4MHOBRPt2lUzy0BVsaxejd8bb6Dk55M1dixZI0ZUOrf2XJoG337rRWSkP4mJBgYOzGXSpMwyMyjOl+H0aQKHDcPeqhXpc+dW2f+94WNPbv95Bkn+rWk1/eFKr/viC2/+/NPMggVpZaYtK3/8UeUA3OnTBk6fNtK4owZ/cmEX4G3btrF8+XIyMzOJioqiVatWTJkypa5iE6Le1CZ3Qx5+GNXfn5zBg8kdPBh727a1iiUuzsyqVRY++8ybvDwD11xTyLx5aTzwQP7ZU3yrYNqzh4AJE/D44w8KbrmF9DfewFGDaXUnThh55RV/fvjBiw4dbCxenMoNN1SxcU5NFG+yk51N2vr1aD6V96fu3Wti18RvGUMcyTMWVLogxGaDOXN86dDBxv33lx2cU3bsoDA8vNIiX3wEUZNmRd9XVT1bbUvfR7kABuFuvPFGbrzxxrqKRYgGU5vcTXvrLfLvvx+t9A7gNZSXp/D5515ER1vZtcu5YOLBB/MYPDi30uWx51JycvCdNw/rhx+iBgaS9u675PXtW6ONcz780Mq8eb4AREZm8MwzOa4uhHOJX1QUnr/9Rtp772G/4opKr8vMVBj2rC/fq9PIa9+Rwgfvr/Tajz+2cOSIiZUrU8rWzvx8lD17sA0dWul74+I8MBg0Gjct+otKmrgXRAtYiEtR3qOPnvd7DxwwsWqVhX/9y0JGhoH27W3MmJHBQw/lVrpPbkWUzz+n8ejRGE+dIqd445wazCn+/XczEycG8OefZu64I4/XX88kLKzqY+Nryuubb/BZtIicwYOdvxgqoWkwdmwAtx/7iMu1g6RMWVlhqxScC0Hmz/flhhsK6d277H4T5j//RLHbq+3/bdvWjtmz6JeUFGAhLm6Fhc7+1VWrrGzd6onZrHHPPc7W7k03FdZogMuYkIDfK69g/v5758Y5ixZhq8GMjrQ0hTfe8GPNGiuhoXaWLUstt6F5XTAePkzAiy9SeM01ZLz6apXXLlli5advNBJ9plPQoQsFvXtXeu1HH1lJTDSyYEFaue+bOa5oBVwVBTg+3kz37gUlFVbRtApPspMCLMQF7sQJI6tXW/j4Ywtnzhhp0cLOpEnOBRPFR6+7zGbDumyZc+McTcM+axZnHnusRhvnfPKJN9On+5GebmDIkGzGj8/Caq39INu5lLw8gp57DoxG0pYsqXInt99+82DWLD+WXPkGfvsSSZ60sNIulMxMhfff96Vnz/wKd0Mzx8ejBQVVOgMlMdE5ABcebkOzVV1hz+6GVsUXWgekAAtRhxwO+M9/PFm1ysrmzZ4oCvTuXcDgwencdltBZf+yrpJ5xw4CJkzA/Oef5EdEkDFzJoHXXOPyvOIDB4xMnhzAL794cu21haxdm8JVV9Vs7waXaRr+kydj2reP1FWrqpyOl5RkYNiwQDo1T+XJU3PJ79mz/CGcpSxe7EN6uoEJE7IqfN0jNhbtuuuqHYALD7fBzqq7IM7uhubGg3BCCKekJAMff2xhzRoLJ06YaNzYwahR2QwcmHvefatKejp+b7yBZc0a1KZNSf3wQ+fGOS72WeTnw4IFvrz/vg9eXhqzZqUzaFDuef0ScJVl3TosGzaQNWYMBb16VXqd3Q7DhweSmanw2+0zMa5JI3XChEqvT0428MEHVu67L6/CU4zJz8f011+o995b6T2KB+A6dbLBLtdawNIFIYSb0jT49VcPoqOtfPONF3a7wi23FBAZmcmdd+af/2wCTcN70yb8XnsNQ1oaOc8+S9b48VVO4TrXli0eTJ4cwOHDJvr0yWXatMwK94moS6bdu/F/5RXy//EPssaOrfLaN9/0ZetWT5bM+IvL3lhC3n33Vbl95Lvv+lBQoPDSS5kVvl48AKdWsZF8XJyZdu3szv2Kq6mwUoCFcFPp6Qr/+peF6GgLBw6YCQhQefLJHAYNyqFt29rNJDAePEjA5Ml4/t//OTfOWbMG+1VXufz+M2cMvPaaH5s2WWjVys66dcn06HF+G+fUhJKeTtBzz6EGBZH+3ntVbrLz3XdeLFzoy+OP5/DYkdkoBQVkVrEr2okTRqKjrfTrl0ubNhV/f82xsQBo115b4eua5hyA69HDOXNCk0E4IS5M11/fhPx8A9deW8hbb6Vx//151GJKsFN+Pj4LF+L73ntoXl6kz5xJ7qBBVRay0lQVVq+28MYbfuTnK7z4YhYjR2a5uhCudlSVwDFjMJ46RfInn6AGB1d66ZEjRsaMCSA8vJCZQ/ZgjYgm99FHq1w48tZbvigKvPhixX2/4ByAcwQGQsuWkJJS7vXERANJScazc6wV16ahySCcEG7moYfyGDw4p84Gsjz++18CJk/GdOgQuQ88QOarr6I2buzy+/fscW6cs3OnB7fcUsCsWem1bonXhGHuXDx++IGMGTOqPEsuLw+eey4IgwGWLk0j5O23QFHIGjOm0vf8/beJjRu9eeaZnCoP+PSIi8PWuTOGSvrH4+OLB+CK/jVQTRNXBuGEcFOzZ2fUyX0MZ844N8759FPsrVqRsnYtBf/4h8vvz8lRmDfPlw8/tBIQoPLOO2k89FDtN86pCY9ffsE4bRp5999PzlNPVXntK6/4s3evmVWrUrg8fx/eGzeS8+yzqFUchTR7ti/e3hovvFDBdmjF8vIw7d9Pfu/eVDbhrXgAruSXpvQBC3GJUlUsa9fiN2sWSm4uWWPGkDVyJDXpx/jiC4XRoxtx8qSJgQNzmDQpk8DAev738jkMiYkEDh8O7dpVu8nOxx978/HHVkaPzqJ37wJ8n5uN5u1N9siRlb4nNtbM11978+KLWQQHV14JzX/+ieJwYAsPr7QAx8aaad/efnZvDSnAQlx6THv3EjBxIh47dlDQtSsZUVE12swnIcFIZKQf331n5sorbSxcmEyXLvU/yFaOzUbg0KEoubnYYmKqPNpo924TU6YEcOutBc4j42Nj8f76a7LGjq2yvzgqypfAQEfRUUOVK1kBV8kZcMUDcLfddnbpculBuIpIARbiIqLk5uL71ltYly5F9fcnbf588h5+2OU5vXa7c+OcuXOdG+fMnGln4MAzdbpxTk34zZqF5/btpC1YgLVDh0oXhWRkKAwZEkRAgMrChWkYjeAbFYUjMLDKY+N/+cWDLVucRw35+lbdsveIi8MRFISjkk3QExMNnDljpHPnUr+oZBBOiEuD5/ff4//KK5gSEsh57DEyJ01CCwpy+f07djg3ztm710xERD4zZ2ZwzTWB53PARp3w+ve/8Vm6lOynniKvTx8qa/uqKowZE0BCgpFPPkkmOFjF45df8NqyhYypU9F8fSt8n6ZBVJQfTZs6eOKJnGrjMcfFOfd/qHQFnHOP5jILOGQQToiLmyEhAf+pU/H+9ltsV1xB8qZNFNZgC8z0dIWoKD9Wr7bQpInKhx86N85pyEG2cxkPHiRg3DgKr72WzKlTq7x20SIfvv/em+nTM5z7C2saflFROJo1I+eJJyp93w8/eLJzpwezZ6dX3y2el4fpr7/Iv/32Si+JizMXrYArNWtF+oCFuEjZ7c6Nc+bOBVUlc/Jk5z+3a7BxzqZN3rz2mh+pqQaeeSaHl17KwsenYQfZzqXk5hI0ZAia2ezcZKeK0z9+/dWDqChf7rsvj6efdrZivb7/Ho+dO0mfM6fSkzocjrNHDfXrl1vhNaWZ9+4tGYCrTFycmSuusJfd3F4KsBAXH/POnc6Nc/buJb9XLzJmzar0eJyKHDrk3Djnv/91bpyzZk09bpxTE5qG/8SJmPbvJ3XNGhxVTB07fdrA8OGBXH65nblz050tdocD3zffxH755eT261fpez/7zJt9+8wsXJjq0u8rc3w8UPkWlJrmLMC9epXdO1gG4YS4iCgZGfhFRWGJjkZt0oTUpUvJv+celwfZCgpgwQIf3n/fFw8PjZkznRvnuLgQrt5ZVq/G8sknZI4bV+VcZZsNhg0LJDtbYf36tJJWu/dnn2Hev5/UhQvBVHHZKSyEefN86djRxn33ubZHsUdsLI7g4EoH4E6dMpCcbDy7AKOYDMIJcRHQNLw//xy/V1/FkJJCztNPk/XyyzXaOOf//s+DSZMCOHTIxP335/Hqqxk0aVLPTa8aMMfG4j91Kvk9e5Jdxao1cA6e/e9/nrz/fhpXXFHUci8sxHfuXGydOpF/332VvnfdOgtHj5pYtSrF5R3bzPHxVQ7Axcc7u0nKHfNU7SBc8csyCCeEWzIePoz/5Ml4bdlCYefOpEZHV7mj17mSk50b53z6qYXLLrOzZk1Kmbmq7kBJTSVwyBAcjRqR9u67lR4VBPD1114sXuzDE0/k8OCDZw/LtKxdi+nYMVKio6s4akjhnXd8ufHGgnLdBZXG5sIAXGysGaNRo2PHmhVg5yWadEEI4XYKCs5unOPhQfrrr5M7eHCNNs5Zt87CzJl+5OYqjB6dxQsvZNV+Q5+6pqoEjh6N8fRpkjdtqnLq3KFDRsaODeDaawuZNu3sUm0lNxffd96h4KabKOjZs9L3L19u5fRpI4sWlT9qqDKmPXuqHYCLjy9eAXfOCy4VYOkDFsLtNLr9dswHD5J3331kvPYaapMmLr/3zz+dG+f8/rsHXbsWEBWVQdu2bjDIVgGfd9/Fa/Nm0mfNwlbJNo8AubkwZEgQJpPGkiVpZU4gsi5fjjEpyTlropLKmpGhsHChD7165XPTTa6v6isegCusYgAuNtZc7vBOqH4QDpwFWPqAhXAzis1GyurVVbbozpWbq/D22z4sWeKDv7/K22+n8cgjDbtxTk14bNmC79y55D74oLN1XwlNg1GjjOzbZ2D16tQyp38oGRn4LFxIfq9eVc5/PnvUUMWbrVcaY1wcjuBg1EoG4E6eNJCScs4KuJLgqh6EA2kBC+GWkjZvrtHGOd9/78krr/iTkGBiwIAcJk/OJChI3zm9VTGcPEngiBHY27cnY/bsKmdyrF1rITrayNixWeX6r30WLcKQkUFmFUcNnTlj4MMPrdx/f16Np9uZi7agrPEAHLjUBaEomgzCCeF2XCy+CQkGpk3z55tvvLniChuffppco39i66KwkKChQ1EKCkhbuhTNYqn00vh4M5GR/kREqIwZU3azdENSEtYPPyT3gQeqPNGjuqOGKlMyAHfnnZVeUzwA16HD+RVgaQELcQGy252DSnPn+uJwwKRJmTz/fLZuG+fUhN/rr+OxYwepixdXuUtbWprCc88FEhzsYOXK8lXK5913UQoLyRo/vtJ7HD/uPGqof/9cWreu2Qbypj17UFT1/AbgQAqwEBejP/4wM2FCAHv2mOnVy7lxTsuWDXc6RW14ffEFPsuWkf3MM1XO11VVGD06kMREI59+mkxIiH+ZjYGMx45hXb2a3P79cbRuXel95s3zxWCo+qihyngUbUFZ1QBcXJyZ22+veEGHVtRtcUEPwkVHR7Njxw5MJhNNmjRh+PDhWKvYF1QId1HXuZuR4dw4JzrauXHOkiWp/POf+m6cUxOmAwcIGD+ewuuvJ/OVV6q89v33ffjxRy9efz2d664r/89737feAoOhyqOG/vrLxCefePPcczk0a1bzZqY5Lg5HSAhqs2YVvn7ypJGUFGPFR9iDi33A9d8CdnG9ScXCw8OZN28ec+fOpVmzZmzatKmu4hKiXtVV7moafP65F7fd1pjVqy08/XQOP/2UxL33XjjFV8nJIfC559A8PUldvLjKTXb++18P5szx5YEHcnnyyfKb5Zj++gvvTz4h58knK52dADBnji8Wi8bIkVVvtl6Z6lbAxcUVnwF3/gXYuRCjfn+ItSrAnTt3xlg0+bx9+/akpqbWSVBC1Le6yN3Dh40MHBjE8OFBNGvm4Ouvk5k+PbPaDcTdiqbhP2ECpr//Jm3BgiqL5qlTBkaMCKRNGztz5mRUWPt8Z89Gs1iqPGpo1y7nUUNDh2YTFFTzJmbxAFxV/b9VDsCB2/QBK5pWN70cUVFRdOvWjR49elT4ekxMDDExMSXXCuEuJHeFXqotwDNmzCA9Pb3c3/fv358uXboA8Omnn3Lw4EHGjx+P4sK/uyZOnOg2iewusbhLHHDxxHIx5667xAESS23iqHYQLjIyssrXf/rpJ3bs2MHUqVNdSmAhGorkrnB3teoD3rVrF59//jkTJkzA07OyA6GFcD+Su8Id1Goa2rJly7Db7cyYMQOAdu3aMaSKk06LRURE1OaxdcpdYnGXOODSiOVCz113iQMkloq4GkedDcIJIYSomVp1QQghhDh/UoCFEEInuu0F4S7LmLdu3crGjRtJSEhg1qxZtGnTpsFj2LVrFytWrEBVVXr37k2fPn0aPAaAhQsXsnPnTvz9/Zk3b54uMQAkJyezYMEC0tPTURSFiIgI7rnnHt3iKc1d8hb0z113yVu4gHNX08muXbs0u92uaZqmRUdHa9HR0brEcfz4cS0hIUGbNm2aduDAgQZ/vsPh0EaOHKklJiZqNptNGz9+vHb8+PEGj0PTNG3Pnj3awYMHtbFjx+ry/GKpqanawYMHNU3TtNzcXG3UqFG6fU/O5S55q2n65q475a2mXbi5q1sXhLssY27evDmhVSy/rG8HDhygadOmNGnSBJPJRLdu3di+fbsusXTs2BGfGpzmW18CAwNpXbSLlre3N2FhYW6zzN1d8hb0zV13ylu4cHPXLfqAN2/ezDXXXKN3GLpITU0lODi45PPg4GC3KTbuICkpicOHD9O2ir1p9SJ5K3lbFVdyt177gF1dCmo0GunevbuucehFq2AWoKzKcsrPz2fevHk8+eSTWKo4maGuuUveuhqLHiRvq+Zq7tZrAXaXpaDVxaGn4OBgUlJSSj5PSUkhMDBQx4jcg91uZ968eXTv3p2bbrqpQZ/tLnnrSix6kbytXE1yV7cuCFkK6tSmTRtOnTpFUlISdrudX3/9lRtuuEHvsHSlaRqLFy8mLCyMe++9V+9wypC8dZK8rVhNc1e3lXAvvPACdru9pOPc1aWgdW3btm0sX76czMxMrFYrrVq1YsqUKQ0aw86dO1m5ciWqqtKzZ0/69u3boM8vNn/+fPbu3UtWVhb+/v7069ePXr16NXgc+/btY+rUqbRs2bKkhTlgwACuu+66Bo/lXO6St6B/7rpL3sKFm7uyFFkIIXTiFrMghBDiUiQFWAghdCIFWAghdCIFWAghdCIFWAghdCIFWAghdCIFWAghdPL/QPs0t2zEAPMAAAAASUVORK5CYII=\n", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "plt.style.use(\"ggplot\")\n", + "\n", + "times = np.linspace(1,len(computed_coeff)/10,4).astype(int)\n", + "\n", + "plt.figure(figsize=(5,5))\n", + "pts = np.linspace(-2,2,100)\n", + "\n", + "\"\"\"\n", + "this needs tydy up badly...\n", + "\"\"\"\n", + "\n", + "plt.subplot(2, 2, 1)\n", + "c1 = computed_coeff[times[0]][0]\n", + "c2 = computed_coeff[times[0]][1]\n", + "for idx in range(c.shape[1]):\n", + " #low\n", + " coeff = c1[:,idx]\n", + " y = []\n", + "\n", + " for x in pts:\n", + " y.append((-coeff[0]*x+coeff[2])/coeff[1])\n", + " \n", + " plt.plot(pts,y,\"b-\")\n", + " \n", + " #high\n", + " coeff = c2[:,idx]\n", + " y = []\n", + "\n", + " for x in pts:\n", + " y.append((-coeff[0]*x+coeff[2])/coeff[1])\n", + " \n", + " plt.plot(pts,y,\"r-\")\n", + " plt.xlim((-2, 2))\n", + " plt.ylim((-2, 2))\n", + "\n", + "\n", + "plt.subplot(2, 2, 2)\n", + "c1 = computed_coeff[times[1]][0]\n", + "c2 = computed_coeff[times[1]][1]\n", + "for idx in range(c.shape[1]):\n", + " #low\n", + " coeff = c1[:,idx]\n", + " y = []\n", + " for x in pts:\n", + " y.append((-coeff[0]*x+coeff[2])/coeff[1])\n", + " \n", + " plt.plot(pts,y,\"b-\")\n", + " \n", + " #high\n", + " coeff = c2[:,idx]\n", + " y = []\n", + " for x in pts:\n", + " y.append((-coeff[0]*x+coeff[2])/coeff[1])\n", + " \n", + " plt.plot(pts,y,\"r-\")\n", + " plt.xlim((-2, 2))\n", + " plt.ylim((-2, 2))\n", + "\n", + "\n", + "plt.subplot(2, 2, 3)\n", + "c1 = computed_coeff[times[2]][0]\n", + "c2 = computed_coeff[times[2]][1]\n", + "for idx in range(c.shape[1]):\n", + " #low\n", + " coeff = c1[:,idx]\n", + " y = []\n", + "\n", + " for x in pts:\n", + " y.append((-coeff[0]*x+coeff[2])/coeff[1])\n", + " \n", + " plt.plot(pts,y,\"b-\")\n", + " \n", + " #high\n", + " coeff = c2[:,idx]\n", + " y = []\n", + " for x in pts:\n", + " y.append((-coeff[0]*x+coeff[2])/coeff[1])\n", + " \n", + " plt.plot(pts,y,\"r-\")\n", + " plt.xlim((-2, 2))\n", + " plt.ylim((-2, 2))\n", + "\n", + "plt.subplot(2, 2, 4)\n", + "c1 = computed_coeff[times[3]][0]\n", + "c2 = computed_coeff[times[3]][1]\n", + "for idx in range(c.shape[1]):\n", + " #low\n", + " coeff = c1[:,idx]\n", + " y = []\n", + "\n", + " for x in pts:\n", + " y.append((-coeff[0]*x+coeff[2])/coeff[1])\n", + " \n", + " plt.plot(pts,y,\"b-\")\n", + " \n", + " #high\n", + " coeff = c2[:,idx]\n", + " y = []\n", + " for x in pts:\n", + " y.append((-coeff[0]*x+coeff[2])/coeff[1])\n", + " \n", + " plt.plot(pts,y,\"r-\")\n", + " plt.xlim((-2, 2))\n", + " plt.ylim((-2, 2))\n", + "\n", + "plt.tight_layout()\n", + "plt.show()" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python [conda env:.conda-jupyter] *", + "language": "python", + "name": "conda-env-.conda-jupyter-py" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.8.5" + } + }, + "nbformat": 4, + "nbformat_minor": 4 +} diff --git a/notebooks/MPC_racecar_tracking.ipynb b/notebooks/MPC_racecar_tracking.ipynb deleted file mode 100644 index cf8e429..0000000 --- a/notebooks/MPC_racecar_tracking.ipynb +++ /dev/null @@ -1,2450 +0,0 @@ -{ - "cells": [ - { - "cell_type": "code", - "execution_count": 1, - "metadata": {}, - "outputs": [], - "source": [ - "import numpy as np\n", - "from scipy.integrate import odeint\n", - "from scipy.interpolate import interp1d\n", - "import cvxpy as cp\n", - "\n", - "import matplotlib.pyplot as plt\n", - "plt.style.use(\"ggplot\")\n", - "\n", - "import time" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### kinematics model equations\n", - "\n", - "The variables of the model are:\n", - "\n", - "* $x$ coordinate of the robot\n", - "* $y$ coordinate of the robot\n", - "* $v$ velocity of the robot\n", - "* $\\theta$ heading of the robot\n", - "\n", - "The inputs of the model are:\n", - "\n", - "* $a$ acceleration of the robot\n", - "* $\\delta$ steering of the robot\n", - "\n", - "These are the differential equations f(x,u) of the model:\n", - "\n", - "$\\dot{x} = f(x,u)$\n", - "\n", - "* $\\dot{x} = v\\cos{\\theta}$ \n", - "* $\\dot{y} = v\\sin{\\theta}$\n", - "* $\\dot{v} = a$\n", - "* $\\dot{\\theta} = \\frac{v\\tan{\\delta}}{L}$\n", - "\n", - "Discretize with forward Euler Integration for time step dt:\n", - "\n", - "${x_{t+1}} = x_{t} + f(x,u)dt$\n", - "\n", - "* ${x_{t+1}} = x_{t} + v_t\\cos{\\theta}dt$\n", - "* ${y_{t+1}} = y_{t} + v_t\\sin{\\theta}dt$\n", - "* ${v_{t+1}} = v_{t} + a_tdt$\n", - "* ${\\theta_{t+1}} = \\theta_{t} + \\frac{v\\tan{\\delta}}{L} dt$\n", - "\n", - "----------------------\n", - "\n", - "The Model is **non-linear** and **time variant**, but the Numerical Optimizer requires a Linear sets of equations. To approximate the equivalent **LTI** State space model, the **Taylor's series expansion** is used around $\\bar{x}$ and $\\bar{u}$ (at each time step):\n", - "\n", - "$ f(x,u) \\approx f(\\bar{x},\\bar{u}) + \\frac{\\partial f(x,u)}{\\partial x}|_{x=\\bar{x},u=\\bar{u}}(x-\\bar{x}) + \\frac{\\partial f(x,u)}{\\partial u}|_{x=\\bar{x},u=\\bar{u}}(u-\\bar{u})$\n", - "\n", - "This can be rewritten usibg the State Space model form Ax+Bu :\n", - "\n", - "$ f(\\bar{x},\\bar{u}) + A|_{x=\\bar{x},u=\\bar{u}}(x-\\bar{x}) + B|_{x=\\bar{x},u=\\bar{u}}(u-\\bar{u})$\n", - "\n", - "Where:\n", - "\n", - "$\n", - "A =\n", - "\\quad\n", - "\\begin{bmatrix}\n", - "\\frac{\\partial f(x,u)}{\\partial x} & \\frac{\\partial f(x,u)}{\\partial y} & \\frac{\\partial f(x,u)}{\\partial v} & \\frac{\\partial f(x,u)}{\\partial \\theta} \\\\\n", - "\\end{bmatrix}\n", - "\\quad\n", - "=\n", - "\\displaystyle \\left[\\begin{matrix}0 & 0 & \\cos{\\left(\\theta \\right)} & - v \\sin{\\left(\\theta \\right)}\\\\0 & 0 & \\sin{\\left(\\theta \\right)} & v \\cos{\\left(\\theta \\right)}\\\\0 & 0 & 0 & 0\\\\0 & 0 & \\frac{\\tan{\\left(\\delta \\right)}}{L} & 0\\end{matrix}\\right]\n", - "$\n", - "\n", - "and\n", - "\n", - "$\n", - "B = \n", - "\\quad\n", - "\\begin{bmatrix}\n", - "\\frac{\\partial f(x,u)}{\\partial a} & \\frac{\\partial f(x,u)}{\\partial \\delta} \\\\\n", - "\\end{bmatrix}\n", - "\\quad\n", - "= \n", - "\\displaystyle \\left[\\begin{matrix}0 & 0\\\\0 & 0\\\\1 & 0\\\\0 & \\frac{v \\left(\\tan^{2}{\\left(\\delta \\right)} + 1\\right)}{L}\\end{matrix}\\right]\n", - "$\n", - "\n", - "are the *Jacobians*.\n", - "\n", - "\n", - "\n", - "So the discretized model is given by:\n", - "\n", - "$ x_{t+1} = x_t + (f(\\bar{x},\\bar{u}) + A|_{x=\\bar{x}}(x_t-\\bar{x}) + B|_{u=\\bar{u}}(u_t-\\bar{u}) )dt $\n", - "\n", - "$ x_{t+1} = (I+dtA)x_t + dtBu_t +dt(f(\\bar{x},\\bar{u}) - A\\bar{x} - B\\bar{u}))$\n", - "\n", - "The LTI-equivalent kinematics model is:\n", - "\n", - "$ x_{t+1} = A'x_t + B' u_t + C' $\n", - "\n", - "with:\n", - "\n", - "$ A' = I+dtA|_{x=\\bar{x},u=\\bar{u}} $\n", - "\n", - "$ B' = dtB|_{x=\\bar{x},u=\\bar{u}} $\n", - "\n", - "$ C' = dt(f(\\bar{x},\\bar{u}) - A|_{x=\\bar{x},u=\\bar{u}}\\bar{x} - B|_{x=\\bar{x},u=\\bar{u}}\\bar{u}) $" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "-----------------\n", - "[About Taylor Series Expansion](https://courses.engr.illinois.edu/ece486/fa2017/documents/lecture_notes/state_space_p2.pdf):\n", - "\n", - "In order to linearize general nonlinear systems, we will use the Taylor Series expansion of functions.\n", - "\n", - "Typically it is possible to assume that the system is operating about some nominal\n", - "state solution $\\bar{x}$ (possibly requires a nominal input $\\bar{u}$) called **equilibrium point**.\n", - "\n", - "Recall that the Taylor Series expansion of f(x) around the\n", - "point $\\bar{x}$ is given by:\n", - "\n", - "$f(x)=f(\\bar{x}) + \\frac{df(x)}{dx}|_{x=\\bar{x}}(x-\\bar{x})$ + higher order terms...\n", - "\n", - "For x sufficiently close to $\\bar{x}$, these higher order terms will be very close to zero, and so we can drop them.\n", - "\n", - "The extension to functions of multiple states and inputs is very similar to the above procedure.Suppose the evolution of state x\n", - "is given by:\n", - "\n", - "$\\dot{x} = f(x1, x2, . . . , xn, u1, u2, . . . , um) = Ax+Bu$\n", - "\n", - "Where:\n", - "\n", - "$ A =\n", - "\\quad\n", - "\\begin{bmatrix}\n", - "\\frac{\\partial f(x,u)}{\\partial x1} & ... & \\frac{\\partial f(x,u)}{\\partial xn} \\\\\n", - "\\end{bmatrix}\n", - "\\quad\n", - "$ and $ B = \\quad\n", - "\\begin{bmatrix}\n", - "\\frac{\\partial f(x,u)}{\\partial u1} & ... & \\frac{\\partial f(x,u)}{\\partial um} \\\\\n", - "\\end{bmatrix}\n", - "\\quad $\n", - "\n", - "Then:\n", - "\n", - "$f(x,u)=f(\\bar{x},\\bar{u}) + \\frac{df(x,u)}{dx}|_{x=\\bar{x}}(x-\\bar{x}) + \\frac{df(x,u)}{du}|_{u=\\bar{u}}(u-\\bar{u}) = f(\\bar{x},\\bar{u}) + A_{x=\\bar{x}}(x-\\bar{x}) + B_{u=\\bar{u}}(u-\\bar{u})$\n", - "\n", - "-----------------" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Kinematics Model" - ] - }, - { - "cell_type": "code", - "execution_count": 2, - "metadata": {}, - "outputs": [], - "source": [ - "\"\"\"\n", - "Control problem statement.\n", - "\"\"\"\n", - "\n", - "N = 4 #number of state variables\n", - "M = 2 #number of control variables\n", - "T = 20 #Prediction Horizon\n", - "DT = 0.2 #discretization step" - ] - }, - { - "cell_type": "code", - "execution_count": 3, - "metadata": {}, - "outputs": [], - "source": [ - "def get_linear_model(x_bar,u_bar):\n", - " \"\"\"\n", - " Computes the LTI approximated state space model x' = Ax + Bu + C\n", - " \"\"\"\n", - " \n", - " L=0.3 #vehicle wheelbase\n", - " \n", - " x = x_bar[0]\n", - " y = x_bar[1]\n", - " v = x_bar[2]\n", - " theta = x_bar[3]\n", - " \n", - " a = u_bar[0]\n", - " delta = u_bar[1]\n", - " \n", - " A = np.zeros((N,N))\n", - " A[0,2]=np.cos(theta)\n", - " A[0,3]=-v*np.sin(theta)\n", - " A[1,2]=np.sin(theta)\n", - " A[1,3]=v*np.cos(theta)\n", - " A[3,2]=v*np.tan(delta)/L\n", - " A_lin=np.eye(N)+DT*A\n", - " \n", - " B = np.zeros((N,M))\n", - " B[2,0]=1\n", - " B[3,1]=v/(L*np.cos(delta)**2)\n", - " B_lin=DT*B\n", - " \n", - " f_xu=np.array([v*np.cos(theta), v*np.sin(theta), a,v*np.tan(delta)/L]).reshape(N,1)\n", - " C_lin = DT*(f_xu - np.dot(A,x_bar.reshape(N,1)) - np.dot(B,u_bar.reshape(M,1)))\n", - " \n", - " return np.round(A_lin,4), np.round(B_lin,4), np.round(C_lin,4)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Motion Prediction: using scipy intergration" - ] - }, - { - "cell_type": "code", - "execution_count": 4, - "metadata": {}, - "outputs": [], - "source": [ - "# Define process model\n", - "# This uses the continuous model \n", - "def kinematics_model(x,t,u):\n", - " \"\"\"\n", - " Returns the set of ODE of the vehicle model.\n", - " \"\"\"\n", - " \n", - " L=0.3 #vehicle wheelbase\n", - " dxdt = x[2]*np.cos(x[3])\n", - " dydt = x[2]*np.sin(x[3])\n", - " dvdt = u[0]\n", - " dthetadt = x[2]*np.tan(u[1])/L\n", - "\n", - " dqdt = [dxdt,\n", - " dydt,\n", - " dvdt,\n", - " dthetadt]\n", - "\n", - " return dqdt\n", - "\n", - "def predict(x0,u):\n", - " \"\"\"\n", - " \"\"\"\n", - " \n", - " x_ = np.zeros((N,T+1))\n", - " \n", - " x_[:,0] = x0\n", - " \n", - " # solve ODE\n", - " for t in range(1,T+1):\n", - "\n", - " tspan = [0,DT]\n", - " x_next = odeint(kinematics_model,\n", - " x0,\n", - " tspan,\n", - " args=(u[:,t-1],))\n", - "\n", - " x0 = x_next[1]\n", - " x_[:,t]=x_next[1]\n", - " \n", - " return x_" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Validate the model, here the status w.r.t a straight line with constant heading 0" - ] - }, - { - "cell_type": "code", - "execution_count": 5, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "CPU times: user 3.39 ms, sys: 0 ns, total: 3.39 ms\n", - "Wall time: 2.79 ms\n" - ] - } - ], - "source": [ - "%%time\n", - "\n", - "u_bar = np.zeros((M,T))\n", - "u_bar[0,:] = 0.2 #m/ss\n", - "u_bar[1,:] = np.radians(-np.pi/4) #rad\n", - "\n", - "x0 = np.zeros(N)\n", - "x0[0] = 0\n", - "x0[1] = 1\n", - "x0[2] = 0\n", - "x0[3] = np.radians(0)\n", - "\n", - "x_bar=predict(x0,u_bar)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Check the model prediction" - ] - }, - { - "cell_type": "code", - "execution_count": 6, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "#plot trajectory\n", - "plt.subplot(2, 2, 1)\n", - "plt.plot(x_bar[0,:],x_bar[1,:])\n", - "plt.plot(np.linspace(0,10,T+1),np.zeros(T+1),\"b-\")\n", - "plt.axis('equal')\n", - "plt.ylabel('y')\n", - "plt.xlabel('x')\n", - "\n", - "plt.subplot(2, 2, 2)\n", - "plt.plot(np.degrees(x_bar[2,:]))\n", - "plt.ylabel('theta(t) [deg]')\n", - "#plt.xlabel('time')\n", - "\n", - "\n", - "plt.tight_layout()\n", - "plt.show()" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Motion Prediction: using the state space model" - ] - }, - { - "cell_type": "code", - "execution_count": 7, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "CPU times: user 2.71 ms, sys: 0 ns, total: 2.71 ms\n", - "Wall time: 1.82 ms\n" - ] - } - ], - "source": [ - "%%time\n", - "\n", - "u_bar = np.zeros((M,T))\n", - "u_bar[0,:] = 0.2 #m/s\n", - "u_bar[1,:] = np.radians(-np.pi/4) #rad\n", - "\n", - "x0 = np.zeros(N)\n", - "x0[0] = 0\n", - "x0[1] = 1\n", - "x0[2] = 0\n", - "x0[3] = np.radians(0)\n", - "\n", - "x_bar=np.zeros((N,T+1))\n", - "x_bar[:,0]=x0\n", - "\n", - "for t in range (1,T+1):\n", - " xt=x_bar[:,t-1].reshape(N,1)\n", - " ut=u_bar[:,t-1].reshape(M,1)\n", - " \n", - " A,B,C=get_linear_model(xt,ut)\n", - " \n", - " xt_plus_one = np.dot(A,xt)+np.dot(B,ut)+C\n", - " \n", - " x_bar[:,t]= np.squeeze(xt_plus_one)" - ] - }, - { - "cell_type": "code", - "execution_count": 8, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "iVBORw0KGgoAAAANSUhEUgAAAagAAACdCAYAAADhcuxqAAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjMuMSwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy/d3fzzAAAACXBIWXMAAAsTAAALEwEAmpwYAAAeUklEQVR4nO3deXxU9b3/8df3JCELIQtJhBIMsopQUJA0isSoBKpANW0tsgoGpRgBgVYL/SmFi1G0prHIWg0IWCxYFmtLrUXKUi0aVlmubAWlsoTsZINkzvf3x1xy4SaBScjMOTP5PB8PHiZzTibvOZ7Me86ZOd+v0lprhBBCCJsxrA4ghBBC1EYKSgghhC1JQQkhhLAlKSghhBC2JAUlhBDClqSghBBC2JKtCso0TZ5//nnmzp1rdRQhhBAW87c6wJU2btxIbGws5eXlLq1/+vTpWm+Pjo4mNze3MaPdMLtlkjzXd61Mbdq08XAa9/OWvye75QH7ZfK2PHX9PdnmCCovL4/du3fTv39/q6MIIYSwAdscQb3zzjuMGjXqmkdPmzZtYtOmTQDMnTuX6OjoWtfz9/evc5lV7JZJ8lyfHTMJ4W30pYtU/GsLdP5uvX/WFgW1a9cuwsPD6dChAwcPHqxzveTkZJKTk6u/r+uQ0W6Ht2C/TJLn+praKT4hGps+cRRzaSZF577F+K8FqNZt6/Xztiiow4cPs3PnTvbs2cOlS5coLy9n3rx5TJ482epoQggh6klXVaL/sga98X0Ib0nEr97gQj3LCWxSUCNGjGDEiBEAHDx4kA8//FDKSQghvJD+9mvMpZnwzb9Rd9+PGvYUgXG3cKEBZ0hsUVBCCCG8mzYd6L9/gN7wLgQ3x0j7JarXXTd0n7YrqO7du9O9e3erYwghhHCRPn8Wc+kbcOwQ9LoLY1QaKizihu/XdgUlhBDCO2it0Vs/Qv9xGRh+qNSpqLvuQynVKPcvBSWEEKLedEEe5vJ5cHAPdLsDY8wkVMuYRv0dUlBCCCFcprVGf74V/d4SqKpCjZiAuu+hRjtqupIUlBBCCJfoC0WY7y6C3Z9Bx64YqVNQN7nvmkApKCGEENel9+7AXLEAyktRPx6DGpiCMvzc+juloITwYqZpMn36dFq2bMn06dMpKSkhMzOT8+fPExMTw9SpUwkNDbU6pvBiuqwU/Ye30P/aDDe3x5g2B9X2Fo/8btsMFiuEqL/LMwBctmHDBnr06MG8efPo0aMHGzZssC6c8Hr6v/dhzp6E/nwLavBQjF++7rFyAikoIbxWbTMAZGdnk5SUBEBSUhLZ2dlWxRNeTF+8iLlqCeZvXoRmgRjTX8NIGYXyD/BoDjnFJ4SXqm0GgKKiIiIjIwGIjIykuLi4zp/31tkB7JYH7JfpRvJcOnyA4t/OwTxzipAhQwkdNQEVGGRJHikoIbyQqzMAXIu3zg5gtzxgv0wNyaMrK9Efvof+aB1ERmH87CUudu3JxQslcKHErXnqmh1ACkoIL1TXDADh4eEUFBQQGRlJQUEBYWFhVkcVXkD/5wRmVib85yTqnmTUY0+igkOsjiUFJYQ3qmsGgJUrV7J161ZSUlLYunUr8fHxFicVdqYdDvTf1qH/9B40D8WY+ALq9u9ZHauaFJQQPiQlJYXMzEw2b95MdHQ006ZNszqSsCl97rRzWox/H0bdeQ9q5NOoFvY64paCEsLLXTkDQIsWLZg5c6bFiYSdadNEb9mIXvsO+DdDPfkz1PfudctQRTdKCkoIIZoInX8e85158N/74Lu9nQO8RkRZHatOUlBCCOHjtNbof21G/+EtME3U6DRU4vdtedR0JSkoIYTwYbq4EHPlAtj7OXTuhvHEFFRMa6tjuUQKSgghfJTe/RnmyoVQUY76yROo5IfdPsBrY5KCEkIIH2OWFGNm/Qa9YwvEdcRInYqKjbM6Vr1JQQkhhA/RB/eQt3I+uiAP9YNhqEFDUf7e+VRvi9S5ubksWLCAwsJClFIkJyczaNAgq2MJIYTX0BXl6LXvoLf8Fb+2t2BMmI66pbPVsW6ILQrKz8+P0aNH06FDB8rLy5k+fTo9e/akbdu2VkcTQgjb08cOYS59A3LPoQY8QtS4KeRduGB1rBtmi4KKjIysHoE5ODiY2NhY8vPzpaCEEOIadOUl9Aer0B+vh5YxGD9LR936XVRgIEhBNb6cnBxOnDhBp06daizz1ukBwH6ZJM/12TGTEJfpb447B3g9/Q0qcSBqaCoqyPoBXhuTrQqqoqKCjIwMxo4dS0hIzQ3trdMDgP0ySZ7ru1amuqYHEMLdtMOB/usf0X/+A4SGY0yeierRx+pYbmGbgqqqqiIjI4PExEQSEhKsjiOEELajz/zHOcDryaOo+ETUyAmo5i2sjuU2tigorTWLFy8mNjaWIUOGWB1HCLcqLi5m27Zt7N69m6+//pqysjJCQkJo164dd9xxB/fdd5/M4ySuok0TvfnP6HUroFkgavzzGPH9rI7ldrYoqMOHD7Nt2zbi4uJ47rnnABg+fDi9e/e2OJkQjWvVqlVs376dXr168cADDxAbG0twcDDl5eV8++23HDp0iF/84hf069ePkSNHWh1X2IDOy8Fc9ls4vB969MF4fCIqoqXVsTzCFgXVtWtX1qxZY3UMIdwuMjKSefPmERAQUGNZ+/bt6devH5cuXWLz5s0WpBN2orVGf7oJvfpt0KDGTHLOdmvzAV4bky0KSoim4qGHHqr+urCwkIiIiBrrlJWV8eCDD3owlbAbXVTgHOB13xdwaw+MsZNR0a2sjuVxhtUBhGiqnn322Vpvnzp1qoeTCDvRO/+JOWsiHNqLeuxJjGlzmmQ5gRxBCWEZrXWN28rKyjAMed3YFOnSC+hVS9BfbINbOjsHeP1O0x6sQApKCA97+umnAbh06VL115eVlJRwzz33WBFLWEjv34W5/E0oKUI9MhL10KMoP++ZFsNdpKCE8LBJkyahteaVV15h0qRJVy2LiIiQi4CbEF1Rhl6zFL39Y4hthzH5RVRcR6tj2YYUlBAe1q1bNwCysrIIDAy0OI2wij5ywPnx8bzzqAd/jHp4BKqWT3c2ZXKyWwgP2rhxI5WVlQB1llNlZSUbN270ZCzhQbryEuaaLMzX/x8ohfH8yxg/HiPlVAs5ghLCgwoLC5k8eTK9evWiW7dutGnThqCgICoqKjh9+jSHDh1iz549JCUlWR1VuIE+edQ5LcaZU6j7BqF+PAYVFGx1LNvyuYIyP1pL7j//jsPhAKX+558BhgF+fuDnD/7+//PfAAgIQDULhGbNICAQAoMgKAgCgyEoGBXSHIJDIDgUQppDTCuUIW9eioYZMWIEQ4YMYcuWLWzevJlvvvmG0tJSQkNDiYuLo1evXgwfPpwWLXx3fLWmSFdVoTeuQf9lDYRFYkyZjerey+pYtudzBUXUTQTc1hOzogK0rv6nHQ4wHeBwgKMKqiqhvBSKK9GVl6DyIly8CBfLoaqq+u7+7weBjd++5ywqIRooLCyMhx9+mIcfftjqKMID9OlvnEdNXx9D3XUfath4VPNQq2N5BZ8rKCM+kfCHfnhDUzfoqiq4WAEV5c4SKyuF8jJ0eQnI4bgQwgXadKA3/Qm9/l0ICsZ4ejqqd1+rY3kVnyuoxqD8/cE/FJqHAjH/e7t1kYQPKisr4/333+fQoUNcuHDhqgt3Fy1aZGEycaP0+bOYy96Ao4fgjgSM0WmosEirY3kd+RSfEBZ5++23OXHiBI8++iglJSWkpqYSHR3N4MGDrY4mGkhrjbntI8zZk+E/J1FPPIuR9ksppwaSIyghLPLll1+SmZlJixYtMAyD+Ph4OnbsyKuvvirzonkhXZiHuXw+HNgFt92OMWYyKirm+j8o6iQFJYRFtNaEhIQAEBQURGlpKREREZw9e9biZKI+tNaUb/sYc8nrUHUJNXw86r5BKBlT8Ya5XFDLly8nKSmJW265xY1xhGg62rVrx6FDh+jRowddu3YlKyuLoKAgvvOd71gdTbhIXyhG/34Rxbs+hQ63YjwxBdU61upYPsPlgnI4HKSnpxMWFkZiYiKJiYlERUW5M5sQPu2nP/1p9QcjUlNTWbVqFaWlpUycONHiZMIVet8XmCvmQ2kJoaMmUNbv+zLAayNzuaBSU1MZO3Yse/bsYfv27axbt47OnTtz7733kpCQQFBQkDtzCuFziouL6dy5M+C8NmrChAkAHDt2zMpY4jp0eRl69VvoTz+BtrdgTJlN817xlN/ApS2idvU6SWoYBnfeeSdTpkwhPT2d4uJiFi5cyFNPPcXixYvJz893V04hfM5LL71U6+3p6ekeTiJcpb/6EnPWJPRn/0A99CjGLzNQN7e3OpbPqteHJMrKytixYwfbt2/n66+/JiEhgXHjxhEdHc2f//xnXn75ZV5//XV3ZRXCJ5imCTjfXL/877Jz587h5+JpotzcXBYsWEBhYSFKKZKTkxk0aBAlJSVkZmZy/vx5YmJimDp1KqGhMnLBjdAXL6LXr0B/8iHc1AbjF3NRHbtaHcvnuVxQGRkZ7Nu3j9tuu40BAwYQHx9PwBWj7z7++OOMHTu2wUH27t3LsmXLME2T/v37k5KS0uD7EsLOhg8fXv31sGHDrlpmGAY//OEPXbofPz8/Ro8eTYcOHSgvL2f69On07NmTLVu20KNHD1JSUtiwYQMbNmxg1KhRjfoYmhJ94gjm0kw4+y3q/sHOAV4D5S0NT3C5oDp37sy4ceOIiIiodblhGLz11lsNCmGaJllZWbzwwgtERUUxY8YM+vTpQ9u2TXu6Y+Gb5s+fj9aaWbNmMXv2bLTWKKVQShEWFkazZs1cup/IyEgiI50XgAYHBxMbG0t+fj7Z2dnMmjULgKSkJGbNmiUF1QC6qhL94Wr0X/8IkS0xps1B3Xa71bGaFJcLypWBLRs6+dqxY8do3bo1rVq1AqBv375kZ2c3qKBmzgzj6FF/Kivt9QnDgAB7ZZI813fnnX7MmNH49xsT47x4c+HChYDzBVpRUVF12TRETk4OJ06coFOnTlfdV2RkJMXFxbX+zKZNm9i0aRMAc+fOJTo6utb1/P3961xmBU/kqfz6OMW//S+qThwl6IFBtEidgnGNAV6b4jaqj4bmscWFuvn5+Vd9ZD0qKoqjR4/WWM+VP6jgYD+UUledfrQDu2WSPNdnGMqtf+SlpaW8/fbb7NixA39/f1auXMnOnTs5duxYjVN/11JRUUFGRgZjx46tvvDXFcnJySQnJ1d/X9cAy9HR0Tc0+HJjc2cebTrQf9uA/tPvIbg5xjO/pPKOu8gvr4DyCksyNYS35WnTpk2tt9uioK58k/gypWoOzerKH9SMGfb7nwP2yyR5ru9amer6g6qPt956i+bNm7Nw4UKmTZsGQJcuXVixYoXLBVVVVUVGRgaJiYkkJCQAEB4eTkFBAZGRkRQUFBAWFnbDWZsCnXPaOS3G8a+g990Yo9JQLcKtjtWk2aKgoqKiyMvLq/4+Ly/vhk53COEN9u/fz5IlS/D3/98/w7CwMIqKilz6ea01ixcvJjY29qqx+/r06cPWrVtJSUlh69atxMfHN3p2X6K1Rm/5K/qPy8DfHzVuGiohqdYXycKzbFFQHTt25MyZM+Tk5NCyZUs+++wzJk+ebHUsIdwqJCSECxcuXPViLDc31+UXZ4cPH2bbtm3ExcXx3HPPAc5PCKakpJCZmcnmzZuJjo6uPjoTNen8XMzl8+DQXujWC2PMJFRL+7x309TZoqD8/PxITU0lPT0d0zS5//77ufnmm62OJYRb9e/fn4yMDIYNG4bWmiNHjvDee+8xYMAAl36+a9eurFmzptZlM2fObMyoPkdrjd6xBf3e78BRhRr5NCrpQTlqshlbFBRA79696d27t9UxhPCYRx55hICAALKysnA4HCxatKj6YlvhPvpCEebKBbBnB3S6zTnA600yQK8d2aaghGhqlFIMHjxYJij0IL1nh7OcyktRj45FDXgEZcgAr3YlBSWEhU6fPs3JkyepqLj6I8wPPPCARYl8ky4rQf/hLfS//gFxHTB+9hIqtp3VscR1SEEJYZF169axdu1a2rVrV+MidymoxqMP7cV8Zx4U5aOGPIYaPBTlb69r7kTtpKCEsMjGjRt5+eWXaddOXsm7g75YgV77DvofG6F1LMb011Dtu1gdS9SDFJQQFmnWrBmxsTL7qjvo4185B3jNOYNKfhj1w9GoZg0bik1Yp17zQQkhboxpmtX/HnvsMZYuXUpBQcFVt1+ejkPUn66sxFy3HPPV6eBwYPw8HeOxJ6WcvJQcQQnhQVdOtXHZJ598UuO21atXeyKOT9GnTjiPmv5zEtVvAGroOFSw62MTCvuRghLCg+bPnw84LxTdsWMHd99991XLtdZ8/vnnVkTzWtrhQH+0Fv3hH6B5KMbEF1G3y/BOvkAKSggPujzVBsDatWtrncZm3bp1/OAHP/BkLK+lz37rPGo6cQTVpx9q5ARUqAyO6yukoITwsAMHDgDgcDiqv77s3LlzBAcHWxHLq2jTRP9jI3rdO+DfDPXkzzASkqyOJRqZFJQQHrZo0SIAKisrq78G58gSERERpKamWhXNKzjOn8XMnAVffQnfvRNjzERUhL0muxSNQwpKCA9bsGAB4Hw/auLEiRan8R5aa/Rnm8lb8zY4TNToZ1CJA2WAVx8mBSWERaScXKeLCpxj6O37goBud+AYlYaKaW11LOFmUlBCCFvTuz7FfHchVFSgfpJK5LBU8vLzrY4lPEAKSghhS7q0BL1qCfqLrdCuE0bqFFSbOJQh4ws0FVJQQgjb0Qd2O2e6vVCE+sFw1KCfoPzl6aqpkf/jQgjb0BXl6PeXobd9BN+5GWPiC6h2nayOJSwiBSWEsAV99BDmsjcg9xxqYAoqZRQqoJnVsYSFpKCEEJbSlZfQG36P/vsGiLoJ4+cvo7p0tzqWsAEpKCGEZfTXx51DFZ3+BnXvg6ifPIEKkpE0hJPlBbVy5Up27dqFv78/rVq1Ii0tjebNm1sdSwjhRrqqCv3XP6L/shpahGM8+yvUd++0OpawGcsLqmfPnowYMQI/Pz/effdd1q9fz6hRo6yOJYRwE33mFObSN+DkUdT3klAjxqOat7A6lrAhywvq9ttvr/66S5cu7Nixw8I0Qgh30aaJ/uRD9PqVEBiI8dPnUX36WR1L2JjlBXWlzZs307dv3zqXb9q0iU2bNgEwd+5coqOja13P39+/zmVWsVsmyXN9dszkrXTuOcxlv4UjB+D272GMfgYVHml1LGFzHimoOXPmUFhYWOP2YcOGER/vnFhs3bp1+Pn5kZiYWOf9JCcnk5ycXP19bm5uretFR0fXucwqdsskea7vWpnatGnj4TTeSWuN/uff0auzQIEaOxnVt78M8Cpc4pGCevHFF6+5fMuWLezatYuZM2fKjiuEj9CF+Zgr5sP+nXBrD4wnnkVF3WR1LOFFLD/Ft3fvXj744ANmz55NYGCg1XGEEI3AzP4n+veL4NJF1LCnUPcPljH0RL1ZXlBZWVlUVVUxZ84cADp37sz48eMtTiWEaAhdUuwc4DV7O7Tv4hzgtXVbq2MJL2V5Qb355ptWRxBCNAK9fyfm8jehpNg5TNGDP0b5+VkdS3gxywtKCOHddEUZes1S9PaPIbYdxuRfoeI6WB1L+AApKCFEg+nDB5wDvObnOo+YHh6BCgiwOpbwEVJQQoh605cuoje8i970J4huhfH8K6hOt1kdS/gYKSghRL3ok0edQxWdOYW6bxDq0bGowCCrYwkfJAUlhHCJrqpC/2UNeuMaCIvEmDob1a2X1bGED5OCEsIH7d27l2XLlmGaJv379yclJeWG7k9/+41zWoxvjqPuuh81/ClUSGjjhBWiDlJQQvgY0zTJysrihRdeICoqihkzZtCnTx/atq3/9UjadFC6YRXm75dAcAjG0zNQve92Q2ohapKCEsLHHDt2jNatW9OqVSsA+vbtS3Z2dr0LSpsOzN/MpOTwfrjjLozRaaiwCDckFqJ2UlBC+Jj8/HyioqKqv4+KiuLo0aM11nNldoDShHsJGPQjAhIH2macTDuOMm+3TL6SRwpKCB+jta5xW23l4tLsAInfp7nNRpr3tpHvreBteeqaHUBGbxTCx0RFRZGXl1f9fV5eHpGRMveS8D5SUEL4mI4dO3LmzBlycnKoqqris88+o0+fPlbHEqLe5BSfED7Gz8+P1NRU0tPTMU2T+++/n5tvvtnqWELUm9K1nbAWQgghLOaTp/imT59udYQa7JZJ8lyfHTNZwW7bwW55wH6ZfCWPTxaUEEII7ycFJYQQwpZ8sqCuvLbDLuyWSfJcnx0zWcFu28FuecB+mXwlj3xIQgghhC355BGUEEII7ycFJYQQwpa8+kLd6815o7Vm2bJl7Nmzh8DAQNLS0ujQoYNbsuTm5rJgwQIKCwtRSpGcnMygQYOuWufgwYO89tpr3HTTTQAkJCTw6KOPuiXPZc888wxBQUEYhoGfnx9z5869arknt9Hp06fJzMys/j4nJ4ehQ4cyePDg6ts8sY0WLlzI7t27CQ8PJyMjA4CSkhIyMzM5f/48MTExTJ06ldDQmvMdNfY8S3Zmx8d6vf3Z3W5k3/FkpjVr1vDJJ58QFhYGwPDhw+ndu7dH8tT1XNig7aS9lMPh0BMnTtRnz57VlZWV+uc//7k+derUVevs2rVLp6ena9M09eHDh/WMGTPclic/P18fP35ca611WVmZnjx5co08Bw4c0K+88orbMtQmLS1NFxUV1bnck9voSg6HQz/55JM6Jyfnqts9sY0OHjyojx8/rqdNm1Z928qVK/X69eu11lqvX79er1y5stbM19vnfIVdH+v19md3a+i+4+lMq1ev1h988IFHc1xW13NhQ7aT157iu3LOG39//+o5b660c+dO7r33XpRSdOnShdLSUgoKCtySJzIysvrIIzg4mNjYWPLz893yuxqTJ7fRlfbv30/r1q2JiYlx++/6v7p161bjlVt2djZJSUkAJCUl1diXwLV9zlc0pcdaHw3ddzydyUp1PRc2ZDt57Sk+V+a8yc/Pv2oOkqioKPLz890+snNOTg4nTpygU6dONZYdOXKE5557jsjISEaPHu2RMdLS09MBGDBgQI2Pe1q1jT799FPuueeeWpdZsY2KioqqH3NkZCTFxcU11nF1niVfYOfHeq392Qqu7DtW+Nvf/sa2bdvo0KEDjz/+uCUlduVzYUO2k9cWlHZhzhtX1mlsFRUVZGRkMHbsWEJCQq5a1r59exYuXEhQUBC7d+/m17/+NfPmzXNrnjlz5tCyZUuKiop46aWXaNOmDd26datebsU2qqqqYteuXYwYMaLGMiu2kaus2FZWsetjvd7+LJwGDhxY/d7t6tWrWbFiBWlpaR7NcK3nQld57Sk+V+a8iYqKumqSLHfPi1NVVUVGRgaJiYkkJCTUWB4SEkJQUBAAvXv3xuFwuP3VVsuWLQEIDw8nPj6eY8eOXbXc09sIYM+ePbRv356IiIgay6zYRuDcPpdPbRYUFFS/uXylpjTPkl0f6/X2Zyu4su94WkREBIZhYBgG/fv35/jx4x79/bU9FzZkO3ltQbky502fPn3Ytm0bWmuOHDlCSEiI2/7ItNYsXryY2NhYhgwZUus6hYWF1a9Mjx07hmmatGjRwi15wPkKpry8vPrrL7/8kri4uKvW8eQ2uuxap/c8vY0u69OnD1u3bgVg69atxMfH11inKc2zZMfH6sr+bAVX9h1Pu/J95C+++MKj063U9VzYkO3k1SNJ7N69m+XLl1fPefOjH/2Ijz/+GHAe4mqtycrKYt++fTRr1oy0tDQ6duzolixfffUVM2fOJC4urvpUyPDhw6uPTgYOHMhHH33Exx9/jJ+fH82aNePxxx/n1ltvdUsegHPnzvH6668D4HA46Nevn6XbCODixYs8/fTTzJ8/v/qw/8o8nthGb7zxBocOHeLChQuEh4czdOhQ4uPjyczMJDc3l+joaKZNm0ZoaCj5+fksWbKEGTNmALXvc77Kbo+1rv3Zk+qz71iZ6eDBg5w8eRKlFDExMYwfP95jR8B1PRd27ty53tvJqwtKCCGE7/LaU3xCCCF8mxSUEEIIW5KCEkIIYUtSUEIIIWxJCkoIIYQtSUEJIYSwJSkoIYQQtiQFJYQQwpakoJqQs2fP8sQTT/Dvf/8bcI5YPW7cOA4ePGhxMiGEqEkKqglp3bo1I0eO5M033+TixYssWrSIpKQkunfvbnU0IYSoQYY6aoJeffVVcnJyUErxyiuvEBAQYHUkIYSoQY6gmqD+/ftz6tQpHnzwQSknIYRtSUE1MRUVFSxfvpwHHniA999/n5KSEqsjCSFEraSgmphly5bRvn17JkyYQO/evfnd735ndSQhhKiVFFQTkp2dzd69exk/fjwAY8aM4cSJE2zfvt3iZEIIUZN8SEIIIYQtyRGUEEIIW5KCEkIIYUtSUEIIIWxJCkoIIYQtSUEJIYSwJSkoIYQQtiQFJYQQwpakoIQQQtjS/wc/4hkaYwGXowAAAABJRU5ErkJggg==\n", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "#plot trajectory\n", - "plt.subplot(2, 2, 1)\n", - "plt.plot(x_bar[0,:],x_bar[1,:])\n", - "plt.plot(np.linspace(0,10,T+1),np.zeros(T+1),\"b-\")\n", - "plt.axis('equal')\n", - "plt.ylabel('y')\n", - "plt.xlabel('x')\n", - "\n", - "plt.subplot(2, 2, 2)\n", - "plt.plot(np.degrees(x_bar[2,:]))\n", - "plt.ylabel('theta(t)')\n", - "#plt.xlabel('time')\n", - "\n", - "\n", - "plt.tight_layout()\n", - "plt.show()" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "The results are the same as expected, so the linearized model is equivalent as expected." - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## PRELIMINARIES" - ] - }, - { - "cell_type": "code", - "execution_count": 9, - "metadata": {}, - "outputs": [], - "source": [ - "def compute_path_from_wp(start_xp, start_yp, step = 0.1):\n", - " \"\"\"\n", - " Computes a reference path given a set of waypoints\n", - " \"\"\"\n", - " \n", - " final_xp=[]\n", - " final_yp=[]\n", - " delta = step #[m]\n", - "\n", - " for idx in range(len(start_xp)-1):\n", - " section_len = np.sum(np.sqrt(np.power(np.diff(start_xp[idx:idx+2]),2)+np.power(np.diff(start_yp[idx:idx+2]),2)))\n", - "\n", - " interp_range = np.linspace(0,1,np.floor(section_len/delta).astype(int))\n", - " \n", - " fx=interp1d(np.linspace(0,1,2),start_xp[idx:idx+2],kind=1)\n", - " fy=interp1d(np.linspace(0,1,2),start_yp[idx:idx+2],kind=1)\n", - " \n", - " final_xp=np.append(final_xp,fx(interp_range))\n", - " final_yp=np.append(final_yp,fy(interp_range))\n", - " \n", - " dx = np.append(0, np.diff(final_xp))\n", - " dy = np.append(0, np.diff(final_yp))\n", - " theta = np.arctan2(dy, dx)\n", - "\n", - " return np.vstack((final_xp,final_yp,theta))\n", - "\n", - "\n", - "def get_nn_idx(state,path):\n", - " \"\"\"\n", - " Computes the index of the waypoint closest to vehicle\n", - " \"\"\"\n", - "\n", - " dx = state[0]-path[0,:]\n", - " dy = state[1]-path[1,:]\n", - " dist = np.hypot(dx,dy)\n", - " nn_idx = np.argmin(dist)\n", - "\n", - " try:\n", - " v = [path[0,nn_idx+1] - path[0,nn_idx],\n", - " path[1,nn_idx+1] - path[1,nn_idx]] \n", - " v /= np.linalg.norm(v)\n", - "\n", - " d = [path[0,nn_idx] - state[0],\n", - " path[1,nn_idx] - state[1]]\n", - "\n", - " if np.dot(d,v) > 0:\n", - " target_idx = nn_idx\n", - " else:\n", - " target_idx = nn_idx+1\n", - "\n", - " except IndexError as e:\n", - " target_idx = nn_idx\n", - "\n", - " return target_idx\n", - "\n", - "def get_ref_trajectory(state, path, target_v):\n", - " \"\"\"\n", - " \"\"\"\n", - " xref = np.zeros((N, T + 1))\n", - " dref = np.zeros((1, T + 1))\n", - " \n", - " #sp = np.ones((1,T +1))*target_v #speed profile\n", - " \n", - " ncourse = path.shape[1]\n", - "\n", - " ind = get_nn_idx(state, path)\n", - "\n", - " xref[0, 0] = path[0,ind] #X\n", - " xref[1, 0] = path[1,ind] #Y\n", - " xref[2, 0] = target_v #sp[ind] #V\n", - " xref[3, 0] = path[2,ind] #Theta\n", - " dref[0, 0] = 0.0 # steer operational point should be 0\n", - " \n", - " dl = 0.05 # Waypoints spacing [m]\n", - " travel = 0.0\n", - "\n", - " for i in range(T + 1):\n", - " travel += abs(target_v) * DT #current V or target V?\n", - " dind = int(round(travel / dl))\n", - "\n", - " if (ind + dind) < ncourse:\n", - " xref[0, i] = path[0,ind + dind]\n", - " xref[1, i] = path[1,ind + dind]\n", - " xref[2, i] = target_v #sp[ind + dind]\n", - " xref[3, i] = path[2,ind + dind]\n", - " dref[0, i] = 0.0\n", - " else:\n", - " xref[0, i] = path[0,ncourse - 1]\n", - " xref[1, i] = path[1,ncourse - 1]\n", - " xref[2, i] = 0.0 #stop? #sp[ncourse - 1]\n", - " xref[3, i] = path[2,ncourse - 1]\n", - " dref[0, i] = 0.0\n", - "\n", - " return xref, dref" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### MPC Problem formulation\n", - "\n", - "**Model Predictive Control** refers to the control approach of **numerically** solving a optimization problem at each time step. \n", - "\n", - "The controller generates a control signal over a fixed lenght T (Horizon) at each time step." - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "\n", - "\n", - "" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "#### Linear MPC Formulation\n", - "\n", - "Linear MPC makes use of the **LTI** (Linear time invariant) discrete state space model, wich represents a motion model used for Prediction.\n", - "\n", - "$x_{t+1} = Ax_t + Bu_t$\n", - "\n", - "The LTI formulation means that **future states** are linearly related to the current state and actuator signal. Hence, the MPC seeks to find a **control policy** U over a finite lenght horizon.\n", - "\n", - "$U={u_{t|t}, u_{t+1|t}, ...,u_{t+T|t}}$\n", - "\n", - "The objective function used minimize (drive the state to 0) is:\n", - "\n", - "$\n", - "\\begin{equation}\n", - "\\begin{aligned}\n", - "\\min_{} \\quad & \\sum^{t+T-1}_{j=t} x^T_{j|t}Qx_{j|t} + u^T_{j|t}Ru_{j|t}\\\\\n", - "\\textrm{s.t.} \\quad & x(0) = x0\\\\\n", - " & x_{j+1|t} = Ax_{j|t}+Bu_{j|t}) \\quad \\textrm{for} \\quad t= 0.0] #min_speed (not really needed)\n", - "constr += [cp.abs(u[0,:]) <= MAX_ACC] #max acc\n", - "constr += [cp.abs(u[1,:]) <= MAX_STEER] #max steer\n", - "# for t in range(T):\n", - "# if t < (T - 1):\n", - "# constr += [cp.abs(u[0,t] - u[0,t-1])/DT <= MAX_ACC] #max acc\n", - "# constr += [cp.abs(u[1,t] - u[1,t-1])/DT <= MAX_STEER] #max steer\n", - "\n", - "prob = cp.Problem(cp.Minimize(cost), constr)\n", - "solution = prob.solve(solver=cp.OSQP, verbose=True)" - ] - }, - { - "cell_type": "code", - "execution_count": 11, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "x_mpc=np.array(x.value[0, :]).flatten()\n", - "y_mpc=np.array(x.value[1, :]).flatten()\n", - "v_mpc=np.array(x.value[2, :]).flatten()\n", - "theta_mpc=np.array(x.value[3, :]).flatten()\n", - "a_mpc=np.array(u.value[0, :]).flatten()\n", - "delta_mpc=np.array(u.value[1, :]).flatten()\n", - "\n", - "#simulate robot state trajectory for optimized U\n", - "x_traj=predict(x0, np.vstack((a_mpc,delta_mpc)))\n", - "\n", - "#plt.figure(figsize=(15,10))\n", - "#plot trajectory\n", - "plt.subplot(2, 2, 1)\n", - "plt.plot(track[0,:],track[1,:],\"b\")\n", - "plt.plot(x_ref[0,:],x_ref[1,:],\"g+\")\n", - "plt.plot(x_traj[0,:],x_traj[1,:])\n", - "plt.axis(\"equal\")\n", - "plt.ylabel('y')\n", - "plt.xlabel('x')\n", - "\n", - "#plot v(t)\n", - "plt.subplot(2, 2, 3)\n", - "plt.plot(a_mpc)\n", - "plt.ylabel('a_in(t)')\n", - "#plt.xlabel('time')\n", - "\n", - "\n", - "plt.subplot(2, 2, 2)\n", - "plt.plot(theta_mpc)\n", - "plt.ylabel('theta(t)')\n", - "\n", - "plt.subplot(2, 2, 4)\n", - "plt.plot(delta_mpc)\n", - "plt.ylabel('d_in(t)')\n", - "\n", - "plt.tight_layout()\n", - "plt.show()" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## full track demo" - ] - }, - { - "cell_type": "code", - "execution_count": 12, - "metadata": {}, - "outputs": [ - { - "name": "stderr", - "output_type": "stream", - "text": [ - "/home/marcello/.conda/envs/jupyter/lib/python3.8/site-packages/cvxpy/problems/problem.py:1054: UserWarning: Solution may be inaccurate. Try another solver, adjusting the solver settings, or solve with verbose=True for more information.\n", - " warnings.warn(\n" - ] - }, - { - "name": "stdout", - "output_type": "stream", - "text": [ - "CVXPY Optimization Time: Avrg: 0.1673s Max: 0.2378s Min: 0.1453s\n" - ] - } - ], - "source": [ - "track = compute_path_from_wp([0,3,4,6,10,12,14,6,1,0],\n", - " [0,0,2,4,3,3,-2,-6,-2,-2],0.05)\n", - "\n", - "# track = compute_path_from_wp([0,10,10,0],\n", - "# [0,0,1,1],0.05)\n", - "\n", - "sim_duration = 200 #time steps\n", - "opt_time=[]\n", - "\n", - "x_sim = np.zeros((N,sim_duration))\n", - "u_sim = np.zeros((M,sim_duration-1))\n", - "\n", - "MAX_SPEED = 1.5 #m/s\n", - "MAX_ACC = 1.0 #m/ss\n", - "MAX_D_ACC = 1.0 #m/sss\n", - "MAX_STEER = np.radians(30) #rad\n", - "MAX_D_STEER = np.radians(30) #rad/s\n", - "\n", - "REF_VEL = 1.0 #m/s\n", - "\n", - "# Starting Condition\n", - "x0 = np.zeros(N)\n", - "x0[0] = 0 #x\n", - "x0[1] = -0.25 #y\n", - "x0[2] = 0.0 #v\n", - "x0[3] = np.radians(-0) #yaw\n", - " \n", - "#starting guess\n", - "u_bar = np.zeros((M,T))\n", - "u_bar[0,:] = MAX_ACC/2 #a\n", - "u_bar[1,:] = 0.0 #delta\n", - "\n", - "for sim_time in range(sim_duration-1):\n", - " \n", - " iter_start = time.time()\n", - " \n", - " # dynamics starting state\n", - " x_bar = np.zeros((N,T+1))\n", - " x_bar[:,0] = x_sim[:,sim_time]\n", - " \n", - " #prediction for linearization of costrains\n", - " for t in range (1,T+1):\n", - " xt = x_bar[:,t-1].reshape(N,1)\n", - " ut = u_bar[:,t-1].reshape(M,1)\n", - " A,B,C = get_linear_model(xt,ut)\n", - " xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n", - " x_bar[:,t] = xt_plus_one\n", - " \n", - " #CVXPY Linear MPC problem statement\n", - " x = cp.Variable((N, T+1))\n", - " u = cp.Variable((M, T))\n", - " cost = 0\n", - " constr = []\n", - "\n", - " # Cost Matrices\n", - " Q = np.diag([20,20,10,0]) #state error cost\n", - " Qf = np.diag([30,30,30,0]) #state final error cost\n", - " R = np.diag([10,10]) #input cost\n", - " R_ = np.diag([10,10]) #input rate of change cost\n", - "\n", - " #Get Reference_traj\n", - " x_ref, d_ref = get_ref_trajectory(x_bar[:,0] ,track, REF_VEL)\n", - " \n", - " #Prediction Horizon\n", - " for t in range(T):\n", - "\n", - " # Tracking Error\n", - " cost += cp.quad_form(x[:,t] - x_ref[:,t], Q)\n", - "\n", - " # Actuation effort\n", - " cost += cp.quad_form(u[:,t], R)\n", - "\n", - " # Actuation rate of change\n", - " if t < (T - 1):\n", - " cost += cp.quad_form(u[:,t+1] - u[:,t], R_)\n", - " constr+= [cp.abs(u[0, t + 1] - u[0, t])/DT <= MAX_D_ACC] #max acc rate of change\n", - " constr += [cp.abs(u[1, t + 1] - u[1, t])/DT <= MAX_D_STEER] #max steer rate of change\n", - "\n", - " # Kinrmatics Constrains (Linearized model)\n", - " A,B,C = get_linear_model(x_bar[:,t], u_bar[:,t])\n", - " constr += [x[:,t+1] == A@x[:,t] + B@u[:,t] + C.flatten()]\n", - " \n", - " #Final Point tracking\n", - " cost += cp.quad_form(x[:, T] - x_ref[:, T], Qf)\n", - "\n", - " # sums problem objectives and concatenates constraints.\n", - " constr += [x[:,0] == x_bar[:,0]] #starting condition\n", - " constr += [x[2,:] <= MAX_SPEED] #max speed\n", - " constr += [x[2,:] >= 0.0] #min_speed (not really needed)\n", - " constr += [cp.abs(u[0,:]) <= MAX_ACC] #max acc\n", - " constr += [cp.abs(u[1,:]) <= MAX_STEER] #max steer\n", - " \n", - " # Solve\n", - " prob = cp.Problem(cp.Minimize(cost), constr)\n", - " solution = prob.solve(solver=cp.OSQP, verbose=False)\n", - " \n", - " #retrieved optimized U and assign to u_bar to linearize in next step\n", - " u_bar = np.vstack((np.array(u.value[0,:]).flatten(),\n", - " (np.array(u.value[1,:]).flatten())))\n", - " \n", - " u_sim[:,sim_time] = u_bar[:,0]\n", - " \n", - " # Measure elpased time to get results from cvxpy\n", - " opt_time.append(time.time()-iter_start)\n", - " \n", - " # move simulation to t+1\n", - " tspan = [0,DT]\n", - " x_sim[:,sim_time+1] = odeint(kinematics_model,\n", - " x_sim[:,sim_time],\n", - " tspan,\n", - " args=(u_bar[:,0],))[1]\n", - " \n", - "print(\"CVXPY Optimization Time: Avrg: {:.4f}s Max: {:.4f}s Min: {:.4f}s\".format(np.mean(opt_time),\n", - " np.max(opt_time),\n", - " np.min(opt_time))) " - ] - }, - { - "cell_type": "code", - "execution_count": 13, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "#plot trajectory\n", - "grid = plt.GridSpec(4, 5)\n", - "\n", - "plt.figure(figsize=(15,10))\n", - "\n", - "plt.subplot(grid[0:4, 0:4])\n", - "plt.plot(track[0,:],track[1,:],\"b+\")\n", - "plt.plot(x_sim[0,:],x_sim[1,:])\n", - "plt.axis(\"equal\")\n", - "plt.ylabel('y')\n", - "plt.xlabel('x')\n", - "\n", - "plt.subplot(grid[0, 4])\n", - "plt.plot(u_sim[0,:])\n", - "plt.ylabel('a(t) [m/ss]')\n", - "\n", - "plt.subplot(grid[1, 4])\n", - "plt.plot(x_sim[2,:])\n", - "plt.ylabel('v(t) [m/s]')\n", - "\n", - "plt.subplot(grid[2, 4])\n", - "plt.plot(np.degrees(u_sim[1,:]))\n", - "plt.ylabel('delta(t) [rad]')\n", - "\n", - "plt.subplot(grid[3, 4])\n", - "plt.plot(x_sim[3,:])\n", - "plt.ylabel('theta(t) [rad]')\n", - "\n", - "plt.tight_layout()\n", - "plt.show()" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "# Iterative Linearization" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "The goal is to have a more accurate linearization of the diff equations. For every time step the optimization is iterativelly repeated using he previous optimization results **u_bar** to approximate the vehicle dynamics, instead of a random starting guess and/or the rsult at time t-1.\n", - "\n", - "In previous case the results at t-1 wer used to approimate the dynamics art time t!\n", - "\n", - "This maks the results less correlated but makes the controller slower!" - ] - }, - { - "cell_type": "code", - "execution_count": 14, - "metadata": {}, - "outputs": [ - { - "name": "stderr", - "output_type": "stream", - "text": [ - ":41: RuntimeWarning: invalid value encountered in true_divide\n", - " v /= np.linalg.norm(v)\n" - ] - }, - { - "name": "stdout", - "output_type": "stream", - "text": [ - "CVXPY Optimization Time: Avrg: 0.6069s Max: 0.8421s Min: 0.2994s\n" - ] - } - ], - "source": [ - "track = compute_path_from_wp([0,3,4,6,10,12,14,6,1,0],\n", - " [0,0,2,4,3,3,-2,-6,-2,-2],0.05)\n", - "\n", - "# track = compute_path_from_wp([0,10,10,0],\n", - "# [0,0,1,1],0.05)\n", - "\n", - "sim_duration = 200 #time steps\n", - "opt_time=[]\n", - "\n", - "x_sim = np.zeros((N,sim_duration))\n", - "u_sim = np.zeros((M,sim_duration-1))\n", - "\n", - "MAX_SPEED = 1.5 #m/s\n", - "MAX_ACC = 1.0 #m/ss\n", - "MAX_D_ACC = 1.0 #m/sss\n", - "MAX_STEER = np.radians(30) #rad\n", - "MAX_D_STEER = np.radians(30) #rad/s\n", - "\n", - "REF_VEL = 1.0 #m/s\n", - "\n", - "# Starting Condition\n", - "x0 = np.zeros(N)\n", - "x0[0] = 0 #x\n", - "x0[1] = -0.25 #y\n", - "x0[2] = 0.0 #v\n", - "x0[3] = np.radians(-0) #yaw\n", - "\n", - "for sim_time in range(sim_duration-1):\n", - " \n", - " iter_start = time.time()\n", - " \n", - " #starting guess for ctrl\n", - " u_bar = np.zeros((M,T))\n", - " u_bar[0,:] = MAX_ACC/2 #a\n", - " u_bar[1,:] = 0.0 #delta \n", - " \n", - " for _ in range(5):\n", - " u_prev = u_bar\n", - " \n", - " # dynamics starting state\n", - " x_bar = np.zeros((N,T+1))\n", - " x_bar[:,0] = x_sim[:,sim_time]\n", - "\n", - " #prediction for linearization of costrains\n", - " for t in range (1,T+1):\n", - " xt = x_bar[:,t-1].reshape(N,1)\n", - " ut = u_bar[:,t-1].reshape(M,1)\n", - " A,B,C = get_linear_model(xt,ut)\n", - " xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n", - " x_bar[:,t] = xt_plus_one\n", - "\n", - " #CVXPY Linear MPC problem statement\n", - " x = cp.Variable((N, T+1))\n", - " u = cp.Variable((M, T))\n", - " cost = 0\n", - " constr = []\n", - "\n", - " # Cost Matrices\n", - " Q = np.diag([20,20,10,0]) #state error cost\n", - " Qf = np.diag([30,30,30,0]) #state final error cost\n", - " R = np.diag([10,10]) #input cost\n", - " R_ = np.diag([10,10]) #input rate of change cost\n", - "\n", - " #Get Reference_traj\n", - " x_ref, d_ref = get_ref_trajectory(x_bar[:,0] ,track, REF_VEL)\n", - "\n", - " #Prediction Horizon\n", - " for t in range(T):\n", - "\n", - " # Tracking Error\n", - " cost += cp.quad_form(x[:,t] - x_ref[:,t], Q)\n", - "\n", - " # Actuation effort\n", - " cost += cp.quad_form(u[:,t], R)\n", - "\n", - " # Actuation rate of change\n", - " if t < (T - 1):\n", - " cost += cp.quad_form(u[:,t+1] - u[:,t], R_)\n", - " constr+= [cp.abs(u[0, t + 1] - u[0, t])/DT <= MAX_D_ACC] #max acc rate of change\n", - " constr += [cp.abs(u[1, t + 1] - u[1, t])/DT <= MAX_D_STEER] #max steer rate of change\n", - "\n", - " # Kinrmatics Constrains (Linearized model)\n", - " A,B,C = get_linear_model(x_bar[:,t], u_bar[:,t])\n", - " constr += [x[:,t+1] == A@x[:,t] + B@u[:,t] + C.flatten()]\n", - "\n", - " #Final Point tracking\n", - " cost += cp.quad_form(x[:, T] - x_ref[:, T], Qf)\n", - "\n", - " # sums problem objectives and concatenates constraints.\n", - " constr += [x[:,0] == x_bar[:,0]] #starting condition\n", - " constr += [x[2,:] <= MAX_SPEED] #max speed\n", - " constr += [x[2,:] >= 0.0] #min_speed (not really needed)\n", - " constr += [cp.abs(u[0,:]) <= MAX_ACC] #max acc\n", - " constr += [cp.abs(u[1,:]) <= MAX_STEER] #max steer\n", - "\n", - " # Solve\n", - " prob = cp.Problem(cp.Minimize(cost), constr)\n", - " solution = prob.solve(solver=cp.OSQP, verbose=False)\n", - "\n", - " #retrieved optimized U and assign to u_bar to linearize in next step\n", - " u_bar = np.vstack((np.array(u.value[0,:]).flatten(),\n", - " (np.array(u.value[1,:]).flatten())))\n", - " \n", - " #check how this solution differs from previous\n", - " #if the solutions are very\n", - " delta_u = np.sum(np.sum(np.abs(u_bar - u_prev),axis=0),axis=0)\n", - " if delta_u < 0.05:\n", - " break\n", - " \n", - " \n", - " # select u from best iteration\n", - " u_sim[:,sim_time] = u_bar[:,0]\n", - " \n", - " \n", - " # Measure elpased time to get results from cvxpy\n", - " opt_time.append(time.time()-iter_start)\n", - " \n", - " # move simulation to t+1\n", - " tspan = [0,DT]\n", - " x_sim[:,sim_time+1] = odeint(kinematics_model,\n", - " x_sim[:,sim_time],\n", - " tspan,\n", - " args=(u_bar[:,0],))[1]\n", - " \n", - " #reset u_bar? -> this simulates that we don use previous solution!\n", - " u_bar[0,:] = MAX_ACC/2 #a\n", - " u_bar[1,:] = 0.0 #delta\n", - " \n", - " \n", - "print(\"CVXPY Optimization Time: Avrg: {:.4f}s Max: {:.4f}s Min: {:.4f}s\".format(np.mean(opt_time),\n", - " np.max(opt_time),\n", - " np.min(opt_time))) " - ] - }, - { - "cell_type": "code", - "execution_count": 15, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "#plot trajectory\n", - "grid = plt.GridSpec(4, 5)\n", - "\n", - "plt.figure(figsize=(15,10))\n", - "\n", - "plt.subplot(grid[0:4, 0:4])\n", - "plt.plot(track[0,:],track[1,:],\"b+\")\n", - "plt.plot(x_sim[0,:],x_sim[1,:])\n", - "plt.axis(\"equal\")\n", - "plt.ylabel('y')\n", - "plt.xlabel('x')\n", - "\n", - "plt.subplot(grid[0, 4])\n", - "plt.plot(u_sim[0,:])\n", - "plt.ylabel('a(t) [m/ss]')\n", - "\n", - "plt.subplot(grid[1, 4])\n", - "plt.plot(x_sim[2,:])\n", - "plt.ylabel('v(t) [m/s]')\n", - "\n", - "plt.subplot(grid[2, 4])\n", - "plt.plot(np.degrees(u_sim[1,:]))\n", - "plt.ylabel('delta(t) [rad]')\n", - "\n", - "plt.subplot(grid[3, 4])\n", - "plt.plot(x_sim[3,:])\n", - "plt.ylabel('theta(t) [rad]')\n", - "\n", - "plt.tight_layout()\n", - "plt.show()" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## V2 Use Dynamics w.r.t Robot Frame\n", - "\n", - "explanation here...\n", - "\n", - "benefits:\n", - "* slightly faster mpc convergence time -> more variables are 0, this helps the computation?\n", - "* no issues when vehicle heading ~PI in world" - ] - }, - { - "cell_type": "code", - "execution_count": 16, - "metadata": {}, - "outputs": [], - "source": [ - "def compute_path_from_wp(start_xp, start_yp, step = 0.1):\n", - " \"\"\"\n", - " Computes a reference path given a set of waypoints\n", - " \"\"\"\n", - " \n", - " final_xp=[]\n", - " final_yp=[]\n", - " delta = step #[m]\n", - "\n", - " for idx in range(len(start_xp)-1):\n", - " section_len = np.sum(np.sqrt(np.power(np.diff(start_xp[idx:idx+2]),2)+np.power(np.diff(start_yp[idx:idx+2]),2)))\n", - "\n", - " interp_range = np.linspace(0,1,np.floor(section_len/delta).astype(int))\n", - " \n", - " fx=interp1d(np.linspace(0,1,2),start_xp[idx:idx+2],kind=1)\n", - " fy=interp1d(np.linspace(0,1,2),start_yp[idx:idx+2],kind=1)\n", - " \n", - " # watch out to duplicate points!\n", - " final_xp=np.append(final_xp,fx(interp_range)[1:])\n", - " final_yp=np.append(final_yp,fy(interp_range)[1:])\n", - " \n", - " dx = np.append(0, np.diff(final_xp))\n", - " dy = np.append(0, np.diff(final_yp))\n", - " theta = np.arctan2(dy, dx)\n", - "\n", - " return np.vstack((final_xp,final_yp,theta))\n", - "\n", - "\n", - "def get_nn_idx(state,path):\n", - " \"\"\"\n", - " Computes the index of the waypoint closest to vehicle\n", - " \"\"\"\n", - "\n", - " dx = state[0]-path[0,:]\n", - " dy = state[1]-path[1,:]\n", - " dist = np.hypot(dx,dy)\n", - " nn_idx = np.argmin(dist)\n", - "\n", - " try:\n", - " v = [path[0,nn_idx+1] - path[0,nn_idx],\n", - " path[1,nn_idx+1] - path[1,nn_idx]] \n", - " v /= np.linalg.norm(v)\n", - "\n", - " d = [path[0,nn_idx] - state[0],\n", - " path[1,nn_idx] - state[1]]\n", - "\n", - " if np.dot(d,v) > 0:\n", - " target_idx = nn_idx\n", - " else:\n", - " target_idx = nn_idx+1\n", - "\n", - " except IndexError as e:\n", - " target_idx = nn_idx\n", - "\n", - " return target_idx\n", - "\n", - "def normalize_angle(angle):\n", - " \"\"\"\n", - " Normalize an angle to [-pi, pi]\n", - " \"\"\"\n", - " while angle > np.pi:\n", - " angle -= 2.0 * np.pi\n", - "\n", - " while angle < -np.pi:\n", - " angle += 2.0 * np.pi\n", - "\n", - " return angle\n", - "\n", - "def get_ref_trajectory(state, path, target_v):\n", - " \"\"\"\n", - " modified reference in robot frame\n", - " \"\"\"\n", - " xref = np.zeros((N, T + 1))\n", - " dref = np.zeros((1, T + 1))\n", - " \n", - " #sp = np.ones((1,T +1))*target_v #speed profile\n", - " \n", - " ncourse = path.shape[1]\n", - "\n", - " ind = get_nn_idx(state, path)\n", - " dx=path[0,ind] - state[0]\n", - " dy=path[1,ind] - state[1]\n", - " \n", - " xref[0, 0] = dx * np.cos(-state[3]) - dy * np.sin(-state[3]) #X\n", - " xref[1, 0] = dy * np.cos(-state[3]) + dx * np.sin(-state[3]) #Y\n", - " xref[2, 0] = target_v #V\n", - " xref[3, 0] = normalize_angle(path[2,ind]- state[3]) #Theta\n", - " dref[0, 0] = 0.0 # steer operational point should be 0\n", - " \n", - " dl = 0.05 # Waypoints spacing [m]\n", - " travel = 0.0\n", - " \n", - " for i in range(T + 1):\n", - " travel += abs(target_v) * DT #current V or target V?\n", - " dind = int(round(travel / dl))\n", - " \n", - " if (ind + dind) < ncourse:\n", - " dx=path[0,ind + dind] - state[0]\n", - " dy=path[1,ind + dind] - state[1]\n", - " \n", - " xref[0, i] = dx * np.cos(-state[3]) - dy * np.sin(-state[3])\n", - " xref[1, i] = dy * np.cos(-state[3]) + dx * np.sin(-state[3])\n", - " xref[2, i] = target_v #sp[ind + dind]\n", - " xref[3, i] = normalize_angle(path[2,ind + dind] - state[3])\n", - " dref[0, i] = 0.0\n", - " else:\n", - " dx=path[0,ncourse - 1] - state[0]\n", - " dy=path[1,ncourse - 1] - state[1]\n", - " \n", - " xref[0, i] = dx * np.cos(-state[3]) - dy * np.sin(-state[3])\n", - " xref[1, i] = dy * np.cos(-state[3]) + dx * np.sin(-state[3])\n", - " xref[2, i] = 0.0 #stop? #sp[ncourse - 1]\n", - " xref[3, i] = normalize_angle(path[2,ncourse - 1] - state[3])\n", - " dref[0, i] = 0.0\n", - "\n", - " return xref, dref" - ] - }, - { - "cell_type": "code", - "execution_count": 17, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "CVXPY Optimization Time: Avrg: 0.1628s Max: 0.1967s Min: 0.1471s\n" - ] - } - ], - "source": [ - "track = compute_path_from_wp([0,3,4,6,10,12,14,6,1,0],\n", - " [0,0,2,4,3,3,-2,-6,-2,-2],0.05)\n", - "\n", - "# track = compute_path_from_wp([0,10,10,0],\n", - "# [0,0,1,1],0.05)\n", - "\n", - "sim_duration = 200 #time steps\n", - "opt_time=[]\n", - "\n", - "x_sim = np.zeros((N,sim_duration))\n", - "u_sim = np.zeros((M,sim_duration-1))\n", - "\n", - "MAX_SPEED = 1.5 #m/s\n", - "MAX_ACC = 1.0 #m/ss\n", - "MAX_D_ACC = 1.0 #m/sss\n", - "MAX_STEER = np.radians(30) #rad\n", - "MAX_D_STEER = np.radians(30) #rad/s\n", - "\n", - "REF_VEL = 1.0 #m/s\n", - "\n", - "# Starting Condition\n", - "x0 = np.zeros(N)\n", - "x0[0] = 0 #x\n", - "x0[1] = -0.25 #y\n", - "x0[2] = 0.0 #v\n", - "x0[3] = np.radians(-0) #yaw\n", - " \n", - "#starting guess\n", - "u_bar = np.zeros((M,T))\n", - "u_bar[0,:] = MAX_ACC/2 #a\n", - "u_bar[1,:] = 0.0 #delta\n", - " \n", - "for sim_time in range(sim_duration-1):\n", - " \n", - " iter_start = time.time()\n", - " \n", - " # dynamics starting state w.r.t. robot are always null except vel \n", - " x_bar = np.zeros((N,T+1))\n", - " x_bar[2,0] = x_sim[2,sim_time]\n", - " \n", - " #prediction for linearization of costrains\n", - " for t in range (1,T+1):\n", - " xt = x_bar[:,t-1].reshape(N,1)\n", - " ut = u_bar[:,t-1].reshape(M,1)\n", - " A,B,C = get_linear_model(xt,ut)\n", - " xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n", - " x_bar[:,t] = xt_plus_one\n", - " \n", - " #CVXPY Linear MPC problem statement\n", - " x = cp.Variable((N, T+1))\n", - " u = cp.Variable((M, T))\n", - " cost = 0\n", - " constr = []\n", - "\n", - " # Cost Matrices\n", - " Q = np.diag([20,20,10,20]) #state error cost\n", - " Qf = np.diag([30,30,30,30]) #state final error cost\n", - " R = np.diag([10,10]) #input cost\n", - " R_ = np.diag([10,10]) #input rate of change cost\n", - "\n", - " #Get Reference_traj\n", - " #dont use x0 in this case\n", - " x_ref, d_ref = get_ref_trajectory(x_sim[:,sim_time] ,track, REF_VEL)\n", - " \n", - " #Prediction Horizon\n", - " for t in range(T):\n", - "\n", - " # Tracking Error\n", - " cost += cp.quad_form(x[:,t] - x_ref[:,t], Q)\n", - "\n", - " # Actuation effort\n", - " cost += cp.quad_form(u[:,t], R)\n", - "\n", - " # Actuation rate of change\n", - " if t < (T - 1):\n", - " cost += cp.quad_form(u[:,t+1] - u[:,t], R_)\n", - " constr+= [cp.abs(u[0, t + 1] - u[0, t])/DT <= MAX_D_ACC] #max acc rate of change\n", - " constr += [cp.abs(u[1, t + 1] - u[1, t])/DT <= MAX_D_STEER] #max steer rate of change\n", - "\n", - " # Kinrmatics Constrains (Linearized model)\n", - " A,B,C = get_linear_model(x_bar[:,t], u_bar[:,t])\n", - " constr += [x[:,t+1] == A@x[:,t] + B@u[:,t] + C.flatten()]\n", - " \n", - " #Final Point tracking\n", - " cost += cp.quad_form(x[:, T] - x_ref[:, T], Qf)\n", - "\n", - " # sums problem objectives and concatenates constraints.\n", - " constr += [x[:,0] == x_bar[:,0]] #starting condition\n", - " constr += [x[2,:] <= MAX_SPEED] #max speed\n", - " constr += [x[2,:] >= 0.0] #min_speed (not really needed)\n", - " constr += [cp.abs(u[0,:]) <= MAX_ACC] #max acc\n", - " constr += [cp.abs(u[1,:]) <= MAX_STEER] #max steer\n", - " \n", - " # Solve\n", - " prob = cp.Problem(cp.Minimize(cost), constr)\n", - " solution = prob.solve(solver=cp.OSQP, verbose=False)\n", - " \n", - " #retrieved optimized U and assign to u_bar to linearize in next step\n", - " u_bar = np.vstack((np.array(u.value[0,:]).flatten(),\n", - " (np.array(u.value[1,:]).flatten())))\n", - " \n", - " u_sim[:,sim_time] = u_bar[:,0]\n", - " \n", - " # Measure elpased time to get results from cvxpy\n", - " opt_time.append(time.time()-iter_start)\n", - " \n", - " # move simulation to t+1\n", - " tspan = [0,DT]\n", - " x_sim[:,sim_time+1] = odeint(kinematics_model,\n", - " x_sim[:,sim_time],\n", - " tspan,\n", - " args=(u_bar[:,0],))[1]\n", - " \n", - "print(\"CVXPY Optimization Time: Avrg: {:.4f}s Max: {:.4f}s Min: {:.4f}s\".format(np.mean(opt_time),\n", - " np.max(opt_time),\n", - " np.min(opt_time))) " - ] - }, - { - "cell_type": "code", - "execution_count": 18, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "#plot trajectory\n", - "grid = plt.GridSpec(4, 5)\n", - "\n", - "plt.figure(figsize=(15,10))\n", - "\n", - "plt.subplot(grid[0:4, 0:4])\n", - "plt.plot(track[0,:],track[1,:],\"b+\")\n", - "plt.plot(x_sim[0,:],x_sim[1,:])\n", - "plt.axis(\"equal\")\n", - "plt.ylabel('y')\n", - "plt.xlabel('x')\n", - "\n", - "plt.subplot(grid[0, 4])\n", - "plt.plot(u_sim[0,:])\n", - "plt.ylabel('a(t) [m/ss]')\n", - "\n", - "plt.subplot(grid[1, 4])\n", - "plt.plot(x_sim[2,:])\n", - "plt.ylabel('v(t) [m/s]')\n", - "\n", - "plt.subplot(grid[2, 4])\n", - "plt.plot(np.degrees(u_sim[1,:]))\n", - "plt.ylabel('delta(t) [rad]')\n", - "\n", - "plt.subplot(grid[3, 4])\n", - "plt.plot(x_sim[3,:])\n", - "plt.ylabel('theta(t) [rad]')\n", - "\n", - "plt.tight_layout()\n", - "plt.show()" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## V3 Add track constraints\n", - "inspried from -> https://arxiv.org/pdf/1711.07300.pdf\n", - "\n", - "explanation here...\n", - "\n", - "benefits:\n", - "* add a soft form of obstacle aoidance" - ] - }, - { - "cell_type": "code", - "execution_count": 19, - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "[]" - ] - }, - "execution_count": 19, - "metadata": {}, - "output_type": "execute_result" - }, - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "def generate_track_bounds(track,width=0.5):\n", - " \"\"\"\n", - " in world frame\n", - " \"\"\"\n", - " bounds_low=np.zeros((2, track.shape[1]))\n", - " bounds_upp=np.zeros((2, track.shape[1]))\n", - " \n", - " for idx in range(track.shape[1]):\n", - " x = track[0,idx]\n", - " y = track [1,idx]\n", - " th = track [2,idx]\n", - " \n", - " \"\"\"\n", - " trasform the points\n", - " \"\"\"\n", - " bounds_upp[0, idx] = 0 * np.cos(th) - width * np.sin(th) + x #X\n", - " bounds_upp[1, idx] = 0 * np.sin(th) + width * np.cos(th) + y #Y\n", - " \n", - " bounds_low[0, idx] = 0 * np.cos(th) - (-width) * np.sin(th) + x #X\n", - " bounds_low[1, idx] = 0 * np.sin(th) + (-width) * np.cos(th) + y #Y\n", - " \n", - " return bounds_low, bounds_upp\n", - "\n", - "track = compute_path_from_wp([0,3,4,6,10,12,14,6,1,0],\n", - " [0,0,2,4,3,3,-2,-6,-2,-2],0.05)\n", - "\n", - "lower, upper = generate_track_bounds(track)\n", - "\n", - "plt.figure(figsize=(15,10))\n", - "\n", - "plt.plot(track[0,:],track[1,:],\"b-\")\n", - "plt.plot(lower[0,:],lower[1,:],\"g-\")\n", - "plt.plot(upper[0,:],upper[1,:],\"r-\")" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "the points can be used to generate the **halfplane constrains** for each reference point.\n", - "the issues (outliers points) should be gone after we are in vehicle frame...\n", - "\n", - "the halfplane constrains are defined given the line equation:\n", - "\n", - "**lower halfplane**\n", - "$$ a1x_1 + b1x_2 = c1 \\rightarrow a1x_1 + b1x_2 \\leq c1$$\n", - "\n", - "**upper halfplane**\n", - "$$ a2x_1 - b2x_2 = c2 \\rightarrow a2x_1 + b2x_2 \\leq c2$$\n", - "\n", - "we want to combine this in matrix form:\n", - "\n", - "$$\n", - "\\begin{bmatrix}\n", - "x_1 \\\\\n", - "x_2 \n", - "\\end{bmatrix}\n", - "\\begin{bmatrix}\n", - "a_1 & a_2\\\\\n", - "b_1 & b_2\n", - "\\end{bmatrix}\n", - "\\leq\n", - "\\begin{bmatrix}\n", - "c_1 \\\\\n", - "c_2 \n", - "\\end{bmatrix}\n", - "$$\n", - "\n", - "becouse our track points have known heading the coefficients can be computed from:\n", - "\n", - "$$ y - y' = \\frac{sin(\\theta)}{cos(\\theta)}(x - x') $$" - ] - }, - { - "cell_type": "code", - "execution_count": 57, - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "(-2.0, 2.0)" - ] - }, - "execution_count": 57, - "metadata": {}, - "output_type": "execute_result" - }, - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "import numpy as np\n", - "import matplotlib.pyplot as plt\n", - "plt.style.use(\"ggplot\")\n", - "\n", - "def get_coeff(x,y,theta):\n", - " m = np.sin(theta)/np.cos(theta)\n", - " return(-m,1,y-m*x)\n", - "\n", - "#test -> assume point 10,1,pi/6\n", - "coeff = get_coeff(1,-1, np.pi/2)\n", - "y = []\n", - "pts = np.linspace(0,20,100)\n", - "\n", - "for x in pts:\n", - " y.append((-coeff[0]*x+coeff[2])/coeff[1])\n", - " \n", - "plt.figure(figsize=(5,5))\n", - "plt.plot(pts,y,\"b-\")\n", - "\n", - "plt.xlim((-2, 2))\n", - "plt.ylim((-2, 2))" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## WARN TANGENT BREAKS AROUND PI/2?\n", - "force the equation to x = val" - ] - }, - { - "cell_type": "code", - "execution_count": 56, - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "(-2.0, 2.0)" - ] - }, - "execution_count": 56, - "metadata": {}, - "output_type": "execute_result" - }, - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "def get_coeff(x,y,theta):\n", - " \n", - " if (theta - np.pi/2) < 0.01:\n", - " #print (\"WARN -> theta is 90, tan is: \" + str(theta))\n", - " # eq is x = val\n", - " m = 0\n", - " return (1,1e-6,x)\n", - " else:\n", - " m = np.sin(theta)/np.cos(theta)\n", - " return(-m,1,y-m*x)\n", - " \n", - "#test -> assume point 10,1,pi/6\n", - "coeff = get_coeff(1,-1, np.pi/2)\n", - "y = []\n", - "pts = np.linspace(0,20,100)\n", - "\n", - "for x in pts:\n", - " y.append((-coeff[0]*x+coeff[2])/coeff[1])\n", - " \n", - "plt.figure(figsize=(5,5))\n", - "\n", - "plt.plot(pts,y,\"b-\")\n", - "plt.axis(\"equal\")\n", - "plt.xlim((-2, 2))\n", - "plt.ylim((-2, 2))" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "becouse the controller uses vhicle reference frame this rquire adapting -> the semiplane constraints must be gathetered from **x_ref points**\n", - "\n", - "*low and up are w.r.t vehicle y axis*" - ] - }, - { - "cell_type": "code", - "execution_count": 21, - "metadata": {}, - "outputs": [], - "source": [ - "def get_track_constrains(x_ref, width=0.5):\n", - " \"\"\"\n", - " x_ref has hape (4,T) -> [x,y,v,theta]_ref \n", - " \"\"\"\n", - " \n", - " #1-> get the upper and lower points\n", - " pts_low=np.zeros((3, x_ref.shape[1]))\n", - " pts_upp=np.zeros((3, x_ref.shape[1]))\n", - " \n", - " for idx in range(x_ref.shape[1]):\n", - " x = x_ref [0, idx]\n", - " y = x_ref [1, idx]\n", - " th = x_ref [3, idx]\n", - " \n", - " \"\"\"\n", - " trasform the points\n", - " \"\"\"\n", - " pts_upp[0, idx] = 0 * np.cos(th) - width * np.sin(th) + x #X\n", - " pts_upp[1, idx] = 0 * np.sin(th) + width * np.cos(th) + y #Y\n", - " pts_upp[2, idx] = th #heading\n", - " \n", - " pts_low[0, idx] = 0 * np.cos(th) - (-width) * np.sin(th) + x #X\n", - " pts_low[1, idx] = 0 * np.sin(th) + (-width) * np.cos(th) + y #Y\n", - " pts_low[2, idx] = th #heading\n", - " \n", - " #get coefficients ->(a,b,c)\n", - " coeff_low=np.zeros((3, x_ref.shape[1]))\n", - " coeff_upp=np.zeros((3, x_ref.shape[1]))\n", - " \n", - " for idx in range(pts_upp.shape[1]):\n", - " f = get_coeff(pts_low[0,idx],pts_low[1,idx],pts_low[2,idx])\n", - " coeff_low[0,idx]=f[0]\n", - " coeff_low[1,idx]=f[1]\n", - " coeff_low[2,idx]=f[2]\n", - " \n", - " f = get_coeff(pts_upp[0,idx],pts_upp[1,idx],pts_upp[2,idx])\n", - " coeff_upp[0,idx]=f[0]\n", - " coeff_upp[1,idx]=f[1]\n", - " coeff_upp[2,idx]=f[2]\n", - " \n", - " return coeff_low, coeff_upp\n", - " " - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "simpe u-turn test\n", - "\n", - "## 1-> NO BOUNDS" - ] - }, - { - "cell_type": "code", - "execution_count": 22, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "CVXPY Optimization Time: Avrg: 0.1656s Max: 0.2061s Min: 0.1480s\n" - ] - } - ], - "source": [ - "track = compute_path_from_wp([0,3,3,0],\n", - " [0,0,1,1],0.05)\n", - "\n", - "track_lower, track_upper = generate_track_bounds(track,0.12)\n", - "\n", - "sim_duration = 50 #time steps\n", - "opt_time=[]\n", - "\n", - "x_sim = np.zeros((N,sim_duration))\n", - "u_sim = np.zeros((M,sim_duration-1))\n", - "\n", - "MAX_SPEED = 1.5 #m/s\n", - "MAX_ACC = 1.0 #m/ss\n", - "MAX_D_ACC = 1.0 #m/sss\n", - "MAX_STEER = np.radians(30) #rad\n", - "MAX_D_STEER = np.radians(30) #rad/s\n", - "\n", - "REF_VEL = 1.0 #m/s\n", - "\n", - "# Starting Condition\n", - "x0 = np.zeros(N)\n", - "x0[0] = 0 #x\n", - "x0[1] = -0.25 #y\n", - "x0[2] = 0.0 #v\n", - "x0[3] = np.radians(-0) #yaw\n", - " \n", - "#starting guess\n", - "u_bar = np.zeros((M,T))\n", - "u_bar[0,:] = MAX_ACC/2 #a\n", - "u_bar[1,:] = 0.0 #delta\n", - " \n", - "for sim_time in range(sim_duration-1):\n", - " \n", - " iter_start = time.time()\n", - " \n", - " # dynamics starting state w.r.t. robot are always null except vel \n", - " x_bar = np.zeros((N,T+1))\n", - " x_bar[2,0] = x_sim[2,sim_time]\n", - " \n", - " #prediction for linearization of costrains\n", - " for t in range (1,T+1):\n", - " xt = x_bar[:,t-1].reshape(N,1)\n", - " ut = u_bar[:,t-1].reshape(M,1)\n", - " A,B,C = get_linear_model(xt,ut)\n", - " xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n", - " x_bar[:,t] = xt_plus_one\n", - " \n", - " #CVXPY Linear MPC problem statement\n", - " x = cp.Variable((N, T+1))\n", - " u = cp.Variable((M, T))\n", - " cost = 0\n", - " constr = []\n", - "\n", - " # Cost Matrices\n", - " Q = np.diag([20,20,10,20]) #state error cost\n", - " Qf = np.diag([30,30,30,30]) #state final error cost\n", - " R = np.diag([10,10]) #input cost\n", - " R_ = np.diag([10,10]) #input rate of change cost\n", - "\n", - " #Get Reference_traj\n", - " #dont use x0 in this case\n", - " x_ref, d_ref = get_ref_trajectory(x_sim[:,sim_time] ,track, REF_VEL)\n", - " \n", - " #Prediction Horizon\n", - " for t in range(T):\n", - "\n", - " # Tracking Error\n", - " cost += cp.quad_form(x[:,t] - x_ref[:,t], Q)\n", - "\n", - " # Actuation effort\n", - " cost += cp.quad_form(u[:,t], R)\n", - "\n", - " # Actuation rate of change\n", - " if t < (T - 1):\n", - " cost += cp.quad_form(u[:,t+1] - u[:,t], R_)\n", - " constr+= [cp.abs(u[0, t + 1] - u[0, t])/DT <= MAX_D_ACC] #max acc rate of change\n", - " constr += [cp.abs(u[1, t + 1] - u[1, t])/DT <= MAX_D_STEER] #max steer rate of change\n", - "\n", - " # Kinrmatics Constrains (Linearized model)\n", - " A,B,C = get_linear_model(x_bar[:,t], u_bar[:,t])\n", - " constr += [x[:,t+1] == A@x[:,t] + B@u[:,t] + C.flatten()]\n", - " \n", - " #Final Point tracking\n", - " cost += cp.quad_form(x[:, T] - x_ref[:, T], Qf)\n", - "\n", - " # sums problem objectives and concatenates constraints.\n", - " constr += [x[:,0] == x_bar[:,0]] #starting condition\n", - " constr += [x[2,:] <= MAX_SPEED] #max speed\n", - " constr += [x[2,:] >= 0.0] #min_speed (not really needed)\n", - " constr += [cp.abs(u[0,:]) <= MAX_ACC] #max acc\n", - " constr += [cp.abs(u[1,:]) <= MAX_STEER] #max steer\n", - " \n", - " # Solve\n", - " prob = cp.Problem(cp.Minimize(cost), constr)\n", - " solution = prob.solve(solver=cp.OSQP, verbose=False)\n", - " \n", - " #retrieved optimized U and assign to u_bar to linearize in next step\n", - " u_bar = np.vstack((np.array(u.value[0,:]).flatten(),\n", - " (np.array(u.value[1,:]).flatten())))\n", - " \n", - " u_sim[:,sim_time] = u_bar[:,0]\n", - " \n", - " # Measure elpased time to get results from cvxpy\n", - " opt_time.append(time.time()-iter_start)\n", - " \n", - " # move simulation to t+1\n", - " tspan = [0,DT]\n", - " x_sim[:,sim_time+1] = odeint(kinematics_model,\n", - " x_sim[:,sim_time],\n", - " tspan,\n", - " args=(u_bar[:,0],))[1]\n", - " \n", - "print(\"CVXPY Optimization Time: Avrg: {:.4f}s Max: {:.4f}s Min: {:.4f}s\".format(np.mean(opt_time),\n", - " np.max(opt_time),\n", - " np.min(opt_time))) " - ] - }, - { - "cell_type": "code", - "execution_count": 23, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "#plot trajectory\n", - "grid = plt.GridSpec(4, 5)\n", - "\n", - "plt.figure(figsize=(15,10))\n", - "\n", - "plt.subplot(grid[0:4, 0:4])\n", - "plt.plot(track[0,:],track[1,:],\"b+\")\n", - "plt.plot(track_lower[0,:],track_lower[1,:],\"g-\")\n", - "plt.plot(track_upper[0,:],track_upper[1,:],\"r-\")\n", - "plt.plot(x_sim[0,:],x_sim[1,:])\n", - "plt.axis(\"equal\")\n", - "plt.ylabel('y')\n", - "plt.xlabel('x')\n", - "\n", - "plt.subplot(grid[0, 4])\n", - "plt.plot(u_sim[0,:])\n", - "plt.ylabel('a(t) [m/ss]')\n", - "\n", - "plt.subplot(grid[1, 4])\n", - "plt.plot(x_sim[2,:])\n", - "plt.ylabel('v(t) [m/s]')\n", - "\n", - "plt.subplot(grid[2, 4])\n", - "plt.plot(np.degrees(u_sim[1,:]))\n", - "plt.ylabel('delta(t) [rad]')\n", - "\n", - "plt.subplot(grid[3, 4])\n", - "plt.plot(x_sim[3,:])\n", - "plt.ylabel('theta(t) [rad]')\n", - "\n", - "plt.tight_layout()\n", - "plt.show()" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## 2-> WITH BOUNDS\n", - "if there is 90 deg turn the optimization fails!\n", - "if speed is too high it also fails ..." - ] - }, - { - "cell_type": "code", - "execution_count": 24, - "metadata": {}, - "outputs": [], - "source": [ - "from scipy.signal import savgol_filter\n", - "def compute_path_from_wp(start_xp, start_yp, step = 0.1):\n", - " \"\"\"\n", - " Computes a reference path given a set of waypoints\n", - " \"\"\"\n", - " \n", - " final_xp=[]\n", - " final_yp=[]\n", - " delta = step #[m]\n", - "\n", - " for idx in range(len(start_xp)-1):\n", - " section_len = np.sum(np.sqrt(np.power(np.diff(start_xp[idx:idx+2]),2)+np.power(np.diff(start_yp[idx:idx+2]),2)))\n", - "\n", - " interp_range = np.linspace(0,1,np.floor(section_len/delta).astype(int))\n", - " \n", - " fx=interp1d(np.linspace(0,1,2),start_xp[idx:idx+2],kind=1)\n", - " fy=interp1d(np.linspace(0,1,2),start_yp[idx:idx+2],kind=1)\n", - " \n", - " # watch out to duplicate points!\n", - " final_xp=np.append(final_xp,fx(interp_range)[1:])\n", - " final_yp=np.append(final_yp,fy(interp_range)[1:])\n", - " \n", - " \"\"\"this smoothens up corners\"\"\"\n", - " window_size = 11 # Smoothening filter window\n", - " final_xp = savgol_filter(final_xp, window_size, 1)\n", - " final_yp = savgol_filter(final_yp, window_size, 1)\n", - " \n", - " dx = np.append(0, np.diff(final_xp))\n", - " dy = np.append(0, np.diff(final_yp))\n", - " theta = np.arctan2(dy, dx)\n", - "\n", - " return np.vstack((final_xp,final_yp,theta))\n" - ] - }, - { - "cell_type": "code", - "execution_count": 62, - "metadata": {}, - "outputs": [ - { - "name": "stderr", - "output_type": "stream", - "text": [ - "/home/marcello/.conda/envs/jupyter/lib/python3.8/site-packages/cvxpy/problems/problem.py:1054: UserWarning: Solution may be inaccurate. Try another solver, adjusting the solver settings, or solve with verbose=True for more information.\n", - " warnings.warn(\n" - ] - }, - { - "name": "stdout", - "output_type": "stream", - "text": [ - "CVXPY Optimization Time: Avrg: 0.1837s Max: 0.2651s Min: 0.1593s\n" - ] - } - ], - "source": [ - "WIDTH=0.12\n", - "computed_coeff = []\n", - "\n", - "track = compute_path_from_wp([0,3,3,0],\n", - " [0,0,1,1],0.05)\n", - "\n", - "track_lower, track_upper = generate_track_bounds(track,WIDTH)\n", - "\n", - "sim_duration = 200 #time steps\n", - "opt_time=[]\n", - "\n", - "x_sim = np.zeros((N,sim_duration))\n", - "u_sim = np.zeros((M,sim_duration-1))\n", - "\n", - "MAX_SPEED = 1.5 #m/s\n", - "MAX_ACC = 1.0 #m/ss\n", - "MAX_D_ACC = 1.0 #m/sss\n", - "MAX_STEER = np.radians(30) #rad\n", - "MAX_D_STEER = np.radians(30) #rad/s\n", - "\n", - "REF_VEL = 0.4 #m/s\n", - "\n", - "# Starting Condition\n", - "x0 = np.zeros(N)\n", - "x0[0] = 0 #x\n", - "x0[1] = -WIDTH/2 #y\n", - "x0[2] = 0.0 #v\n", - "x0[3] = np.radians(-0) #yaw\n", - " \n", - "#starting guess\n", - "u_bar = np.zeros((M,T))\n", - "u_bar[0,:] = MAX_ACC/2 #a\n", - "u_bar[1,:] = 0.0 #delta\n", - " \n", - "for sim_time in range(sim_duration-1):\n", - " \n", - " iter_start = time.time()\n", - " \n", - " # dynamics starting state w.r.t. robot are always null except vel \n", - " x_bar = np.zeros((N,T+1))\n", - " x_bar[2,0] = x_sim[2,sim_time]\n", - " \n", - " #prediction for linearization of costrains\n", - " for t in range (1,T+1):\n", - " xt = x_bar[:,t-1].reshape(N,1)\n", - " ut = u_bar[:,t-1].reshape(M,1)\n", - " A,B,C = get_linear_model(xt,ut)\n", - " xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n", - " x_bar[:,t] = xt_plus_one\n", - " \n", - " #CVXPY Linear MPC problem statement\n", - " x = cp.Variable((N, T+1))\n", - " u = cp.Variable((M, T))\n", - " cost = 0\n", - " constr = []\n", - "\n", - " # Cost Matrices\n", - " Q = np.diag([20,20,10,20]) #state error cost\n", - " Qf = np.diag([30,30,30,30]) #state final error cost\n", - " R = np.diag([10,10]) #input cost\n", - " R_ = np.diag([10,10]) #input rate of change cost\n", - "\n", - " #Get Reference_traj\n", - " #dont use x0 in this case\n", - " x_ref, d_ref = get_ref_trajectory(x_sim[:,sim_time] ,track, REF_VEL)\n", - " \n", - " #Prediction Horizon\n", - " for t in range(T):\n", - "\n", - " # Tracking Error\n", - " cost += cp.quad_form(x[:,t] - x_ref[:,t], Q)\n", - "\n", - " # Actuation effort\n", - " cost += cp.quad_form(u[:,t], R)\n", - "\n", - " # Actuation rate of change\n", - " if t < (T - 1):\n", - " cost += cp.quad_form(u[:,t+1] - u[:,t], R_)\n", - " constr+= [cp.abs(u[0, t + 1] - u[0, t])/DT <= MAX_D_ACC] #max acc rate of change\n", - " constr += [cp.abs(u[1, t + 1] - u[1, t])/DT <= MAX_D_STEER] #max steer rate of change\n", - "\n", - " # Kinrmatics Constrains (Linearized model)\n", - " A,B,C = get_linear_model(x_bar[:,t], u_bar[:,t])\n", - " constr += [x[:,t+1] == A@x[:,t] + B@u[:,t] + C.flatten()]\n", - " \n", - " #Final Point tracking\n", - " cost += cp.quad_form(x[:, T] - x_ref[:, T], Qf)\n", - "\n", - " # sums problem objectives and concatenates constraints.\n", - " constr += [x[:,0] == x_bar[:,0]] #starting condition\n", - " constr += [x[2,:] <= MAX_SPEED] #max speed\n", - " constr += [x[2,:] >= 0.0] #min_speed (not really needed)\n", - " constr += [cp.abs(u[0,:]) <= MAX_ACC] #max acc\n", - " constr += [cp.abs(u[1,:]) <= MAX_STEER] #max steer\n", - " \n", - " #Track constrains\n", - " low,upp = get_track_constrains(x_ref,WIDTH)\n", - " computed_coeff.append((low,upp))\n", - " for ii in range(low.shape[1]):\n", - " constr += [low[0,ii]*x[0,ii] + x[1,ii] >= low[2,ii]]\n", - " #constr += [upp[0,ii]*x[0,ii] + x[1,ii] <= upp[2,ii]]\n", - " \n", - " # Solve\n", - " prob = cp.Problem(cp.Minimize(cost), constr)\n", - " solution = prob.solve(solver=cp.OSQP, verbose=False)\n", - " \n", - " #retrieved optimized U and assign to u_bar to linearize in next step\n", - " u_bar = np.vstack((np.array(u.value[0,:]).flatten(),\n", - " (np.array(u.value[1,:]).flatten())))\n", - " \n", - " u_sim[:,sim_time] = u_bar[:,0]\n", - " \n", - " # Measure elpased time to get results from cvxpy\n", - " opt_time.append(time.time()-iter_start)\n", - " \n", - " # move simulation to t+1\n", - " tspan = [0,DT]\n", - " x_sim[:,sim_time+1] = odeint(kinematics_model,\n", - " x_sim[:,sim_time],\n", - " tspan,\n", - " args=(u_bar[:,0],))[1]\n", - " \n", - "print(\"CVXPY Optimization Time: Avrg: {:.4f}s Max: {:.4f}s Min: {:.4f}s\".format(np.mean(opt_time),\n", - " np.max(opt_time),\n", - " np.min(opt_time))) " - ] - }, - { - "cell_type": "code", - "execution_count": 63, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "#plot trajectory\n", - "grid = plt.GridSpec(4, 5)\n", - "\n", - "plt.figure(figsize=(15,10))\n", - "\n", - "plt.subplot(grid[0:4, 0:4])\n", - "plt.plot(track[0,:],track[1,:],\"b+\")\n", - "plt.plot(track_lower[0,:],track_lower[1,:],\"g.\")\n", - "plt.plot(track_upper[0,:],track_upper[1,:],\"r.\")\n", - "plt.plot(x_sim[0,:],x_sim[1,:])\n", - "plt.axis(\"equal\")\n", - "plt.ylabel('y')\n", - "plt.xlabel('x')\n", - "\n", - "plt.subplot(grid[0, 4])\n", - "plt.plot(u_sim[0,:])\n", - "plt.ylabel('a(t) [m/ss]')\n", - "\n", - "plt.subplot(grid[1, 4])\n", - "plt.plot(x_sim[2,:])\n", - "plt.ylabel('v(t) [m/s]')\n", - "\n", - "\n", - "plt.subplot(grid[2, 4])\n", - "plt.plot(np.degrees(u_sim[1,:]))\n", - "plt.ylabel('delta(t) [rad]')\n", - "\n", - "plt.subplot(grid[3, 4])\n", - "plt.plot(x_sim[3,:])\n", - "plt.ylabel('theta(t) [rad]')\n", - "\n", - "plt.tight_layout()\n", - "plt.show()" - ] - }, - { - "cell_type": "code", - "execution_count": 66, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "import numpy as np\n", - "import matplotlib.pyplot as plt\n", - "plt.style.use(\"ggplot\")\n", - "\n", - "times = np.linspace(1,len(computed_coeff)/10,4).astype(int)\n", - "\n", - "plt.figure(figsize=(5,5))\n", - "pts = np.linspace(-2,2,100)\n", - "\n", - "\"\"\"\n", - "this needs tydy up badly...\n", - "\"\"\"\n", - "\n", - "plt.subplot(2, 2, 1)\n", - "c1 = computed_coeff[times[0]][0]\n", - "c2 = computed_coeff[times[0]][1]\n", - "for idx in range(c.shape[1]):\n", - " #low\n", - " coeff = c1[:,idx]\n", - " y = []\n", - "\n", - " for x in pts:\n", - " y.append((-coeff[0]*x+coeff[2])/coeff[1])\n", - " \n", - " plt.plot(pts,y,\"b-\")\n", - " \n", - " #high\n", - " coeff = c2[:,idx]\n", - " y = []\n", - "\n", - " for x in pts:\n", - " y.append((-coeff[0]*x+coeff[2])/coeff[1])\n", - " \n", - " plt.plot(pts,y,\"r-\")\n", - " plt.xlim((-2, 2))\n", - " plt.ylim((-2, 2))\n", - "\n", - "\n", - "plt.subplot(2, 2, 2)\n", - "c1 = computed_coeff[times[1]][0]\n", - "c2 = computed_coeff[times[1]][1]\n", - "for idx in range(c.shape[1]):\n", - " #low\n", - " coeff = c1[:,idx]\n", - " y = []\n", - " for x in pts:\n", - " y.append((-coeff[0]*x+coeff[2])/coeff[1])\n", - " \n", - " plt.plot(pts,y,\"b-\")\n", - " \n", - " #high\n", - " coeff = c2[:,idx]\n", - " y = []\n", - " for x in pts:\n", - " y.append((-coeff[0]*x+coeff[2])/coeff[1])\n", - " \n", - " plt.plot(pts,y,\"r-\")\n", - " plt.xlim((-2, 2))\n", - " plt.ylim((-2, 2))\n", - "\n", - "\n", - "plt.subplot(2, 2, 3)\n", - "c1 = computed_coeff[times[2]][0]\n", - "c2 = computed_coeff[times[2]][1]\n", - "for idx in range(c.shape[1]):\n", - " #low\n", - " coeff = c1[:,idx]\n", - " y = []\n", - "\n", - " for x in pts:\n", - " y.append((-coeff[0]*x+coeff[2])/coeff[1])\n", - " \n", - " plt.plot(pts,y,\"b-\")\n", - " \n", - " #high\n", - " coeff = c2[:,idx]\n", - " y = []\n", - " for x in pts:\n", - " y.append((-coeff[0]*x+coeff[2])/coeff[1])\n", - " \n", - " plt.plot(pts,y,\"r-\")\n", - " plt.xlim((-2, 2))\n", - " plt.ylim((-2, 2))\n", - "\n", - "plt.subplot(2, 2, 4)\n", - "c1 = computed_coeff[times[3]][0]\n", - "c2 = computed_coeff[times[3]][1]\n", - "for idx in range(c.shape[1]):\n", - " #low\n", - " coeff = c1[:,idx]\n", - " y = []\n", - "\n", - " for x in pts:\n", - " y.append((-coeff[0]*x+coeff[2])/coeff[1])\n", - " \n", - " plt.plot(pts,y,\"b-\")\n", - " \n", - " #high\n", - " coeff = c2[:,idx]\n", - " y = []\n", - " for x in pts:\n", - " y.append((-coeff[0]*x+coeff[2])/coeff[1])\n", - " \n", - " plt.plot(pts,y,\"r-\")\n", - " plt.xlim((-2, 2))\n", - " plt.ylim((-2, 2))\n", - "\n", - "plt.tight_layout()\n", - "plt.show()" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Python 3", - "language": "python", - "name": "python3" - }, - "language_info": { - "codemirror_mode": { - "name": "ipython", - "version": 3 - }, - "file_extension": ".py", - "mimetype": "text/x-python", - "name": "python", - "nbconvert_exporter": "python", - "pygments_lexer": "ipython3", - "version": "3.8.5" - } - }, - "nbformat": 4, - "nbformat_minor": 4 -} diff --git a/notebooks/MPC_racecar_crosstrack.ipynb b/notebooks/cte_based_formulation/MPC_racecar_crosstrack.ipynb similarity index 99% rename from notebooks/MPC_racecar_crosstrack.ipynb rename to notebooks/cte_based_formulation/MPC_racecar_crosstrack.ipynb index d6b4e58..804a892 100644 --- a/notebooks/MPC_racecar_crosstrack.ipynb +++ b/notebooks/cte_based_formulation/MPC_racecar_crosstrack.ipynb @@ -564,15 +564,6 @@ "The controller generates a control signal over a fixed lenght T (Horizon) at each time step." ] }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "![mpc](img/mpc_block_diagram.png)\n", - "\n", - "![mpc](img/mpc_t.png)" - ] - }, { "cell_type": "markdown", "metadata": {}, diff --git a/notebooks/diff_drive_kinematics/MPC_cte_cvxpy.ipynb b/notebooks/old_scipy_implementation/MPC_cte_cvxpy.ipynb similarity index 100% rename from notebooks/diff_drive_kinematics/MPC_cte_cvxpy.ipynb rename to notebooks/old_scipy_implementation/MPC_cte_cvxpy.ipynb diff --git a/notebooks/diff_drive_kinematics/MPC_tracking_cvxpy.ipynb b/notebooks/old_scipy_implementation/MPC_tracking_cvxpy.ipynb similarity index 100% rename from notebooks/diff_drive_kinematics/MPC_tracking_cvxpy.ipynb rename to notebooks/old_scipy_implementation/MPC_tracking_cvxpy.ipynb