mpc_python_learn/.ipynb_checkpoints/MPC_cvxpy-checkpoint.ipynb

1175 lines
197 KiB
Plaintext

{
"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",
"* $\\theta$ heading of the robot\n",
"* $\\psi$ heading error = $\\psi = \\theta_{ref} - \\theta$\n",
"* $cte$ crosstrack error = lateral distance of the robot from the path \n",
"\n",
"The inputs of the model are:\n",
"\n",
"* $v$ linear velocity of the robot\n",
"* $w$ angular velocity of the robot\n",
"\n",
"These are the differential equations f(x,u) of the model:\n",
"\n",
"* $\\dot{x} = v\\cos{\\theta}$ \n",
"* $\\dot{y} = v\\sin{\\theta}$\n",
"* $\\dot{\\theta} = w$\n",
"* $\\dot{\\psi} = -w$\n",
"* $\\dot{cte} = v\\sin{-\\psi}$\n",
"\n",
"The **Continuous** State Space Model is\n",
"\n",
"$ {\\dot{x}} = Ax + Bu $\n",
"\n",
"with:\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 \\theta} & \\frac{\\partial f(x,u)}{\\partial \\psi} & \\frac{\\partial f(x,u)}{\\partial cte} \\\\\n",
"\\end{bmatrix}\n",
"\\quad\n",
"=\n",
"\\quad\n",
"\\begin{bmatrix}\n",
"0 & 0 & -vsin(\\theta) & 0 & 0 \\\\\n",
"0 & 0 & vcos(\\theta) & 0 & 0 \\\\\n",
"0 & 0 & 0 & 0 & 0 \\\\\n",
"0 & 0 & 0 & 0 & 0 \\\\\n",
"0 & 0 & 0 & vcos(-\\psi) & 0 \n",
"\\end{bmatrix}\n",
"\\quad $\n",
"\n",
"\n",
"$ B = \\quad\n",
"\\begin{bmatrix}\n",
"\\frac{\\partial f(x,u)}{\\partial v} & \\frac{\\partial f(x,u)}{\\partial w} \\\\\n",
"\\end{bmatrix}\n",
"\\quad\n",
"=\n",
"\\quad\n",
"\\begin{bmatrix}\n",
"\\cos{\\theta_t} & 0 \\\\\n",
"\\sin{\\theta_t} & 0 \\\\\n",
"0 & 1 \\\\\n",
"0 & -1 \\\\\n",
"\\sin{(-\\psi_t)} & 0 \n",
"\\end{bmatrix}\n",
"\\quad $\n",
"\n",
"discretize with forward Euler Integration for time step 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",
"* ${\\theta_{t+1}} = \\theta_{t} + w_t*dt$\n",
"* ${\\psi_{t+1}} = \\psi_{t} - w_t*dt$\n",
"* ${cte_{t+1}} = cte_{t} + v_t\\sin{-\\psi}*dt$\n",
"\n",
"The **Discrete** State Space Model is then:\n",
"\n",
"${x_{t+1}} = Ax_t + Bu_t $\n",
"\n",
"with:\n",
"\n",
"$\n",
"A = \\quad\n",
"\\begin{bmatrix}\n",
"1 & 0 & -v\\sin{\\theta}dt & 0 & 0 \\\\\n",
"0 & 1 & v\\cos{\\theta}dt & 0 & 0 \\\\\n",
"0 & 0 & 1 & 0 & 0 \\\\\n",
"0 & 0 & 0 & 1 & 0 \\\\\n",
"0 & 0 & 0 & vcos{(-\\psi)}dt & 1 \n",
"\\end{bmatrix}\n",
"\\quad\n",
"$\n",
"\n",
"$\n",
"B = \\quad\n",
"\\begin{bmatrix}\n",
"\\cos{\\theta_t}dt & 0 \\\\\n",
"\\sin{\\theta_t}dt & 0 \\\\\n",
"0 & dt \\\\\n",
"0 & -dt \\\\\n",
"\\sin{-\\psi_t}dt & 0 \n",
"\\end{bmatrix}\n",
"\\quad\n",
"$\n",
"\n",
"This State Space Model is not linear (A,B are time changing), to linearize it the **Taylor's series expansion** is used around $\\bar{x}$ and $\\bar{u}$:\n",
"\n",
"$ \\dot{x} = f(x,u) \\approx f(\\bar{x},\\bar{u}) + A(x-\\bar{x}) + B(u-\\bar{u})$\n",
"\n",
"So:\n",
"\n",
"$ x{t+1} = x_t + (f(\\bar{x},\\bar{u}) + A(x-\\bar{x}) + B(u-\\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 Discrete linearized kinematics model is\n",
"\n",
"$ x_{t+1} = A'x_t + B' u_t + C' $\n",
"\n",
"with:\n",
"\n",
"$ A' = I+dtA $\n",
"\n",
"$ B' = dtB $\n",
"\n",
"$ C' = dt(f(\\bar{x},\\bar{u}) - A\\bar{x} - B\\bar{u}) $"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"------------------\n",
"NB: psi and cte are expressed w.r.t. the track as reference frame.\n",
"In the reference frame of the veicle the equtions would be:\n",
"* psi_dot = w\n",
"* cte_dot = sin(psi)\n",
"-----------------"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"### Kinematics Model"
]
},
{
"cell_type": "code",
"execution_count": 2,
"metadata": {},
"outputs": [],
"source": [
"# Control problem statement.\n",
"\n",
"N = 5 #number of state variables\n",
"M = 2 #number of control variables\n",
"T = 20 #Prediction Horizon\n",
"dt = 0.25 #discretization step\n",
"\n",
"x = cp.Variable((N, T+1))\n",
"u = cp.Variable((M, T))"
]
},
{
"cell_type": "code",
"execution_count": 3,
"metadata": {},
"outputs": [],
"source": [
"def get_linear_model(x_bar,u_bar):\n",
" \"\"\"\n",
" \"\"\"\n",
" \n",
" x = x_bar[0]\n",
" y = x_bar[1]\n",
" theta = x_bar[2]\n",
" psi = x_bar[3]\n",
" cte = x_bar[4]\n",
" \n",
" v = u_bar[0]\n",
" w = u_bar[1]\n",
" \n",
" A = np.zeros((N,N))\n",
" A[0,2]=-v*np.sin(theta)\n",
" A[1,2]=v*np.cos(theta)\n",
" A[4,3]=v*np.cos(-psi)\n",
" A_lin=np.eye(N)+dt*A\n",
" \n",
" B = np.zeros((N,M))\n",
" B[0,0]=np.cos(theta)\n",
" B[1,0]=np.sin(theta)\n",
" B[2,1]=1\n",
" B[3,1]=-1\n",
" B[4,0]=np.sin(-psi)\n",
" B_lin=dt*B\n",
" \n",
" f_xu=np.array([v*np.cos(theta),v*np.sin(theta),w,-w,v*np.sin(-psi)]).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 A_lin,B_lin,C_lin"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"Motion Prediction: using scipy intergration"
]
},
{
"cell_type": "code",
"execution_count": 4,
"metadata": {},
"outputs": [],
"source": [
"# Define process model\n",
"def kinematics_model(x,t,u):\n",
" \"\"\"\n",
" \"\"\"\n",
"\n",
" dxdt = u[0]*np.cos(x[2])\n",
" dydt = u[0]*np.sin(x[2])\n",
" dthetadt = u[1]\n",
" dpsidt = -u[1]\n",
" dctedt = u[0]*np.sin(-x[3])\n",
"\n",
" dqdt = [dxdt,\n",
" dydt,\n",
" dthetadt,\n",
" dpsidt,\n",
" dctedt]\n",
"\n",
" return dqdt\n",
"\n",
"def predict(x0,u):\n",
" \"\"\"\n",
" \"\"\"\n",
" \n",
" x_bar = np.zeros((N,T+1))\n",
" \n",
" x_bar[:,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_bar[:,t]=x_next[1]\n",
" \n",
" return x_bar"
]
},
{
"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 4.51 ms, sys: 390 µs, total: 4.9 ms\n",
"Wall time: 4.39 ms\n"
]
}
],
"source": [
"%%time\n",
"\n",
"u_bar = np.zeros((M,T))\n",
"u_bar[0,:] = 1 #m/s\n",
"u_bar[1,:] = np.radians(-10) #rad/s\n",
"\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0\n",
"x0[1] = 1\n",
"x0[2] = np.radians(0)\n",
"x0[3] = 0\n",
"x0[4] = 1\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": "iVBORw0KGgoAAAANSUhEUgAAAagAAAEYCAYAAAAJeGK1AAAABHNCSVQICAgIfAhkiAAAAAlwSFlzAAALEgAACxIB0t1+/AAAADl0RVh0U29mdHdhcmUAbWF0cGxvdGxpYiB2ZXJzaW9uIDMuMC4zLCBodHRwOi8vbWF0cGxvdGxpYi5vcmcvnQurowAAIABJREFUeJzs3XmcjeX/x/HXdc/YlyyjhAhJkZBC6RtKRZuWbxdFtIhCKUqlbO2lkjWJCln6FKLSqkV9i5T2XbstWcqe5b5+f9zHr6EZc8acc+5zznyej8c85pz7PnPfb8fc8zn3fV+Lcc6hlFJKJRsv7ABKKaVUTrRAKaWUSkpaoJRSSiUlLVBKKaWSkhYopZRSSUkLlFJKqaSkBUoppVRS0gKllFIqKWmBUkoplZQyww5QADoEhkoUE3aABNLjSiVKnsdVKhcoVqxYkePyrKws1qxZk+A0OdMsOUuVLFWqVElwmtiy1rYFRgAZwAQRuTevn9HjKn80S85icVzpJT6l0pS1NgMYA7QD6gEXWWvrhZtKqehpgVIqfTUFlorIjyKyHZgBtN+fDbmvPmHHD9/ENJxSeUnpS3xKqX2qCvyW7fkyoNneL7LWdge6A4gIWVlZe6x3zrFuzlTW/fw9Jc/uSOmLumGKFY9j7LxlZmb+K2dYNEvOYpFFC5RShZyIjAfGR566nO4buD6DKfHCDLbMmcaW997Au6QX5siGCc2ZXarca0m0VMmi96CUUsuBQ7I9rxZZlm+mZGnK9rwZ74a7wHj4Dw3Ef3IEbvPGmARVKid6BqVU+loM1LHW1iQoTB2BiwuyQVO3Ad7gEbgXnsa9Mgv32YeYi3pgjm2BMYWpNb5KBD2DUipNichOoDfwCvB1sEi+LOh2TdFieOd3wbttOFSohBt/P/6Yu3DrkuPSkkofegalVBoTkXnAvHhs2xxSE++WYbj5c3FzpuIP7oW5oCvmpLYYTz/7qoLTAqVUHFhro/0L7UQkZUdvMBkZmNPOwzU+Hv+psbip43CL3sbr0htz8CF5b0CpfdCPOUrFx44ovnYCm8IKGEumUmW864ZiLusDK37Dv70P/gszcDt3hB1NpTA9g1IqPrYC9fN4jQE+SUCWhDDGYE44BXfUMbgZE3BzpuEWvxucTdU+Iux4KgVpgVIqPh4QkV/yepG19qFEhEkkU7Y8pvuNuGat8Kc+gn/fTZiTz8Kc2xlTvETY8VQK0QKlVByIyJAoX3d7nKOExjQ8Du/w+rjZk3FvvID7eCFe556YBk3CjqZShBYopeLMWlsrl1V/AytFxE9knkQyJUpiLr4K1/Qk/Mlj8EcOxTRrienQDVPmgLDjqSSnBUqp+FvKP/MsGfacc8m31s4FeorI7wlPliDmsHp4Ax/GvfQMbt6zuC+XBEWqWSvt4Ktypa34lIq/K4FpwOFAcaAuMAXoCTQg+KA4JrR0CWKKFME752K8gQ/DgVVwE4fjPzwEtyZt67IqoKQ4g7LWHgJMBg4i+HQ5XkRGhJtKqZgZChwmItsiz5daa3sC34nIo9baS4HvQ0uXYKZqdbyb7sW9+RJu9hT8wb0x53UOGlJ4GWHHU0kkWc6gdgL9RKQe0BzopROrqTTiAYfutaw6wSy3AJtJkg+LiWK8DLxTzsIbOhrqNsA9PRH/nv64ZT+FHU0lkaQ4KERkJbAy8nijtfZrgrlsvgo1mFKx8TDwhrX2CYL5maoBl0WWA5wBvB9StlCZipXwrhmI+2ABbsZj+Hf2xZx+AeYsiylSNOx4KmTGueQaZcVaeyiwADhKRDbstS77xGpNtm/fnuM2MjMz2blzZ5yTRkez5CxVshQtWhSChg0FYq1tC1wIVCH4MCYi8nJBtxsHbsWKFTmuiPdcQ27jBtwzE3HvvwmVq+Jd0htzeM59nVNl3qNES5Uskfmg8jyukqpAWWtLA28Dd4nIrDxeHtqBlB+aJWepkiXaAymNhH5cuS8/xp8yBtauxrRsizm/K6ZkqVCyREOz5CwWx1VSXOIDsNYWAWYCU6MoTkqlDGttMWAQcBFQUUQOsNaeBhwuIqPDTZd8TP3GeENH456bipv/PO7TxXidemAaNQ87mkqwpGgkYa01wETgaxFJu6FfVKE3HDgK6MQ/faC+BK4OLVGSM8WK43W4Au+W+6FUafwxd7Nr3L24v9aHHU0lUFIUKKAFcAlwsrX2k8jXGWGHUipGzgMuFpH3AR9ARJYTNARS+2BqHo5323DMuZ3h08X4g3riv/sayXRrQsVPUlziE5F3KVzX+VXhsp29jjVrbSVgbThxUovJzMScaXFNTsCfMgY3aRR/LnkP1/FKzIFVwo6n4ihZzqCUSmfPAJOstTUBrLUHA6OBGaGmSjGmcjW8fndhLunJjh++wR9yLf7LM3G7doUdTcWJFiil4m8A8BPwOVCOYNSIFQQjTKh8MJ6Hd1JbKo6cBvUb42ZOwr+7H+6XH8KOpuIgKS7xKZXORGQ7cD1wfeTS3ppUnuY9GWRUrITXcwAseR9/+qP4d/fDnNoec/bFmGLFwo6nYkQLlFJxsI8pNgDKWGsBEJEfE5Mo/RhjoMkJeEccjZv5JO6V2bgl7+Nd0gtzZMOw46kY0AKlVHzsnmIj+/QauxsCZT970tFRC8iUKo3p0juYc2rKGPyHBmJatMFceDmmVOmw46kC0AKlVByIyP/f37XWXga0AYYAvwA1CDruzg8lXJoyRxyNN3gk7vkZuFdn4z7/EO+i7tCkhc45laK0QCkVf3cAdURka+T599baHsB3wJOhpUpDpmgxzAVdccediD9pNP6j90PDpngXX4WpkBV2PJVPaVeg/McfZt3a39nlHGQWgcwimBIloWTp4KtsOUz5ilA+CypkBc/105WKr93TbXydbVkN9PJe3JjqtfEGPIB7fS5u7lT8wb0wF3TFnNQW42nj5VSRdgWKkqUwW0vB1q2wYzts2YxbtQy2bA6+nL/HDQCKl4CDqmIOrgZVamBq1IYatTGlyoT1L1DpZzh7TrdxCHBpZLmKE5ORgTn9PFzj5vhPjcVNHYdbtACvS+/geFdJL+0KlNfxSsrnMoqu833YvBHWr4H1a3FrVsPvy3G/L8d9+wUsfOuf4lWpMqZOfTi8PubwoyDrID3TUvtFRIZZaz8nmG6jMcF0G5cn6XQbaccceDDe9bfj3nsDJxPxb78Wc2YHTNvzMZlFwo6n9iHtCtS+GM+DMgcEX9Vr/2tsJbdpA/z6I+6XH3A/fYv77AN4b35QtCpVxjQ4FtPgWKh7lE6mpvIlUoxiXpCstcOAswmGU/oBuExE/oysuwW4AtgFXCsir8R6/6nCGINpcQquwTG46Y/h5kzFffhucDZVq27Y8VQu9GJsNqZ0WUy9RnjtLiCj5wC8B6fgDRmNubgHVK6Ge/dV/BFD8Ptegj/xIdynH+B27Ag7tkpC1tpuUb7uigLu6jWCyT2PJmh0cUtku/WAjkB9oC0w1lpb6O95mbLl8Xr0x+t1K2zehH9vf/wZj+G2bc37h1XCFaozqPwyngdVq2OqVofWZ+K2/w3ffo5b8n7wtfCt4J5Xs5aYE0/FVK8ddmSVPB6y1k5k34MgG2AYwVQz+0VEXs32dCHw38jj9sAMEfkb+MlauxRoSiGdWn5vplEzvLoNcLMmB3NOfbIIr/PVmKOahB1NZaMFKh9M0WIQucznOl0FX3+GW/gW7p3XcG/OCy4btmqHad5KLwGq0kBec9obYFsM93k58HTkcVWCgrXbMnKZ3sNa2x3oDiAiZGXl3Bw7MzMz13WJFrMsfW5j+2nnsGHMPewaMZTiLU+nzOV98MqWS3yWGEi3LFqg9pPJLAINmmAaNMFt7oFb9BZuwSu4yaNxs6dgWrbDtD4DkuSXRSVczShfl+eYfNba14HKOay6VUTmRF5zK0FBnBp1wggRGQ+M350nt2m6U2U68XyrVAV360OYecK2l2ay7aP3MR26BVdGomgYlbbvSwFFMeV7nrRAxYApVRpz8lm41mfCN5/hvz4X98IM3Kuz2Hj6ebiT2mHKVQg7pkogEfklhttqs6/11tpLgbOAU7INQrucoDn7btUiy1QOTJEimPadcMeeiD9pFG7iQ7hFb+F17ompeGDY8QotLVAxZIyBIxuScWRD3KpluHnPsOXFZ+Hl2ZiWbTFnWkzpsmHHVGnEWtsW6A+0FJEt2VbNBaZZax8CqgB1gA9CiJhSTNUaeDffh3tzHm72FPzBvTHnXYJpfQbGK/RtTBJOW/HFialcDe/y66k4ejqm6X9w81/AH9AD/6WZQWMLpWJjNFAGeM1a+4m1dhyAiHwJCPAVQfP2XiKiM/tFwXgZeKecjTd0NNSpj5vxGP69N+GWx+ykWEXJOJey09K4FStW5LgiGa/DuuW/4s+aBJ8thooH4nW8EtOoWShZkkGqZIlcKy9MPbRT6riKN+cc7oMFuBmPwdYtmHYXYM6wmCL/dPAtjO9LNGJxXCXNJb7IpYoRBOOTTRCRe0OOFFOmanUyrhmI++Yz/Onj8cfcBUcfFxSqSjnd/1ZKhc0Yg2nWElevMU4m4l54Gvfh/4IOvnXqhR0v7SVFgYp0IBwDnErQHHaxtXauiHwVbrLYM0ccjTfw4aDvxfPT8YdcEwxi2eoMHcQyzVhrs4AuwJlAQ+AA4C/gU+AlYJKI/BFeQhUtU6Ys5orrcc1a4j81Fv/+m4MuJed3DTtaWou6QFlrhxMcUJ/EIUdTYOnu2UWttTMIOhrmu0ANGlSW77/PZMeOijGOuH+KFMktSzfcjq7w+3JYsAlKbgoGrS0av/5TuWdJvGTK0qRJBrfcEtttWmvvBToB8wg64n4NbCS4X3Qk0BJYYq2dKiI3x3bvKl7MUcfgDRmFmzMt0sH3A7Zd3R9qHRl2tLSUnzOoDOAVa+0fwBRgqogsi1GOqgSjPO+2DPjXDZpoOhSWKJGBMYYiRZJjEMh9ZilSBHdoHfw/17Jr5TL4ZSlelepklCuf+CwJlkxZPM/Eo3PjMuCwyEgOe/uYoIVdcSCqIZFU8jDFS2A6XIFr+h/8SaP4656bME1aYC7qjjkgPsduYRV1gRKRa6211wPtCD4Z3matXQRMBmaJyKY4ZcyeIc8Ohbfckjo3CrNzaw3+Yw/AD98E01Vf1B1TrHgoWRIhVbJE26FwbyIyevdja21lEVmVw8vKZX+dSi2m5uF4tw2nxDsvs1mewH39STDNfIs2OvNBjOTrpoeI7BKRF0TkIqA5UIlgRtBV1toJ1toch1KJQqHvVGgqHoh34z2YMyzuvfn499yI+yOnv2kqBX2Xy/K0u8da2JjMTEpfeCne4BFQtQZu0ij8hwbiVq8MO1payFcjCWttWYI5bToDRwMzgZ7Ar0A/ghu/R+9HjsVAHWttTYLC1BG4eD+2k9JMRgbmvM64uvXxHx2Gf2dfvO43Yuo3DjuaKph/fZyOHEt+CFlUHJjK1fBuuBv3zqu4mU8GjZ/aX4xp0x6ToR1891d+Gkk8C5wOLADGAc9lv75ure1L0EIp30Rkp7W2N/AKwb2uxyMdDQslU68x3m0P4Y+5C3/EUEzHbngnnxV2LJVP1trfCMbaK2Gt/XWv1RWB6YlPpeLFeB6mZVvc0cfhTxuHe/ZJ3AcL8LpeozMd7Kf8nEEtBHrnci0dEfGttQftbxARmUfQ4kkBplJlvFuG4U94EDd9PP7aP4Lm6NoUPZV0Jjh7mgdckm25A34XkW9DSaXiypSviNdzACx5D3/ao/h39cOcei7mnIuCGRFU1PLTSOKBKF6zJa/XqOiZYsXxrr4ZN+Mx3Kuzg6nqL79Op6lOESLyNgT9ofTYKFyMMdCkBd4RDXHPPoF7ZRZuyXtBB98j9ucuSOGkH8eTnPEyMBf1wPz3Utzid/DH3oPbsT3sWCoP1tprrbXFIPcPbtbaYtbaaxObTCWSKVUar+s1eH3vAMB/8LZgtPTNcW/0nBaSYiQJtW/GGMzp5+OXKIl76hH8kbfj9boVU7xE2NFU7ioDS62184C3gW/5p6Pu4UArgi4bk8MKqBLHHNkw6OD7/Azcq7Nxny3Gu7gHHHOCNknfBz2DSiHeSW0xl18H336BP/pOHRU9iYnIAKAx8D1wBUEL1y8I7kddDnwDNBaR20ILqRLKFC2Gd0FXvFsfhHIV8cfdF1wRWb827GhJS8+gUozXvDU+Bvf4cPxH7sXrOWCPkZVV8hCRNcADkS+lADDVa+MNeAD3+hzcnGn4g3thLrgU85/TtBHUXvTdSEFe81aYzj3hi4+CVn6+TvOjVCoxGRl4p5+PN2Qk1DgM99RY/AcG4FbFavS49KBnUCnKO+l0/L+3BVMAyOPQoZtey05SkU65QwgGiM0iW8ddEakeUiyVBMyBVfD63oF7bz5OJuIPvRZzVkfM6edpa130DCqleae2x7RpH4yq/PrcsOOo3I0FjgFuByoA1xCMvjI8zFAqORhj8Fq0wbt9LKZRc9xzT+Hf2Rf3U24jZBUeWqBSnLnwMjjmBNwzj+O++yLsOCpnpwEXiMgcYFfkewf27LyrCjlzQHm8Hv3xet0Kmzfh33Mj/tMTcNu2hh0tNHqJL8UZz8O74nrcW0dAbZ2TJkl5/DMM2CZr7QHASuCw8CKpZGUaNcOr2wA3azLu9bm4jxfide6JOeqYsKMlnJ5BpQFTtBjeaefqoJTJ61OC+08A7xBc8nuE3Ec5V4WcKVESr9NVeP3vhSJF8UcMwZ84HLdxQ9jREkoLlFLxdyXwc+RxH2ArUI5gOnilcmXq1MMb9DDmrA64xQvwB/XEX/Q2zrmwoyWEXuJTKv4qicgiABFZTWQWXWtt01BTqZRgihTFtO+Ea9ICf/Jo3IQHcYvexut0NaZipbDjxZWeQSkVf6/lsvzlhKZQKc1UOxTv5vswHa+E777AH9wLf/4Lad0PUs+glIoTa61H0OfJWGsNe05cWBvYGUowlbKMl4E55Wxco2b4T43FzRiP++BtvC7XYKqmX5c6PYNSKn52AtuBkpHHO7J9fUXQWEKpfDMVD8S7djDmir6wegX+Hdfhz5mWdjMd6BmUUvFTk+Cs6W3gpMhjF/n6Q0QKbwcXVWDGGEzzVrj6jYMRZV6YwdpPFuI6XY05LD26nGiBUipOROSXyMMa8P+X/A4SkZXhpVLpxpQ5AHNFX1yzlrhp4/DvvxnTqh3mvC6YEiXDjlcgWqCUijNrbTmCy3n/Jbi8V8paew7QNFbTbVhr+xGMml5JRNZE7nmNAM4AtgCXisiSWOxLJSdzVBMqjJjKmokjcG+8gPvkg6ClX8Pjwo6230IvUNbaYcDZBNfqfwAuE5E/w02lVEyNA9YTnEl9FVn2PvAgUOACZa09hGA4pV+zLW4H1Il8NSPoGNysoPtSyc0rURKv45W4pifhTx6NP/oOzHH/wXTshilbPux4+ZYMjSReA44SkaMJetbfEnIepWLtFODayKU9ByAifwAHxmj7w4H+u7cd0R6YLCJORBYC5ay1B8dofyrJmVp18W57KOg/9fH7+AN74f9vfsp18A39DEpEXs32dCHBZRCl0slfBNNs/P+9J2tt9ezP95e1tj2wXEQ+tdZmX1UV+C3b82WRZf/ap7W2O9AdQETIysrKcV+ZmZm5rks0zZKzf2W5tBc725zJhrH3sePJERRZ8j/KXH0TmZWrJj7L/mwjRlli5XLg6dxW6oFUMJolZwnIMgGYaa29FfCstccDdxNc+suTtfZ1oHIOq24FBhBc3ttvIjIeGB956tasWZPj67KysshtXaJplpzlmKV4adx1QzELXmH7zCdZ26cTpn0nzCnnxHX8zn29L1WqVIlqGwkpUPs6wCJTDxA5eHcCU3Pbjh5IBaNZchaLAykP9xGMvzcGKAI8DjxK0IghTyLSJqfl1toGBE3Zd589VQOWRIZQWg4cku3l1SLLVCFkPA/Tqh2uYVP8qY/gnnkC98E7eF16Y6rXCjterkwyXJO01l4K9ABOEZEtUf6YW7FiRY4rUuWPX6JplpxFUaBSYqpia+3PwLGRVnxnAr0JWvE1A0aKSDRj/+lxlU+plsU5B0vew5/2KGzaEMzee1ZHTNFiCcsS7XEV+iU+a21bghu8LfNRnJRKKdbaukBDoHT25SLyeJx2OY+gOC0laGZ+WZz2o1KMMQaatMA74ujgTOqlmbiP3gvOpuo2CDveHkIvUMBooBjwWuQyxUIRuSrcSErFjrV2ADCIYF6o7B/CHMHlvpgQkUOzPXZAr1htW6UfU6oM5tJrcc1a4k8Zg//ArZj/nIb576WYkqXz3kAChF6gRERnFVXp7jqCTrmfhR1Eqb2ZIxviDR6Fe34a7tU5uM8W413cA3PMCWFHS4p+UEqlu63AN2GHUCo3plgxvP9ehnfrg1C2HP4j97Jr7N24P9eGmiv0Myil0lFk3L3dBgKjrLVDgN+zv05E/ETmUmpfTI3aeAMexL0+Bzd3Ov6gXsElvxNPw3iJP5/RAqVUfOzkn5EddrdW6pZt/e6RzePXEUWp/WAyMzFtL8Adczz+5DG4KWODGXwv6YWpXC2hWbRAKRUfNcMOoFRBmAOr4PW7E/e/13HPPI4/tA/mrA6Y08/HZCamdGiBUioOsk21gbX2BhF5YO/XWGv7Ag8lNJhS+WCMwZx4Kq7Bsbjp43HPPYX78N1gBt+adeK+f20koVT8DcpleUym2lAq3swB5fGuugmv1wDYtAH/nhvxn56I+3tbXPerZ1BKxYm19uTIwwxrbWv27DlfC9iY+FRK7T/TqDne4Q1wsycHDSk+fj+4N1W/cVz2pwVKqfiZGPlenD075DpgFXBNwhMpVUCmZClMp6txTVviTx6F//BgzPGtMfYKTOmyMd2XFiil4kREagJYayeLSJew8ygVS6ZOPbxBI3AvCu7lmbgvlmA6dMM0PSkYTikG9B6UUnGmxUmlK1OkKN65nfFuGw5ZB+EmPIg/6g7c2j9isn0tUEoppQrEVDsU7+b7MB2ugG8/xx/cmy3znsX5BeuHrgVKKaVUgRkvA69Ne7yho6H2EWx98yX+6au+f/QelFJKqZgxWQfhXTeE8iWKsW7b9gJtS8+glFJKxZQxBi8GLfq0QCmllEpKWqCUUkolJeNcwW5ihShlg6uUE5tOHalBjyuVKHkeV6l8BmVy+7LWfrSv9Yn80ixpkaUwSZf/M82S/FnylMoFSimlVBrTAqWUUioppWuBGh92gGw0S840S+pJpvdJs+QsrbKkciMJpZRSaSxdz6CUUkqluJQe6sha2xYYAWQAE0Tk3r3WFwMmA02AtUAHEfk5DjkOieznIIJmuuNFZMRer2kFzAF+iiyaJSK3xzpLZF8/E0yGtwvYKSLH7rXeELxvZwBbgEtFZEkcctQFns62qBYwSEQezvaaVsTpfbHWPg6cBawWkaMiyypEMh0K/AxYEVmfw8925Z8Zb+8UkUmxyJSq8jrWEpzlZ/bx+x3nfe/371SCsgwBrgR2Dyc+QETmJSBLjn8DC/repOwZlLU2AxgDtAPqARdZa+vt9bIrgPUichgwHLgvTnF2Av1EpB7QHOiVQxaAd0SkUeQrLsUpm9aR/eR08LYD6kS+ugOPxCOAiHy7+99L8CFhCzA7h5fG6315Emi717KbgfkiUgeYH3m+h8hBNRhoBjQFBltry8cwV0qJ8lhLtH39fsfTk+zH71QCswAMz3Y8xb04ReT2N7BA703KFiiCPxxLReRHEdkOzADa7/Wa9sDuT77PAqdEzh5iSkRW7j4DEZGNwNdA1VjvJ4baA5NFxInIQqCctfbgOO/zFOAHEfklzvv5fyKyAFi31+LsvxOTgHNz+NHTgddEZF3k095r5PyHoLCI5lgrFArwO5WoLKHYx9/AAr03qXyJryrwW7bnywg+8eb4GhHZaa39C6gIrIlXKGvtoUBjYFEOq4+31n4KrABuEJEv4xTDAa9aax3wqIjs3Zomp/euKrAyTnkAOgLTc1mXqPcF4CAR2f3vXEVwSWJvub0/hVU0x1oi5fX7nWjR/E4lUm9rbRfgQ4Kzmrhfbsxur7+BBXpvUvkMKulYa0sDM4HrRGTDXquXADVEpCEwCngujlFOFJFjCC7J9LLWnhTHfeXJWlsUOAd4JofViXxf9iAiDh3aJxUl1e93dknwO/UIUBtoRPCB88FE7nxffwP3571J5QK1HDgk2/NqkWU5vsZamwkcQNBYIuastUUI/mOmisisvdeLyAYR2RR5PA8oYq3NikcWEVke+b6a4J5P071eEs17F0vtgCUi8vveKxL5vkT8vvtyZuT76hxek+j3J9kl1fsRxe93okXzO5UQIvK7iOwSER94jAS+N7n8DSzQe5PKBWoxUMdaWzPyCb0jMHev18wFukYe/xd4I1LFYypyX2si8LWIPJTLayrvvv9lrW1K8N7HvFhaa0tZa8vsfgycBnyx18vmAl2stcZa2xz4K9tpeDxcRC6X9xL1vmST/XeiK0ELwr29ApxmrS0faRxxWmRZYRXNsZYQUf5+J1o0v1MJsde95PNI0Huzj7+BBXpvUrqjrrX2DOBhgqavj4vIXdba24EPRWSutbY4MIXgeug6oKOI/BiHHCcC7wCfA35k8QCgOoCIjLPW9gauJmjtshXoKyLvxSFLLf5pKZcJTIu8L1dly2KA0QQ3/rcAl4nIh7HOEslTCvgVqCUif0WWZc8St/fFWjsdaAVkAb8TtMx7DhCC/5tfCJq9rrPWHgtcJSLdIj97OcH/IcBdIvJELDKlqpyOtZBy5Pj7ncD9R/07FVKWVgSX9xxBs+4ecf7wuTtLbn8DF1GA9yalC5RSSqn0lcqX+JRSSqUxLVBKKaWSkhYopZRSSUkLlFJKqaSkBUoppVRS0gKllFIqKWmBUkoplZS0QCmllEpKqTyauYqCtbY2wVA1bURkibW2CvApcKGIvBVqOKWU2gcdSaIQsNZeCVwPHEswTMznInJDuKmUUmrf9BJfISAijwFLCcbFOhi4NdxESimVNy1QhcdjwFHAKBH5O+wwSimVF73EVwhEJhH7FHiTYG6mBokYbVkppQpCz6AKhxEEU5B0A14ExoWcRyml8qQFKs1Za9sTzPt0dWRRX+AYa22n8FIppVSb74FpAAAgAElEQVTe9BKfUkqppKRnUEoppZKSFiillFJJSQuUUkqppKQFSimlVFLSAqWUUiopaYFSSimVlLRAKaWUSkpaoJRSSiUlLVBKKaWSkhYopZRSSUkLlFJKqaSkBUoppVRS0gKllFIqKWmBUkoplZS0QCmllEpKWqCUUkolpcywAxSAzrSoEsWEHSCB9LhSiZLncZXKBYoVK1bkuDwrK4s1a9YkOE3ONEvOUiVLlSpVEpwmtqy1jwNnAatF5KhofkaPq/zRLDmLxXGll/iUSm9PAm3DDqHU/tACpQo1t24N27/5POwYcSMiC4B1Bd2O+/l7tn/xMe6n73DLfsL9vgK3bg1u0wbc39twTq8MqthL6Ut8Su0v5/u4t1/GzZrEhgqVcINHYrzC+XnNWtsd6A4gImRlZf3rNeuGD2L9V5/kvpHMInjlK5JRIQuvQiW8ClmRx1lkHFiFzOo18UqXjVnmzMzMHHOGQbPkLBZZtECpQset/A1/8mhY+jUc2ZBy197Gn4W0OAGIyHhgfOSpy+m+gbvwcsp78NeaP2DHdtyO7bB9O+z+vnkj7q917PhzHfz0PXy8ELZt3XMj5SpCleqYqtWhag1MlepQpQamWLF8Z06Vey2JlipZor0HpQVKFRpu5w7cyzNxLwoULY65rA/m+JPJrFQJkuSgTlam2qEUzcrCRN6naJo1um1b4M918Mcq3PJfYPmvuBW/4N56KShyABkZUL02pk59TJ16UKceplSZeP5TVArRAqUKBffDN8FZ04pfMcf9B9OxG6Zs+bBjpTVTvCRULgmVq2EaHPv/y52/C/74HZb/jPvpe9z3X+LmP497dXbwgirVMXXqYY5sCPUbB9tRhZIWKJXW3LatuOeewr3xApSriNf7NkzDpmHHShhr7XSgFZBlrV0GDBaRiWFmMl4GHFQFDqqCOeYEANz2v+Gn73FLvwoK1qK3cW+/DJmZULcBpmEzTMOmmArJcX9FJYYWKJW23Ocf4T81FtavwbRshzm/C6ZE4fo0LiIXhZ0hGqZoMah7FKZu0FXL7doFP3yD+3QR7pNFuGnjcNPGBZcDGzZl5ylnQKkDQk6t4k0LlEo7buNfuKcn4Ba9DQcfgtf/Hsxh9cKOpfLBZGTA4fUxh9fH/fcyWLU8KFaffoB7YQZrn58eFKsTTsY0bYkpE7sWgip5aIFSacM5h1v0Fu7pCbB1K+bsjph2F2KKFAk7mioAYwwcXA1zcDVoewFuw5+U+vpjNr72PG7GY7hnHocGx+GdcDI0aILJ1P/vdKEFSqUFt+b34HLelx9Drbp4Xa4JmjOrtGPKlqPkmReypVlr3PJfcO+9gVv4Jv4nC6F0WUzz1piTz8RUqhx2VFVAWqBUSnP+LtwbL+BmPwXGYDp2x7RuF9yIV2nPVK2BufAy3Pld4KuPcf+bj3vzBdz856FRU7w250Cd+sFZmEo5WqBUynLLfsKfNBp+/h4aHIvX6SpMxQPDjqVCYDIyoMGxmAbH4tavxb01D/f2y/gfL4TqtTCnnBN0L9DLvSlFC5RKOW7HdtwLgntlJpQohenWD9P0JP2UrAAw5StizrsEd4bFLXoT9/rzuCcexs2ahGl9Jubkswpda85UpQVKpRT33Zf4U0bDquWY41tjLrxCW3CpHJlixTAntcX953T46hP8154L+sS9Ngdz2rnBfSrtBJzUtECplOC2bMbNmhR03qx4IN51QzH1G4cdS6UAYwzUb0xG/ca4n77Hf346bvYU3GvPYU47LzirKl4i7JgqB3kWKGvt5VFua6eITC5gHqX+xX2yCH/qOPhrPaZNe8y5nTDFiocdS6UgU7MOGdcOwv34bVCoZk3Gvfoc5vRIodLfq6QSzRnUeOCdKF53HBBVgbLWZgAfAstF5CxrbU1gBlAR+Ai4RES2R7Mtlb7cX+tx08fjPvofVDsUr+cATM06YcdSacDUqktGnyHBGI3PT8fNnIR7fS7m3M5B519tBZoUoilQW0WkdV4vstauz8d++wBfA7tvHtwHDBeRGdbaccAVwCP52J5KI8453P9eDzpgbt8e/NE4/XxMpl6RVrFlah9BxnVDcUu/wn/mCdykUbg3X8Sz3f5/2CUVnmgmwTkmym0dF82LrLXVgDOBCZHnBjgZeDbykknAuVHuU6UZt3ol/kMDcZNGBWdNg0fgnWm1OKm4MofVw7v5fky3frBpA/4DA9j1yD241SvDjlao5XnUi8j30WxIRJZGuc+Hgf7A7klfKgJ/isjOyPNlQNWcfjCamT8h/WaVjJVkzuJ27WTL3KfZNOMxTGYRSl/dnxJtzknILLfJ9L6o8BhjMM1a4ho3x702B/fSs/ifLcacfDbmTIspWSrsiIVOvj6WWmtvz2XV3wSF5WUR+X0fP38WsFpEPrLWtsrPviG6mT8hdWaVTLRkzeJ++QF/8ij49Udo1Axz8VVsKV+RLevWJTzL3qKd+VOlD1O0GOZMi2vRBvdc0NrPLXwT0/FKzLEnan+7BMrvx9PDgZuA1sBhke83AY2Bq4EfrbVt9/HzLYBzrLU/EzSKOBkYAZSz1u4ultWA5fnMpVKQ+/tv/GefxL+7H/y1Hu+qm4OGEOUrhh1NKUy5CniX9sG79UEon4UbPwx/1B24tavDjlZo5LdAeUBHEfmPiFwsIv8BLLBLRJoDPYF7c/thEblFRKqJyKFAR+ANEekEvAn8N/KyrsCcfOZSKWb7Zx/iD70G98osTIs2eEPHYJqcoJ9OVdIxNQ7DGzAM06EbfPcF/qBe+K8+F8xZpeIqvwXqdGDuXsteANpFHj8F1NqPHDcBfa21SwnuSYU646eKH7d5E/6TI1k/+FowBq/fnXhdemNKlQ47mlK5Ml4GXptz8IaOgSOOxj3zOP7dN+B+ifbWu9of+W0a9QPBpbzR2ZZdFVkOkAVsiWZDIvIW8Fbk8Y9A4ZmHuxByzsFH/8OfPh42baDkeZ3Y1ubcYCZVpVKEqVgJr/dtsOQ9/Onj8e+6gY3ndMCdfgGmSNGw46Wd/BaobsAsa+1NBPeJqgK7gPMj6+sCA2MXT6UDt24N/rRx8OkHUL02Xp/BlDmmGX8nSYMNpfLDGANNWuAd2RA3czJb5kyHxf/Du+J6TPXaYcdLK/kqUCKyxFpbB2gOVAFWAu+LyI7I+gXAgpinVCnJ+T5uwcu4mZPA34X572WYNucEUyMoleJMydKYS3pSpuVp/DnyTvy7b8SccxGm7fk6EkWMFKiTSaQgFbXWagcBtQe3chn+sAG4qeOg5uF4g0fhnX6eFieVdood0xxvyEhM4+a42VPw779FO/jGSH77QTUgaCTxN0Fz8KeBlgQt7zrEPJ1KOW7nDtzLs3AvPg1Fi2Mu7ROMbaat81QaM6XLQvcboVEz3NRx+Lf3wdgrMP85TX/3CyC/Z1CPAINE5AhgR2TZ28CJMU2lUpL78Vv8O/vi5kzFND4e744xeC1O0QNUFQrGGLxmLfGGjIRadXFTxuCPuQu3eWPY0VJWfgtUfYKm5AAOQEQ2AzqZSiHmtm3Fn/EY/r39YfMmvF634nW/EVO2fNjRlEo4U6FSMF9Zh27wxRL826/D/fBN2LFSUn5b8f0MNCGYKgMAa21TQDsDFFLui4/wn3oE1q7GtDoDc34XnU5bFXrG8zBtzsEddiT+o/fjD7sFc35XzKnt9YpCPuS3QA0EXoxMiVHUWnsLQT+oK2OeTCU1t3EDTibgFr4Flavh9b8XU6de2LGUSirm0Dp4A4fjPzES98zjuO+/xLu0j3ZMj1K+LvGJyAtAW6ASwb2nGsD5IvJqHLKpJOScw1/4Fv6gnrjF72LO6oA3aIQWJ6VyYUqWxut5C6bDFfD5h/h3XIf7KapJIgq9fE+yIyIfE4y5pwoZt3Y1/lNj4YslQdPxrtdgqtYIO1bKstYeSDB8WEOgHPAn8CnwmoisCjObii1jDKZNe1ytI4JLfvfdhLGXB9PM6yW/XOVZoPYxxcYeRGRQweOoZOT8Xbg3XsQ9F7SPMR2vxLQ+Qzsj7idr7ZHAHQSzAXxEMLv0KoI50i4BHrbWvknQYvar0IKqmDO16uINehj/iRG46ePh1x+gU09MkSJhR0tK0ZxBHZLtcXHgAmAx8AtQnWAMvZmxj6aSgVv+C/6kUfDTd3BUE7zOV2MqHhh2rFT3JDAM6CQif++90lpbDDiHYNDk4xMbTcWbKVUGr+cA3PMzcC/MwK1chnf1LZhyFcKOlnSimVH3st2PrbUzgItEZGa2ZecDF8YnngqL27EDN09wLz0LJUphuvXDND1JL0fEgIg0y2P938AzkS+VhoznYdpfjKt2KP4TD+Pf1TcoUrXqhh0tqeS3H1Q74Lm9ls0FzohNHJUM3Pdf4d/eB/fC05jjTsK7fSxes5ZanOLAWpvj3GfW2lmJzqISzzQ5Ae/m+yAjE3/YLfjvzQ87UlLJb4FaCvTaa9nV/DPdhkphbusW/KmP4N9/M+zYjtdnSDBCc5myYUdLZ61zWd4qkSFUeEy1mni3PgS1j8Q9MQL/6Qk6GWLE/ky3Mdta259/ptvYyT/TbagU5T5ZhD91HPy1HtOmPab9xZjiOkBIvGRrfFQ0h4ZItQju8apCwpQpi3fdUNyzT+Ben4tb8Stej5swJQv3ONz5nW7j431Nt6FSj9uwHjf9MdyH70LVGkF/jZqHhx2rMNjd+Mhjz4ZIDvgNGJLoQCpcJjMT0/FK/Ko1cJErGd61gzAVKoUdLTT70w9qB/BOHLKoBHLO4d6bj5PHYfs2TPtOwTw2mdrcNRF2Nz6y1r4nIo/Faz/W2rbACCADmCAi98ZrXyo2vP+chqt4IP64e/HvvhHv2oGFdiLEPO9BWWvfimZD1lq9u5ci3OqV+MMH4Z4cCVWr4w0aiXdWBy1OCWKtPWj3430Vp+yv28/9ZABjCBo31QMustbqkB8pwNRrhNf/XvA8/PsH4D7/KOxIoYjmDKqZtfYyIK8mXMfGII+KI7drJ/4rs3Fzp0JGJqZzz2C+Gq9A81aq/HvDWvs2MAVYJCL+7hXWWo+gb2EX4CTgqALspymwVER+jGx7BtAe0M6/KcBUOxRvwDD8kbfjj74D0+kqvJPahh0roaIpUIsIDpa8LCxgFhVH7tcfWXfPI7gfv4VGzfAuvgpTvmLYsQqrxkB34DGgprX2R2AjwUgSNQlayz4KXFfA/VQluJ+12zLgX32wrLXdI3kQEbKysnLcWGZmZq7rEq3QZMnKwr9vPH8NG8j2KWMptnkjpTv1yPVDZbq9L9F01G1VoD2oULntfwc91l+dDWXL4V11ExxzgvZpCpGIbAdGA6OttYcADQjG4lsPfCYiyxOcZzwwPvLUrVmzJsfXZWVlkdu6RCtsWVyPmzDTxrFl1hS2LvsFc1mfHC/Jp8r7UqVKlai2ke9GEip1uG8+w58yBlavxJx4KhV79GPdtu1hx1LZiMhv7HmWE0vL2bOFYLXIMpViTEYGdO4JFQ/EzZ6C27IJ76pbMMWKhR0trrRApSG3eVPQn+Ld16BSZby+d2CObIhXuixsS45PVyoQGXdvEHARUFFEDrDWngYcLiKjC7j5xUAda21NgsLUEbi4gNtUITHGYM64EL90WdxTj+APH4h3zaC0nltK746nEecc7qP/BXM1vTcfc/r5eINHYY5sGHY0lbvhBA0hOhH0gQL4kmCElgIRkZ1Ab+AVghHTRUS+LOh2Vbi8k07H63Ej/LwUf9gtuD/XhR0pbvQMKk249Wvxp42DTxZB9Vp41w7G1CicfSdSzHnAYSKy2VrrA4jIcmtt1VhsXETmAfNisS2VPEyTFnglSuKPvSfo0Hv97ZhKlcOOFXP5KlCRG7p7TK4WuYauQuJ8H7fgFdysSbBzJ+aCrphTzw2uWatUsJ29jkNrbSVgbThxVKow9Rrj9b0jaIZ+38141w2BJGnBFyvRTFhYBOgR+apF0AR2d5PYw6y1PwHjgPGR1kn72tYhwGTgIILLGeNFZIS1tgLwNHAo8DNgRWT9fv6bCg23ahn+5NHw/VdwxNF4l/TEHBhd6xiVNJ4BJllrrwew1h4MPAzMCDWVSgmmVl28G+/Bf3gQ/rBb2D7wIcg6OOxYMRPNPahPgSMIClRZEWkoIieKSEOgLHBlZP3HUWxrJ9BPROoRjOfXK9Kz/WZgvojUAeZHnqtcuJ078F8U/KHXwvJfMF2vCRpCaHFKRQOAn4DPCa5MfA+sAKKayVopU7U63k33Qemy/Dn0Oty3X4QdKWaiucTXSkRW57RCRHYB7wPvRy5L7JOIrCQYYBYR2Wit/ZqgM2F7/pleYBLwFnBTFNkKHffTd8EMt8t/wTRpgbmoO+aA8mHHUvspctXheuD6yDG0RkRcHj+m1B5M1kF4N96DGTGEXSOH4PUemBaNo4xz0R8L1tobROSBHJb3FZGH8rNja+2hwAKCFky/iki5yHIDrN/9fK+fyd7jvcn27TlfUczMzGTnzp35iRM3scritm1l07TxbHnxGbzyFSlzZT+KNzsplCyxkCpZihYtCnkP87XfrLXrRORfc31ba1eLyIHx2u8+uBUrVuS4IlU6gSZaMmUpn+mx5rZesHolXq9bMfUbh5Ylio66eR5X+W3FNwj4V4ECbgOiLlDW2tLATOA6Edlgrf3/dSLirLU5Vs3C2uPdfbEE/6mxsHY1plU7OK8Lm0qWYlM+t5tu70usxKLHewH8aziAyH1fbeWi8i2jXAW8fnfiPzQQf/SdwfQ5DVJ3mNSoCpS19uTIwwxrbWv2rHy1CBpNRCVy8M0EporI7mmtf7fWHiwiKyM3iXO8pFjYuI0bcDIRt/BNqFwNr/+9mDo6GHU6sNa+Q9BQqLi1dsFeq6sRXDpXKt9MmQOCIjV8EP7Yu/GuuhnTsGnYsfZLtGdQEyPfiwOPZ1vugFXANdFsJHL5biLw9V6XBOcCXYF7I9/nRJkrLTnncB8swM14DLZuxpzVAXPGhZgiRcOOpmJnAsEHveP45/iC4Jj6naCxkFL7xZQui9f3TvyHB+M/cg9e9/6YY44PO1a+RVWgRKQmgLV2sohEM7J5bloAlwCfW2s/iSwbQFCYxFp7BcFU1zaXn097bu0f+FMfgc8/hJqH43Xpjal2aNixVIyJyCQAa21n4HsReW/3OmvtCQSX0gs6mrkqxEyp0njX344/Ygj+o/dhut2Ad9yJYcfKl/xO+V6Q4oSIvEvuN8ZOKci2U53zd+HefAk3ezIApkM3zMlnYjy9FZHmGgIf7rXsI+A5tECpAjIlS+FdNxR/5FDchAdwGRkpdSYVTUfdxcD9wJycOuJaa4sC5xL0b/rXXDMqb275r/iTR8GP38JRx+B17ompGEYDLhUCx78bRGSg42SqGDElSuL1GYw/fDD++GF4vQakTMOJaM6guhJ0GnzEWrsE+JZ/RpI4HDgGeAO4NE4Z05bbsQM37xncS89CiRKYK/pimrXUuZoKl3eAO6y1/UXEj8yoOySyXKmYMMUjRerBgfhj78G7ZiCmXqOwY+UpmgkLvwL+a62tDJxKMLlaFsHkapOBS3LryKty55Z+hT9pNKxahmneCmOvwJQ5IOxYKvH6AC8AK621vwDVCTqznx1qKpV2TMnSeNcPxX/gVvwxd+L1GYI5/KiwY+1T1PegRGQVMCWOWQoFt3ULbtZk3FvzoEKlYNTxBk3CjqVCIiLLrLXHAE0JJhf8DfhARPxwk6l0FLTuuwN/2AD8kXfgXT8UU/uIsGPlKpp7UCeJyILI45Nze52IvBHLYOnIfbo4aKH351rMKWdjzu2MKV4i7FgqZJFitDDypVRcmbLl8PpFitSIIcE4nofWCTtWjqI5gxpLMBwR7NlfIztH0GFX5cBtWI+bMQG3+B2oWgPvqpswteqGHUspVUiZchWDzrz334I/fDDeDXdhDqkZdqx/ieYe1FHZHiffvyCJOefY+saL+BNHwPZtmPadMG3Px2T+a3QbpZRKKFOhUlCkhg3AHz4I76b7MAcl14wIBWrKaq1tba3N34ilhYT7YxX+8EFsGHUXVKmON2gk3lkdtDgppZKGqVQZr+/t4Bz+8EG49ck1T2a+CpS19m1rbYvI45sIJlWbbq0dEI9wqcjt2oX/6mz8Ib3hp+8o0+MGvBvvxhxcLexoSin1L6ZytWA23s0bgyK1aUPYkf5ffs+gjuKfG7lXAq0JJh68KpahUpX79Uf8e27EPfMEHNkIb+gYSrY9H+Npn0ulVPIyNQ7D630b/LEKf+TtuG1bw44E5L9AeYCz1tYGjIh8JSK/AYV6xjy3/W/8WZPw7+oL69fg9egfzMVSISvsaEopFRVTtwFe9xvh56X4j9yD27Ej7Ej5ng/qXWA0cDAwGyBSrJJjYp8QuG+/wJ88GlavwLRog7nwMkypMmHHUkqpfDONm2O69sY9ORI38SHofkOo44Hmt0BdCvQD/gCGRZYdAYyIYaaU4LZswj37JO6dV6FS5aAvQRpMsayUKty8Fm3wN28MblVMLQ2de4Y2/Fp+RzNfSzA9RvZlL8Y0UQpwS97Dn/YobPgLc/p5mLMvxhQrFnYspZSKCe+08/A3bQzGCS1dFnPeJaHkyFeBioxcfhtwEVAFWEHQku8uEdkW+3jJxa1fGxSmTxbCITXxrhmEqVE77FhKKRVz5rxLYNMG3Lxn8MtVxGt9RsIz5PcS3yNAXeBagokFaxCcUVUFLo9ttOThfB/3zqu4mU/Czp2YC7pi2rTHZOb37VNKqdRgjIFOV+P+Wo+bPh5XvgKmUfOEZsjvX9hzgdoi8mfk+VfW2kXAUtK0QLlVy/CnjIHvvoS6DfAu6ZV0va2VUioeTEYGXvcbgxHQH3sAr++dCR1cNr/NzFcBJfdaVoJgeoC04nbuxH9R8If2gWU/Y7r0xut3pxYnpVShYooVx7tmIBxQAX/0nbjfVyRs3/k9g5oCvGytHQUsI5geoBcwOftI56k+srn76Xv8SSNh+S+YJi0wF3XHHFCou3oppQoxU7Yc3nVD8O/pH4yAfvP9mLLl4r7f/BaoHpHvew9tdBX/jCaRsiObu7+34Z6bipv/PBxQLpgaOcHXXJVSKhmZA6vgXTMQ/8Fb8UfdEYyAXqx4XPeZ32bmaTuaufvy4+Be09rVmJZtMed3xZQsFXYspZRKGqZWXbwrb8Qfew/++GF4PQdgMuLXkbfQDxLnNm3Af3w4/sODoUgRvBvvwevcU4uTUkrlwDRqhrm4B3y2GDftUZxzcdtXoW0n7ZzDfbAA9/QE2LIJc6YNvooUDTuaUkolNa9VO/x1q3EvzYSDqmBOOzcu+ymUBcqt/SOYev3zD6Hm4Xhd7sBUOzTsWEoplTLMuZfgVq/EPfsE7sCDMY2axXwfhapAOX8X7q2XcLOmgPMxHbphTj4z1MEQlVIqFRnPw7vsevy1fwR9pG66F1M9tiPrFJoC5Zb/ij9lNPzwDdRvHNxnyjoo7FhKxYW19kJgCHAk0FREPgw3kUpHplgxvN634d/dD3/UnXgDHsCUrxiz7ad9Iwm3Ywf+3Gn4d1wHvy/HXH49Xp8hWpxUuvsCOB9YEHYQld7MAeWDjrxbt+CPvgP3d+yGZU2aMyhrbVuCaTsygAkicm9Bt+mWfh3M1bTyN0yzlsElvTIHFDirUslORL4GsNaGHUUVAqZaTbzuN+CPvgt/woN4V98ck+0mRYGy1mYAY4BTCUaoWGytnSsiX+3P9vytm/GnjcO99RKUz8K7djCmQZNYRlYqbVhruwPdAUSErKycZ4LOzMzMdV2iaZachZrl5HZs2bKRjRMfpvi8Z8jsdl2BsyRFgQKaAktF5EcAa+0MoD2Q7wLlPl3M2umP4tb9gTn5LMy5nTHFS8Q4rlLhs9a+DlTOYdWtIjIn2u2IyHhgfOSpW7Mm5wmys7KyyG1dommWnIWdxTVrjfnhO7bMmUZGlUPYckyLHF9XpUp0Y5omS4GqCvyW7fky4F9tFvP6pOd8n3XzBEqXoVz/uyhyeP04Ro6OfrrKmWYpOBFpE3YGpbIzxkDHK3FrVrFlznRcg6aYIkX2e3vJUqCiEs0nPdfjJrJq1mbtX39BEnyqCfsTTXaaJWf7yhLtJz2lVCCYoqM/FcqWYd2OXQXaVrK04ltOMDL6btUiy/LNVMgqUMVWKh1Ya8+z1i4DjgdetNa+EnYmVXiYEiXxYjADRLKcQS0G6lhraxIUpo7AxeFGUip1ichsYHbYOZQqiKQ4gxKRnUBv4BXg62CRfBluKqWUUmEy8RyJNs5SNrhKOSbsAAmkx5VKlDyPq6Q4g9pPJrcva+1H+1qfyC/NkhZZCpN0+T/TLMmfJU+pXKCUUkqlMS1QSimlklK6Fqjxeb8kYTRLzjRL6kmm90mz5CytsqRyIwmllFJpLF3PoJRSSqU4LVBKKaWSUrKMJBET8ZhTqoB5fgY2AruAnSJybAL3/ThwFrBaRI6KLKsAPA0cCvwMWBFZH1KWIcCVwB+Rlw0QkXlxznEIMBk4iKC/z3gRGRHW+5JKkunY0uNqn1mGkODjKrLfuBxbaXMGlW1OqXZAPeAia229cFMB0FpEGiXyIIp4Emi717KbgfkiUgeYH3keVhaA4ZH3plEiDiJgJ9BPROoBzYFekd+RsN6XlJCkx5YeV8lzXEGcjq20KVBkm1NKRLYDu+eUKpREZAGwbq/F7YFJkceTgHNDzJJwIrJSRJZEHm8kGFarKiG9LylEj60IPa5yFq9jK50u8UU1p1SCOeBVa60DHo1MFxKmg0RkZeTxKoLT8TD1ttZ2AT4k+PSVsMtq1tpDgcbA/7V3tzwNBEEYx/8kgAEcBoOAL0AQqIZUIXCYsZUIDBqDQkJwCAIOSCaBQL8CCg0JGkFIkXhexG6hpmB6t8Pl+Zlr7sRNJn0y6fZye0e8vkQTLVvK1e+K5QpGm60m/YKKqOXuy6SlkS0zWy1dUJ+7f1L2vWtHwJ7v1WAAAAFDSURBVCKwBLwA+3Xd2MymgUtg293fBq8F6Iv8TbkarliuYPTZatKAGtmeUqPi7s/5+Era+mClZD1Az8zmAPLxtVQh7t5z93d3/wCOqak3ZjZBCtCZu1/l02H6ElSobClXw5XKFVSTrSYNqO89pcxskrSnVLdUMWY2ZWYz/c/AGvBQqp6sC3Ty5w5wU6qQ/pc226CG3pjZGHACPLr7wcClMH0JKky2lKvflchVvm8l2WrUmyTMbB04JD0Ke+ruewVrWeBnw7hx4LzOeszsAmgDs0AP2AWuAQfmgSfSI5+V/8k6pJY2aRnik/T46ebAWnVVdbSAW+Ae+Mind0hr5bX35T+Jki3l6s9a2tScq1xLJdlq1IASEZHmaNISn4iINIgGlIiIhKQBJSIiIWlAiYhISBpQIiISkgaUiIiEpAElIiIhfQE1wHSB/VkiEAAAAABJRU5ErkJggg==\n",
"text/plain": [
"<Figure size 432x288 with 4 Axes>"
]
},
"metadata": {
"needs_background": "light"
},
"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",
"plt.subplot(2, 2, 3)\n",
"plt.plot(np.degrees(x_bar[3,:]))\n",
"plt.ylabel('psi(t) [deg]')\n",
"#plt.xlabel('time')\n",
"\n",
"plt.subplot(2, 2, 4)\n",
"plt.plot(x_bar[4,:])\n",
"plt.ylabel('cte(t)')\n",
"\n",
"plt.tight_layout()\n",
"plt.show()"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"the results seems valid:\n",
"* the cte is correct\n",
"* theta error is correct"
]
},
{
"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 1.31 ms, sys: 5.59 ms, total: 6.91 ms\n",
"Wall time: 2.05 ms\n"
]
}
],
"source": [
"%%time\n",
"\n",
"u_bar = np.zeros((M,T))\n",
"u_bar[0,:] = 1 #m/s\n",
"u_bar[1,:] = np.radians(-10) #rad/s\n",
"\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0\n",
"x0[1] = 1\n",
"x0[2] = np.radians(0)\n",
"x0[3] = 0\n",
"x0[4] = 1\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(5,1)\n",
" ut=u_bar[:,t-1].reshape(2,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": [
"<Figure size 432x288 with 4 Axes>"
]
},
"metadata": {
"needs_background": "light"
},
"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(x_bar[2,:])\n",
"plt.ylabel('theta(t)')\n",
"#plt.xlabel('time')\n",
"\n",
"plt.subplot(2, 2, 3)\n",
"plt.plot(x_bar[3,:])\n",
"plt.ylabel('psi(t)')\n",
"#plt.xlabel('time')\n",
"\n",
"plt.subplot(2, 2, 4)\n",
"plt.plot(x_bar[4,:])\n",
"plt.ylabel('cte(t)')\n",
"\n",
"plt.tight_layout()\n",
"plt.show()"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"The results are the same as expected"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"------------------\n",
"\n",
"the kinematics model predictits psi and cte for constant heading references. So, for non-constant paths appropriate functions have to be developed.\n",
"\n",
"-----------------"
]
},
{
"cell_type": "code",
"execution_count": 9,
"metadata": {},
"outputs": [],
"source": [
"def calc_err(state,path):\n",
" \"\"\"\n",
" Finds psi and cte w.r.t. the closest waypoint.\n",
"\n",
" :param state: array_like, state of the vehicle [x_pos, y_pos, theta]\n",
" :param path: array_like, reference path ((x1, x2, ...), (y1, y2, ...), (th1 ,th2, ...)]\n",
" :returns: (float,float)\n",
" \"\"\"\n",
"\n",
" dx = state[0]-path[0,:]\n",
" dy = state[1]-path[1,:]\n",
" dist = np.sqrt(dx**2 + dy**2)\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",
"# front_axle_vect = [np.cos(state[2] - np.pi / 2),\n",
"# np.sin(state[2] - np.pi / 2)]\n",
" path_ref_vect = [np.cos(path[2,target_idx] + np.pi / 2),\n",
" np.sin(path[2,target_idx] + np.pi / 2)]\n",
" \n",
" #heading error w.r.t path frame\n",
" psi = path[2,target_idx] - state[2]\n",
" \n",
" # the cross-track error is given by the scalar projection of the car->wp vector onto the faxle versor\n",
" #cte = np.dot([dx[target_idx], dy[target_idx]],front_axle_vect)\n",
" cte = np.dot([dx[target_idx], dy[target_idx]],path_ref_vect)\n",
"\n",
" return target_idx,psi,cte\n",
"\n",
"def compute_path_from_wp(start_xp, start_yp, step = 0.1):\n",
" \"\"\"\n",
" Interpolation range is computed to assure one point every fixed distance step [m].\n",
" \n",
" :param start_xp: array_like, list of starting x coordinates\n",
" :param start_yp: array_like, list of starting y coordinates\n",
" :param step: float, interpolation distance [m] between consecutive waypoints\n",
" :returns: array_like, of shape (3,N)\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,section_len/delta)\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))"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"test it"
]
},
{
"cell_type": "code",
"execution_count": 10,
"metadata": {},
"outputs": [],
"source": [
"track = compute_path_from_wp([0,5],[0,0])\n",
"\n",
"u_bar = np.zeros((M,T))\n",
"u_bar[0,:] = 1 #m/s\n",
"u_bar[1,:] = np.radians(-10) #rad/s\n",
"\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0\n",
"x0[1] = 1\n",
"x0[2] = np.radians(0)\n",
"_,psi,cte = calc_err(x0,track)\n",
"x0[3]=psi\n",
"x0[4]=cte\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(5,1)\n",
" ut=u_bar[:,t-1].reshape(2,1)\n",
" \n",
" A,B,C=get_linear_model(xt,ut)\n",
" \n",
" xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n",
" \n",
" _,psi,cte = calc_err(xt_plus_one,track)\n",
" xt_plus_one[3]=psi\n",
" xt_plus_one[4]=cte\n",
" \n",
" x_bar[:,t]= xt_plus_one"
]
},
{
"cell_type": "code",
"execution_count": 11,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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\n",
"text/plain": [
"<Figure size 432x288 with 4 Axes>"
]
},
"metadata": {
"needs_background": "light"
},
"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(track[0,:],track[1,:],\"b-\")\n",
"plt.axis('equal')\n",
"plt.ylabel('y')\n",
"plt.xlabel('x')\n",
"\n",
"plt.subplot(2, 2, 2)\n",
"plt.plot(x_bar[2,:])\n",
"plt.ylabel('theta(t)')\n",
"#plt.xlabel('time')\n",
"\n",
"plt.subplot(2, 2, 3)\n",
"plt.plot(x_bar[3,:])\n",
"plt.ylabel('psi(t)')\n",
"#plt.xlabel('time')\n",
"\n",
"plt.subplot(2, 2, 4)\n",
"plt.plot(x_bar[4,:])\n",
"plt.ylabel('cte(t)')\n",
"\n",
"plt.tight_layout()\n",
"plt.show()"
]
},
{
"cell_type": "code",
"execution_count": 12,
"metadata": {},
"outputs": [],
"source": [
"track = compute_path_from_wp([0,2,4,5,10],[0,0,3,1,1])\n",
"\n",
"u_bar = np.zeros((M,T))\n",
"u_bar[0,:] = 1 #m/s\n",
"u_bar[1,:] = np.radians(10) #rad/s\n",
"\n",
"x0 = np.zeros(N)\n",
"x0[0] = 2\n",
"x0[1] = 2\n",
"x0[2] = np.radians(0)\n",
"_,psi,cte = calc_err(x0,track)\n",
"x0[3]=psi\n",
"x0[4]=cte\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(5,1)\n",
" ut=u_bar[:,t-1].reshape(2,1)\n",
" \n",
" A,B,C=get_linear_model(xt,ut)\n",
" \n",
" xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n",
" \n",
" _,psi,cte = calc_err(xt_plus_one,track)\n",
" xt_plus_one[3]=psi\n",
" xt_plus_one[4]=cte\n",
" \n",
" x_bar[:,t]= xt_plus_one"
]
},
{
"cell_type": "code",
"execution_count": 13,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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\n",
"text/plain": [
"<Figure size 432x288 with 4 Axes>"
]
},
"metadata": {
"needs_background": "light"
},
"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(track[0,:],track[1,:],\"b-\")\n",
"plt.axis('equal')\n",
"plt.ylabel('y')\n",
"plt.xlabel('x')\n",
"\n",
"plt.subplot(2, 2, 2)\n",
"plt.plot(x_bar[2,:])\n",
"plt.ylabel('theta(t)')\n",
"#plt.xlabel('time')\n",
"\n",
"plt.subplot(2, 2, 3)\n",
"plt.plot(x_bar[3,:])\n",
"plt.ylabel('psi(t)')\n",
"#plt.xlabel('time')\n",
"\n",
"plt.subplot(2, 2, 4)\n",
"plt.plot(x_bar[4,:])\n",
"plt.ylabel('cte(t)')\n",
"\n",
"plt.tight_layout()\n",
"plt.show()"
]
},
{
"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",
"![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",
"$J(x(t),U) = \\sum^{t+T-1}_{j=t} x^T_{j|t}Qx_{j|t} + u^T_{j|t}Ru_{j|t}$\n",
"\n",
"This accounts for quadratic error on deviation from 0 of the state and the control inputs sequences. Q and R are the **weight matrices** and are used to tune the response.\n",
"\n",
"Becouse the goal is tracking a **reference signal** such as a trajectory, the objective function is rewritten as:\n",
"\n",
"$J(x(t),U) = \\sum^{t+T-1}_{j=t} \\delta x^T_{j|t}Q\\delta x_{j|t} + u^T_{j|t}Ru_{j|t}$\n",
"\n",
"where the error w.r.t desired state is accounted for:\n",
"\n",
"$\\delta x = x_{j,t,ref} - x_{j,t}$\n",
"\n",
"#### Non-Linear MPC Formulation\n",
"\n",
"In general cases, the objective function is any non-differentiable non-linear function of states and inputs over a finite horizon T. In this case the constrains include nonlinear dynamics of motion.\n",
"\n",
"$J(x(t),U) = \\sum^{t+T}_{j=t} C(x_{j|t},{j|t})$\n",
"\n",
"s.t.\n",
"\n",
"$ x_{j+1|t} = f(x_{j|t},{j|t}) t<j<t+T-1 $\n",
"\n",
"Other nonlinear constrains may be applied:\n",
"\n",
"$ g(x_{j|t},{j|t})<0 t<j<t+T-1 $"
]
},
{
"cell_type": "code",
"execution_count": 14,
"metadata": {},
"outputs": [
{
"name": "stderr",
"output_type": "stream",
"text": [
"/home/marcello/.local/lib/python3.5/site-packages/ipykernel_launcher.py:18: RuntimeWarning: invalid value encountered in true_divide\n"
]
},
{
"name": "stdout",
"output_type": "stream",
"text": [
"CPU times: user 329 ms, sys: 173 ms, total: 502 ms\n",
"Wall time: 281 ms\n"
]
}
],
"source": [
"%%time\n",
"\n",
"track = compute_path_from_wp([0,2,2,10],[0,0,2,2])\n",
"\n",
"MAX_SPEED = 2.5\n",
"MIN_SPEED = 0.5\n",
"MAX_STEER_SPEED = 1.57/2\n",
"\n",
"#starting guess\n",
"u_bar = np.zeros((M,T))\n",
"u_bar[0,:]=0.5*(MAX_SPEED+MIN_SPEED)\n",
"u_bar[1,:]=0.01\n",
"\n",
"# Starting Condition\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0\n",
"x0[1] = 0\n",
"x0[2] = np.radians(-0)\n",
"_,psi,cte = calc_err(x0,track)\n",
"x0[3]=psi\n",
"x0[4]=cte\n",
"\n",
"# Prediction\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(5,1)\n",
" ut=u_bar[:,t-1].reshape(2,1)\n",
" \n",
" A,B,C=get_linear_model(xt,ut)\n",
" \n",
" xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n",
" \n",
" _,psi,cte = calc_err(xt_plus_one,track)\n",
" xt_plus_one[3]=psi\n",
" xt_plus_one[4]=cte\n",
" \n",
" x_bar[:,t]= xt_plus_one\n",
"\n",
"\n",
"#CVXPY Linear MPC problem statement\n",
"cost = 0\n",
"constr = []\n",
"\n",
"for t in range(T):\n",
" \n",
" # Cost function\n",
" #cost += 5*cp.sum_squares( x[3, t]) # psi\n",
" #cost += 100*cp.sum_squares( x[4, t]) # cte\n",
" \n",
" # Tracking\n",
" idx,_,_ = calc_err(x_bar[:,t],track)\n",
" delta_x = track[:,idx]-x[0:3,t]\n",
" cost+= cp.quad_form(delta_x,10*np.eye(3))\n",
" \n",
" # Tracking 5 states\n",
" #delta_x = np.append(track[:,idx],[0,0])\n",
" #cost+= cp.quad_form(delta_x-x[:,t],500*np.eye(N))\n",
" \n",
" # Actuation effort\n",
" cost += cp.quad_form( u[:, t],1*np.eye(M))\n",
" \n",
" # Actuation rate of change\n",
" if t < (T - 1):\n",
" cost += cp.quad_form(u[:, t + 1] - u[:, t], 5*np.eye(M))\n",
" \n",
" #constrains\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",
"# sums problem objectives and concatenates constraints.\n",
"constr += [x[:,0] == x0]\n",
"constr += [u[0, :] <= MAX_SPEED]\n",
"constr += [u[0, :] >= MIN_SPEED]\n",
"constr += [cp.abs(u[1, :]) <= MAX_STEER_SPEED]\n",
"\n",
"\n",
"prob = cp.Problem(cp.Minimize(cost), constr)\n",
"solution = prob.solve(solver=cp.ECOS, verbose=False)"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"Print Results:"
]
},
{
"cell_type": "code",
"execution_count": 15,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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\n",
"text/plain": [
"<Figure size 432x288 with 3 Axes>"
]
},
"metadata": {
"needs_background": "light"
},
"output_type": "display_data"
}
],
"source": [
"x_mpc=np.array(x.value[0, :]).flatten()\n",
"y_mpc=np.array(x.value[1, :]).flatten()\n",
"theta_mpc=np.array(x.value[1, :]).flatten()\n",
"psi_mpc=np.array(x.value[1, :]).flatten()\n",
"cte_mpc=np.array(x.value[1, :]).flatten()\n",
"v_mpc=np.array(u.value[0, :]).flatten()\n",
"w_mpc=np.array(u.value[1, :]).flatten()\n",
"\n",
"#simulate robot state trajectory for optimized U\n",
"x_traj=predict(x0, np.vstack((v_mpc,w_mpc)))\n",
"\n",
"#plot trajectory\n",
"plt.subplot(2, 2, 1)\n",
"plt.plot(track[0,:],track[1,:],\"b*\")\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, 2)\n",
"plt.plot(v_mpc)\n",
"plt.ylabel('v(t)')\n",
"#plt.xlabel('time')\n",
"\n",
"#plot w(t)\n",
"plt.subplot(2, 2, 3)\n",
"plt.plot(w_mpc)\n",
"plt.ylabel('w(t)')\n",
"#plt.xlabel('time')\n",
"\n",
"#plot theta(t)\n",
"#plt.subplot(2, 2, 4)\n",
"#plt.plot(cte_mpc)\n",
"#plt.ylabel('cte(t)')\n",
"#plt.xlabel('time')\n",
"#plt.legend(loc='best')\n",
"\n",
"plt.tight_layout()\n",
"plt.show()"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"full track demo"
]
},
{
"cell_type": "code",
"execution_count": 24,
"metadata": {},
"outputs": [
{
"name": "stderr",
"output_type": "stream",
"text": [
"/home/marcello/.local/lib/python3.5/site-packages/ipykernel_launcher.py:18: RuntimeWarning: invalid value encountered in true_divide\n"
]
}
],
"source": [
"\n",
"track = compute_path_from_wp([0,5,7.5,10,12,13,13,10],\n",
" [0,0,2.5,2.5,0,0,5,10])\n",
"\n",
"sim_duration =100 \n",
"\n",
"x_sim = np.zeros((N,sim_duration))\n",
"u_sim = np.zeros((M,sim_duration-1))\n",
"\n",
"MAX_SPEED = 2.5\n",
"MIN_SPEED = 0.5\n",
"MAX_STEER_SPEED = 1.57/2\n",
"\n",
"# Starting Condition\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0\n",
"x0[1] = -0.5\n",
"x0[2] = np.radians(-0)\n",
"_,psi,cte = calc_err(x0,track)\n",
"x0[3]=psi\n",
"x0[4]=cte\n",
"\n",
"x_sim[:,0]=x0\n",
" \n",
"#starting guess\n",
"u_bar = np.zeros((M,T))\n",
"u_bar[0,:]=0.5*(MAX_SPEED+MIN_SPEED)\n",
"u_bar[1,:]=0.01\n",
"\n",
"for sim_time in range(sim_duration-1):\n",
" \n",
" # Prediction\n",
" x_bar=np.zeros((N,T+1))\n",
" x_bar[:,0]=x_sim[:,sim_time]\n",
"\n",
" for t in range (1,T+1):\n",
" xt=x_bar[:,t-1].reshape(5,1)\n",
" ut=u_bar[:,t-1].reshape(2,1)\n",
"\n",
" A,B,C=get_linear_model(xt,ut)\n",
"\n",
" xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n",
"\n",
" _,psi,cte = calc_err(xt_plus_one,track)\n",
" xt_plus_one[3]=psi\n",
" xt_plus_one[4]=cte\n",
"\n",
" x_bar[:,t]= xt_plus_one\n",
"\n",
"\n",
" #CVXPY Linear MPC problem statement\n",
" cost = 0\n",
" constr = []\n",
"\n",
" for t in range(T):\n",
"\n",
" # Cost function\n",
" #cost += 5*cp.sum_squares( x[3, t]) # psi\n",
" #cost += 100*cp.sum_squares( x[4, t]) # cte\n",
"\n",
" # Tracking\n",
" idx,_,_ = calc_err(x_bar[:,t],track)\n",
" delta_x = track[:,idx]-x[0:3,t]\n",
" cost+= cp.quad_form(delta_x,10*np.eye(3))\n",
"\n",
" # Tracking 5 states\n",
" #delta_x = np.append(track[:,idx],[0,0])\n",
" #cost+= cp.quad_form(delta_x-x[:,t],500*np.eye(N))\n",
"\n",
" # Actuation effort\n",
" cost += cp.quad_form( u[:, t],1*np.eye(M))\n",
"\n",
" # Actuation rate of change\n",
" if t < (T - 1):\n",
" cost += cp.quad_form(u[:, t + 1] - u[:, t], 5*np.eye(M))\n",
"\n",
" #constrains\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",
" # sums problem objectives and concatenates constraints.\n",
" constr += [x[:,0] == x_sim[:,sim_time]]\n",
" constr += [u[0, :] <= MAX_SPEED]\n",
" constr += [u[0, :] >= MIN_SPEED]\n",
" constr += [cp.abs(u[1, :]) <= MAX_STEER_SPEED]\n",
" \n",
" # Solve\n",
" prob = cp.Problem(cp.Minimize(cost), constr)\n",
" solution = prob.solve(solver=cp.ECOS, 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",
" # 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"
]
},
{
"cell_type": "code",
"execution_count": 32,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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\n",
"text/plain": [
"<Figure size 1080x720 with 3 Axes>"
]
},
"metadata": {
"needs_background": "light"
},
"output_type": "display_data"
}
],
"source": [
"#plot trajectory\n",
"grid = plt.GridSpec(2, 3, wspace=0.4, hspace=0.3)\n",
"\n",
"plt.figure(figsize=(15,10))\n",
"\n",
"plt.subplot(grid[0:2, 0:2])\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, 2])\n",
"plt.plot(np.degrees(u_sim[0,:]))\n",
"plt.ylabel('v(t) [m/s]')\n",
"\n",
"plt.subplot(grid[1, 2])\n",
"plt.plot(np.degrees(u_sim[1,:]))\n",
"plt.ylabel('w(t) [rad/s]')\n",
"\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.5.2"
}
},
"nbformat": 4,
"nbformat_minor": 2
}