{ "cells": [ { "cell_type": "code", "execution_count": null, "metadata": {}, "outputs": [], "source": [] }, { "cell_type": "code", "execution_count": 2, "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 **non-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_t-\\bar{x}) + B(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 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": [ "-----------------\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": 3, "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": 4, "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": 5, "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": 6, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ "CPU times: user 7.87 ms, sys: 0 ns, total: 7.87 ms\n", "Wall time: 7.41 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": 7, "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", "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": 8, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ "CPU times: user 1.8 ms, sys: 650 µs, total: 2.45 ms\n", "Wall time: 1.79 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": 9, "metadata": {}, "outputs": [ { "data": { "image/png": "iVBORw0KGgoAAAANSUhEUgAAAaIAAAEYCAYAAAAeWvJ8AAAABHNCSVQICAgIfAhkiAAAAAlwSFlzAAALEgAACxIB0t1+/AAAADh0RVh0U29mdHdhcmUAbWF0cGxvdGxpYiB2ZXJzaW9uMy4xLjMsIGh0dHA6Ly9tYXRwbG90bGliLm9yZy+AADFEAAAgAElEQVR4nOzdeVxU5f7A8c9zQEVEdvct13LLDdMsxQXLbCNLzdJy6Za5kLaZlomZaxqJW5vh1i1bjPZF9LqU18IUzfSqqKUmhgIiiChwnt8f8xMlQBBhzszwfb9evS4zc+acr8/l8J15lu+jtNYaIYQQwiKG1QEIIYQo3yQRCSGEsJQkIiGEEJaSRCSEEMJSkoiEEEJYShKREEIIS7lbHcC1On78eIHPBwYGcurUKTtH45ikLS4prC1q165tQTTOQe6xoklbXFKSe8zpE5EQwiYuLo6oqChM06RXr16EhobmeT0rK4uFCxdy6NAhqlatyrhx46hevbpF0QpxiXTNCeECTNNk6dKlTJo0iYiICH766SeOHTuW55j169dTpUoVFixYwJ133sn7779vUbRC5CWJSAgXEB8fT82aNalRowbu7u506dKF2NjYPMds27aN7t27A9C5c2d2795NSQqr6Mxz5Mx9kfM7Y4s+WIhikK45IVxAcnIyAQEBuY8DAgI4cOBAoce4ubnh6elJWloa3t7eeY6LiYkhJiYGgFmzZhEYGJjn9eyEY5xOP8Pp8KfwvGsAXoOfRFWqVBb/LKfh7u6er53Kq5K0hSQiIUQeISEhhISE5D7ON/BcwQM9aS6Vv/mIjK8+IuPX/2KMGI9q0MTOkToOmaxwSUkmK0jXnBAuwN/fn6SkpNzHSUlJ+Pv7F3pMTk4OGRkZVK1atUTXUxUr4f3YeIzxU+FcBubM5zC//gidk1Pyf4QotyQRCeECGjduTEJCAomJiWRnZ7NlyxaCgoLyHNOhQwc2bNgAwNatW2nZsiVKqWu6rmrRDiN8Aap9F3T0KszXJqITC57uLURhJBEJ4QLc3NwYPnw406dPZ/z48dx8883Uq1eP1atXs23bNgB69uxJeno6Y8eO5auvvuLhhx8ulWurKl4Yjz+HeuwZSDiK+co4zE3flWgihCiflLPvRySL7YombXGJLGi9eldzj+nkU5jL5sPendA6COPRsSgfP3uEaSm5xy6RMSIhhKWUfyDGuKmoBx+H/+3CDB+L3v5fq8MSDk4SkRCiVCnDwOh1F8bkCPCvhrlkJmbUfPS5DKtDEw5KEpEQokyoWvUwJs5B3TkA/d//YE4NQ+/fbXVYwgFJIhJClBnlXgEjdDDGhFng5oY590XMT5ahs7KsDk04EElEQogypxrfgDH5DVTX29Hfr8Gc8Qz62GGrwxIOQhKREMIulEdljCGjMMZOhjOnMac/g/n9GrQpi2DLO0lEQgi7Ujd2xAhfAK2D0J8sw5z3EvrU31aHJSwkiUgIYXeqqg/GkxNRQ5+CI4cwp4Zhblkni2DLKUlEQghLKKUwbumFMSUS6jVER83HfHMWOu2M1aEJO5NEJISwlAqsgfHsdNQDQ2FnLGb4GPRv26wOS9iRJCIhhOWU4YZxez+MF+dBVR/MyFcwVy1Gn8+0OjRhBw6zH9GpU6dYtGgRp0+fRilFSEgIffv2tTosIYQdqXoNMV6ch45+H702Gr13J8bw8ajGN1gdmihDDpOI3NzcGDJkCI0aNeLcuXO88MIL3HjjjdStW9fq0IRwaOnp6URERHDy5EmqVavG+PHj8fLyynPMH3/8wTvvvMO5c+cwDIN+/frRpUsXiyK+MlWhIqr/MPSNHTHfi8Cc/QLqzv6oOwei3B3mT5YoRQ7TNefn50ejRo0AqFy5MnXq1CE5OdniqIRwfNHR0bRu3ZrIyEhat25NdHR0vmMqVqzImDFjeP3115k0aRLLli3j7NmzFkRbfOr6VhhTIlGdu6O/Wo0563l0wjGrwxJlwCE/XiQmJnL48GGaNMm/9XBMTAwxMTEAzJo1q9C90WUP+UukLS5xxbaIjY0lPDwcgODgYMLDwxk8eHCeYy4vwe/v74+Pjw9nzpyhSpUq9gz1qinPKqjh49BtbsJctQhz2jjUA0NR3fuiDIf5HC2ukcMloszMTObNm8fQoUPx9PTM93pISAghISG5jwvbA0T2B7lE2uISV9yPKDU1FT8/254/vr6+pKamXvH4+Ph4srOzqVGjRoGvO+SHvdvvIadjF84snsmFD96mwp4deI99CbeAava5fhFc8QNOSZWkLRwqEWVnZzNv3jy6du1Kp06drA5HCIcxbdo0Tp8+ne/5Bx98MM9jpdQVt/9OSUlhwYIFjB49GqOQbxSO/GFPP/ECatP3XPhoKafCHkYNfhKjY1e7xlAQ+bB3SUk+7DlMItJa8+abb1KnTh3uuusuq8MRwqFMnjy50Nd8fHxISUnBz8+PlJQUvL29CzwuIyODWbNmMWjQIJo1a1ZWoZYppRQquA/6hhsxl76Ofvs1zLhfUA89gariVfQJhENymE7Wffv2sWnTJnbv3s1zzz3Hc889x/bt260OSwiHFxQUxMaNGwHYuHEjHTt2zHdMdnY2c+fOpVu3bnTu3NneIZY6VaM2xoTZqHsfQv/6o22vo707rQ5LlJDDfCO64YYb+Oijj6wOQwinExoaSkREBOvXr8+dvg1w8OBB1q5dy8iRI9myZQt79+4lLS2NDRs2ADB69Giuu+466wK/RsrNDXXXg+hWHTCXvo75+mRUyD2o+4agKlayOjxxFZR28iqDx48fL/B56bO9RNriElecrFDWnOEe0+fPo9csR6//CmrVw3jsaVT9xna7viO1hdWceoxICFd05swZNm3axPbt2/nzzz/JyMjA09OTBg0a0LZtW7p3717omI4oPlWpEmrQ47ZFsMvmY854FnX3INQd96MMN6vDE0WQRCREGXn//ff58ccfadeuHT179qROnTpUrlyZc+fO8ddff7Fnzx4mTJjArbfeysMPP2x1uC5BtWyHEb4AvWoJOnoV+rdtthJB1WtZHZq4AklEQpSRgIAAIiMjqVChQr7XGjZsyK233sqFCxdYv369BdG5LlWlKjz+HLTthH7/TcxXnkINGIHqetsVp7YL6zjMrDkhXE2fPn1yk1BBa4DANqW6T58+9gyrXFBKYXQKxgiPhEbXo1cuwlz4KvpMitWhiQJIIhLCDp566qkCn784w02UDeVfDWPcVNTAx2DvTswpY9E7tlodlvgHl+ya0//bxQVvb/TFUieGG1SqBJU8oFJlqOqNqlDR2iBFuVLQ5NSMjIxCqxuI0qMMAxVyD7pFW9s078UzULeEoAY+hqqcv4yYsD+XTETmG1NIycm58kGVPaGqL/gHoqrVhMAaqBq1oXYDqF4L5SYzbcS1e/LJJwG4cOFC7s8Xpaenc8stt1gRVrmkatfHmPga+ssP0d9+iv7fLttEhmYtrQ6t3HPJRGQ8/So+Pt6Xij/m5MD5TNtuj+fPQdoZSEuF1BR08kl03M+QlkruZ1b3ClCnAaphM2h0Parx9VCtlgx0iqs2duxYtNbMnDmTsWPH5nnN19dX1i/ZmXKvgLpvCLp1kG2vo7mTULf3Q93zEKqASSXCPmRB6//T5zPhxF/ov/6Av/5EHzkEhw/YEheAXyCqeRto3gbVsh2qqk8pRG8fstjuEqsWtJ4/f55KlZxztb8zLGgtCZ15Dv3RUvTmH6BuQ9si2DoNSnQuZ2+L0iQLWq+BquQBDRqjGlxaja3NHDh+FB2/F/2/nbZvTlvWoZUBTZuj2nVGteuCcpBS9MKxfPPNN/Tu3ZsKFSoUmoSysrJYu3Ytffv2tXN0QnlURj0yBt2mE+bySMxXx9vKA4XcK3sd2ZkkoitQhhvUvQ5V9zrofoctMf15CL3rF/SOrejVS9Grl0KzVqjO3VEdbkF5OvZGY8J+Tp8+TVhYGO3ataNFixbUrl0bDw8PMjMzOX78OHv27GHHjh0EBwdbHWq5ptp0xJi6EHPFQvTHUehd2zCGPYUKqG51aOWGdM1dA514HP3LZvTWDfD3X1CxIuqmYNvukQ3sV+eqKNJtcIm9u+bOnDnDhg0biIuL48iRI5w9exYvLy/q169Pu3btCA4OpmrVqmVy7dLiql1z/6S1Rv8Ug/7wXTAUatATtg+YxRgbdrW2uBYlucckEZUCrTX8cQC9+Qf0zxvhwnlodD3G7fdB206W17qSm+QSVyx6mp6eTkREBCdPnsytvu3lVfDePBkZGTz99NN07NiRESNGFOv8jnCP2ZM+eQLzvTcgfg906IIxeBTK68r1AF21LUqiJPeYdISWAqUUqmEzjEfGYLwWhXrwX5CWirlkFubLYzA3/4DOzrY6TOGioqOjad26NZGRkbRu3Zro6OhCj129ejXNmze3Y3TOR1WrifHcdNT9j0LcL5jhY9G//Wp1WC5NxohKmfL0QvW6G92jL/rX/6K/+wS9YiH6209sU0Rv6mr5NyRhfxkZGXz88cfs2bOHtLS0PAtclyxZck3njo2NJTw8HIDg4GDCw8MZPHhwvuMOHTpEamoqbdu25eDBg9d0TVenDDdUn/vRLdvbFsFGTkV1vwP1wDDbxCZRquQbURlRhhtGx1sxXorAGDMZKlVGL30d85Vx6D07rA5P2Nm7777L4cOHeeCBB0hPT2f48OEEBgZy5513XvO5U1NT8fPzA2xrk3LXz13GNE1WrFjBkCFDrvl65Ymq1xDjxXmo20LRG7+z3b+H9lkdlsuRb0RlTCkFbTpitO6A/nUL+rMVmBFToM1NGP2H26o5CJe3a9cuIiIiqFq1KoZh0LFjRxo3bszs2bO56667inz/tGnTCiyc+uCDD+Z5rJQqcHD9hx9+oF27dgQEBBR5rZiYGGJiYgCYNWsWgYGBBR7n7u5e6Gsu58nnudA1hNTIaZizX6DKA49Spf9QlLvtT2i5aosilKQtHCoRxcXFERUVhWma9OrVi9DQUKtDKjXKMFAdb0W37YRe9wX6q48ww8eg7hyA6nM/yl1WdbsyrTWenra6Zh4eHmRkZODr68uJEyeK9f7JkycX+pqPjw8pKSn4+fmRkpJS4EZ7+/fvZ+/evfzwww9kZmaSnZ2Nh4dHgfsghYSEEBISkvu4sEH4cjdAX7M+vPQG6sO3OfvRe5z9eRPGiKdRteqWv7a4gpJMVnALv9i5XAzLli3D19cXX1/fEgV4JaZpMmPGDF588UXuu+8+oqKiaNGiRZG7V6alpRX4vKenJxkZGaUe57VSbm6oJi1QXXpB8kn0+q/R2/+Lqt8Y5V82n6gctS2sUFhblPUU6p07dxIYGEiNGjWIj49nx44d7Nq1i+zs7Dx/9Evi1KlTJCQkcMMNN/D9999TrVo1brzxxjzHdOrUibvuuos777wTHx8fvL29efTRR4t1fme7x8qSqlAR1e5mVJ366K0b0P/5Gip74tmiDefOnbM6PIdQknvsqr4RmabJ9OnT8fb2pmvXrnTt2rVYX/WLIz4+npo1a1KjRg0AunTpQmxsLHXr1r3qc738sjcHDriTlVU6sZWNAGAWOj0Nth2Hz7IgIBsCqpd6TbsKFRy9LeynQwc3Jk60/3WfeOKJ3AkKw4YN44MPPuDs2bOMGTPmms8dGhpKREQE69evz52+DXDw4EHWrl3LyJEjr/kaIi/V4RaMxs0xl0eiP3ib03vj0A89ifKT+6wkrnodkWma7Nixg82bN7N9+3aaNm1Kt27d6NSpEx4eJZ9NsnXrVuLi4nJvmk2bNnHgwIF8ax3+2X994cKFfOd65hk3fvvNKLD0viPSOTnkJBzDPJ2MquyJe93rUKVYl0wp5TRtUdbatlW89lpWvucrVizbbUEOHDhA06ZN8z0fHx9PkyZNyvTa16q8rSO6Glpr9MZv0R9HgXsF1OBRGB1vtTosS9l9QevRo0eJjIzkyJEjVKxYkVtuuYUBAwbg7+9/1ecqbiL6J1e6SfSvWzBXLoKcbIyhYagOpbNFgDO2RVmxakHro48+yvLly/M9P2zYMKKiosr02tfKle6xsuJ7PoOkeS/D4f2oTsGoh55AeRa8qNjV2aXoaUZGBlu3bmXz5s38+eefdOrUiREjRhAYGMhXX33FjBkzmDt37tWeFn9/f5KSknIfJyUllSihOTPVoQtGw6aYb83BfHM2KuQe1P2XZuYI52OaJvD/n5z//7+L/v77b9xk3yuX4F6nPsaE2ehvPkZ/9SF6/++2enXN21gdmlO4qr9w8+bNY+fOnTRv3pzevXvTsWNHKly2h8cjjzzC0KFDSxRI48aNSUhIIDExEX9/f7Zs2UJYWFiJzuXMlH81jOdmoD9Zho75Av3XnxhPTEBVKZ+frpzdoEGDcn/+51RrwzC477777B2SKCPKzQ1194PoVh1si2Bfn2z7MNnvEdkRughX1TX3xRdf0K1btyvOmruWfVe2b9/O8uXLMU2THj160K9fvyLf48rdBuaWdegViyCwBsaYl1A165ToPK7QFqXF3l1zJ0+eRGtNeHg4U6dORWudu9bH29u7zMemSoMr32Ol5Z9toc+fR38ahf7PN1Crnm2vo/qOUwi5LEnR08u4yk2iD+zBXDwD0BhhU2y7xl4lV2mL0mB10VPTNPNUQnAGrn6PlYbC2kLv3o65LBLSz6DuGYTq08/lS3xJ0VMXpJq2wJg4Bzw8Mee9JOWBnNTZs2eZP38+Dz/8cG6X87Zt2/jwww8tjkyUJdWqPcbUBah2ndGfrcScMxF9sniLmMsTSUROQFWvjTFhNlSriRk5Db1jq9Uhiav0zjvv4OnpyeLFi3H//8knzZo1Y8uWLRZHJsqaqlIV9fhzqMeegeNHMaeG2SryO3dnVKmSROQklK8/xnMzoH4jzLdmSzJyMr/99hvDhg3L0yXn7e1dYIFS4XqUUhidgjHCI6FhM/SKhZiLpqPPpFgdmkOQRORElKcXxripUL+xLRnF/Wx1SKKYPD0985XKOXXqlFONFYlrp/yrYYx/BTVwBPy+AzM8TD5UIonI6SjPKpcloznofb9ZHZIohl69ejFv3jx2796N1pr9+/ezaNEievfubXVows6UYWCE3IsxOQL8AjAXz8BcFonOLF91+y4nicgJKc8qGGEv28aMFr6KPiKbnDm6e++9ly5durB06VJycnJYsmQJQUFB9O3b1+rQhEVU7foYE19D9e2P3rIec+pT6AN7rA7LEjJ924np5JOYsyeAqTGmv4mqWPD6rfLQFsVl9fRtZ1Se77Hiuta20PF7MN97A079jbq9n2035wrOuTWMXUr8CMeh/KthjHsFEhMKTULCcRw/fpw//viDzMzMPM/37NnTooiEo1BNWmC8/Ab6o/fQ332K3r3dtgi2TgOrQ7MLSUROTtWqC7WufqsMYV9r1qzh008/pUGDBvkqj1xrIkpPTyciIoKTJ0/mbgPh5ZW/JNSpU6d48803c2s6Tpw4kerVq1/TtUXpUR6eqEfGoNvchLl8Aear41H3PWIrE2S49iiKJCIh7OCbb75hxowZNGhQ+p9wo6Ojad26NaGhoURHRxMdHc3gwYPzHbdw4UL69evHjTfeSGZmZqnveyVKh2pzE0b4AsyVi9Afv4feFYsxbBwqoJrVoZUZ106zQjiIihUrUqdOyWoFFiU2Npbg4GAAgoODiY2NzXfMsWPHyMnJyd251cPDo8Q1IUXZU96+GKMmoR4dC3/EY04di7n1Py67CFa+EQlRRi5uAQEwcOBA3nvvPfr374+Pj0+e44xr7Ha5vHadr69vgYtkjx8/TpUqVZg7dy6JiYm0bt2ahx9+uMBr/3PzycDAgrewd3d3L/S18qbM2iJ0ENmdu3Em8lWylkZQcU8c3iOfx/D2Kfq9FilJW0giEqKMXL4FxEXr1q3L99zq1auLPNe0adM4ffp0vuf/ubXExcre/2SaJnv37mXOnDkEBgYSERHBhg0bChyfCgkJISQkJPdxYbPBZNbcJWXaFu6V0OPCUd9Hc/7z9zm5ZyfG0LGoVh3K5nrXSGbNCeFAFi5cCNg2xdu6dSs333xznte11vz8c/GqY0yePLnQ13x8fEhJScHPz4+UlBS8vb3zHePv7891111HjRo1ALjpppvYv3+/zNhzEspwQ91xP7plO8z3IjDnT0V174t6YCiqkofV4V0zGSMSooxUq1aNatWqUb16dT799NPcx5c/v2bNmmu+TlBQEBs3bgRg48aNdOzYMd8xTZo0ISMjgzNnzgCwe/du6taV2ZbORtVvhPHiPNRtoeiN32K+Mg59aJ/VYV0z+UYkRBnavXs3ADk5Obk/X/T3339TuXLla75GaGgoERERrF+/Pnf6NsDBgwdZu3YtI0eOxDAMhgwZwiuvvILWmkaNGuXpfhPOQ1WoiOo/HN06CDPqDczZE1B3DkD1HYByd84/6VJZoRyQtrjE3pUVRo8eDdjGWS4fwFVK4evrS2hoKEFBQWVy7dIi91jRrGoLnXEW/eHb6P/+Bxo0sS2CrWntN12nHSNauXIlv/76K+7u7tSoUYNRo0ZRpUoVq8MS4potWrQIsI0XjRkzxuJohKtRnlVQw8fbFsGuXIw5bRzqgWG28SMnWifmEGNEN954I/PmzWPu3LnUqlWLzz77zOqQhChVkoREWVIdbsEIXwDNWqH//Rbm/HD06SSrwyo2h0hEbdq0wc3Nto97s2bNSE5OtjgiIYRwLsrXHyNsCurhkXDgd9teR9t+tDqsYnGIRHS59evX07ZtW6vDEEIIp6OUwujeF2PyfNs2MW/NwVz6Ojoj3erQrshuY0RXWpB3cbrpmjVrcHNzo2vXroWeR1Z9Xz1pi0ukLUR5oGrWwZgwG/3Nx+ivV6P377bVq7vhRqtDK5DDzJrbsGEDa9eu5eWXX76qGlgyo6do0haXyH5EV0/usaI5clvow/sxl0bA33+hQu5F9RuCqlCxzK5XknvMIbrm4uLi+Pzzz5kwYYIUYhRCiFKkGjbDmPwGqkdfdMznmK8+jT5yyOqw8nCI6dtLly4lOzubadOmAdC0aVMef/xxi6MSQgjXoCpVQj00En1jR8xlCzBnPIu69yHU7fehDDerw3OMRLRgwQKrQxBCCJenWnXACI9Er1qCXrPCttfR8PGoajUtjcshuuaEEELYh/LyRj3xPGrE0/DXEcypT2Fu/sHSvY4kEQkhRDmjlMLo3B1jSiRc1wS9YiHmounoM/lnNtuDJCIhhCinVEA1jKenoQaMgN93YIaPRccVb2uS0uQQY0RCiJJLT08nIiKCkydP5lbf9vLyynfcqlWr2L59O1prWrduzbBhw5yqHpkoG8owUL3vRbdoi/nu65iLpqNu7Y0aOALl4WmXGOQbkRBOLjo6mtatWxMZGUnr1q2Jjo7Od8y+ffvYt28fc+fOZd68eRw8eJA9e/ZYEK1wVKpOA4wX59o24PspBnPqU+h4+/yOSCISwsnFxsYSHBwMQHBwMLGxsfmOUUpx4cIFsrOzycrKIicnBx8fH3uHKhyccq+A0e9RjOdmAmDOmYS5ZgU6O6tMrytdc0I4udTUVPz8/ADw9fUlNTU13zHNmjWjZcuWPP7442it6dOnT6E7tEoZravncm0R2A2zbQfS3osk89tPcPvfTnzGTcG9fqMi31qStpBEJIQTuFKtxssppQoc9zlx4gR//fUXb775Zu759u7dS/PmzfMdGxISkmf31sJK1zhyWRt7c9m2GPgvjOtvJHvFQpKeGYbq9wiq190oo/DONKfdGE8IcWWTJ08u9DUfHx9SUlLw8/MjJSUFb2/vfMf88ssvNG3aFA8PDwDatWvH/v37C0xEQlxOte2E0eh6zBUL0R8ttS2CHfoUKqBaqV1DxoiEcHJBQUFs3LgRgI0bN+ZWs79cYGAge/fuJScnh+zsbPbs2UOdOnXsHapwUsrbF2P0i6hHxsDhA5hTwzC3bii1RbCSiIRwcqGhoezatYuwsDB+++03QkNDATh48GBuV1znzp2pUaMGzz77LM899xwNGjQgKCjIyrCFk1FKYXS9DWPKfKhTH730dfTbr6HPpl37uR1lG4iSkhL1RZO2uES2gbh6co8Vrby1hTZz0N9/hv783+DljTE0DNWqPeDE20AIIYRwHspww7jjAYxJr4FnFcz54Zj/fhN9/nyJzieJSAghRImo+o0xJkfYKjP85xvMaePIOrz/qs8jiUgIIUSJqQoVMQaMwHjatp+ccq9w1eeQRCSEEOKaqeZtMF5ZiHu9hlf9XklEQgghSkVJd3uVRCSEEMJSkoiEEEJYyunXEQkhhHBuLvuN6IUXXrA6BIchbXGJtEXpkba8RNrikpK0hcsmIiGEEM5BEpEQQghLuYWHh4dbHURZadSo6E2cygtpi0ukLUqPtOUl0haXXG1byGQFIYQQlpKuOSGEEJZyuR1a4+LiiIqKwjRNevXqlbs3S3k0evRoPDw8MAwDNzc3Zs2aZXVIdrN48WK2b9+Oj48P8+bNAyA9PZ2IiAhOnjxJtWrVGD9+PF5eXhZH6nzK8z0mv1eXnDp1ikWLFnH69GmUUoSEhNC3b9+StYd2ITk5OXrMmDH6xIkTOisrSz/77LP66NGjVodlmVGjRunU1FSrw7DE77//rg8ePKiffvrp3OdWrlypP/vsM6211p999pleuXKlVeE5rfJ+j8nv1SXJycn64MGDWmutMzIydFhYmD569GiJ2sOluubi4+OpWbMmNWrUwN3dnS5duhAbG2t1WMICLVq0yPcpLDY2luDgYACCg4Pld6MEyvs9Jr9Xl/j5+eVOSqhcuTJ16tQhOTm5RO3hUl1zycnJBAQE5D4OCAjgwIEDFkZkvenTpwPQu3dvQkJCLI7GWqmpqfj5+QHg6+tLamqqxRE5H7nH8pPfK0hMTOTw4cM0adKkRO3hUolI5DVt2jT8/f1JTU3l1VdfpXbt2rRo0cLqsByCUgqllNVhCBdTHn+vMjMzmTdvHkOHDsXT0zPPa8VtD5fqmvP39ycpKSn3cVJSEv7+/hZGZK2L/3YfHx86duxIfHy8xRFZy8fHh5SUFABSUlLw9va2OCLnI/dYfuX59yo7O5t58+bRtWtXOnXqBOvNKi4AACAASURBVJSsPVwqETVu3JiEhAQSExPJzs5my5YtBAUFWR2WJTIzMzl37lzuz7t27aJ+/foWR2WtoKAgNm7cCMDGjRvp2LGjxRE5H7nH8iuvv1daa958803q1KnDXXfdlft8SdrD5Ra0bt++neXLl2OaJj169KBfv35Wh2SJv//+m7lz5wKQk5PDrbfeWq7a4o033mDPnj2kpaXh4+PDgAED6NixIxEREZw6dapcTbMtbeX5HpPfq0v+97//8fLLL1O/fv3c7rdBgwbRtGnTq24Pl0tEQgghnItLdc0JIYRwPpKIhBBCWEoSkRBCCEtJIhJCCGEpSURCCCEsJYlICCGEpSQRCSGEsJQkIiGEEJaSROSiTpw4wbBhwzh06BBgq5o8YsQIfv/9d4sjE0KIvCQRuaiaNWvy8MMPs2DBAs6fP8+SJUsIDg6mZcuWVocmhBB5SIkfFzd79mwSExNRSjFz5kwqVKhgdUhCCJGHfCNycb169eLo0aP06dNHkpAQwiFJInJhmZmZLF++nJ49e/Lxxx+Tnp5udUhCCJGPJCIXFhUVRaNGjRg5ciTt27fn7bfftjokIYTIRxKRi4qNjSUuLo5//etfADz66KMcPnyYzZs3WxyZEELkJZMVhBBCWEq+EQkhhLCUJCIhhBCWkkQkhBDCUpKIhBBCWEoSkRBCCEtJIhJCCGEpSURCCCEsJYlICCGEpSQRCSGEsJQkIiGEEJaSRCSEEMJSkoiEEEJYShKREEIIS0kiEkIIYSl3qwO4VsePHy/w+cDAQE6dOmXnaByTtMUlhbVF7dq1LYim9CxevJjt27fj4+PDvHnz8r2utSYqKoodO3ZQqVIlRo0aRaNGjYp1brnHiiZtcUlJ7jH5RiSEC+jevTuTJk0q9PUdO3Zw4sQJIiMjefzxx3n33XftGJ0QV+b034iEKA59Nh29+h2yHxwBnt5Wh1PqWrRoQWJiYqGvb9u2jW7duqGUolmzZpw9e5aUlBT8/Pyu+lo6/Qx6zQrOeHhgZmbmP8AwoIo3VK0KXt4oL2+4+J+PP6pChau+pnBtkoiEy9N74jCj5kPaabI63AxtOlsdkt0lJycTGBiY+zggIIDk5OQCE1FMTAwxMTEAzJo1K8/7AHIwSd69nfMKVAH7O+ucbHT6GTBN2+PLXzQM3KrXwq1OfdzrNMCtTgPc//9nw9f/mv+dVnF3d8/XTuVVSdpCEpFwWfrCefSaFeh1X0LNuhijJ1E56GbOSl/+FYWEhBASEpL7OH9/v4Ga816hYwEK0KYJ5zIg/UzufzotFZJPYp74i5yEY1zY9StkXbj0Rv9AVJMW0KS57X/r1EcZbmXzjyxlMkZ0SUnGiCQRCZek/4zHfPd1OHEM1etuVL9HUBUrWR2WZfz9/fP8cUhKSsLfv+y+gSjDgCpetv9q2P4AqX8co00TUk5BwjF0wlE4tA+9fzf8ssn2LaqyJzS6HtW0Jap1ENRriFL/PItwBZKIhEvROTno7z5Ff/kBVPXFGD8V1aKd1WFZLigoiO+++45bbrmFAwcO4OnpWaLxodKkDAMCqkNAdVSr9oBtdh9Jiej4vRC/Bx2/F/35++joVbbj2tyEatsJmrZEucufL1ch/08Kl6ETj2O+9wYc/B/qpm6oh0aiqnhZHZZdvPHGG+zZs4e0tDRGjhzJgAEDyM7OBuC2226jXbt2bN++nbCwMCpWrMioUaMsjrhgSikIrIEKrAGduwOgz6Sgd8aid/6C3vwDev1X4FkF1ToI1b4L3BiEcpcJEM5Maa0LGG4sfXFxcURFRWGaJr169SI0NDTP66dOnWLRokWcPXsW0zR56KGHaN++fZHnlTUORXP1ttBaozd/j/7oPXBzQz00EqNTcIHHuuo6orLkSPeYPp8Je+LQcT+jd/0C6WlQ1QfVuTvq1t6o2vXtGs9Frn6PXQ2HHSMyTZOlS5fy0ksvERAQwMSJEwkKCqJu3bq5x3z66afcfPPN3HbbbRw7doyZM2cWKxGJ8k2npmAuXwC/bYPmbTCGPoXyl9lLrkpV8oB2nVHtOqNzcmDPDswf16LXf4Ve+7ltTOmWEFTHrqjKnlaHK4rJLokoPj6emjVrUqNGDQC6dOlCbGxsnkSklCIjIwOAjIwMy/uvhePT2/+LuXIRnM9EPfg4qkdf27iDKBeUmxu0DsKtdRD6zGn01g3oH9eiVy5Cr34XdXMP1G2hqOrybdfR2SURJScnExAQkPs4ICCAAwcO5Dmmf//+vPrqq3z33XecP3+eyZMnF3iuotY4XCTz+i9xtbYwM86StvQNMtd/jXuj6/EZNwX3etcV672u1hbCRnn7om4LRfe+1zb7bvMP6J9i0Ju+h/Y3Y9x+P6phU6vDFIVwmMkKP/30E927d+fuu+9m//79LFiwgHnz5mH84xNu0WscbKTP9hJXagu9f7dtQkLyKdSdAzDvGshp9wpQzH+fjBG5NqUUNL4B1fgG9H1D0Ou+RG/4FvPXLXB9a4zb+0Gr9jIN3MHYpR/D39+fpKSk3McFrWFYv349N998MwDNmjUjKyuLtLQ0e4QnnIDOysL8ZBnm3BfBMDCen4kROlhmS4lCKR8/jH6PYMxZiuo/HBITMCOnYk4NQ2//L3aapyWKwS6JqHHjxiQkJJCYmEh2djZbtmwhKCgozzGBgYHs3r0bgGPHjpGVlYW3t+vVBBNXTx/7A3PGM+jv16C63obx8nxUk+ZWhyWchPLwxLgtFGPGW6hh4yAnG3PJTMxZz6P37bY6PIGduubc3NwYPnw406dPxzRNevToQb169Vi9ejWNGzcmKCiIRx55hLfeeouvv/4agFGjRsnX53JOmznotV+go1eCpxfGmMmoNh2tDks4KeVeAdWlJ7pTMHrLOvQXH2DOnQStgzD6DUHVbWh1iOWW3dYRlRVHWuPgqJyxLXRSom0saP9uaNcZY8hoVFWfaz6vjBFdPVe9x/SF87Zp399+AucyUJ2CUfc8hKpW86rP5extUZocdh2REMWltUb/9z/oD94CQA19CtWlp3w7FqVOVayE6nM/uuvttrJQ675Eb/sJdccDqDvuR1WoaHWI5YYkIuEwdNoZzFWLYPt/oWkLjOHjbaVehChDqooX6v5H0T3vQn8Shf7yA/TW/2A89ASqVQerwysXJBEJh6B/24a5LBLOpqMeGIrqfa/TbAEgXIPyC0D961n0rb0x//0m5vyp0L4LxsARKP9qVofn0iQRCUvpzHPoj6PQm76DOg0wxk1F1ZNBY2Ed1bwNxsuR6B8+Q3/zEebv21F3D7JtJyIVv8uEtKqwjD74P8z3IuDkCdRt96FCH5Z+eeEQVIUKqDsHoDsFY374jq3L7ucNtu7iutdZHZ7LkcJcwu50djbm5+9jzn4BsrMxnnkVo/8wSULC4ajAGriNeQlj1CQ4nYw5/WnMbz9FmzlWh+ZS5BuRsCudcAxz6evwZzzq5p6oB/+F8qxidVhCXJFq1xmjSQvM9xej1yxH7/wZY9g4VA2Z9l8aJBEJu9Cmid7wDfqTZVCpEsbIF1Adulgdlkspas+vDRs2sHLlytzyWn369KFXr15WhOqUVFVvjCcmoH/ZhP73W5ivhKHuH4rq3tfq0JyeJCJR5nRKkm1G3J4dtlXsj4xB+foX/UZRbMXZ8wtsW7CMGDHCoiidn1IK1SkYfX0rzOUL0R+8jY77mZxnXgFkrVtJyRiRKFNm7GbM8LEQvwc1eBTG2MmShMrA5Xt+ubu75+75JcqG8g3ACHsZ9cgYOLSPpKcfRe/+1eqwnJZ8IxJlQp9NR//7LfQvG6FhM4wRT0t/ehkqzp5fAD///DN79+6lVq1aPProowXuzSR7fl2F+x4i+6ZbSJ07mez5U6ly/yNUGfQYyq38/mktye9F+W0tUWb0njjMqPmQdhp170OoO/rbdtMUlurQoQO33HILFSpUYO3atSxatIgpU6bkO072/LpKlaoQMOsdTi6aydlPV3D2t18x/vUsyjeg6Pe6IIeuNVfUQCrAli1b+Pjjj1FK0aBBA5566il7hSdKgb5wHr1mBXrdl1CzDsboOajrZFdMeyjOnl9Vq1bN/blXr16sWrXKbvG5OlWpEsYjYzCbtUSvWoL5yjhbL0DLdlaH5hTskoiKM5CakJBAdHQ006ZNw8vLi9TUVHuEJkqJ/vOgbVp2wlFUz7tQ/R5FVapkdVjlxuV7fvn7+7NlyxbCwsLyHJOSkoKfnx8A27ZtyzeRQVw7o3MPdIOmmG/NxpwfjurbH3XPIClXVQS7JKLLB1KB3IHUy2+EdevWcfvtt+Pl5QWAj8+1l/wXZU/n5NgqF3/5AVT1sZXokU+BdlecPb++/fZbtm3bhpubG15eXowaNcrqsF2SqlUXY+Jc9Advob/+CH30MMZjz6Aqe1odmsOyy35EW7duJS4ujpEjRwKwadMmDhw4kGca6Zw5c6hduzb79u3DNE369+9P27Zt853rnwOpFy5cKPCa7u7uZGdnl8G/xvmUVVtkJxzjTOQ0sv73G5Vu7YX3489hVHXsXXULa4uKFaWqQ2FcdT+i0lRYW5j/+Qb94dtQow7GmJdQ1WtZEJ19OfQYUVFM0yQhIYEpU6aQnJzMlClTmDt3LlWq5F11LwOpV6+020Jrjd78A/qjpWC4oR57huxOwSSfvwDnHbvNZWM8YU9Gj77omnUw35qDOf0ZjJETUM3bWB2Ww7HLOqLiDKT6+/sTFBSEu7s71atXp1atWiQkJNgjPHEV9JkUzIWvolcugkbXY4RHYnQKtjosIRyWat4GY9Jc8PHDfGMK5n++xsk3xi51dklElw+kZmdns2XLFoKCgvIcc9NNN/H7778DcObMGRISEnLHlIRj0HFbMcPDYE8cauBjtvEg2adFiCKp6rUwJr4GrYNs6+tWLUFnZ1kdlsOwS9dccQZS27Rpw86dOxk/fjyGYTB48OA8002FdXRmBvrDd9E/xUD9RhjPTEfVqW91WEI4FVXZE2PURHT0KvS3n6L//gtj1ESUp5fVoVnOLpMVypIMpBbtWtpCH9hj2zMo6STqjgdQdw9EuVco5Qjtx4oxotTUVHbu3Mkff/xBRkYGnp6eXHfdddx44434+vqW2XVLi9xjRbvatjD/+x/08gW29XZPhaP8XGfxa5lOVjh16hR//vknZ8+epUqVKjRo0EDKe7gwnZWF/uLf6O/XQGANjOdnopo0tzosp3Ls2DFWr17N77//TqNGjahTpw6+vr6cO3eOTZs2sWzZMlq2bMnAgQNlTU85Y9zcA+3jh7lkJuas5zDCwst1L8MVE1F2djYxMTGsXbuWxMREatasiYeHB5mZmZw4cYLq1avTu3dvQkJCcJctdF2G/utPzHdfh2OHUV1vQw0YgfKobHVYTmfx4sXcc889hIWFUaFC/m+RWVlZbNu2jSVLljB9+nQLIhRWUi3aYjw3EzNyKuacCRijX0I1a2l1WJa4Ytfc+PHjadWqFbfeeitNmzbFMC7NbTBNk/j4eDZv3szvv//O66+/bpeA/0m6DYpW3LbQpomO+QL92QqoXAXj0TBUm452iNB+ZPr21ZN7rGjX1P196m/M+VPh1N8Yjz2N6nBLKUdnX6XeNRceHl5ohQPDMGjWrBnNmjXjzJkzVxmqcDQ6KdFWqHTfb9C2M8Yjo1FVpbpFaZkzZw7PP/98vufnzp3Ls88+a0FEwlGowBoYL8zGXDAN8605qIH/wuh1l9Vh2dUVp29fnoS++OKLAo/56quv8PZ27NX0onBaa8wt6zGnhsEf8aihYbaZPJKEStXFpQnFfV6UL6pKVYynp0GbTugP38b8bFW5WmtU7IGdTz/9lHvuuafA5++6q3xlb1eh085grloM27dAkxYYw8ehqtW0OiyXsnr1asA23nrx54v+/vtvqlWTdVjCRlWshPHkBNsao28+gguZMGAESrn+zq9FJqLdu3cDtjGhiz9f9Pfff1O5sgxiOyP926+YyyMhPc1WKfv2UKkQXAYuVhQxTTNPdRGw9aUPGDDAirCEg1KGGwwZDRUroWO+gPOZMPhJl783i0xES5YsAeDChQu5P4Nt73ZfX1+GDx9edtGJUqfPZ6I/iUJv+BZq18cIm4Kq38jqsFzWxQrXzZo1y1MjUYjCKKVg4GNQqfL/fzM6D8PGufTmkkUmokWLFgGwcOFCxowZU+YBibKjD+3DXBoBJxNQt4WiQgejKkjV6bJy+vTp3AWrV0pClx8nBNiSkbpvMGbFirZKDFkXbLu+OvFi8isp9hiRJCHnpbOzMT//t+3Tla8/xtPTUDfcaHVYLu+VV16hRYsWdOvWjSZNmhS4/GHTpk3s3buXefPmWRipcFTGnQMwK3mgV7+LuWgGxpMvoCq63oaTV0xEEydO5J577qFjx44FLljNzs7ml19+4auvvmLGjBllFqQoOX3iGMmzn0fH/w91cw/Ug4+jPKsU/UZxzebMmUNMTAxvvfUWiYmJVK9encqVK3Pu3LncBeK9e/dm6NChpXK9uLg4oqKiME2TXr16ERoamuf1rKwsFi5cyKFDh6hatSrjxo2jevXqpXJtUXaMkHswK1ZCr1qMGfkKxtjJqEoeVodVqq6YiEaPHs3q1at59913adiwIbVr186trJCQkMChQ4do1aqV7PTogLTW6A3f2MaDKnrY9kFx8oVyzsbd3Z0+ffrQp08fTp06xZEjR8jIyMgtkfXPrVCuhWmaLF26lJdeeomAgAAmTpxIUFBQntJB69evp0qVKixYsICffvqJ999/n/Hjx5daDKLsGN1utyWj997AXPgqxpjJqEqu883oiomobt26PPPMM5w+fZpdu3Zx5MgR0tLSqFKlCt26dWPMmDHF3tK7qE9rF23dupXXX3+dmTNn0rhx46v/Fwn06STMZZHw+w5o1Z6A8eGkmFZHVb4FBgaWaW3G+Ph4atasmbt1SpcuXYiNjc2TiLZt20b//v0B6Ny5M++99x5a63IxPdgVGJ27Y6JtyWjxdNuOry4yxlusMSJfX1+6detW4osU59MawLlz5/j2229p2rRpia9V3pmxP6JXLYbsLNTDT6KC++DmHwhSisVSWVlZfPLJJ/z000+kpaWxfPlydu7cSUJCAn369Lnm8ycnJxMQcKmCc0BAAAcOHCj0GDc3Nzw9PUlLS8u3ID0mJoaYmBgAZs2aVWgCdXd3l8LH/89ubXFXf85VrsyZhTNwf3cevi/MdLhkVJK2uGIi2rNnDy1atADIt4bocq1atbriRYrzaQ1si//uvffeQqs4iMLpjHTbhls/b4SGzTCGj0fVrGN1WOL/LV++nOTkZMLCwnLHU+vVq8fy5ctLJRGVppCQkDyz/AqroSa15i6xa1u06YwaMpoLKxeROP15W7e7A82mK/Vac0uXLs2dzXP5GqLLKaVYuHDhFQMrzqe1Q4cOcerUKdq3by+J6CrpvTttdeJSk1H3PoS6o79LrzlwRr/88guRkZF4eHjkdoX5+/uTnJxcKuf39/fPs2A2KSkp3xjUxWMCAgLIyckhIyNDNp90Uka32zFzctD/fhPznbkY/3oO5cQ7IFwx8sunlF5cT1QWTNNkxYoVxZr0IN0Gl+gL50lf9SYZX67GrU59fCbOokLTFvmOKw9tUVxWtYW7uzummXeg7syZM6WWCBo3bkxCQgKJiYn4+/uzZcsWwsLC8hzToUMHNmzYQLNmzdi6dSstW7aU8SEnZvToi5mTjV79Lnrp6/DYM077AbTEKXT37t0YhpHbdXclRX1ay8zM5OjRo0ydOhWwLfC7WK34nxMWpNvARh85aNszKOEoqsed6PuHklqpUoFjQa7eFlfDqm0gOnfuzMKFC3OnaqekpLBs2TK6dOlSKud3c3Nj+PDhTJ8+HdM06dGjB/Xq1WP16tU0btyYoKAgevbsycKFCxk7dixeXl6MGzeuVK4trGOE3GP7ZvRJFLi72yowGFesZe2Qir1V+JQpUxg0aBA33HAD0dHRfP311xiGwe23306/fv2u+N6cnByeeuopXn75Zfz9/Zk4cSJhYWHUq1evwOPDw8MZMmRIsWbNlbe9UrSZg/5uDfqLD6CqN8bQp1At213xPa7aFiVhVSLKzs5m1apVrFu3jgsXLlCxYkV69erFww8/XOCmeY6kvN1jJWF1W5hff4SOXoXqcSdq0OOWftMt063Cjx49SrNmzQBYt24dU6ZMwcPDg8mTJxeZiIrzaU0UTZ88gfleBMTvRXW4BTVkFKqK9PE7A3d3d4YOHcrQoUNzu+SkW0yUFtW3P5xNQ6/9HKr6oO5+0OqQrkqxE9HFL04nTpwAyJ3xdvbs2WK9v3379rRv3z7PcwMHDizw2PDw8OKGVS5ordE/rkWvXgqGgRrxNKpTsPwhcyLDhg0jKioKIM906ccee4x3333XqrCEi1BKwQPDID0N/cW/Mb2qYvS40+qwiq3Yiej666/nvffeIyUlhY4dbdtHnzhxQmbdlDF9JgVzxSLY+Qtc39q2Z5C/7GHjbHJycvI9l52dnW8CgxAlpQwDHh1rW8rxwduYnl4YnYKtDqtYip2IRo8ezZdffom3t3fuBnnHjx+nb9++ZRZceafjttqS0LkM1MARqJ53O+VAZHn28ssvo5QiKyuLKVOm5HktKSkpt7tbiNKg3NwwHn8Oc/5UdNQbaE8vVOsOVodVpGInosqVK2MYBps3b+bLL7/Ez8+PLl26FDk+JK6ezsxAf/gu+qcYqN8I45npqDr1rQ5LlEDPnj0B26LuHj165D6vlMLHx4fWrVtbFZpwUapiJYzRL2LOexHzzZkY46ehmjS3OqwrKnYieuedd0hISGD48OFUq1aNkydP8tlnn5GcnCxFT0uRPrDHNiEh6SSqb3/U3Q861KppcXW6d+8OwObNm6lVqxbXX3997mv79u1j5cqVpVZ9W4iLlGcVjKfCMWe/gLngFYznZqLqXmd1WIUqdj9PbGwsEyZMoF27dtStW5d27drx/PPPExsbW5bxlRs6OwtzzXLM1yaCUhjPz8C4b4gkIRfxxx9/5FuO0KhRI3788UeLIhKuTnn7Yjz9ClSshBn5Cjolqeg3WaTYicjX15fz58/nee7ChQv4+fmVelDljf7rT8zpz6K//RR1a2+Ml99ANSl6obBwHkqpfBMTTNOkmMv4hCgRFVAdI2wKnDtrS0bnMqwOqUBu4cWcK33u3Dnef/99DMMgNTWV33//nWXLltG1a1eys7NJTEzM3fzLntLS0gp83tPTk4wMx2z0i7Rpotd+jn57DuTkYDz+HMbt95X6tyBnaAt7Kawtynr25/79+zl8+DCtW7fOTUqrV6/Gw8ODW25x7H2inPkesxdHbgvl44dq0AQd8zn6j3hUx65lOumpJPdYsSsrjB49ushjilMAtbQ566pvnXQSM+oN2PcbtO2EMWQ0ytu3TK7l6G1hT1ZVVkhKSmLWrFmcPn06NwY/Pz8mTJiQpyCwI3LWe8yenKEtzB/XopcvQN3aG/XImDJbh1imlRXKsuhpeaK1Rm/dgP7gLTA16tGxqFtCZHGqiwsICGD27NnEx8fnVsBu0qQJhkzHF3Zi3NobMykR/dVqCKiOuqvgggJWcN664U5Ip5/BXLUYft0CTZrb9gyqVtPqsISdGIYh64aEpdQ9D8GpRPTn72P6V8Po0tPqkABJRHajd/+KuWwBpJ9B9XsEdft9KMM5S7YLIZyTUgoeHYM+nYResQDtF4Bq3sbqsIo/a06UjD6fifn+m5jzp0IVL4xJczHueECSkBDCEsq9AsaTL0CNOphLZqKPH7E6JPlGVJb04f2YSyMg8Tiq972o+4Y43P7ywvmlp6cTERHByZMnqVatGuPHj8fLyyvfcQMHDqR+fVuFjsDAQCZMmGDvUIWDUJ5eGGFTMGc8g7nwVYxJc1Fe3kW/sYzYLRHFxcURFRWFaZr06tWL0NDQPK9/9dVXrFu3Djc3N7y9vXnyySepVs05i3vq7Gz0Nx+hv/4IfP0xnp6GuuFGq8MSLio6OprWrVsTGhpKdHQ00dHRDB48ON9xFStW5LXXXrMgQuGIVEA1jFGTMOe+iPnmbIxx4ZYtoLdL15xpmixdupRJkyYRERHBTz/9xLFjx/Icc9111zFr1izmzp1L586dWbVqlT1CK3X6xDHM2RPQX36IuqkbxpRISUKiTMXGxhIcbKuyHBwcLNVORLGpxjegHh0L+35Df/C2ZQus7fKNKD4+npo1a1KjRg0AunTpQmxsbO6eRgCtWrXK/blp06Zs3rzZHqGVGq01esM3ti17K1TCGDkB1cGxFyoK15Camppb4cTX15fU1NQCj8vKyuKFF17Azc2Ne++9l5tuusmeYQoHZXTujnn8CPrbT6B2fVSvu+0eg10SUXJycp5FewEBARw4cKDQ49evX0/btm0LfC0mJoaYmBgAZs2aRWBgYIHHubu7F/paactJPsmZhTO4sONnKrbrjPeYSbj52+faxWHPtnB0ztoW06ZN4/Tp0/mef/DBvDtxKqUKXZO2ePFi/P39+fvvv3nllVeoX78+NWvmXz7giPeYo3P2ttCPjSM1OZHzHy2larPmVGrXucTnKklbONxkhU2bNnHo0KFCd2kNCQkhJCQk93Fhq5nttdJZb/sRc9USyDqPengk2cF3kGICDrTK2hlWfduLVZUVrtXkyZMLfc3Hx4eUlBT8/PxISUnJswPs5fz9/QGoUaMGLVq04I8//igwETnaPeYMXKEt9ODR8NcRTr82GWPia6hadYt+UwFKco/ZZYzI39+fpKRLlV+TkpJyb4rL7dq1i88++4znn3+eChUcu+q0zkjHXPo65ltzoHotjMnzMbr3lQoJwu6CgoLYuHEjABs3bszdQfly6enpZGVlAXDmzBn27duXp2tcCOVRGWPMS+DujrlwGvpswTUGy4JdvhE1btyYhIQEEhMT8ff3Z8uWFMn+uQAACV9JREFULYSFheU55vDhw7zzzjtMmjQJHx8fe4RVYnrvTsxl8+F0MuruQag7B6DcZF2QsEZoaCgRERGsX78+d/o2wMGDB1m7di0jR47kr7/+4u2338YwDEzTJDQ0VBKRyEcFVLfNpJt3cSbdVLv8bSt20dNrtX37dpYvX45pmvTo0YN+/fqxevVqGjduTFBQENOmTePIkSP4+toKfxZ3nYM9CzLqrAvoNSvRMZ9DjToYI55GNWxaqtcoC67QbVBanLVrzkpS9LRortYW5k/r0Mvmo24Lxeg//KreW6ZFT69V+/btad++fZ7nBg68VHTvSn3gjkAfOWhbnHr8CKpHX9T9w1CVKlkdlhBClDrjll6Yfx5A/xCN2aAJxk3dyvR6DjdZwdFoMwf9/Wfoz/8NXt4YT4WjWrUv+o1CCOHE1IAR6KN/oJdHomvXQ9VtWGbXklpzV6BPnsB8bRJ6zQpU204Y4ZGShIQQ5YJyr4AxcgJ4emEunlmmkxckERVAa425+QfMqU/BX0dQI55GPfG8pbWYhBDC3pSPH8bIFyD5FOa789BmTplcRxLRP+gzpzEXTUevWAgNm2KER2J07i7TsoUQ5ZJqfANq0OOwe7ttiKIMyBjRZXTcz5grFsK5DNTAEaied5fp3u5CCOEMVLfb4c949Dcfoxs0QbW/uVTPL4kI0JkZ6NVL0T+uhXoNMZ6ZjqpT3+qwhBDCISilYNAT6GN/YL73Bkatuqha9Urt/OX+476O34M59Sn0T+tQdzxg25dDkpAQQuShKlSwjRdVrIi5ZBY681ypnbvcJiKdnYW5ZjnmnEmgFMbzMzD6PWLZfhxCCOHolH8gxr+ehRN/oVcuLrVtI8pl15z+6wjm0nlw9DCq622oAcNRHp5WhyWEEA5PNW+DumcQ+vP3oWkLVPc7rvmc5SoRadNEr/sSvWYFVPbEGP0iqm0nq8MSQginovr2Rx/ci179DrphU1SDJtd0vnLTNaeTTmK+Phn90VJo2c62OFWSkBBCXDVlGBjDn4aqvphvzkafTb+m87l8ItJaY279D+bUMPjjAOqRMbZvQt5+VocmhBBOS1X1xnjieUg5hbls/jWNF9mtay4uLo6oqChM06RXr16EhobmeT0rK4uFCxdy6NAhqv5fe3cX09QZxgH8f1oytYCVFsGl1mRWjdE7LKgkBnVNlqDZotlUlpARLhYubPkIWYAJaWYIzbKuJn6MkHlBmEu8GVwvxMgFSMQxkikhYmMWTDQIpQzSaaB9d6G0NpUJ7bEHzvn/7nrO4Zw3T87Th/NweN/sbNTU1CAvLy+la4r5fyB++Qnij37Athe6ylpIeR+mdE4iInpFsu2F9HnFq39/+b0H0ienkjpPWp6IIpEIrl+/jqamJvh8PvT39+PJkydxx9y6dQuZmZm4fPkyTpw4gRs3bqR0zZd/DiLidkGMDEI6VQ7dN20sQkREMpM+/hQoKIb4rRNifDSpc6SlED169Ajbtm1Dfn4+MjIyUFxcjKGhobhj7t27h6NHjwIADh06hPv37yf1qCdevkTk13YEv6sDDJnQNf0AXekXkHRcuI7U6c6dO6irq8PZs2fh9/uXPW5kZATV1dVwOp3o6elJ4whJzSRJgu4rJ5Cbj0jH94gEA6s+R1pac4FAAGazOfrZbDZjfHx82WP0ej0MBgPm5uaweXP8RKO9vb3o7e0FAHg8HuTm5sbtj/wbQmDsL2z8rAyZX34N6QOuGZSRkZEQJ61SYyysVivq6+vR0dGx7DFLXYkLFy7AbDajsbERdrudq7SSLCRDJnRVDYj82IyFv/2AZXVLRqy717cdDgccDkf089tWAhTfepFl2f56X/rWXV+r1LZ6ZCrUuELrSorJm10JANGuBAsRyUWyfgSd52dssGzH3Cq/b9LSmjOZTJieno5+np6ehslkWvaYcDiMUCiE7OzspK4nbdiY/GCJVOhtXYlAYPUtFKL/k+x3b1qeiGw2G54+fYrJyUmYTCYMDAzA5XLFHXPgwAHcvn0be/bsweDgIPbv38+lF4heu3jxIoLBYML2c+fOobCwUNZrvav9vUSNbc5kMRYxycQiLYVIr9ejsrISra2tiEQiOHbsGKxWK27evAmbzQa73Y7jx4/jypUrcDqdyMrKQk1NTTqGRrQuNDc3p/TzK+lKLFlJ+xtgy/dNjEVMMu1vScg1ax0RKcrtdqO8vBw2my1hXzgcRnV1NVpaWmAymdDY2AiXywWrVb6p/ImSpdqZFRoaGpQewprBWMSoMRZ3795FVVUVHj58CI/Hg9bWVgCv/i7U1tYGIL4rUVtbi8OHD6dchNQYy2QxFjHJxGLdvTVHRPGKiopQVFSUsH3pyWdJQUEBCgoK0jk0ohVR7RMRERGtD3q32+1WehDvy86dO5UewprBWMQwFvJhLGMYi5jVxoIvKxARkaLYmiMiIkWxEBERkaJU99bcu9Y9Urtr165heHgYRqMRXq8XADA/Pw+fz4fnz59j69atqK2tRVZWlsIjfb+mpqZw9epVBINBSJIEh8OB0tJSTcZCblrOMeZXjKw5JlQkHA6L8+fPi2fPnomFhQVRX18vJiYmlB5WWj148ED4/X5RV1cX3dbV1SW6u7uFEEJ0d3eLrq4upYaXNoFAQPj9fiGEEKFQSLhcLjExMaHJWMhJ6znG/IqRM8dU1ZpbybpHardv376E3z6GhoZQUlICACgpKdFETHJycqJv7mzatAkWiwWBQECTsZCT1nOM+RUjZ46pqhBxhuG3m52dRU5ODgBgy5YtmJ2dVXhE6TU5OYnHjx9j165dmo9FqphjiXhPpZ5jqipE9G6SJGlqVvMXL17A6/WioqICBoMhbp/WYkHvnxbvKTlyTFWFaDUzDGuJ0WjEzMwMAGBmZiZh1Vu1WlxchNfrxZEjR3Dw4EEA2o2FXJhjibR8T8mVY6oqRG+ue7S4uIiBgQHY7Xalh6U4u92Ovr4+AEBfX5/s69esRUIItLe3w2Kx4OTJk9HtWoyFnJhjibR6T8mZY6qbWWF4eBidnZ3RdY9Onz6t9JDS6tKlSxgdHcXc3ByMRiPOnDmDwsJC+Hw+TE1Naeb10rGxMbS0tGDHjh3R1kBZWRl2796tuVjITcs5xvyKkTPHVFeIiIhofVFVa46IiNYfFiIiIlIUCxERESmKhYiIiBTFQkRERIpiISIiIkWxEBERkaL+A1AZp+TS5iHfAAAAAElFTkSuQmCC\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(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": 10, "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", " #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,int(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": 11, "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": 12, "metadata": {}, "outputs": [ { "data": { "image/png": "iVBORw0KGgoAAAANSUhEUgAAAaIAAAEYCAYAAAAeWvJ8AAAABHNCSVQICAgIfAhkiAAAAAlwSFlzAAALEgAACxIB0t1+/AAAADh0RVh0U29mdHdhcmUAbWF0cGxvdGxpYiB2ZXJzaW9uMy4xLjMsIGh0dHA6Ly9tYXRwbG90bGliLm9yZy+AADFEAAAgAElEQVR4nOzdeVxUVf/A8c+5oCIiO+5LSu67gpmVqFDZTv5SK61cWnxScWtRS8VMs9JwzxZF0xafFi0tK9FH7cnHxNxSy73MRFFABHEB7vn9MUUSoIjD3Jnh+369eiUzd+Z+74E737nnnvM9SmutEUIIISxiWB2AEEKIsk0SkRBCCEtJIhJCCGEpSURCCCEsJYlICCGEpSQRCSGEsJSn1QFcq2PHjhX6eHBwMKdOnXJwNKVPjqt01ahRw+oQnEZZO7dKStrjb5dri8udWy6fiIQo67Zv3058fDymaRIZGUl0dHS+57Ozs5k9ezaHDh2icuXKDBs2jCpVqlgUrRAFSdecEC7MNE3mz5/PmDFjiIuL4/vvv+fo0aP5tlm7di2VKlVi1qxZ3HXXXbz//vsWRStE4SQRCeHCDhw4QLVq1ahatSqenp507NiRxMTEfNts2bKFzp07A9ChQwd27dpFSQqq6AsXyJ36Ahe2brJH6ELkka45IVxYamoqQUFBeT8HBQWxf//+Irfx8PDA29ubjIwMfH19822XkJBAQkICAFOmTCE4ODjf87knjpGWlcnpiSOoeFs0Pn0HY1T0Lo3Dcimenp4F2qqsKmlbSCISQgAQFRVFVFRU3s8Fbjp7lEePfh3vbz4j64sPObdtE0a/YagGTR0cqXORwQp/K+lgBemaE8KFBQYGkpKSkvdzSkoKgYGBRW6Tm5tLVlYWlStXLtH+VLnyVO47GOOZyaA15uujMT+JR2dfLPlBiDJPEpEQLiw0NJSkpCSSk5PJyclh48aNhIWF5dumXbt2rFu3DoBNmzbRrFkzlFLXtF/VsBnG+BmoW25Df7MM8+UR6CMHr+k9RdkliUgIF+bh4UH//v2ZNGkSw4cP58Ybb6R27dosXbqULVu2ANC1a1cyMzMZMmQIK1eupHfv3nbZt/LyxnhkEEbMODibiTn5GcyVS9G5uXZ5f1F2KFdfj6isTbqT4ypdMqH1b1dzbumzGej356ETv4N6DTH6D0NVq+WIMC3nLH+7zkDuEQkhLKMqVcZ48lnUk89BchLmS8Mw16xAm6bVoQkXIIlICGE3RvjNGLGzoHFL9EfvYMaNQ6ectDos4eQkEQkh7Er5B2IMGYt6ZBAc3o85YQjm92tKNIlWlA2SiIQQdqeUwuh0O8b4GVC7HnrhDMw5k9Bn0qwOTTghSURCiFKjQqphjJyE6tEfdm/DHD8EvXWj1WEJJyOJSAhRqpRhYNwWjTE2DgJDMN+cgjk/Dp2VaXVowklIIhJCOISqUQdj9Ouoex5Eb16PGRuD3rPN6rCEE5BEJIRwGOXpiXHvwxijXweviphx4zE/mIe+cN7q0ISFJBEJIRxOXdcA48U3UFH3odetwnxpKPrgL1aHJSwiiUgIYQlVvgJGrwEYIydBbi7mq6MwP3sPnZ1tdWjCwSQRCSEspRo1xxg/E3VTJHrVJ5iTR6KPHrY6LOFATpWI5s6dy+OPP87IkSOtDkUI4UCqojfGY0MwBo+FM6cxXx6J+dXHUkC1jHCqhfE6d+5Mt27dmDNnjtWhCOH0MjMziYuL4+TJk4SEhDB8+HB8fHzybfPrr7/yzjvvcO7cOQzDoHv37nTs2NGiiK9MtQrHiJ2N+f5c9LLF6B2bMfoPR1WVYrTuzKkSUdOmTUlOTr7m9zEXzuR09gVyLxa+WJcqVx4qeNn+K1/h7397VURV9oPKfuDrD5X9URUqXHM8QpSG5cuX06JFC6Kjo1m+fDnLly+nT58++bYpX748gwcPpnr16qSmpjJq1ChatWpFpUqVLIr6ylRlX4ynnkdv3oD+YB7mS0NRD/RFRdyBMpyqE0fYiVMlouJISEggISEBgClTphS6Pnra2TOY6Wl4FlraSqMvXEBfOIc+fx59/hyYuZc8m5/y8sbw88cICMajanU8qtbEo2oNPKrVwKNKDYzAYIeeHCVdE97ZuetxlabExERiY2MBiIiIIDY2tkAiurT0fmBgIH5+fpw5c8apExHYSgSpGyLQDZtjLpqJ/uAt9LZNGH1jUIEhVocn7MzlElFUVBRRUVF5Pxe69sWgF6+4Roj68z+tNeTkwMXzcC4LMs5Axmn0mdOQkQ5n0jHPnCb3dArZP22FDd/CpcUbPctB1RqomnWhZl1UzeugVl0IDLnmVTAL465rnzjLcbnSekTp6ekEBAQA4O/vT3p6+mW3P3DgADk5OVStWrXQ54vzJQ8c/KUhOBg9cTbnvv2czIWz0BOG4vPEcLwiupXK+VUS8iXqbyVtC5dLRPamlIJy5Wz/VaoMwbaTtKg/cZ2TDakn4eQJ9MnjcOo4OumobQ7E5g1/X1FV9LYlpusaQP3GqNBG8k1OXLWJEydy+vTpAo8/+OCD+X5WSl32gzktLY1Zs2YxaNAgjCKu4Iv1JQ+LvjS0uxlVOxQzfjpnZkzkzIbVGH2eRvn6OzaOQjjLlyhnUNKF8cp8IrpayrMcVKkBVWoUSFY66ywc+w199Df44zf00cPo9V9Dwhe2BOUfBPUb2ZJSaBO4rgHKw8OCoxCuYuzYsUU+5+fnR1paGgEBAaSlpeHr61vodllZWUyZMoWHHnqIhg0bllaopU5VqY7x7GT06s/Ry5dgxg7BeGQQqk0Hq0MT18ipEtH06dPZs2cPGRkZDBw4kJ49e9K1a1erwyo25V0Jrm+Kur5p3mM6JweOHkYf3AuH9qIP/YLeutGWmCp6Q6MWqCatUE1bQ9WaTtPdIJxfWFgY69evJzo6mvXr1xMeHl5gm5ycHKZOnUqnTp3o0MH1P7CV4YG6vTu6eTvMBXGYcyejbuyKevAJ2/knXJLSLr5a1bFjxwp93Jkvl3V6Guzfjf55B3rPdjh1wvZEYLAtKbUIh2ZtUF4VC7zWmY/rWjjLcbnSPaKMjAzi4uI4depUvuHbBw8eZPXq1QwcOJANGzbw5ptvUqtWrbzXDRo0iOuuu+6K7+/s55bOyUavXIpe9Qn4B2L0HYpq0srhcThLeziDknbNSSJyAjo56e+k9MtOyMqEcuWhaWtUmw6olu1RlW3dLq50XFfDWY7LlRJRaXOVc0sf2ou5YDqc+AMVeQ/q/kcdOu3C2drDSnKPyIWpKtVRVapDRDfbTPIDe9DbNtn+27EZrQxo0BTV9kZyb7/P6nBFMZw5c4YNGzawdetWfvvtN7KysvD29qZu3bq0bt2azp07F3lPR1wdVb8Rxtjp6GXvodesQO/aitF/GKp+I6tDE8UkV0ROTGsNRw6ht/0PvW0THDsChoet265DZ1TrG1Dl3WPCrbP8vuxxRfT+++/z3//+lzZt2tC0aVNq1qxJxYoVOXfuHH/88Qd79uxh27Zt3HzzzfTu3dsOUZcOVzy39M87MBfOgLRU1B0PoO7pZRtgVIqcuT0cTa6I3JBSCuqGouqGQnQf9B9H8Nr5A1n/WYV+ZyraqyKqXUdUhy7QsLnMOncSQUFBzJw5k3LlCn4A1qtXj5tvvpmLFy+ydu1aC6Jzb6pJK4zxs9BL30V/9W/0T4kYA0bY5vkJpyVXRC4mODiYk8nJsG8X+n//Qf+4ES6cgyrVbSVQbopEVapsdZhXzVl+X/a+R3T69Gn8/QvOdSnqcWfi6ueW3r4J8705cO4s6r7eqNuiUYb9p0u4Sns4QkmviOQrtAtShoFq3BKj31CMae+hBowAX3/0xwswn+2HuXAm+rcDVocpgKFDhxb6+PDhwx0cSdmjWnfAmDAbWoajP12E+foYdHKS1WGJQkjXnItTFSqgOnSGDp3Rvx9Gr1uF/mEd+vsEqNcQ1fVuVPgtMnHWIoV1OGRlZRVZ3UDYl6rshzFwlO2c+ODtPwuo9kM5UYkgIYnIraja9VCPPI3+v8fQm/6D/s9X6PlvoJcvQd0ajbr5Vqkm7iD/+te/ALh48WLev/+SmZnJTTfdZEVYZZJSCtWhy58FVGeh338TveMHjEeHoAKCrA5PIPeIXM7VHJc2TfjpR8yvP4UDe8DH13aF1OVOlI9zDR12lt+Xve4R7dmzB601r7zyCmPGjMn3nL+/v0vMV3LHc0trbes1+GQBeJZDPTwQ1b7TNV0duXJ72JtMaP0Hd/3jKOlx6QN7ML/+DHZshvIVbF0T3f7PKYpGgvP8vuydIC5cuEAFF70KdedzS584hhk/HQ7+gmp3E6r3v/ImjV8td2gPe5HBCuKy1PVN8Rj8IkbsLFTbjuiEFZhjnsRctgSdlWl1eG7lq6++Ijs7G6DIJJSdnc1XX33lyLDEJVTVGhjPvYLq/ih6+w+YsYPROxKtDqvMkntEZYyqWRc1YDj6rh7oLz60zbVY9yXqtvtt5VEKqW8nrs7p06eJiYnJm9Bao0YNvLy8OH/+PMeOHcub0BoREWF1qGWaMjxQdzzwdwHV2RNt91F7DkBV9LY6vDJFuuZcjL2PSx85hPn5+7AzESr7oe7qZeu283TsdxRn+X3Zq2vuzJkzrFu3ju3bt3PkyBHOnj2Lj48PderUoU2bNkRERFC5snPP9ypL55bOzkav+BD99WcQGIzRbxiqUfNivdYd26Ok5B7RP7jrH0dpHZc++AvmssWw9yeoXhuj5wBU87Z2309RnOX35QqDCP6SmZlJXFwcJ0+ezFd9uzBZWVmMGDGC8PBwBgwYUKz3L2vnFvx5HiyIg5PHUZH3ou7vc8UyWu7cHldL7hGJa6JCG2OMfBlj0AuQk405I5bcWRPRx/+wOjRRhOXLl9OiRQtmzpxJixYtWL58eZHbLl26lCZNmjgwOtekQhtjjJuB6nwHOuFzzJdHoH/db3VYbk/uEYk8SilofQNGs7botSvQK5dixg5BRd5t67KThceuWlZWFh9//HHego+XdkC8+eab1/TeiYmJxMbGAhAREUFsbCx9+vQpsN2hQ4dIT0+ndevWHDx48Jr2WRaoCl6ohweiW9+AGT8T85VnUXf1RN3Z0+Fd1mWFXBGJAlS5chi3d8d4eR6qQ2f06s8xxw1C/7ix0EoBomjvvvsuhw8f5oEHHiAzM5P+/fsTHBzMXXfddc3vnZ6eTkBAAGCbm5Senl5gG9M0ee+993jkkUeueX9ljWraxjbKtH0n9IqPMKc8hz52xOqw3JKkd1Ek5ReA6huDjrgDc/FszHlTbFdMDw+UGenFtHPnTuLi4qhcuTKGYRAeHk5oaCivvvoqd9999xVfP3HiRE6fPl3g8QcffDDfz0qpQidlfvvtt7Rp04agoCv/vhISEkhISABgypQpBAcHF7qdp6dnkc+5neBgeH4y5/+3jjPzXsN8eQQ+vZ/C+55eedXuy1R7XEFJ28KpEtH27duJj4/HNE0iIyOJjo62OiQBqHoNMMZMQyd8jv7iQ8zxg1DdH0V16iZLT1yB1hpvb9tQYC8vL7KysvD39+f48ePFev3YsWOLfM7Pz4+0tDQCAgJIS0srdKG9ffv28fPPP/Ptt99y/vx5cnJy8PLyKnQdpKioKKKiovJ+Luqmc5m8Od+gOWr8DPTiuWQunEXmxrW2pclDqpXN9ihCSQcreMT+1clcDAsXLsTf379UytebpsnkyZN54YUXuP/++4mPj6dp06ZXXMUyIyOj0Me9vb3Jysqye5xWs+q4lGGgrm+KCr8FfeQQrP0S/csO1PVN7FIuyFl+X/YeUr1jxw6Cg4OpWrUqBw4cYNu2bezcuZOcnJx8H/olcerUKZKSkmjcuDHffPMNISEhtGzZMt82N9xwA3fffTd33XUXfn5++Pr68thjjxXr/cvauXUlqkJFVPgtEFQVNq5Br1sFlf3wbtycc+fOWR2eU7jc38blzq2ruiIyTZNJkybh6+vLLbfcwi233FKsS/7iOHDgANWqVaNq1aoAdOzYkcTERGrVqnXV7zVunC/793uSne1+3Uflyll9XEFoPRfOpEHicXjfhCoK/AK5lmLGjj6upk2zeemlM6W+n6eeeirvvlq/fv348MMPOXv2LIMHD77m946OjiYuLo61a9fmDd8GOHjwIKtXr2bgwIHXvA+Rn1IKdVMkunFLzIUz0O/N5vTuregHn0T5B1odnsu66nlEpmmybds2vvvuO7Zu3UqDBg3o1KkTN9xwA15eXiUOZNOmTWzfvj3v5NmwYQP79+8vMOfhn/3YFy9eLPBeI0d68NNPhlveWFdKOc1x6exscv74DZ2Zgarsi2eNOqhCViUtDkcfV8uWmmnTcgs8Xr58ebvuZ//+/TRo0KDA4wcOHOD666+3677srSzOI7oa2jTR//kS/dkiKFcB1ftfGOE3Wx2WpSyZ0Pr7778zc+ZMjhw5Qvny5bnpppvo2bMngYFX/82guInon8rayeJsx6W1tp2MnyyECl4Yjw5Gtelw1e/jLMdl7wmtjz32GIsWLSrweL9+/YiPj7frvuytrJ1bJeV/4Swp08bD4X22St4PP+WSqyTbQ0kT0VUPVsjKymLTpk189913/Pbbb9xwww0MGDCA4OBgVq5cyeTJk5k6derVvi2BgYGkpKTk/ZySklKihCYcSymF6no3ukkrzHffwJw7GXXLbaheT5TptY9M0wT+TNR//veXEydO4CELFboNz5p1MZ5/Fb3qE/TKj9D7dmE8NgTVvJ3VobmMq0pE06ZNY8eOHTRp0oRbb72V8PBwyl3SFfPoo4/St2/fEgUSGhpKUlISycnJBAYGsnHjRmJiYkr0XsLxVPXaGKNfsxVS/fpT9KG9GANHoarVtDo0Szz00EN5//7nUGvDMLj//vsdHZIoRcrDA3V3L3TLMMwF0zFnTLCNKu3RTwoJF8NVdc198cUXdOrU6bKj5q5l/ZWtW7eyaNEiTNOkS5cudO/e/YqvKWvdB65wXHrXVsz50yAnB6NvDKrdlVcjdZbjslfX3MmTJ9FaExsby4QJE9Ba58318fX1tfu9qNJQ1s6tkvpne+jsbPTn76O/XQbBVW0FVBs0tTBCx5Gip//grieLqxyXTjmJ+dartn7zqPtQ//fYZcujOMtxlVbRU9M081VCcAVl7dwqqaLaQ+/fY1t879QJ1G3RqPt6o8o5/xeQayFFT4VTUUEhtoXHIu+xFY+cOgZ9OuXKL3QzZ8+eZcaMGfTu3Tuvq3nLli189NFHFkcmSptq0NRWQPWW29HfLLMVUD0itf4KI4lIlBrlWQ7jwSdQTz4LR3/FnDQS/dsBq8NyqHfeeQdvb2/mzp2L559XhA0bNmTjxo0WRyYcQXlVxHjkaYyh4yErE3PyM5grP0LnFpw6UJZJIhKlzgi/BWPUq2B4YL42Cv1j2fkQ/umnn+jXr1++LjlfX99CC5QK96Wat7MVUG13E/rzD2wFVJOOWh2W05BEJBxC1aqH8cJUqFUPc94UzC//7TQTc0uTt7d3gVI5p06dcql7RcI+VKXKGE88g3ryOTh5HHPiMMyEL9B/DvUvyyQRCYdRvgEYz0xCtY9AL1+Cnv8GOrtgZQx3EhkZybRp09i1axdaa/bt28ecOXO49dZbrQ5NWMQIvxkjdhY0bole+i7mG2PRKclWh2Wpqyp66ozKWmFGVz8u5eEBbW8EwwO9ZgV63y5Umw5U8vN3iuOyd9HTRo0aceHCBT755BPOnj3Lnj17uPnmm7nzzjsLXbbBmZS1c6ukStIeyqsiqn0nCAiG79eg168CvwCoXc/p/y4up6RFT2X4totxp+MyN29AL5gO1WsT/NJM0nKt/1MsreHbrqisnVslda3toU8ex1w4E/btglbtMR4dhPJ1za5bh5X4EcJejPad0JUqY775Cmmjn0LHjEdVqW51WHZ37Ngxfv31V86fP5/v8a5du1oUkXAmKqQaxsiXbT0En72HOX4IRp+nUe06Wh2aw0giEpZSzdpgjJiIOWsi+tXnMYbGourUtzosu/nss8/49NNPqVu3boGKI9eaiDIzM4mLi+PkyZN5y0D4+PgU2O7UqVPMmzcvr5bj6NGjqVKlyjXtW9iXMgzUrfehm7fFnB+HOW8KqkNn1ENPorwL/k7djXTNuRh3PS7/c5mkjI+B81kYg8eiGjazJA57d809/vjjjB07lrp169r1fQGWLFmCj48P0dHRLF++nMzMTPr06VNgu9jYWLp3707Lli05f/48SqlileEqa+dWSdm7PXRODvqrj9FfLgXfAFuZrGZt7Pb+pUkqKwiX5ln7OttcI78AzBmx6H27rA7JLsqXL0/NmqVT+DUxMZGIiAgAIiIiSExMLLDN0aNHyc3NzVu51cvLq8S1IIVjKE9PjHsfwhj9OlT0xpw+HvP9eegL56/8YhclXXPCaajAEIxnJmNOexFzxgSMoeNRDZtbHdZVMy+ZF9KrVy8WLFhAjx498PPzy7edYVzb98BLa9f5+/sXOkn22LFjVKpUialTp5KcnEyLFi3o3bt3ofv+56KTwcHBhe7X09OzyOfKolJrj+BgdIu2ZL4/j6yV/8bYuxPfmLGUb9zC/vuyk5K2hSQi4VSUXwDGyJddOhldugTEX9asWVPgsaVLl17xvSZOnMjp06cLPP7PpSX+quz9T6Zp8vPPP/Paa68RHBxMXFwc69atK/T+VFRUFFFRUXk/F9XFIl1z+ZV6e9zbG6NRK3Ljp5M25l+o2+9H3ftwiVdDLk0yak64DVdPRrNnzwZsi+Jt2rSJG2+8Md/zWmt++OGHYr3X2LFji3zOz8+PtLQ0AgICSEtLw9fXt8A2gYGBXHfddVStWhWA9u3bs2/fPhmx52JUo+YYsTPR/15gW+/rpy0YA0agatezOjS7kHtEwin9lYwIqoI5YwJ6/x6rQyq2kJAQQkJCqFKlCp9++mnez5c+/tlnn13zfsLCwli/fj0A69evJzw8vMA2119/PVlZWZw5cwaAXbt2UatWrWvet3A85eWN8ehgjCFjISMdc9JIzK8+dosCqpKIhNPKS0YBwbbh3UcPWx1Sse3atYtdu3aRm5ub9++//luzZg0VK177qp3R0dHs3LmTmJgYfvrpJ6KjowE4ePAg8+bNA2z3oR555BFeeuklRo4cidY6X/ebcD2qZThG7GxU6xvQyxbbCgmfKHyEo6uQ4dsupiwel045iTnlOdAmxvOvokKqlVoc9hq+PWjQIMB2n+XSm7dKKfz9/YmOjiYsLMwu+yotZe3cKimr2kNrjd68Af3BW5BzEfV/fVGd70Rd4yCYayErtP6Du54sZfW49LEjmK+Ogko+GKNeLbUSKPaeRzR79mwGDx5s1/d0lLJ2bpWU1e2hT6dgLpoFu7ZCk1a2eUeBIZbE4tLziP73v/8xYsQIevXqxcGDsoKhKEjVqIMRMw7S0zCnx6KzzlodUrG4ahISrkP5B2HEjEf1eRoO7cWMjcH8339capkVp0hEtWvX5plnnqFJkyZWhyKcmAptjPGvUXDsCOacSW6/hIQQxaWUwojohjFuBtSsi14Qh/nmK+gM11iA0SkSUa1ataTqsSgW1bwdqt8wyMmGixesDkcIp6KqVMd4dhLqgb7w0xbM8YPR2zZZHdYVudw8orI++1uOC7jr/9Ddom1rGwkh8lGGB+r27ujm7TDnv4E5dzLqxq6oB59AeVeyOrxCOSwRXW6GeGHzH4pS1md/y3GVLrkyF+5C1ayLMWYqeuVS9KpP0Ht3YvQdimrSyurQCnBYIrrcDHEhhBD2pzzLoaL7oFuGYy6YjvnGWFTXu1HdH0M5UfFbp7hHJIQQovSo+o0wxk5HRd6DXrsSc+Iw9KG9VoeVxykS0ebNmxk4cCD79u1jypQpTJo0yeqQhBDCragKFTAefAJjxETIvog55XnMZUvQOdlWh+YcgxXat29P+/btrQ5DCCHcnmrSCmP8TPTSd9Ff/Rv9UyJG/+GoWtdZFpNTXBEJIYRwHOVdCaPfUIxBL8DpVMxJIzC//hRtWlNAVRKREEKUUar1DRgTZkPLcPSnizBfH4NOTnJ4HE7RNSeEuHqZmZnExcVx8uRJQkJCGD58OD4+PgW2W7JkCVu3bkVrTYsWLejXr1+hi+iJsklV9sMYOAr9wzr0B29jvjQU9UA/VEQ3h/2dyBWREC5q+fLltGjRgpkzZ9KiRQuWL19eYJu9e/eyd+9epk6dyrRp0zh48CB79rjO2k7CMZRSGB26YMTOhNDG6PffxJw5AZ2W4pD9SyISwkUlJiYSEREBQEREBImJiQW2UUpx8eJFcnJyyM7OJjc3Fz8/P0eHKlyECgzBGDYB9fBA2LcbM3Yw5g/rS72AqnTNCeGi0tPTCQiwLYfh7+9PenrBApcNGzakWbNmPPnkk2it6datW5ErtJb18lkl5Zbt0eNRcm7qwpmZE8l+dxrld2/Fd+CzGL7+l31ZSdtCEpEQTuxypbEupZQqtD//+PHj/PHHH3krtk6cOJGff/650Er3Zb18Vkm5bXuUr4geMRH1zTIufP4BJ3dvw3h0CKpV0SXZSroekSQiIZzY5Upj+fn5kZaWRkBAAGlpafj6+hbYZvPmzTRo0AAvLy8A2rRpw759+2TJFVEsyvBA3fGArYDqgjjM2RNRN0Whej2Oquhtt/3IPSIhXFRYWBjr168HYP369YUWDw4ODubnn38mNzeXnJwc9uzZQ82aNR0dqnBxqnY9jDHTbElp41rMCTHovT/Z7f0lEQnhoqKjo9m5cycxMTH89NNPREdHA3Dw4MG8rrgOHTpQtWpVnnnmGZ599lnq1q1LWFiYlWELF6XKlcPo/ijG81PAwwNz6guYS99F22FdMKVdaT3ZQhw7dqzQx92131aOq3TJMhB/K2vnVkmVxfbQF86jP12I/s9XUK0WxoDhqOsalPgekVwRCSGEuCqqghfGwwMxhk+A8+cwX3kW84sP0Dk5JXo/SURCCCFKRDVtgxE7C9W+E3rFR6SOehKdXPiV9OVIIhJCCFFiqpIPxoARtjJBWWeh3NUvuCfDt4UQQlwz1a4jQVF3kZKWdtWvlSsiIYQQdqE8PEr0OklEQgghLCWJSNtibsQAACAASURBVAghhKVcfh6REEII1+a2V0SjRo2yOoRSIcclrCa/q/ykPf5W0rZw20QkhBDCNUgiEkIIYSmP2NjYWKuDKC3169e3OoRSIcclrCa/q/ykPf5WkraQwQpCCCEsJV1zQgghLOV2JX62b99OfHw8pmkSGRmZt0aLqzt16hRz5szh9OnTKKWIiorizjvvtDosuzFNk1GjRhEYGCijkJyUu55bxTV37ly2bt2Kn58f06ZNAyAzM5O4uDhOnjxJSEgIw4cPx8fHx+JIHaOoz6QStYl2I7m5uXrw4MH6+PHjOjs7Wz/zzDP6999/tzosu0hNTdUHDx7UWmudlZWlY2Ji3ObYtNZ6xYoVevr06fqVV16xOhRRCHc+t4pr9+7d+uDBg3rEiBF5jy1evFgvW7ZMa631smXL9OLFi60Kz+GK+kwqSZu4VdfcgQMHqFatGlWrVsXT05OOHTuSmJhodVh2ERAQkHcTsGLFitSsWZPU1FSLo7KPlJQUtm7dSmRkpNWhiCK487lVXE2bNi3wzT4xMZGIiAgAIiIiylSbFPWZVJI2catElJqaSlBQUN7PQUFBbvNhfank5GQOHz7M9ddfb3UodrFw4UL69OmDUsrqUEQRysq5dbXS09MJCAgAwN/fn/T0dIsjssaln0klaRO3SkRlwfnz55k2bRp9+/bF29vb6nCu2Y8//oifn58MfxUuTylVJr9MXe4zqbht4laDFQIDA0lJScn7OSUlhcDAQAsjsq+cnBymTZvGLbfcwg033GB1OHaxd+9etmzZwrZt27h48SLnzp1j5syZxMTEWB2auIS7n1sl5efnR1paGgEBAaSlpeHr62t1SA5V2GdSSdrEra6IQkNDSUpKIjk5mZycHDZu3EhYWJjVYdmF1pp58+ZRs2ZN7r77bqvDsZuHH36YefPmMWfOHIYNG0bz5s0lCTkhdz63rkVYWBjr168HYP369YSHh1sckeMU9ZlUkjZxuwmtW7duZdGiRZimSZcuXejevbvVIdnFL7/8wrhx46hTp07epe5DDz1E27ZtLY7Mfnbv3s2KFStk+LaTctdzq7imT5/Onj17yMjIwM/Pj549exIeHk5cXBynTp0qc8O3i/pMatCgwVW3idslIiGEEK7FrbrmhBBCuB5JREIIISwliUgIIYSlJBEJIYSwlCQiIYQQlpJEJIQQwlKSiIQQQlhKEpEQQghLSSJyY8ePH6dfv34cOnQIsFVQHjBgALt377Y4MiGE+JskIjdWrVo1evfuzaxZs7hw4QJvvvkmERERNGvWzOrQhBAij5T4KQNeffVVkpOTUUrxyiuvUK5cOatDEkKIPHJFVAZERkby+++/061bN0lCQginI4nIzZ0/f55FixbRtWtXPv74YzIzM60OSQgh8pFE5Obi4+OpX78+AwcOpG3btrz99ttWhySEEPlIInJjiYmJbN++nSeeeAKAxx57jMOHD/Pdd99ZHJkQQvxNBisIIYSwlFwRCSGEsJQkIiGEEJaSRCSEEMJSkoiEEEJYShKREEIIS0kiEkIIYSlJREIIISwliUgIIYSlJBEJIYSwlCQiIYQQlpJEJIQQwlKSiIQQQlhKEpEQQghLSSISQghhKU+rA7hWx44dK/Tx4OBgTp065eBonJe0R35FtUeNGjUsiKbk5s6dy9atW/Hz82PatGkFntdaEx8fz7Zt26hQoQJPP/009evXL9Z7y7lVPNIef7tcW1zu3JIrIiFcWOfOnRkzZkyRz2/bto3jx48zc+ZMnnzySd59910HRidE8bj8FZEQV0NnnEH/+11y+jwFFSpZHc41a9q0KcnJyUU+v2XLFjp16oRSioYNG3L27FnS0tIICAi46n3prEz0Jws54+WFef58wQ2UAZV8wKcy+PiifHzBx9f2s28AyqviVe9TlA2SiESZoXckYr43C85mkn1DJ2geZnVIpS41NZXg4OC8n4OCgkhNTS00ESUkJJCQkADAlClT8r0OIPe0QequrVxQoApZ11nn5qDPZkBuru3nfzxvBATjUbMOnjXr2v5fow4eNevgEVIN5eFxbQdqIU9PzwJtVVaVtC0kEQm3p89lof89H/3f1VCzLsawCVRsE85Z6dfPJyoqiqioqLyfC+vrV68tKPI+gMJ2T4pzWXA2AzLPQGYGOvMMnE5BH/+D7BN/kP3dasjK/PuFFb2hXiNUaGPU9U2gfkOUl3dpHGKpkHtEfyvpPSJJRMKt6b27MOOnQ+op1B3/h7rnYVS5claH5TCBgYH5PhhSUlIIDAwstf0ppcC7ku2/kGq2x/6xjdbalqSO/4E+fhSOHEQf+Bm98iPbc8qAWnVR1zdBNW0NTVqjKniVWszCepKIhFvSFy+gly1Br/kCgqtiPPeK7dt2GRMWFsbXX3/NTTfdxP79+/H29i7R/SF7UkpBZT+o7Idq0DTvcZ11Fg7vsyWlgz+jN65F/+crKFcemrRCtWqPahmO8i+9RCqsIYlIuB39637MBdMh6XdU5ztRD/R122/U06dPZ8+ePWRkZDBw4EB69uxJTk4OALfddhtt2rRh69atxMTEUL58eZ5++mmLIy6a8q4EzdqgmrUBQOfkwP7d6B2b0dt/QO9MtN13qtfQlpTad0L9edUlXJvSWhdy29H+tm/fTnx8PKZpEhkZSXR0dL7nT506xZw5czh79iymafLwww/Ttm3bK76vzHUonrLQHjonB/3Vv9Ff/ht8AzD6xuR9qP2Tu8wjKk3OdG5preHYEVtC2rEZDu+zPdGoBapjJKpdR8u+bJSFc6u4nPoekWmazJ8/nxdffJGgoCBGjx5NWFgYtWrVytvm008/5cYbb+S2227j6NGjvPLKK8VKREIA6GNHbFdBvx1A3RCBeugpVCUfq8MSdqKUgpp1UTXrwl090amn0P9bi964Bh0/Hf3hW6jwW1AdIyG0sW174TIckogOHDhAtWrVqFq1KgAdO3YkMTExXyJSSpGVlQVAVlaW5f3YwjVo00QnfIFethi8vDAGjkK162h1WKKUqcBg1F090Xf2gP170BsT0Js3oL/7FqrVQkXeg+rYFVW+gtWhimJwSCJKTU0lKCgo7+egoCD279+fb5sePXrw8ssv8/XXX3PhwgXGjh1b6Htdaa7DX2Rsf37u2B65J46RPvNlsvdsp0L4zVR+ehQexbyR7Y7tURYppaBhM1TDZugHn0T/+D163Sr0+2+iP38f1eUuVJc7UZX9rA5VXIbTDFb4/vvv6dy5M/fccw/79u1j1qxZTJs2DcPIX4WoOHMdQPpt/8md2kNrjf7vavTS+aBA9R1KdseupOWYUMxjlHtE7kd5VUTdFIXuGAn7d2N+uxy94kP015/aro5ujUZVld+vM3JIIgoMDCQlJSXv58LmMqxduzavZlbDhg3Jzs4mIyMDPz/5JiP+pk+nYr43G37aAo1aYPQbigqqYnVYwonYrpKa49GwOTrpd/Tqz9HfJ6A3fANtbsS492FUzTpWhyku4ZCip6GhoSQlJZGcnExOTg4bN24kLCx/eZXg4GB27doFwNGjR8nOzsbX19cR4QkXYSb+FzN2CPyyE9XrcYwREyUJictS1WtjPDoYY8p81B09YM82zAkxmAumo0+dsDo88SeHXBF5eHjQv39/Jk2ahGmadOnShdq1a7N06VJCQ0MJCwvj0Ucf5a233uLLL78E4Omnn5aRLwIAfTYD/cFb6M0b4LoGGP2Ho6rXuvILhfiT8gtA3d8HHXUv+utP0Gu/RG/egIrohrqrB8pXBkdZyWHziEqLM811cGau2h5614+YC2dBZjrq7gdRdzxglwKZco/oytz53NKpJ9Erl6K/T4By5VFR96Juu982qfYquUN72ItTzyMS4mrp8+fQH8ejN3wNNepgDBmLqhtqdVjCTajAENSjg9G33Y/+/H30l/9Gb/jGVoWjQxeUIUu1OZIkIuF09P49tkKlp06gbr8fdV9vVLnyVocl3JCqVhP11HPobt0xP3gLHT8D/d23GA8PRNWuZ3V4ZYYkIuE0dPZF27fTb5dDUBWMZyajGjazOixRBqi612M8/6qtWsMnCzEnDrfNP7rvYZS3VOgobZKIhFPQRw5izo+DY0dQnW5H9ejnUmvSCNenDMM2D6l1B/TyJej/fIVO/A71QD/UjV1k8FQpkkQkLKVzc9GrPkGv/Ah8/DBixqNatLM6LFGGqUo+qN4D0TffivnBPFstu/+txXhsCCq4qtXhuSVJRMIy+vhRW6HSw/tsJf0ffgpVqbLVYQkBgKobauuu+++36I/jMWNjUD37oW65Xa6O7EwSkXA4bZro/3yJ/nQRlK+AevI5jPCbrQ5LiAKUYaA6dUM3a4u5aBZ68Vz0jxttV0eBIVaH5zYkEQmH0iknMRfOgF92QoswjEcHy4qb1+hKa32tW7eOxYsX55XV6tatG5GRkVaE6rJUUBWM4S+h16+yDWaIHYLqOQB1U9SVXyyuSBKRcAittW3p56XvgKlRjwxC3XKbdHFco+Ks9QW2pVcGDBhgUZTuQSmF6nyn7epo4Uz0olnoHzeSOyLW6tBcnszaEqVOn0nDnDMJvXAG1K6HMX4GRifpZ7eHS9f68vT0zFvrS5QeFVINY+TLqAefhH0/kTr8UfSebVaH5dLkikiUKr11I+biuXD+HKpHf1spFZm1bjfFWesL4IcffuDnn3+mevXqPPbYY4WuxSRrfV2lXn3JubET6VPHkjM9lkrdH6HSQ4+jPMrux2pJ/zbKbouJUqWzMtEfvo3etA7qhNoKlUrpfUu0a9eOm266iXLlyrF69WrmzJnD+PHjC2wna32VgLcvQa/P5+TsVzj76Xuc3bEF44mRZXYgg9PXmrvSDVWAjRs38vHHH6OUom7dugwdOtRR4Qk70nu2YcbPhDNptkKld/VEecp3ntJQnLW+Klf+e0h8ZGQkS5YscVh8ZYGq4IXx2BDMxi3Ri+divjQMo98wVKtwq0NzGQ75dCjODdWkpCSWL1/OxIkT8fHxIT093RGhCTvSF86jP1mIXvcVVKuF8fQYVL0GVofl1i5d6yswMJCNGzcSExOTb5u0tDQCAmzLHGzZsqXAQAZhH8YNEejrGmC+9Srm7ImoW+9DdX9MvoQVg0Na6NIbqkDeDdVLT4g1a9Zw++234+Njq+skK7O6Fn3wF8wFcZCcZLsPdP8jqPIVrA7L7RVnra9Vq1axZcsWPDw88PHx4emnn7Y6bLelqtbAGP26rXL86s/RRw5hPPU8qrIs8nk5DlmPaNOmTWzfvp2BAwcCsGHDBvbv359vOOlrr71GjRo12Lt3L6Zp0qNHD1q3bl3gvf55Q/XixYuF7tPT05OcnJxSOBrXVFrtobMvkrl0AVnLlmAEVcEv5kXKN29r9/3YW1HtUb68VPn+izuvR2RPRbWH+b//oN+bDX4BGINeKBPVvJ3+HtGVmKZJUlIS48ePJzU1lfHjxzN16lQqVcq/UJXcUC2Z0mgPffSwrVDp0V9tE/t6Pc6Zit7gAu0uC+OJ0mbc2AVdrRbm3MmYU57D6DcUFSYVRArjkHG0xbmhGhgYSFhYGJ6enlSpUoXq1auTlJTkiPDEVdJmLuaqTzBfHglnTmMMfhGjbwyqolTLFuJSql4DjBffgNr1MN96DXPZYrRpWh2W03FIIrr0hmpOTg4bN24kLCws3zbt27dn9+7dAJw5c4akpKS8e0rCeegTxzBfG43+7D1o3R4jdjaqVXurwxLCaSm/AIyRk1C33Ib+6mPb5O6ss1aH5VQc0jVXnBuqrVq1YseOHQwfPhzDMOjTp0++YafCWlpr9LpV6E/iwdMT9fhIW8VsqY4gxBWpcuXgkUFQuz566Tu2rrqYcbKsxJ8cMlihNMkN1eK5lvbQqacwF82EPduhWRuMx2JQAUFXfqETc8Q9ovT0dHbs2MGvv/5KVlYW3t7eXHfddbRs2RJ/f3+77ae0yLlVPFfbHnrvT5hzJ0O58hhDxqLqXl+K0TlWqQ9WOHXqFL/99htnz56lUqVK1K1bV8p8uDmtNXrTOvSHb4OZi+rztG31VLkKuqyjR4+ydOlSdu/eTf369alZsyb+/v6cO3eODRs2sHDhQpo1a0avXr1kTk8ZpBq1wHj+VcwZEzBfH4Px1HOoFmFXfqEbu2wiysnJISEhgdWrV5OcnEy1atXw8vLi/PnzHD9+nCpVqnDrrbcSFRWFp0zacis6Ix1zyVzY+j+4voltpniV6laH5RLmzp3LvffeS0xMDOXKlSvwfHZ2Nlu2bOHNN99k0qRJFkQorKZq1MEY/TrmrJcwZ7+M6v0vjE63Wx2WZS7bNTd8+HCaN2/OzTffTIMGDTAuKVZpmiYHDhzgu+++Y/fu3bzxxhsOCfifpPugeK6mPfT2HzDfmw3nzqKi+9hmiBsepRyhY8nw7SuTc6t4rqnb+/w5zLdehV1bUXf2REX3dukeh1LpmouNjS2ywoFhGDRs2JCGDRty5syZqwhVOCuddRa99F30xjW25RpGvoyqWdfqsFzaa6+9xnPPPVfg8alTp/LMM89YEJFwJsqrIsagF9EfzEN/9W9ITYbHhqA8C15Ju7PLDt++NAl98cUXhW6zcuVKfH2lfIWr0z/vwJwQg/7ff1B39cQYM1WSkB38NSWhuI+Lskd5etoWiozug960DnPWRPSF81aH5VDFvrHz6aefcu+99xb6+N13323XoITj6AsX0MveQ69ZAVVrYox6FVW/kdVhubylS5cCtvusf/37LydOnCAkpGwuEyAKp5RC3dUT0z8IvWgWZtw42/Bubx+rQ3OIKyaiXbt2AbZ7Qn/9+y8nTpygYsWKpROZKHX60F7MBdPhxB+oyHtQ9z+KqiCFSu3hr0oipmnmqyoCtn70nj17WhGWcHLGTZFor4qY70zFnPoCxrAJKF/nH+p/ra6YiN58800ALl68mPdvsGVwf39/+vfvX3rRiVKhc7LRK5aiV30CAYEYIyaimrSyOiy38leF64YNG+arjSjElah2HTEqvID55iuYr4/GGD4RFejeU2WumIjmzJkDwOzZsxk8eHCpByRKl/7jN8z5b8Dvh1EdI1G9Hkd5V7ryC0WxnT59Om/C6uWS0KXbCXEp1bwdxtAJtuHdr42yfVl04+kTxa41J0nItencXMxvPsN8eTicTsUYNMZWDViSkN299NJLvPvuu+zbtw/zHwUuTdNk3759vPvuu0ycONGiCIUrUA2bYTwzCS6cs9V3/OOI1SGVmsvOIxo9ejT33nsv4eHhhU5YzcnJYfPmzaxcuZLJkyeXaqBFkbkOV6aTk/BYMpfsn3dAmw4YjwxCVS7bCw+W5jyif04Er1KlChUrVuTcuXN5E8NvvfVWunbtapeJ4Nu3byc+Ph7TNImMjCQ6Ojrf89nZ2cyePZtDhw5RuXJlhg0bRpUqVa74vnJuFU9pt4c+dgTzjXGQk40xfIJTlwQq6Tyiyyaiv0qV7Nmzh3r16lGjRo28ygpJSUkcOnSI5s2b06NHD8tKlcjJUjStNXrDN+iPF6A8POHBJ1AdOrv0hDl7cdSE1lOnTnHkyBGysrLySmP9cwmUa2GaJkOHDuXFF18kKCiI0aNHM3To0Hzn4zfffMNvv/3Gk08+yffff8/mzZsZPnz4Fd9bzq3icUR76JPHMae9COfOYox4GVU3tFT3V1KlMqG1Vq1ajBw5ktOnT7Nz506OHDlCRkYGlSpVolOnTgwePLjYS3pf6VvbXzZt2sQbb7zBK6+8Qmiocza2K9BpKZjvzYJdW6FJK4JGxJKGe1VHcAXBwcGlWpPxwIEDVKtWLW/JlI4dO5KYmJgvEW3ZsoUePXoA0KFDBxYsWIDWWr6QuBAVUg3jmUmYU1/AfGOs7Z6RkyajkihWv4C/vz+dOnUq8U5M02T+/Pn5vrWFhYUVuIo6d+4cq1atokGDBiXeV1mntUZv3oD+YB7kZKMefgoVcQcewVVcYuVUd5Odnc0nn3zC999/T0ZGBosWLWLHjh0kJSXRrVu3a37/1NRUgoL+roQeFBTE/v37i9zGw8MDb29vMjIyCkxET0hIICEhAYApU6YUmUA9PT2l4PElHNYewcHkTppL6thB6Onj8J8wk3JONuevpG1x2US0Z88emjZtClBgDtGlmjdvftmdFOdbG9gmAd53331FVnEQl6czzqDffxP94/dQvxFG/+GoqlI7zUqLFi0iNTWVmJiYvPuotWvXZtGiRXZJRPYUFRWVb5RfUV0s0jWXn0Pbw6M8DJ+InjqG1HExtjJctes5Zt/FUCpdc/Pnz2fatGkA+eYQXUopxezZsy8bXHG+tR06dIhTp07Rtm1bSUQloHck2rrizmai7n8EdXt3lId0xVlt8+bNzJw5Ey8vr7yusMDAQFJTU+3y/oGBgfkmzKakpBS4B/XXNkFBQeTm5pKVlSWLTrowWzfdZMzXx2C+8aLtnpETJaOSuGwi+isJwd/ziUqDaZq89957eZMAL0e6D/Izs86SET+T8wkr8Kwbim/sDMrVK9i1WVbao7gc1R6enp4FhnCfOXPGbokgNDSUpKQkkpOTCQwMZOPGjcTExOTbpl27dqxbt46GDRuyadMmmjVrJveHXFzePaO/ktHIl1G1XDcZlXjs6K5duzAMI6/r7nKu9K3t/Pnz/P7770yYMAGwTfT7q2rxPwcsSPfB3/TeXZjx0yH1FOqO/8O852HSy5Ur9F5QWWiPq+GoUXMdOnRg9uzZ9O3bF4C0tDQWLlxIx44d7fL+Hh4e9O/fn0mTJmGaJl26dKF27dosXbqU0NBQwsLC6Nq1K7Nnz2bIkCH4+PgwbNgwu+xbWEtVqY7x7J/JaNpYjGcno2rUsTqsEin2UuHjx4/noYceonHjxixfvpwvv/wSwzC4/fbb6d69+2Vfm5uby9ChQxk3bhyBgYGMHj2amJgYateuXej2sbGxPPLII8UaNVcWh5jqixfQy5ag13wBwVVt94Kub3LZ17hze5SEoxJRTk4OS5YsYc2aNVy8eJHy5csTGRlJ7969C100z5mUxXOrJKxuD33iGObro0EpjOemoEKqWRZLqS8V/vvvv9OwYUMA1qxZw/jx4/Hy8mLs2LFXTETF+dYmikf/ut9WqDTpd1TnO1EP9EVV8LI6LFEET09P+vbtS9++ffO65KRbTNiTqloDY5ht2XEzbpwtGfnbb66aIxQ7Ef114XT8+HGAvBFvZ8+eLdbr27ZtS9u2bfM91qtXr0K3jY2NLW5YZYbOyUF/9TH6y6XgG2CrytusjdVhiSvo168f8fHxAPmGSz/++OO8++67VoUl3IyqdR3G0PGYb4zFnD7e1k1XyXUGpBQ7ETVq1IgFCxaQlpZGeHg4YEtKMvqm9OljR2xXQb8dQN0QgXroKVSlsrFOiavLzc0t8FhOTk6BAQxCXCtVvxHGoBcwZ07AnDHBNunVyzWW6Sl2Iho0aBArVqzA19c3b4G8Y8eOceedd5ZacGWdNk10whfoZYvBywtj4ChUO/vc5Bala9y4cSilyM7OZvz48fmeS0lJyevmFsKeVJNWGE8+hzlvCubcyRhDxqLKlbc6rCsqdiKqWLEihmHw3XffsWLFCgICAujYseMV7w+JktEnj2MunAH7dkOr9hiPDkL5Blgdliimrl27ArbJ3F26dMl7XCmFn58fLVq0sCo04eZUmw6ox2LQ8dMx356KMfB5p59TWOxE9M4775CUlET//v0JCQnh5MmTLFu2jNTU1GLN/xHFo7VG/3c1eul8UKD6DkV17Co3uF1M586dAfjuu++oXr06jRr9XYpl7969LF68OG9ItxD2ZnTsinkuC/3R2+hFs6DfUKf+DCl2IkpMTGTWrFlUqmRbv6ZWrVo0aNCAIUOGlFpwZY0+nYr53mz4aQs0amFbLyjoyuX6hfP69ddfC0xDqF+/Pq+//rokIlGqjMi7MbMy0V98AP4BqO6PWR1SkYqdiPz9/blw4UJeIgLb8uEBAdJdZA9m4n/R778JFy/YVk3tejfKKPa6hcJJKaUKXRyvmNP3hLgm6u5ecDoVvepTzIAQjC7OeU+/2ImoU6dOTJ48mW7duhEUFERKSgrffPMNnTp1ylcQ9UoFUEV++mwG+v156MTv4LoGtsmp1a1Z20nYX+PGjfnoo4/o06cPhmFgmiYff/wxjRs3tjo0UQYopeDhp9DpqegP30L7B6LadLA6rAKKXVlh0KBBV36zYhRAtTdXnv2td/2IuXAWZKaj7n4QdccDpXZT0RXaw5EcVVkhJSWFKVOmcPr06bx9BgQE8Pzzz+crBOyMXPncciRXaA994QLmtBfg6K+2Yd1XqMRSUqWyQqsrcMWTRZ8/h/44Hr3ha6hRx3YVVMqLXDlze1jBUYkIbF1xBw4cyKuAff3112O4QLerK55bVnCV9tAZ6ZhTnoOzmRijXkVVs3/PS6mX+BH2offvsRUqPXUCddv9qOjeLjHOX5ScYRgyb0hYTlX2wxgaiznlOczpsRijX0f5Occ9fuf/WuYmdPZFzE/ibcUJAeOZyRg9+kkSEkI4jKpSHWPIOMhIx5z5Evp8ltUhAZKIHEIfOYj58gj0N8tQt9yOMW4GqmEzq8MSQpRBql4DjKeeg6OHMd96DV1IGSpHk665UqRzc9GrPkGv/Ah8/DBixqNatLM6LOEmMjMziYuL4+TJk4SEhDB8+HB8fArWIOzVqxd16tjWqQkODub55593dKjCyaiW4ajeA9GL56L/PR/10JOWxuOwRLR9+3bi4+MxTZPIyEiio6PzPb9y5UrWrFmDh4cHvr6+/Otf/yIkJMRR4dmdPn7UVqj08D5U+06oh59yqWq4wvktX76cFi1aEB0dzfLly1m+fDl9+vQpsF358uV5/fXXLYhQODOjUzfM43+gV3+OWa0mRpe7rIvFETsxTZP58+czZswY4uLi+P777zl69Gi+ba677jqmSzWU5AAAC+dJREFUTJnC1KlT6dChA0uWLHFEaHanTRNzzQrMl4ZBchLqyWcxnnhGkpCwu8TERCIiIgCIiIggMTHR4oiEq1EP9IWW4eiP3kHv2mpZHA5JRAcOHKBatWpUrVoVT09POnbsWOCkad68ORUqVACgQYMGpKamOiI0u9IpyZhvjEV/9A40bokROwsj/BarwxJuKj09Pa+yib+/P+np6YVul52dzahRo3jhhRfYvHmzI0MUTk4ZHhhPjIQadTDffg197IglcTikay41NTXf5L2goCD2799f5PZr166ldevWhT6XkJBAQkICAFOmTCE4OLjQ7Tw9PYt8zt601pxf+yUZ86ejNPg8PYqKUfc4VZFBR7aHK3CV9pg4cSKnT58u8PiDDz6Y72elVJF/b3PnziUwMJATJ07w0ksvUadOHapVK7ictDOeW67AHdojd9wbpD73OGruZAJffQejhMO6S9oWTjdYYcOGDRw6dKjIVVqjoqKIiorK+7moyVOOmmSmz6RhvjcHdmyGhs0w+g4lK6QaWSkppb7vq+Eqk+4cxZETWq/F2LFji3zOz8+PtLQ0AgICSEtLy7cC7KUCA23LRletWpWmTZvy66+/FpqInO3cchVu0R7KE/41mtzXx3Dy5Wdt1RfKlbvqtynphFaHdM0FBgaScskHc0pKSt7JcamdO3eybNkynnvuOcqVoBEcTf+4EXP8ENi9DdWjP8bISaiQgie4EKUhLCyM9evXA7B+/fq8lZMvlZmZSXZ2NgBnzpxh79691KoltQxFQap+I1T/YXBgD3rxbIcW5nXIFVFoaChJSUkkJycTGBjIxo0biYmJybfN4cOHeeeddxgzZgx+fn6OCKvEdFYm+sO30ZvWQZ1QjAHDUTXqWB2WKGOio6OJi4tj7dq1ecO3AQ4ePMjq1asZOHAgf/zxB2+//XZewdXo6GhJRKJIRvgttpF0X3wA1Wuj7njAIft1WK25rVu3smjRIkzTpEuXLnTv3p2lS5cSGhpKWFgYEydO5MiRI/j7+wPFn+/g6HpYes82zPiZcCYNdVdP1J09UZ5O18NZgFt0H9iRq3TNWUlqzRWPu7WH1hr9zlT0lv/alhpvEVbs10rR03+w9x+HvnAe/clC9LqvoFot21XQdQ3s9v6lzd1OlmsliejKJBEVjzu2h75wAfPV5+BUMsaYqahqNYv1Oqe+R+Tq9MFfMF8ail6/ChV1H8bYOFwpCQkhxNVQFSpgPD0GPDww505GnyvdmnSSiC5DZ2djfrYI89VRkJuLMfJljF4DUOUrWB2aEEKUKhVc1VaT7sQfmAvi0P9YadieJBEVQf9+GHPySPSqT1E3RWKMn4lq1MLqsIQQwmFU45aongNg+w/olUtLbT/Of5fdwXRuLvqbz9BffAiVfDAGj0W1KjgsVgghygLV9W747SB6xYfoOvVQre2/1LgkokvoE8dsi9Yd/AXadcTo/TSqcuGTBIUQoixQSsEjT6OTfuf/27vXmKjSMw7g//fAqtwWmcHLZha3dcCs+GETHPCSWryQbCo2sWbrJakta7vRbWC4lGaBKMuWsNLdkqERjdK1lqBtTdrFpNsPTSgrH0QqhtDWW9DRJtjoIgwQWJaVmfP2AwV2BHZh5uwcOOf/+8acM2censyTh3nm8L7qBy4oJe9r/u8qHM3h/wuVfvxXqL/IBR51QfzkZ1AOv8UmREQEQDy3CMqbxcDixVBPvgs5PKTp9U3fiKTnCdTqtyF/fwZISoZSVgNlQ/q8WieOiEhvwhIP5c0ioPcTqL+t1vTmBdOO5qSUkK2XIf9QC6g+iB/8FOLbr7IBERHNQCQmQ3z/x5B/rIX824earbxgykYkBwegnj8FtF8FEtdCeT0PYvkLeodFRDTvie2ZgPs2ZMN5yG8kQax9Jehrmm40Jzv+AfXtbOBfbRCvZUH5+btsQkREsySEgPhhNrDSBvU3v4LsC36nAdM0Ijn8KdRzv4Z6sgKIs0I56oLy6h4IJUzv0IiIFhSxJGLs5oWnT6Ge+SWkdzSo65miEcnb/4T6jhOy9WOIzL1Qit+HsL2kd1hERAuWeOFFiB/lAO47kH/6XVDXCtl3RB0dHTh37hxUVcWOHTuwe/duv+Ojo6OoqanB/fv3ERMTg7y8PCxfvjyo15Sffw75YR1k00fAChuUovcgvrkmqGsSEdEYJfVbUN23If/+F6j2l4HvfC+w62gc17RUVcXZs2dRUlICl8uFK1eu4OHDh37nNDU1ISoqCidOnEBmZiYuXLgQ1GuOdt6EWp4H2fQRxI7vQjlWzSZERKQx8VoWYH8Zsq4G3q7/BHSNkDSie/fuYeXKlVixYgXCw8OxefNmtLW1+Z1z/fp1bN26FQCwceNG3LhxI6AdAqXXC7XhPDzFh4HRp1AKyqHsfwNiMRcqJWO5evUqCgoKsG/fPrjd7hnP6+joQG5uLnJycnDp0qUQRkhmIMKfg3L4LWDRIvS/VwI58tmcrxGS0ZzH44HVap342Wq14u7duzOeExYWhsjISAwODuL55/1XN2hsbERjYyMAoLKyEvHx8X7HpdcLT+e/sWjbTkS97oQSFf11/EoLTnh4+JRcmZkR8pGQkIDCwkLU1tbOeM74NOLo0aOwWq0oLi6Gw+HgLq2kKRFnhfJGIdQPqiA++S/wUuKcnr/g/o8oIyMDGRkZEz9PtwmTzHsHMbYXx459NhLK8OYtI27eFQwjbIw3m2byxWkEgIlpBBsRaU2sfQXxZ/6M3qFP5/zckIzmLBYLensn7zXv7e2FxWKZ8Ryfz4fh4WHExMQE9Hpi8ZLAgyUykOmmER6PR8eIyMjEkoiAnheST0R2ux2PHj1Cd3c3LBYLWlpa4HQ6/c5Zv349Ll++jDVr1qC1tRXr1q3jcjtkeuXl5ejv75/y+P79+5Gaqu32JF819h5nhLGmlpiPSYHmIiSNKCwsDIcOHUJFRQVUVcW2bduQkJCAixcvwm63w+FwYPv27aipqUFOTg6io6ORl5cXitCI5rVjx44F9fzZTCPGzWbsDXDM+yzmY9KX5eLLxt5CBnJrGhHNG2VlZTh48CDsdvuUYz6fD7m5uSgtLYXFYkFxcTGcTicSEhJ0iJRoeoZdWaGoqEjvEOYV5sOfEfJx7do1HDlyBJ2dnaisrERFRQWAse+Fjh8/DsB/GpGfn49NmzYF3YSMkDstMR+TAs3FgrtrjojGpKWlIS0tbcrj4598xqWkpCAlJSWUoRHNiWE/ERER0cIQVlZWVqZ3EF+X1atX6x3CvMJ8+GM+Asfc+WM+JgWSC96sQEREuuJojoiIdMVGREREujLcXXNfte+RGZw6dQrt7e2IjY1FVVUVAGBoaAgulwtPnjzBsmXLkJ+fj+ho4y8I29PTg5MnT6K/vx9CCGRkZGDnzp2mzUcwzF5brCt/mtaWNBCfzyezs7Pl48eP5ejoqCwsLJRdXV16hxVyN2/elG63WxYUFEw8Vl9fLxsaGqSUUjY0NMj6+nq9wgspj8cj3W63lFLK4eFh6XQ6ZVdXl2nzESjWFuvqWVrWlqFGc7PZ98gMkpOTp/wF0tbWhvT0dABAenq6afISFxc3cRdPREQEbDYbPB6PafMRKNYW6+pZWtaWoRoRVxqe2cDAAOLi4gAAS5cuxcDAgM4RhV53dzcePHiAxMRE5mOOWFvT4/toTLC1ZahGRLMjhDDdyuYjIyOoqqpCVlYWIiMj/Y6ZMR+kPbO+j7SoLUM1ormsNGw2sbGx6OvrAwD09fVN2fnWyLxeL6qqqrBlyxZs2LABgLnzEQjW1vTM/j7SqrYM1Yi+uO+R1+tFS0sLHA6H3mHNCw6HA83NzQCA5uZmzfeyma+klDh9+jRsNht27do18bhZ8xEo1tb0zPw+0rK2DLeyQnt7O+rq6ib2PdqzZ4/eIYVcdXU1bt26hcHBQcTGxmLv3r1ITU2Fy+VCT0+PqW4zvXPnDkpLS7Fq1aqJEcGBAweQlJRkynwEw+y1xbryp2VtGa4RERHRwmKo0RwRES08bERERKQrNiIiItIVGxEREemKjYiIiHTFRkRERLpiIyIiIl39DzOzvMZbtPkrAAAAAElFTkSuQmCC\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(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": 13, "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": 14, "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(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", "\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", " 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 last time step\n", " if t == T:\n", " idx,_,_ = calc_err(x_bar[:,t],track)\n", " delta_x = track[:,idx]-x[0:3,t]\n", " cost+= cp.quad_form(delta_x,100*np.eye(3))\n", "\n", " # Actuation rate of change\n", " if t < (T - 1):\n", " cost += cp.quad_form(u[:, t + 1] - u[:, t], 25*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.OSQP, verbose=False)" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Print Results:" ] }, { "cell_type": "code", "execution_count": 29, "metadata": {}, "outputs": [ { "name": "stderr", "output_type": "stream", "text": [ "No handles with labels found to put in legend.\n" ] }, { "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", "theta_mpc=np.array(x.value[2, :]).flatten()\n", "psi_mpc=np.array(x.value[3, :]).flatten()\n", "cte_mpc=np.array(x.value[4, :]).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", "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_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", "plt.subplot(2, 2, 4)\n", "plt.plot(cte_mpc)\n", "plt.ylabel('cte(t)')\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": 23, "metadata": {}, "outputs": [ { "name": "stderr", "output_type": "stream", "text": [ "/home/marcello/.local/lib/python3.6/site-packages/ipykernel_launcher.py:18: RuntimeWarning: invalid value encountered in true_divide\n" ] }, { "name": "stdout", "output_type": "stream", "text": [ "CVXPY Optimization Time: Avrg: 0.1416s Max: 0.2571s Min: 0.1279s\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", "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.25\n", "MIN_SPEED = 0.75\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", " iter_start=time.time()\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", " # Tracking\n", " if t > 0:\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 last time step\n", " if t == T:\n", " idx,_,_ = calc_err(x_bar[:,t],track)\n", " delta_x = track[:,idx]-x[0:3,t]\n", " cost+= cp.quad_form(delta_x,100*np.eye(3))\n", "\n", " # Actuation rate of change\n", " if t < (T - 1):\n", " cost += cp.quad_form(u[:, t + 1] - u[:, t], 25*np.eye(M))\n", " \n", " # Actuation effort\n", " cost += cp.quad_form( u[:, t],1*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]] # starting condition\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.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": 24, "metadata": {}, "outputs": [ { "data": { "image/png": "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\n", "text/plain": [ "
" ] }, "metadata": {}, "output_type": "display_data" } ], "source": [ "#plot trajectory\n", "grid = plt.GridSpec(2, 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(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) [deg/s]')\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.6.9" } }, "nbformat": 4, "nbformat_minor": 4 }