{ "cells": [ { "cell_type": "code", "execution_count": 1, "metadata": {}, "outputs": [], "source": [ "import numpy as np\n", "from scipy.integrate import odeint\n", "from scipy.interpolate import interp1d\n", "import cvxpy as cp\n", "\n", "import matplotlib.pyplot as plt\n", "plt.style.use(\"ggplot\")\n", "\n", "import time" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "### kinematics model equations\n", "\n", "The variables of the model are:\n", "\n", "* $x$ coordinate of the robot\n", "* $y$ coordinate of the robot\n", "* $v$ velocity of the robot\n", "* $\\theta$ heading of the robot\n", "\n", "The inputs of the model are:\n", "\n", "* $a$ acceleration of the robot\n", "* $\\delta$ steering of the robot\n", "\n", "These are the differential equations f(x,u) of the model:\n", "\n", "$\\dot{x} = f(x,u)$\n", "\n", "* $\\dot{x} = v\\cos{\\theta}$ \n", "* $\\dot{y} = v\\sin{\\theta}$\n", "* $\\dot{v} = a$\n", "* $\\dot{\\theta} = \\frac{v\\tan{\\delta}}{L}$\n", "\n", "Discretize with forward Euler Integration for time step dt:\n", "\n", "${x_{t+1}} = x_{t} + f(x,u)dt$\n", "\n", "* ${x_{t+1}} = x_{t} + v_t\\cos{\\theta}dt$\n", "* ${y_{t+1}} = y_{t} + v_t\\sin{\\theta}dt$\n", "* ${v_{t+1}} = v_{t} + a_tdt$\n", "* ${\\theta_{t+1}} = \\theta_{t} + \\frac{v\\tan{\\delta}}{L} dt$\n", "\n", "----------------------\n", "\n", "The Model is **non-linear** and **time variant**, but the Numerical Optimizer requires a Linear sets of equations. To approximate the equivalent **LTI** State space model, the **Taylor's series expansion** is used around $\\bar{x}$ and $\\bar{u}$ (at each time step):\n", "\n", "$ f(x,u) \\approx f(\\bar{x},\\bar{u}) + \\frac{\\partial f(x,u)}{\\partial x}|_{x=\\bar{x},u=\\bar{u}}(x-\\bar{x}) + \\frac{\\partial f(x,u)}{\\partial u}|_{x=\\bar{x},u=\\bar{u}}(u-\\bar{u})$\n", "\n", "This can be rewritten usibg the State Space model form Ax+Bu :\n", "\n", "$ f(\\bar{x},\\bar{u}) + A|_{x=\\bar{x},u=\\bar{u}}(x-\\bar{x}) + B|_{x=\\bar{x},u=\\bar{u}}(u-\\bar{u})$\n", "\n", "Where:\n", "\n", "$\n", "A =\n", "\\quad\n", "\\begin{bmatrix}\n", "\\frac{\\partial f(x,u)}{\\partial x} & \\frac{\\partial f(x,u)}{\\partial y} & \\frac{\\partial f(x,u)}{\\partial v} & \\frac{\\partial f(x,u)}{\\partial \\theta} \\\\\n", "\\end{bmatrix}\n", "\\quad\n", "=\n", "\\displaystyle \\left[\\begin{matrix}0 & 0 & \\cos{\\left(\\theta \\right)} & - v \\sin{\\left(\\theta \\right)}\\\\0 & 0 & \\sin{\\left(\\theta \\right)} & v \\cos{\\left(\\theta \\right)}\\\\0 & 0 & 0 & 0\\\\0 & 0 & \\frac{\\tan{\\left(\\delta \\right)}}{L} & 0\\end{matrix}\\right]\n", "$\n", "\n", "and\n", "\n", "$\n", "B = \n", "\\quad\n", "\\begin{bmatrix}\n", "\\frac{\\partial f(x,u)}{\\partial a} & \\frac{\\partial f(x,u)}{\\partial \\delta} \\\\\n", "\\end{bmatrix}\n", "\\quad\n", "= \n", "\\displaystyle \\left[\\begin{matrix}0 & 0\\\\0 & 0\\\\1 & 0\\\\0 & \\frac{v \\left(\\tan^{2}{\\left(\\delta \\right)} + 1\\right)}{L}\\end{matrix}\\right]\n", "$\n", "\n", "are the *Jacobians*.\n", "\n", "\n", "\n", "So the discretized model is given by:\n", "\n", "$ x_{t+1} = x_t + (f(\\bar{x},\\bar{u}) + A|_{x=\\bar{x}}(x_t-\\bar{x}) + B|_{u=\\bar{u}}(u_t-\\bar{u}) )dt $\n", "\n", "$ x_{t+1} = (I+dtA)x_t + dtBu_t +dt(f(\\bar{x},\\bar{u}) - A\\bar{x} - B\\bar{u}))$\n", "\n", "The LTI-equivalent kinematics model is:\n", "\n", "$ x_{t+1} = A'x_t + B' u_t + C' $\n", "\n", "with:\n", "\n", "$ A' = I+dtA|_{x=\\bar{x},u=\\bar{u}} $\n", "\n", "$ B' = dtB|_{x=\\bar{x},u=\\bar{u}} $\n", "\n", "$ C' = dt(f(\\bar{x},\\bar{u}) - A|_{x=\\bar{x},u=\\bar{u}}\\bar{x} - B|_{x=\\bar{x},u=\\bar{u}}\\bar{u}) $" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "-----------------\n", "[About Taylor Series Expansion](https://courses.engr.illinois.edu/ece486/fa2017/documents/lecture_notes/state_space_p2.pdf):\n", "\n", "In order to linearize general nonlinear systems, we will use the Taylor Series expansion of functions.\n", "\n", "Typically it is possible to assume that the system is operating about some nominal\n", "state solution $\\bar{x}$ (possibly requires a nominal input $\\bar{u}$) called **equilibrium point**.\n", "\n", "Recall that the Taylor Series expansion of f(x) around the\n", "point $\\bar{x}$ is given by:\n", "\n", "$f(x)=f(\\bar{x}) + \\frac{df(x)}{dx}|_{x=\\bar{x}}(x-\\bar{x})$ + higher order terms...\n", "\n", "For x sufficiently close to $\\bar{x}$, these higher order terms will be very close to zero, and so we can drop them.\n", "\n", "The extension to functions of multiple states and inputs is very similar to the above procedure.Suppose the evolution of state x\n", "is given by:\n", "\n", "$\\dot{x} = f(x1, x2, . . . , xn, u1, u2, . . . , um) = Ax+Bu$\n", "\n", "Where:\n", "\n", "$ A =\n", "\\quad\n", "\\begin{bmatrix}\n", "\\frac{\\partial f(x,u)}{\\partial x1} & ... & \\frac{\\partial f(x,u)}{\\partial xn} \\\\\n", "\\end{bmatrix}\n", "\\quad\n", "$ and $ B = \\quad\n", "\\begin{bmatrix}\n", "\\frac{\\partial f(x,u)}{\\partial u1} & ... & \\frac{\\partial f(x,u)}{\\partial um} \\\\\n", "\\end{bmatrix}\n", "\\quad $\n", "\n", "Then:\n", "\n", "$f(x,u)=f(\\bar{x},\\bar{u}) + \\frac{df(x,u)}{dx}|_{x=\\bar{x}}(x-\\bar{x}) + \\frac{df(x,u)}{du}|_{u=\\bar{u}}(u-\\bar{u}) = f(\\bar{x},\\bar{u}) + A_{x=\\bar{x}}(x-\\bar{x}) + B_{u=\\bar{u}}(u-\\bar{u})$\n", "\n", "-----------------" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "### Kinematics Model" ] }, { "cell_type": "code", "execution_count": 2, "metadata": {}, "outputs": [], "source": [ "\"\"\"\n", "Control problem statement.\n", "\"\"\"\n", "\n", "N = 4 #number of state variables\n", "M = 2 #number of control variables\n", "T = 20 #Prediction Horizon\n", "DT = 0.2 #discretization step" ] }, { "cell_type": "code", "execution_count": 3, "metadata": {}, "outputs": [], "source": [ "def get_linear_model(x_bar,u_bar):\n", " \"\"\"\n", " Computes the LTI approximated state space model x' = Ax + Bu + C\n", " \"\"\"\n", " \n", " L=0.3 #vehicle wheelbase\n", " \n", " x = x_bar[0]\n", " y = x_bar[1]\n", " v = x_bar[2]\n", " theta = x_bar[3]\n", " \n", " a = u_bar[0]\n", " delta = u_bar[1]\n", " \n", " A = np.zeros((N,N))\n", " A[0,2]=np.cos(theta)\n", " A[0,3]=-v*np.sin(theta)\n", " A[1,2]=np.sin(theta)\n", " A[1,3]=v*np.cos(theta)\n", " A[3,2]=v*np.tan(delta)/L\n", " A_lin=np.eye(N)+DT*A\n", " \n", " B = np.zeros((N,M))\n", " B[2,0]=1\n", " B[3,1]=v/(L*np.cos(delta)**2)\n", " B_lin=DT*B\n", " \n", " f_xu=np.array([v*np.cos(theta), v*np.sin(theta), a,v*np.tan(delta)/L]).reshape(N,1)\n", " C_lin = DT*(f_xu - np.dot(A,x_bar.reshape(N,1)) - np.dot(B,u_bar.reshape(M,1)))\n", " \n", " return np.round(A_lin,4), np.round(B_lin,4), np.round(C_lin,4)" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Motion Prediction: using scipy intergration" ] }, { "cell_type": "code", "execution_count": 4, "metadata": {}, "outputs": [], "source": [ "# Define process model\n", "# This uses the continuous model \n", "def kinematics_model(x,t,u):\n", " \"\"\"\n", " Returns the set of ODE of the vehicle model.\n", " \"\"\"\n", " \n", " L=0.3 #vehicle wheelbase\n", " dxdt = x[2]*np.cos(x[3])\n", " dydt = x[2]*np.sin(x[3])\n", " dvdt = u[0]\n", " dthetadt = x[2]*np.tan(u[1])/L\n", "\n", " dqdt = [dxdt,\n", " dydt,\n", " dvdt,\n", " dthetadt]\n", "\n", " return dqdt\n", "\n", "def predict(x0,u):\n", " \"\"\"\n", " \"\"\"\n", " \n", " x_ = np.zeros((N,T+1))\n", " \n", " x_[:,0] = x0\n", " \n", " # solve ODE\n", " for t in range(1,T+1):\n", "\n", " tspan = [0,DT]\n", " x_next = odeint(kinematics_model,\n", " x0,\n", " tspan,\n", " args=(u[:,t-1],))\n", "\n", " x0 = x_next[1]\n", " x_[:,t]=x_next[1]\n", " \n", " return x_" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Validate the model, here the status w.r.t a straight line with constant heading 0" ] }, { "cell_type": "code", "execution_count": 5, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ "CPU times: user 3.25 ms, sys: 0 ns, total: 3.25 ms\n", "Wall time: 2.87 ms\n" ] } ], "source": [ "%%time\n", "\n", "u_bar = np.zeros((M,T))\n", "u_bar[0,:] = 0.2 #m/ss\n", "u_bar[1,:] = np.radians(-np.pi/4) #rad\n", "\n", "x0 = np.zeros(N)\n", "x0[0] = 0\n", "x0[1] = 1\n", "x0[2] = 0\n", "x0[3] = np.radians(0)\n", "\n", "x_bar=predict(x0,u_bar)" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Check the model prediction" ] }, { "cell_type": "code", "execution_count": 6, "metadata": {}, "outputs": [ { "data": { "image/png": "iVBORw0KGgoAAAANSUhEUgAAAagAAACdCAYAAADhcuxqAAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjMuMSwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy/d3fzzAAAACXBIWXMAAAsTAAALEwEAmpwYAAAhAUlEQVR4nO3deVxVdf7H8dc5LAIugECSKOaa2Vhqko1JmGJj6BjTmIlpEpUpqaVNpfNrzMYwayLK3JrCJVpGc2sZ29REJ2tyT+WX22D1ywXxssgmy/n+/iB56AByQe49514+z8eDxwPuOVze93jvfXvOPef71ZRSCiGEEMJidLMDCCGEEDWRghJCCGFJUlBCCCEsSQpKCCGEJUlBCSGEsCQpKCGEEJZkqYIyDIOnnnqKefPmmR1FCCGEyTzNDnCxDRs2EBYWRnFxsV3rnzhxosbbg4ODyc7ObsxoV8xqmSRP3S6XqW3btk5O43iu8nqyWh6wXiZXy1Pb68kye1Bnz55l9+7dDB482OwoQgghLMAye1DLly9n7Nixl9172rhxIxs3bgRg3rx5BAcH17iep6dnrcvMYrVMkqduVswkhKtRpecp+WYLdP1NvX/XEgW1a9cu/P396dSpEwcPHqx1vejoaKKjo6t+rm2X0Wq7t2C9TJKnbk3tEJ8QjU1lHsFYmkLe6V/Q/7oQLbRdvX7fEgV16NAhdu7cyZ49eygtLaW4uJj58+czdepUs6MJIYSoJ1VehvrnKtSGD8C/NQHPvsq5epYTWKSgxowZw5gxYwA4ePAgH3/8sZSTEEK4IPXLjxhLU+Cn/6D99na00Q/TLPwazjXgCIklCkoIIYRrU0YF6ssPUevfAd/m6Il/Rut9yxXdp+UK6vrrr+f66683O4YQQgg7qTOnMJa+CkczoPct6GMT0VoFXPH9Wq6ghBBCuAalFCr9M9TqZaB7oCVMQ7tlIJqmNcr9S0EJIYSoN5VzFmPFfDi4B3r0Qh8/Ba11SKP+DSkoIYQQdlNKof6djnr/DSgvRxszEW3gnY2213QxKSghhBB2UefyMN5ZDLu3Q+fu6AmPo13luGsCpaCEEELUSe39FuPthVBciPbH8Wh3xKLpHg79m1JQQrgwwzCYMWMGrVu3ZsaMGRQUFJCSksKZM2cICQlh2rRptGjRwuyYwoWpokLUP95EfbMZ2ndEnz4Hrd01TvnblhksVoimwDAMu76UUnbd34UZAC5Yv349PXv2ZP78+fTs2ZP169c76JGIpkD97z6M56ag/r0Fbdgo9D+/7LRyAtmDEsKp4uLi7FrP29ubtLS0y65zYQaAu+++m08++QSAHTt2MHv2bACioqKYPXs2Y8eOvaLMoulR58+j1ixHffVPCA1Dn/ESWsduTs8hBSWEE3l7e/PKK69cdh2lFE899VSd91XTDAB5eXkEBgYCEBgYSH5+fq2/76qzA1gtD1gv05XkKT10gPzX5mCc/Bm/4aNoMXYiWjMfU/JIQQnhRL///e8JCan7WpHhw4dfdrm9MwBcjqvODmC1PGC9TA3Jo8rKUB+/j/psLQQGoT/xPOe738D5cwVwrsCheWqbHUAKSggnGjVqlF3rjRw58rLLa5sBwN/fn5ycHAIDA8nJyaFVq1aNEVu4OfV/mRipKfB/x9FujUa79yE0Xz+zY0lBCWGW06dP13i7l5cXAQEB6Hrt5zDVNgNAWloa6enpxMbGkp6eTkREhEOyC/egKipQn69FffQ+NG+BPvkZtBtvNjtWFSkoIUxyuSlldF3npptu4qGHHiIgIMDu+4yNjSUlJYXNmzcTHBzM9OnTGyGpcEfq9InKaTH+cwjtplvR7puE1tJae9xSUEKY5JFHHiEjI4ORI0dWHaNfvXo11157LT169ODdd98lNTWVJ5544rL3c/EMAC1btmTWrFnOiC9clDIM1JYNqDXLwdMb7aEn0G6+zSFDFV0puQ5KCJOsWrWKCRMmEBoaiqenJ6GhoTz88MOsWbOGsLAwEhMTycjIMDumcCPKdgbj1WdR7/8duv0G/bnX0ftFWbKcQPaghDCNUoozZ85ccqFtdnY2hmEA4OPjQ0VFhVnxhBtRSqG+2Yz6x5tgGGjjEtEif2fZYrpACkoIk8TExPDXv/6VgQMHEhQUhM1m46uvviImJgaA3bt3062b8y+OFO5F5edipC2Evf+Grj3QH3gcLSTU7Fh2kYISwiR33XUXHTp04JtvviEzM5OAgAAmTZpEr169ALj55pu5+WbrnFElXI/avR0jbRGUFKPd8wBa9AiHD/DamKSghDBRr169qgpJiMZiFORjpL6C+nYLhHdGT5iGFhZudqx6k4ISwiRlZWWsXr2ar7/+mnPnzrFixQr27dvHyZMnGTp0qNnxhItSB/dwNm0BKucs2u9Ho8WMQvN0zbd6S6TOzs5m4cKF5Obmomka0dHRVcfhhXBXK1aswGazMXXqVObOnQtA+/btWbFihRSUqDdVUlw5wOuWT/Fodw36xBlo13Q1O9YVsURBeXh4MG7cODp16kRxcTEzZszghhtuoF27dmZHE8JhvvvuO+bPn4+Pj0/V2VStW7fGZrOZnEy4GnU0A2Ppq5B9Gm3IXQQ9+Dhnz50zO9YVs0RBBQYGVo3A7OvrS1hYGDabTQpKuDVPT8+qU8ovyM/Pp2XLliYlEq5GlZWiPnwP9cU6aB2C/kQS2rW/QWvWDKSgGl9WVhaZmZl06dKl2jJXnR4ArJdJ8tTN0ZluueUWFixYQHx8PAA5OTksX76c/v37O+xvCvehfjpWOcDriZ/QIu9AG5WA5mP+AK+NSVP2Tt3pBCUlJTz77LPcfffd9OvXr871T5w4UePtVhv6HqyXSfLU7XKZapseoD7Ky8t555132LRpE6WlpXh7ezN48GDGjh2LpwkfarvK68lqecC5mVRFBerT1ahP/gEt/NHHT0br2de0PPZw+ek2ysvLSU5OJjIy0q5yEsLVeXp6Eh8fT3x8fNWhPatf2S/MpU7+X+UAr8ePoEVEot03Ea25+x4StkRBKaVYsmQJYWFhdU7UJoQrq22KDeCSmXHbtGnjjDjCRSjDQG3+BLX2bfBuhjbhKfSIAWbHcjhLFNShQ4fYunUr4eHhPPnkkwDExcXRp08fk5MJ0bguN8XGxVauXOngJMJVqLNZGMteg0P7oWdf9PsnowW0NjuWU1iioLp3786qVavMjiGEw11cPF999RX79+/nnnvuISQkhDNnzrB69Wp69uxpYkJhFUop1NcbUSvfAgXa+CmVs902ocPAligoIZqilStXMn/+fLy9vQG4+uqrmTBhAo899hgDBw40N5wwlcrLqRzgdd93cG1P9PipaMFN77CvFJQQJlFKkZWVdcn1fmfOnKl2bZRoWtTOf2G8uxjOn0e79yG0QcPR9KY5dZ8UlBAmGTZsWNV0GxdOw01PT2fYsGFmRxMmUIXnUO+9gfpuK1zTtXKA16ub9mAFUlBCmGTEiBGEh4fzzTffcPz48WrTbYimQ+3fhbHidSjIQ7vrPrQ7R6J5uM60GI4iBSWEiWS6jaZNlRShVi1FbfsCwjqgT/0LWnhns2NZRtM8sCmESTZt2mTXeps3b3ZwEmE2dfgAxnOPof61EW3oH9H/5xUpp/8iBSWEE7399tsopTAM47JfaWlpZkcVDqLKSjFWpWK8/D+gaehPzUX/43g0Ly+zo1mOHOITwolKSkoYPXp0net5yZuVW1LHj1ROi3HyZ7SBMWh/HI/m42t2LMtyu4IyPltD9r++pKKiAjSt8kv3AF0HDw/w9AIPT/DyqvzeyxvNuxl4N4NmzaCZL/j4gq8v+Pih+TYHv1+/mrcAvxZonvLmIRpmwYIFdq3XlC7GbApUeTlqwyrUP1dBq0D0x59Du7632bEsz+0KiqCr8LruBoySElCq8quiAqUMqKiA8jIoL4fS81BYAGWlqLJSOF9Sedv5kkvurqah3vUZL6F17u6cxyPcSkhIiNkRhJOpEz9V7jX9eBTtloFooyegNW9hdiyX4HYFpUdE4n/nHxo81LwyDCgtgZJiKC6GogIoLkQVFlR+X1gATfCKbiFE/SijArXxI9S6d8DHF33SDLQ+MtdXfbhdQV0pTdfBx6/yK+Ci201LJIRwNerMKYxlr8KRDOjVD31cIlqrQLNjuRwpKCGEaCRKKdS2z1GrloKuoz3wGNpvB8lnig0kBSWEEI1A5Z7FWLEADuyC625EHz8VLUg+c7wSUlBCOFl+fj5bt25l9+7d/PjjjxQVFeHn50eHDh3o1asXAwcOpFWrVmbHFHZSSlG89QuMN16G8lK0uAloA2Oa7ACvjcnuglqxYgVRUVFcc801DowjhHt777332LZtG71792bQoEGEhYXh6+tLcXExv/zyCxkZGTz99NMMGDCA++67z+y4og7qXD7q3cXk7/oaOl2L/sDjaKFhZsdyG3YXVEVFBUlJSbRq1YrIyEgiIyMJCgpyZDYh3E5gYCDz58+v8ULcjh07MmDAAEpLS2WoIxeg9n2H8fYCKCygxdiJFA34nQzw2sjsLqiEhATi4+PZs2cP27ZtY+3atXTt2pXbbruNfv364ePj48icQriFO++8s+r73NxcAgICqq1TVFTE0KFDnZhK1IcqLkKtfBP19SZodw3648/RvHcExQ28tEXUrl4HSXVd56abbuLxxx8nKSmJ/Px8Fi1axMMPP8ySJUuw2WyOyimE23nsscdqvH3atGlOTiLspX74HmP2FNT2r9DuHIn+52S09h3NjuW26nWSRFFREd9++y3btm3jxx9/pF+/fjz44IMEBwfzySefMHfuXF5++WVHZRXCrShVfZySoqIidDs/XM/OzmbhwoXk5uaiaRrR0dHExMRQUFBASkoKZ86cISQkhGnTptGihYxccCXU+fOodW+jNn0MV7VFf3qejCbjBHYXVHJyMvv27eO6665jyJAhREREXHIc/f777yc+Pr7BQfbu3cuyZcswDIPBgwcTGxvb4PsSwsomTZoEQGlpadX3FxQUFHDrrbfadT8eHh6MGzeOTp06UVxczIwZM7jhhhvYsmULPXv2JDY2lvXr17N+/XrGjh3b6I+jqVCZhzGWpsCpX9BuH1Y5wGsz+UjDGewuqK5du/Lggw/WeMwcKg//vfnmmw0KYRgGqampPPPMMwQFBTFz5kz69u1Lu3ZNe7pj4Z6mTJmCUooXXniBKVOmXLIsICCAtm3b2nU/gYGBBAZWjk7g6+tLWFgYNpuNHTt2MHv2bACioqKYPXu2FFQDqPIy1McrUZ+uhsDW6NPnoF13o9mxmhS7C2rEiBF1rtOsWbMGhTh69CihoaG0aVM5xl3//v3ZsWNHgwpq1qxWHDniSVmZtc4w9PKyVibJU7ebbvJg5szGv98ePXoAkJqa2uDXzH/LysoiMzOTLl26kJeXV1VcgYGB5Ofn1/g7GzduZOPGjQDMmzeP4ODgGtfz9PSsdZkZnJGn7Mdj5L/2V8ozj+AzKIaWCY+jX2aA16a4jeqjoXkscaGuzWa75JT1oKAgjhw5Um09e15Qvr4eaJpmufl0rJZJ8tRN17VGf5Fv2LCBIUOG4OXlVWs5lZWV8eWXXxITE2PXfZaUlJCcnEx8fDx+fn52Z4mOjiY6Orrq59oGWA4ODm7w4MuO4Mg8yqhAfb4e9dG74Nsc/dE/U9brFmzFJVBcUuvvNaVt1BB15antqIElCqqmD4trGrvKnhfUzJnW+8cB62WSPHW7XCZ7D8P9t9zcXKZOnUrv3r3p0aMHbdu2xcfHh5KSEk6cOEFGRgZ79uwhKirKrvsrLy8nOTmZyMhI+vXrB4C/vz85OTkEBgaSk5Mjo1LYSWWdqJwW49gP0Oe36GMT0Vr6mx2rSbNEQQUFBXH27Nmqn8+ePVt1iEIIdzJmzBiGDx/Oli1b2Lx5Mz/99BOFhYW0aNGC8PBwevfuTVxcHC1btqzzvpRSLFmyhLCwMIYPH151e9++fUlPTyc2Npb09HQiIiIc+ZBcnlIKteVT1Opl4OmJ9uB0tH5RMsCrBViioDp37szJkyfJysqidevWbN++nalTp5odSwiHaNWqFSNGjLDrc93LOXToEFu3biU8PJwnn3wSgLi4OGJjY0lJSWHz5s0EBwczffr0xojtlpQtG2PFfMjYCz16o4+fgtbaOp/dNHWWKCgPDw8SEhJISkrCMAxuv/122rdvb3YsISyte/furFq1qsZls2bNcnIa16KUQn27BfX+36GiHO2+SWhRQ2WvyWIsUVAAffr0oU+fPmbHEMJpioqK+OCDD8jIyODcuXOXfBa7ePFiE5O5N3UuD+OdRbD7G+hyXeUAr1ddbXYsUQMZD14Ik7z11ltkZmYycuRICgoKSEhIIDg4mGHDhpkdzW2pvd9iPDsZvt+BNjIe/cm5Uk4WZpk9KCGamu+//56UlBRatmyJrutERETQuXNnXnzxxUtOehBXThUVov7xJuqbzRDeCf2J59HCOpgdS9RBCkoIkyilqq5b8vHxobCwkICAAE6dOmVyMvei/ncfxvLXINeGNmwU2vB70Tytdc2dqJkUlBAm6dChAxkZGfTs2ZPu3buTmpqKj48PV18th5wagzpfglqzHPXVBghthz7jJbSO3cyOJepBCkoIkzzyyCNVJ0YkJCTw3nvvUVhYyOTJk01O5vrUsR8qB3jNOokWPQLtD+PQvBtnWCnhPFJQQpgkPz+frl27ApXXRk2cOBGoHJtSNIwqK0N9/B7qs3XQOhj9T0lo1/Y0O5ZoIDmLTwiTPP/88zXenpSU5OQk7kH9nImRNB316Rq0WwejPztfysnFyR6UEE5mGAbw68Wiv35dcPr0aTw8PMyK5pJURQXqszWoj/8BzVugT/4L2o0yvJM7kIISwsni4uKqvh89evQly3Rd5w9/+IOzI7ksdeqXys+aMg+j9R2Adt9EtBYyOK67kIISwskWLFiAUorZs2fz3HPPoZRC0zQ0TaNVq1Z4e3ubHdHylGGgvtqAWrscPL3RHv4T+s23mR1LNDIpKCGcLCQkBIBFixYBlYf8Lp5kUFxeRdZJjJTn4Ifv4Tc3oY+fjBZgrckuReOQghLCJIWFhbz11lt8++23eHp6kpaWxs6dOzl69Gi1Q3/i18/stm/m7Mo3wVBo4x5Fi7xDBnh1Y3IWnxAmefPNN/Hz82PRokV4elb+X7Fbt25s377d5GTWo/JyMBYmoZa/hmfHbujPvoZ+2++knNyc7EEJYZL9+/fzxhtvVJUTVF4PlZeXZ2Iq61G7vq4cfbykBO2eBAJHJ3DWZjM7lnACKSghTOLn58e5c+cu+ewpOztbPov6lSosQL33Buq7dOjQBT3hcbS24Wi6HPhpKqSghDDJ4MGDSU5OZvTo0SilOHz4MO+//z5DhgwxO5rp1IHdlTPdnstD+30cWsw9aJ7ydtXUyL+4ECa566678PLyIjU1lYqKChYvXkx0dDQxMTFmRzONKilGfbAMtfUzuLo9+uRn0Dp0MTuWMIkUlBAm0TSNYcOGyQSFv1JHMjCWvQrZp9HuiEWLHYvmJdeENWVSUEKY6MSJExw/fpySkpJLbh80aJBJiZxPlZWi1r+L+nI9BF2F/qe5aN2uNzuWsAApKCFMsnbtWtasWUOHDh1o1uzSqSCaSkGpH49VDlV04ie024ai3fMAmo+v2bGERZheUGlpaezatQtPT0/atGlDYmIizZs3NzuWEA63YcMG5s6dS4cOTW/qcVVejvp0NeqfK6GlP/pjz6L95iazYwmLMb2gbrjhBsaMGYOHhwfvvPMO69atY+zYsWbHEsLhvL29CQsLMzuG06mTP2MsfRWOH0G7OQptzAS05i3NjiUsyPQLCm688caq6QW6deuGTS7AE27MMIyqr3vvvZelS5eSk5Nzye0XpuNwN8owML78EGPONMg+hf7IU+gPPyHlJGpl+h7UxTZv3kz//v1rXb5x40Y2btwIwLx58wgODq5xPU9Pz1qXmcVqmSRP3RyR6eKpNi7YtGlTtdtWrlzZqH/XbCr7NMay1+DwAbjxZvRxj6L5ywXJ4vKcUlBz5swhNze32u2jR48mIqJyYrG1a9fi4eFBZGRkrfcTHR1NdHR01c/Z2dk1rhccHFzrMrNYLZPkqdvlMrVt27ZB97lgwYIrieRylFKof32JWpkKGmjxU9H6D5Yx9IRdnFJQf/nLXy67fMuWLezatYtZs2bJE1e4tQtTbQB89NFHjBgxoto6n3zyCcOHD3dmLIdQuTaMtxfA/p1wbU/0Bx5DC7rK7FjChZj+GdTevXv58MMPefrpp6udaiuEO1uzZk29bnclxo5/YcyeAj98jzb6YfTpc6ScRL2Z/hlUamoq5eXlzJkzB4CuXbsyYcIEk1MJ4TgHDhwAKk+YuPD9BadPn8bX13WvA1IF+ZUDvO7YBh27VQ7wGtrO7FjCRZleUK+//rrZEYRwqsWLFwNQWlpa9T1UDn0UEBBAQkKCWdGuiNq/E2PF61CQXzlM0dA/ov16hq4QDWF6QQnR1CxcuBCoPGFi8uTJJqe5cqqkCLVqKWrbFxDWAX3qs2jhncyOJdyAFJQQJnGLcjp0oHKAV1t25R7TiDFoXl5mxxJuQgpKCFFvqvQ8av07qI0fQXAb9KdeQOtyndmxhJuRghJC1Is6fqRyqKKTP6MNjEEbGY/WzMfsWMINSUEJIeyiystR/1yF2rAKWgWiT3sOrUdvs2MJNyYFJYQb2rt3L8uWLcMwDAYPHkxsbOwV3Z/65afKaTF+OoZ2y+1ocQ+j+bVonLBC1EIKSgg3YxgGqampPPPMMwQFBTFz5kz69u1Lu3b1vx5JGRUUrn8P4903wNcPfdJMtD6/dUBqIaqTghLCzRw9epTQ0FDatGkDQP/+/dmxY0e9C0oZFRivzKLg0H7odQv6uES0VgEOSCxEzaSghHAzNpuNoKCgqp+DgoI4cuRItfXsmR2gsN9teMXcjVfkHZYZJ7OpjHx/JdwljxSUEG5GKVXttprKxa7ZASJ/R3OLjTTvaiPfm8HV8tQ2O4Dpg8UKIRpXUFAQZ8+erfr57NmzBAbK3EvC9UhBCeFmOnfuzMmTJ8nKyqK8vJzt27fTt29fs2MJUW9yiE8IN+Ph4UFCQgJJSUkYhsHtt99O+/btzY4lRL1pqqYD1kIIIYTJ3PIQ34wZM8yOUI3VMkmeulkxkxmsth2slgesl8ld8rhlQQkhhHB9UlBCCCEsyS0L6uJrO6zCapkkT92smMkMVtsOVssD1svkLnnkJAkhhBCW5JZ7UEIIIVyfFJQQQghLcukLdeua80YpxbJly9izZw/NmjUjMTGRTp06OSRLdnY2CxcuJDc3F03TiI6OJiYm5pJ1Dh48yEsvvcRVV10FQL9+/Rg5cqRD8lzw6KOP4uPjg67reHh4MG/evEuWO3MbnThxgpSUlKqfs7KyGDVqFMOGDau6zRnbaNGiRezevRt/f3+Sk5MBKCgoICUlhTNnzhASEsK0adNo0aL6fEeNPc+SlVnxsdb1fHa0K3nuODPTqlWr2LRpE61atQIgLi6OPn36OCVPbe+FDdpOykVVVFSoyZMnq1OnTqmysjL1pz/9Sf3888+XrLNr1y6VlJSkDMNQhw4dUjNnznRYHpvNpo4dO6aUUqqoqEhNnTq1Wp4DBw6oF154wWEZapKYmKjy8vJqXe7MbXSxiooK9dBDD6msrKxLbnfGNjp48KA6duyYmj59etVtaWlpat26dUoppdatW6fS0tJqzFzXc85dWPWx1vV8drSGPnecnWnlypXqww8/dGqOC2p7L2zIdnLZQ3wXz3nj6elZNefNxXbu3Mltt92Gpml069aNwsJCcnJyHJInMDCwas/D19eXsLAwbDabQ/5WY3LmNrrY/v37CQ0NJSQkxOF/67/16NGj2v/cduzYQVRUFABRUVHVnktg33POXTSlx1ofDX3uODuTmWp7L2zIdnLZQ3z2zHljs9kumYMkKCgIm83m8JGds7KyyMzMpEuXLtWWHT58mCeffJLAwEDGjRvnlDHSkpKSABgyZEi10z3N2kZff/01t956a43LzNhGeXl5VY85MDCQ/Pz8auvYO8+SO7DyY73c89kM9jx3zPD555+zdetWOnXqxP33329KiV38XtiQ7eSyBaXsmPPGnnUaW0lJCcnJycTHx+Pn53fJso4dO7Jo0SJ8fHzYvXs3f/vb35g/f75D88yZM4fWrVuTl5fH888/T9u2benRo0fVcjO2UXl5Obt27WLMmDHVlpmxjexlxrYyi1Ufa13PZ1HpjjvuqPrsduXKlbz99tskJiY6NcPl3gvt5bKH+OyZ8yYoKOiSSbIcPS9OeXk5ycnJREZG0q9fv2rL/fz88PHxAaBPnz5UVFQ4/H9brVu3BsDf35+IiAiOHj16yXJnbyOAPXv20LFjRwICAqotM2MbQeX2uXBoMycnp+rD5Ys1pXmWrPpY63o+m8Ge546zBQQEoOs6uq4zePBgjh075tS/X9N7YUO2k8sWlD1z3vTt25etW7eilOLw4cP4+fk57EWmlGLJkiWEhYUxfPjwGtfJzc2t+p/p0aNHMQyDli1bOiQPVP4Ppri4uOr777//nvDw8EvWceY2uuByh/ecvY0u6Nu3L+np6QCkp6cTERFRbZ2mNM+SFR+rPc9nM9jz3HG2iz9H/u6775w63Upt74UN2U4uPZLE7t27WbFiRdWcN3fffTdffPEFULmLq5QiNTWVffv24e3tTWJiIp07d3ZIlh9++IFZs2YRHh5edSgkLi6uau/kjjvu4LPPPuOLL77Aw8MDb29v7r//fq699lqH5AE4ffo0L7/8MgAVFRUMGDDA1G0EcP78eSZNmsSCBQuqdvsvzuOMbfTqq6+SkZHBuXPn8Pf3Z9SoUURERJCSkkJ2djbBwcFMnz6dFi1aYLPZeOONN5g5cyZQ83POXVntsdb2fHam+jx3zMx08OBBjh8/jqZphISEMGHCBKftAdf2Xti1a9d6byeXLighhBDuy2UP8QkhhHBvUlBCCCEsSQpKCCGEJUlBCSGEsCQpKCGEEJYkBSWEEMKSpKCEEEJYkhSUEEIIS5KCakJOnTrFAw88wH/+8x+gcsTqBx98kIMHD5qcTAghqpOCakJCQ0O57777eP311zl//jyLFy8mKiqK66+/3uxoQghRjQx11AS9+OKLZGVloWkaL7zwAl5eXmZHEkKIamQPqgkaPHgwP//8M0OHDpVyEkJYlhRUE1NSUsKKFSsYNGgQH3zwAQUFBWZHEkKIGklBNTHLli2jY8eOTJw4kT59+vD3v//d7EhCCFEjKagmZMeOHezdu5cJEyYAMH78eDIzM9m2bZvJyYQQojo5SUIIIYQlyR6UEEIIS5KCEkIIYUlSUEIIISxJCkoIIYQlSUEJIYSwJCkoIYQQliQFJYQQwpKkoIQQQljS/wNktEfqpqpQbAAAAABJRU5ErkJggg==\n", "text/plain": [ "
" ] }, "metadata": {}, "output_type": "display_data" } ], "source": [ "#plot trajectory\n", "plt.subplot(2, 2, 1)\n", "plt.plot(x_bar[0,:],x_bar[1,:])\n", "plt.plot(np.linspace(0,10,T+1),np.zeros(T+1),\"b-\")\n", "plt.axis('equal')\n", "plt.ylabel('y')\n", "plt.xlabel('x')\n", "\n", "plt.subplot(2, 2, 2)\n", "plt.plot(np.degrees(x_bar[2,:]))\n", "plt.ylabel('theta(t) [deg]')\n", "#plt.xlabel('time')\n", "\n", "\n", "plt.tight_layout()\n", "plt.show()" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Motion Prediction: using the state space model" ] }, { "cell_type": "code", "execution_count": 7, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ "CPU times: user 2.37 ms, sys: 684 µs, total: 3.05 ms\n", "Wall time: 2.18 ms\n" ] } ], "source": [ "%%time\n", "\n", "u_bar = np.zeros((M,T))\n", "u_bar[0,:] = 0.2 #m/s\n", "u_bar[1,:] = np.radians(-np.pi/4) #rad\n", "\n", "x0 = np.zeros(N)\n", "x0[0] = 0\n", "x0[1] = 1\n", "x0[2] = 0\n", "x0[3] = np.radians(0)\n", "\n", "x_bar=np.zeros((N,T+1))\n", "x_bar[:,0]=x0\n", "\n", "for t in range (1,T+1):\n", " xt=x_bar[:,t-1].reshape(N,1)\n", " ut=u_bar[:,t-1].reshape(M,1)\n", " \n", " A,B,C=get_linear_model(xt,ut)\n", " \n", " xt_plus_one = np.dot(A,xt)+np.dot(B,ut)+C\n", " \n", " x_bar[:,t]= np.squeeze(xt_plus_one)" ] }, { "cell_type": "code", "execution_count": 8, "metadata": {}, "outputs": [ { "data": { "image/png": "iVBORw0KGgoAAAANSUhEUgAAAagAAACdCAYAAADhcuxqAAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjMuMSwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy/d3fzzAAAACXBIWXMAAAsTAAALEwEAmpwYAAAeUklEQVR4nO3deXxU9b3/8df3JCELIQtJhBIMsopQUJA0isSoBKpANW0tsgoGpRgBgVYL/SmFi1G0prHIWg0IWCxYFmtLrUXKUi0aVlmubAWlsoTsZINkzvf3x1xy4SaBScjMOTP5PB8PHiZzTibvOZ7Me86ZOd+v0lprhBBCCJsxrA4ghBBC1EYKSgghhC1JQQkhhLAlKSghhBC2JAUlhBDClqSghBBC2JKtCso0TZ5//nnmzp1rdRQhhBAW87c6wJU2btxIbGws5eXlLq1/+vTpWm+Pjo4mNze3MaPdMLtlkjzXd61Mbdq08XAa9/OWvye75QH7ZfK2PHX9PdnmCCovL4/du3fTv39/q6MIIYSwAdscQb3zzjuMGjXqmkdPmzZtYtOmTQDMnTuX6OjoWtfz9/evc5lV7JZJ8lyfHTMJ4W30pYtU/GsLdP5uvX/WFgW1a9cuwsPD6dChAwcPHqxzveTkZJKTk6u/r+uQ0W6Ht2C/TJLn+praKT4hGps+cRRzaSZF577F+K8FqNZt6/Xztiiow4cPs3PnTvbs2cOlS5coLy9n3rx5TJ482epoQggh6klXVaL/sga98X0Ib0nEr97gQj3LCWxSUCNGjGDEiBEAHDx4kA8//FDKSQghvJD+9mvMpZnwzb9Rd9+PGvYUgXG3cKEBZ0hsUVBCCCG8mzYd6L9/gN7wLgQ3x0j7JarXXTd0n7YrqO7du9O9e3erYwghhHCRPn8Wc+kbcOwQ9LoLY1QaKizihu/XdgUlhBDCO2it0Vs/Qv9xGRh+qNSpqLvuQynVKPcvBSWEEKLedEEe5vJ5cHAPdLsDY8wkVMuYRv0dUlBCCCFcprVGf74V/d4SqKpCjZiAuu+hRjtqupIUlBBCCJfoC0WY7y6C3Z9Bx64YqVNQN7nvmkApKCGEENel9+7AXLEAyktRPx6DGpiCMvzc+juloITwYqZpMn36dFq2bMn06dMpKSkhMzOT8+fPExMTw9SpUwkNDbU6pvBiuqwU/Ye30P/aDDe3x5g2B9X2Fo/8btsMFiuEqL/LMwBctmHDBnr06MG8efPo0aMHGzZssC6c8Hr6v/dhzp6E/nwLavBQjF++7rFyAikoIbxWbTMAZGdnk5SUBEBSUhLZ2dlWxRNeTF+8iLlqCeZvXoRmgRjTX8NIGYXyD/BoDjnFJ4SXqm0GgKKiIiIjIwGIjIykuLi4zp/31tkB7JYH7JfpRvJcOnyA4t/OwTxzipAhQwkdNQEVGGRJHikoIbyQqzMAXIu3zg5gtzxgv0wNyaMrK9Efvof+aB1ERmH87CUudu3JxQslcKHErXnqmh1ACkoIL1TXDADh4eEUFBQQGRlJQUEBYWFhVkcVXkD/5wRmVib85yTqnmTUY0+igkOsjiUFJYQ3qmsGgJUrV7J161ZSUlLYunUr8fHxFicVdqYdDvTf1qH/9B40D8WY+ALq9u9ZHauaFJQQPiQlJYXMzEw2b95MdHQ006ZNszqSsCl97rRzWox/H0bdeQ9q5NOoFvY64paCEsLLXTkDQIsWLZg5c6bFiYSdadNEb9mIXvsO+DdDPfkz1PfudctQRTdKCkoIIZoInX8e85158N/74Lu9nQO8RkRZHatOUlBCCOHjtNbof21G/+EtME3U6DRU4vdtedR0JSkoIYTwYbq4EHPlAtj7OXTuhvHEFFRMa6tjuUQKSgghfJTe/RnmyoVQUY76yROo5IfdPsBrY5KCEkIIH2OWFGNm/Qa9YwvEdcRInYqKjbM6Vr1JQQkhhA/RB/eQt3I+uiAP9YNhqEFDUf7e+VRvi9S5ubksWLCAwsJClFIkJyczaNAgq2MJIYTX0BXl6LXvoLf8Fb+2t2BMmI66pbPVsW6ILQrKz8+P0aNH06FDB8rLy5k+fTo9e/akbdu2VkcTQgjb08cOYS59A3LPoQY8QtS4KeRduGB1rBtmi4KKjIysHoE5ODiY2NhY8vPzpaCEEOIadOUl9Aer0B+vh5YxGD9LR936XVRgIEhBNb6cnBxOnDhBp06daizz1ukBwH6ZJM/12TGTEJfpb447B3g9/Q0qcSBqaCoqyPoBXhuTrQqqoqKCjIwMxo4dS0hIzQ3trdMDgP0ySZ7ru1amuqYHEMLdtMOB/usf0X/+A4SGY0yeierRx+pYbmGbgqqqqiIjI4PExEQSEhKsjiOEELajz/zHOcDryaOo+ETUyAmo5i2sjuU2tigorTWLFy8mNjaWIUOGWB1HCLcqLi5m27Zt7N69m6+//pqysjJCQkJo164dd9xxB/fdd5/M4ySuok0TvfnP6HUroFkgavzzGPH9rI7ldrYoqMOHD7Nt2zbi4uJ47rnnABg+fDi9e/e2OJkQjWvVqlVs376dXr168cADDxAbG0twcDDl5eV8++23HDp0iF/84hf069ePkSNHWh1X2IDOy8Fc9ls4vB969MF4fCIqoqXVsTzCFgXVtWtX1qxZY3UMIdwuMjKSefPmERAQUGNZ+/bt6devH5cuXWLz5s0WpBN2orVGf7oJvfpt0KDGTHLOdmvzAV4bky0KSoim4qGHHqr+urCwkIiIiBrrlJWV8eCDD3owlbAbXVTgHOB13xdwaw+MsZNR0a2sjuVxhtUBhGiqnn322Vpvnzp1qoeTCDvRO/+JOWsiHNqLeuxJjGlzmmQ5gRxBCWEZrXWN28rKyjAMed3YFOnSC+hVS9BfbINbOjsHeP1O0x6sQApKCA97+umnAbh06VL115eVlJRwzz33WBFLWEjv34W5/E0oKUI9MhL10KMoP++ZFsNdpKCE8LBJkyahteaVV15h0qRJVy2LiIiQi4CbEF1Rhl6zFL39Y4hthzH5RVRcR6tj2YYUlBAe1q1bNwCysrIIDAy0OI2wij5ywPnx8bzzqAd/jHp4BKqWT3c2ZXKyWwgP2rhxI5WVlQB1llNlZSUbN270ZCzhQbryEuaaLMzX/x8ohfH8yxg/HiPlVAs5ghLCgwoLC5k8eTK9evWiW7dutGnThqCgICoqKjh9+jSHDh1iz549JCUlWR1VuIE+edQ5LcaZU6j7BqF+PAYVFGx1LNvyuYIyP1pL7j//jsPhAKX+558BhgF+fuDnD/7+//PfAAgIQDULhGbNICAQAoMgKAgCgyEoGBXSHIJDIDgUQppDTCuUIW9eioYZMWIEQ4YMYcuWLWzevJlvvvmG0tJSQkNDiYuLo1evXgwfPpwWLXx3fLWmSFdVoTeuQf9lDYRFYkyZjerey+pYtudzBUXUTQTc1hOzogK0rv6nHQ4wHeBwgKMKqiqhvBSKK9GVl6DyIly8CBfLoaqq+u7+7weBjd++5ywqIRooLCyMhx9+mIcfftjqKMID9OlvnEdNXx9D3XUfath4VPNQq2N5BZ8rKCM+kfCHfnhDUzfoqiq4WAEV5c4SKyuF8jJ0eQnI4bgQwgXadKA3/Qm9/l0ICsZ4ejqqd1+rY3kVnyuoxqD8/cE/FJqHAjH/e7t1kYQPKisr4/333+fQoUNcuHDhqgt3Fy1aZGEycaP0+bOYy96Ao4fgjgSM0WmosEirY3kd+RSfEBZ5++23OXHiBI8++iglJSWkpqYSHR3N4MGDrY4mGkhrjbntI8zZk+E/J1FPPIuR9ksppwaSIyghLPLll1+SmZlJixYtMAyD+Ph4OnbsyKuvvirzonkhXZiHuXw+HNgFt92OMWYyKirm+j8o6iQFJYRFtNaEhIQAEBQURGlpKREREZw9e9biZKI+tNaUb/sYc8nrUHUJNXw86r5BKBlT8Ya5XFDLly8nKSmJW265xY1xhGg62rVrx6FDh+jRowddu3YlKyuLoKAgvvOd71gdTbhIXyhG/34Rxbs+hQ63YjwxBdU61upYPsPlgnI4HKSnpxMWFkZiYiKJiYlERUW5M5sQPu2nP/1p9QcjUlNTWbVqFaWlpUycONHiZMIVet8XmCvmQ2kJoaMmUNbv+zLAayNzuaBSU1MZO3Yse/bsYfv27axbt47OnTtz7733kpCQQFBQkDtzCuFziouL6dy5M+C8NmrChAkAHDt2zMpY4jp0eRl69VvoTz+BtrdgTJlN817xlN/ApS2idvU6SWoYBnfeeSdTpkwhPT2d4uJiFi5cyFNPPcXixYvJz893V04hfM5LL71U6+3p6ekeTiJcpb/6EnPWJPRn/0A99CjGLzNQN7e3OpbPqteHJMrKytixYwfbt2/n66+/JiEhgXHjxhEdHc2f//xnXn75ZV5//XV3ZRXCJ5imCTjfXL/877Jz587h5+JpotzcXBYsWEBhYSFKKZKTkxk0aBAlJSVkZmZy/vx5YmJimDp1KqGhMnLBjdAXL6LXr0B/8iHc1AbjF3NRHbtaHcvnuVxQGRkZ7Nu3j9tuu40BAwYQHx9PwBWj7z7++OOMHTu2wUH27t3LsmXLME2T/v37k5KS0uD7EsLOhg8fXv31sGHDrlpmGAY//OEPXbofPz8/Ro8eTYcOHSgvL2f69On07NmTLVu20KNHD1JSUtiwYQMbNmxg1KhRjfoYmhJ94gjm0kw4+y3q/sHOAV4D5S0NT3C5oDp37sy4ceOIiIiodblhGLz11lsNCmGaJllZWbzwwgtERUUxY8YM+vTpQ9u2TXu6Y+Gb5s+fj9aaWbNmMXv2bLTWKKVQShEWFkazZs1cup/IyEgiI50XgAYHBxMbG0t+fj7Z2dnMmjULgKSkJGbNmiUF1QC6qhL94Wr0X/8IkS0xps1B3Xa71bGaFJcLypWBLRs6+dqxY8do3bo1rVq1AqBv375kZ2c3qKBmzgzj6FF/Kivt9QnDgAB7ZZI813fnnX7MmNH49xsT47x4c+HChYDzBVpRUVF12TRETk4OJ06coFOnTlfdV2RkJMXFxbX+zKZNm9i0aRMAc+fOJTo6utb1/P3961xmBU/kqfz6OMW//S+qThwl6IFBtEidgnGNAV6b4jaqj4bmscWFuvn5+Vd9ZD0qKoqjR4/WWM+VP6jgYD+UUledfrQDu2WSPNdnGMqtf+SlpaW8/fbb7NixA39/f1auXMnOnTs5duxYjVN/11JRUUFGRgZjx46tvvDXFcnJySQnJ1d/X9cAy9HR0Tc0+HJjc2cebTrQf9uA/tPvIbg5xjO/pPKOu8gvr4DyCksyNYS35WnTpk2tt9uioK58k/gypWoOzerKH9SMGfb7nwP2yyR5ru9amer6g6qPt956i+bNm7Nw4UKmTZsGQJcuXVixYoXLBVVVVUVGRgaJiYkkJCQAEB4eTkFBAZGRkRQUFBAWFnbDWZsCnXPaOS3G8a+g990Yo9JQLcKtjtWk2aKgoqKiyMvLq/4+Ly/vhk53COEN9u/fz5IlS/D3/98/w7CwMIqKilz6ea01ixcvJjY29qqx+/r06cPWrVtJSUlh69atxMfHN3p2X6K1Rm/5K/qPy8DfHzVuGiohqdYXycKzbFFQHTt25MyZM+Tk5NCyZUs+++wzJk+ebHUsIdwqJCSECxcuXPViLDc31+UXZ4cPH2bbtm3ExcXx3HPPAc5PCKakpJCZmcnmzZuJjo6uPjoTNen8XMzl8+DQXujWC2PMJFRL+7x309TZoqD8/PxITU0lPT0d0zS5//77ufnmm62OJYRb9e/fn4yMDIYNG4bWmiNHjvDee+8xYMAAl36+a9eurFmzptZlM2fObMyoPkdrjd6xBf3e78BRhRr5NCrpQTlqshlbFBRA79696d27t9UxhPCYRx55hICAALKysnA4HCxatKj6YlvhPvpCEebKBbBnB3S6zTnA600yQK8d2aaghGhqlFIMHjxYJij0IL1nh7OcyktRj45FDXgEZcgAr3YlBSWEhU6fPs3JkyepqLj6I8wPPPCARYl8ky4rQf/hLfS//gFxHTB+9hIqtp3VscR1SEEJYZF169axdu1a2rVrV+MidymoxqMP7cV8Zx4U5aOGPIYaPBTlb69r7kTtpKCEsMjGjRt5+eWXaddOXsm7g75YgV77DvofG6F1LMb011Dtu1gdS9SDFJQQFmnWrBmxsTL7qjvo4185B3jNOYNKfhj1w9GoZg0bik1Yp17zQQkhboxpmtX/HnvsMZYuXUpBQcFVt1+ejkPUn66sxFy3HPPV6eBwYPw8HeOxJ6WcvJQcQQnhQVdOtXHZJ598UuO21atXeyKOT9GnTjiPmv5zEtVvAGroOFSw62MTCvuRghLCg+bPnw84LxTdsWMHd99991XLtdZ8/vnnVkTzWtrhQH+0Fv3hH6B5KMbEF1G3y/BOvkAKSggPujzVBsDatWtrncZm3bp1/OAHP/BkLK+lz37rPGo6cQTVpx9q5ARUqAyO6yukoITwsAMHDgDgcDiqv77s3LlzBAcHWxHLq2jTRP9jI3rdO+DfDPXkzzASkqyOJRqZFJQQHrZo0SIAKisrq78G58gSERERpKamWhXNKzjOn8XMnAVffQnfvRNjzERUhL0muxSNQwpKCA9bsGAB4Hw/auLEiRan8R5aa/Rnm8lb8zY4TNToZ1CJA2WAVx8mBSWERaScXKeLCpxj6O37goBud+AYlYaKaW11LOFmUlBCCFvTuz7FfHchVFSgfpJK5LBU8vLzrY4lPEAKSghhS7q0BL1qCfqLrdCuE0bqFFSbOJQh4ws0FVJQQgjb0Qd2O2e6vVCE+sFw1KCfoPzl6aqpkf/jQgjb0BXl6PeXobd9BN+5GWPiC6h2nayOJSwiBSWEsAV99BDmsjcg9xxqYAoqZRQqoJnVsYSFpKCEEJbSlZfQG36P/vsGiLoJ4+cvo7p0tzqWsAEpKCGEZfTXx51DFZ3+BnXvg6ifPIEKkpE0hJPlBbVy5Up27dqFv78/rVq1Ii0tjebNm1sdSwjhRrqqCv3XP6L/shpahGM8+yvUd++0OpawGcsLqmfPnowYMQI/Pz/effdd1q9fz6hRo6yOJYRwE33mFObSN+DkUdT3klAjxqOat7A6lrAhywvq9ttvr/66S5cu7Nixw8I0Qgh30aaJ/uRD9PqVEBiI8dPnUX36WR1L2JjlBXWlzZs307dv3zqXb9q0iU2bNgEwd+5coqOja13P39+/zmVWsVsmyXN9dszkrXTuOcxlv4UjB+D272GMfgYVHml1LGFzHimoOXPmUFhYWOP2YcOGER/vnFhs3bp1+Pn5kZiYWOf9JCcnk5ycXP19bm5uretFR0fXucwqdsskea7vWpnatGnj4TTeSWuN/uff0auzQIEaOxnVt78M8Cpc4pGCevHFF6+5fMuWLezatYuZM2fKjiuEj9CF+Zgr5sP+nXBrD4wnnkVF3WR1LOFFLD/Ft3fvXj744ANmz55NYGCg1XGEEI3AzP4n+veL4NJF1LCnUPcPljH0RL1ZXlBZWVlUVVUxZ84cADp37sz48eMtTiWEaAhdUuwc4DV7O7Tv4hzgtXVbq2MJL2V5Qb355ptWRxBCNAK9fyfm8jehpNg5TNGDP0b5+VkdS3gxywtKCOHddEUZes1S9PaPIbYdxuRfoeI6WB1L+AApKCFEg+nDB5wDvObnOo+YHh6BCgiwOpbwEVJQQoh605cuoje8i970J4huhfH8K6hOt1kdS/gYKSghRL3ok0edQxWdOYW6bxDq0bGowCCrYwkfJAUlhHCJrqpC/2UNeuMaCIvEmDob1a2X1bGED5OCEsIH7d27l2XLlmGaJv379yclJeWG7k9/+41zWoxvjqPuuh81/ClUSGjjhBWiDlJQQvgY0zTJysrihRdeICoqihkzZtCnTx/atq3/9UjadFC6YRXm75dAcAjG0zNQve92Q2ohapKCEsLHHDt2jNatW9OqVSsA+vbtS3Z2dr0LSpsOzN/MpOTwfrjjLozRaaiwCDckFqJ2UlBC+Jj8/HyioqKqv4+KiuLo0aM11nNldoDShHsJGPQjAhIH2macTDuOMm+3TL6SRwpKCB+jta5xW23l4tLsAInfp7nNRpr3tpHvreBteeqaHUBGbxTCx0RFRZGXl1f9fV5eHpGRMveS8D5SUEL4mI4dO3LmzBlycnKoqqris88+o0+fPlbHEqLe5BSfED7Gz8+P1NRU0tPTMU2T+++/n5tvvtnqWELUm9K1nbAWQgghLOaTp/imT59udYQa7JZJ8lyfHTNZwW7bwW55wH6ZfCWPTxaUEEII7ycFJYQQwpZ8sqCuvLbDLuyWSfJcnx0zWcFu28FuecB+mXwlj3xIQgghhC355BGUEEII7ycFJYQQwpa8+kLd6815o7Vm2bJl7Nmzh8DAQNLS0ujQoYNbsuTm5rJgwQIKCwtRSpGcnMygQYOuWufgwYO89tpr3HTTTQAkJCTw6KOPuiXPZc888wxBQUEYhoGfnx9z5869arknt9Hp06fJzMys/j4nJ4ehQ4cyePDg6ts8sY0WLlzI7t27CQ8PJyMjA4CSkhIyMzM5f/48MTExTJ06ldDQmvMdNfY8S3Zmx8d6vf3Z3W5k3/FkpjVr1vDJJ58QFhYGwPDhw+ndu7dH8tT1XNig7aS9lMPh0BMnTtRnz57VlZWV+uc//7k+derUVevs2rVLp6ena9M09eHDh/WMGTPclic/P18fP35ca611WVmZnjx5co08Bw4c0K+88orbMtQmLS1NFxUV1bnck9voSg6HQz/55JM6Jyfnqts9sY0OHjyojx8/rqdNm1Z928qVK/X69eu11lqvX79er1y5stbM19vnfIVdH+v19md3a+i+4+lMq1ev1h988IFHc1xW13NhQ7aT157iu3LOG39//+o5b660c+dO7r33XpRSdOnShdLSUgoKCtySJzIysvrIIzg4mNjYWPLz893yuxqTJ7fRlfbv30/r1q2JiYlx++/6v7p161bjlVt2djZJSUkAJCUl1diXwLV9zlc0pcdaHw3ddzydyUp1PRc2ZDt57Sk+V+a8yc/Pv2oOkqioKPLz890+snNOTg4nTpygU6dONZYdOXKE5557jsjISEaPHu2RMdLS09MBGDBgQI2Pe1q1jT799FPuueeeWpdZsY2KioqqH3NkZCTFxcU11nF1niVfYOfHeq392Qqu7DtW+Nvf/sa2bdvo0KEDjz/+uCUlduVzYUO2k9cWlHZhzhtX1mlsFRUVZGRkMHbsWEJCQq5a1r59exYuXEhQUBC7d+/m17/+NfPmzXNrnjlz5tCyZUuKiop46aWXaNOmDd26datebsU2qqqqYteuXYwYMaLGMiu2kaus2FZWsetjvd7+LJwGDhxY/d7t6tWrWbFiBWlpaR7NcK3nQld57Sk+V+a8iYqKumqSLHfPi1NVVUVGRgaJiYkkJCTUWB4SEkJQUBAAvXv3xuFwuP3VVsuWLQEIDw8nPj6eY8eOXbXc09sIYM+ePbRv356IiIgay6zYRuDcPpdPbRYUFFS/uXylpjTPkl0f6/X2Zyu4su94WkREBIZhYBgG/fv35/jx4x79/bU9FzZkO3ltQbky502fPn3Ytm0bWmuOHDlCSEiI2/7ItNYsXryY2NhYhgwZUus6hYWF1a9Mjx07hmmatGjRwi15wPkKpry8vPrrL7/8kri4uKvW8eQ2uuxap/c8vY0u69OnD1u3bgVg69atxMfH11inKc2zZMfH6sr+bAVX9h1Pu/J95C+++MKj063U9VzYkO3k1SNJ7N69m+XLl1fPefOjH/2Ijz/+GHAe4mqtycrKYt++fTRr1oy0tDQ6duzolixfffUVM2fOJC4urvpUyPDhw6uPTgYOHMhHH33Exx9/jJ+fH82aNePxxx/n1ltvdUsegHPnzvH6668D4HA46Nevn6XbCODixYs8/fTTzJ8/v/qw/8o8nthGb7zxBocOHeLChQuEh4czdOhQ4uPjyczMJDc3l+joaKZNm0ZoaCj5+fksWbKEGTNmALXvc77Kbo+1rv3Zk+qz71iZ6eDBg5w8eRKlFDExMYwfP95jR8B1PRd27ty53tvJqwtKCCGE7/LaU3xCCCF8mxSUEEIIW5KCEkIIYUtSUEIIIWxJCkoIIYQtSUEJIYSwJSkoIYQQtiQFJYQQwpakoJqQs2fP8sQTT/Dvf/8bcI5YPW7cOA4ePGhxMiGEqEkKqglp3bo1I0eO5M033+TixYssWrSIpKQkunfvbnU0IYSoQYY6aoJeffVVcnJyUErxyiuvEBAQYHUkIYSoQY6gmqD+/ftz6tQpHnzwQSknIYRtSUE1MRUVFSxfvpwHHniA999/n5KSEqsjCSFEraSgmphly5bRvn17JkyYQO/evfnd735ndSQhhKiVFFQTkp2dzd69exk/fjwAY8aM4cSJE2zfvt3iZEIIUZN8SEIIIYQtyRGUEEIIW5KCEkIIYUtSUEIIIWxJCkoIIYQtSUEJIYSwJSkoIYQQtiQFJYQQwpakoIQQQtjS/wc/4hkaYwGXowAAAABJRU5ErkJggg==\n", "text/plain": [ "
" ] }, "metadata": {}, "output_type": "display_data" } ], "source": [ "#plot trajectory\n", "plt.subplot(2, 2, 1)\n", "plt.plot(x_bar[0,:],x_bar[1,:])\n", "plt.plot(np.linspace(0,10,T+1),np.zeros(T+1),\"b-\")\n", "plt.axis('equal')\n", "plt.ylabel('y')\n", "plt.xlabel('x')\n", "\n", "plt.subplot(2, 2, 2)\n", "plt.plot(np.degrees(x_bar[2,:]))\n", "plt.ylabel('theta(t)')\n", "#plt.xlabel('time')\n", "\n", "\n", "plt.tight_layout()\n", "plt.show()" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "The results are the same as expected, so the linearized model is equivalent as expected." ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "## PRELIMINARIES" ] }, { "cell_type": "code", "execution_count": 9, "metadata": {}, "outputs": [], "source": [ "def compute_path_from_wp(start_xp, start_yp, step = 0.1):\n", " \"\"\"\n", " Computes a reference path given a set of waypoints\n", " \"\"\"\n", " \n", " final_xp=[]\n", " final_yp=[]\n", " delta = step #[m]\n", "\n", " for idx in range(len(start_xp)-1):\n", " section_len = np.sum(np.sqrt(np.power(np.diff(start_xp[idx:idx+2]),2)+np.power(np.diff(start_yp[idx:idx+2]),2)))\n", "\n", " interp_range = np.linspace(0,1,np.floor(section_len/delta).astype(int))\n", " \n", " fx=interp1d(np.linspace(0,1,2),start_xp[idx:idx+2],kind=1)\n", " fy=interp1d(np.linspace(0,1,2),start_yp[idx:idx+2],kind=1)\n", " \n", " final_xp=np.append(final_xp,fx(interp_range))\n", " final_yp=np.append(final_yp,fy(interp_range))\n", " \n", " dx = np.append(0, np.diff(final_xp))\n", " dy = np.append(0, np.diff(final_yp))\n", " theta = np.arctan2(dy, dx)\n", "\n", " return np.vstack((final_xp,final_yp,theta))\n", "\n", "\n", "def get_nn_idx(state,path):\n", " \"\"\"\n", " Computes the index of the waypoint closest to vehicle\n", " \"\"\"\n", "\n", " dx = state[0]-path[0,:]\n", " dy = state[1]-path[1,:]\n", " dist = np.hypot(dx,dy)\n", " nn_idx = np.argmin(dist)\n", "\n", " try:\n", " v = [path[0,nn_idx+1] - path[0,nn_idx],\n", " path[1,nn_idx+1] - path[1,nn_idx]] \n", " v /= np.linalg.norm(v)\n", "\n", " d = [path[0,nn_idx] - state[0],\n", " path[1,nn_idx] - state[1]]\n", "\n", " if np.dot(d,v) > 0:\n", " target_idx = nn_idx\n", " else:\n", " target_idx = nn_idx+1\n", "\n", " except IndexError as e:\n", " target_idx = nn_idx\n", "\n", " return target_idx\n", "\n", "def get_ref_trajectory(state, path, target_v):\n", " \"\"\"\n", " \"\"\"\n", " xref = np.zeros((N, T + 1))\n", " dref = np.zeros((1, T + 1))\n", " \n", " #sp = np.ones((1,T +1))*target_v #speed profile\n", " \n", " ncourse = path.shape[1]\n", "\n", " ind = get_nn_idx(state, path)\n", "\n", " xref[0, 0] = path[0,ind] #X\n", " xref[1, 0] = path[1,ind] #Y\n", " xref[2, 0] = target_v #sp[ind] #V\n", " xref[3, 0] = path[2,ind] #Theta\n", " dref[0, 0] = 0.0 # steer operational point should be 0\n", " \n", " dl = 0.05 # Waypoints spacing [m]\n", " travel = 0.0\n", "\n", " for i in range(T + 1):\n", " travel += abs(target_v) * DT #current V or target V?\n", " dind = int(round(travel / dl))\n", "\n", " if (ind + dind) < ncourse:\n", " xref[0, i] = path[0,ind + dind]\n", " xref[1, i] = path[1,ind + dind]\n", " xref[2, i] = target_v #sp[ind + dind]\n", " xref[3, i] = path[2,ind + dind]\n", " dref[0, i] = 0.0\n", " else:\n", " xref[0, i] = path[0,ncourse - 1]\n", " xref[1, i] = path[1,ncourse - 1]\n", " xref[2, i] = 0.0 #stop? #sp[ncourse - 1]\n", " xref[3, i] = path[2,ncourse - 1]\n", " dref[0, i] = 0.0\n", "\n", " return xref, dref" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "### MPC Problem formulation\n", "\n", "**Model Predictive Control** refers to the control approach of **numerically** solving a optimization problem at each time step. \n", "\n", "The controller generates a control signal over a fixed lenght T (Horizon) at each time step." ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "\n", "\n", "" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "#### Linear MPC Formulation\n", "\n", "Linear MPC makes use of the **LTI** (Linear time invariant) discrete state space model, wich represents a motion model used for Prediction.\n", "\n", "$x_{t+1} = Ax_t + Bu_t$\n", "\n", "The LTI formulation means that **future states** are linearly related to the current state and actuator signal. Hence, the MPC seeks to find a **control policy** U over a finite lenght horizon.\n", "\n", "$U={u_{t|t}, u_{t+1|t}, ...,u_{t+T|t}}$\n", "\n", "The objective function used minimize (drive the state to 0) is:\n", "\n", "$\n", "\\begin{equation}\n", "\\begin{aligned}\n", "\\min_{} \\quad & \\sum^{t+T-1}_{j=t} x^T_{j|t}Qx_{j|t} + u^T_{j|t}Ru_{j|t}\\\\\n", "\\textrm{s.t.} \\quad & x(0) = x0\\\\\n", " & x_{j+1|t} = Ax_{j|t}+Bu_{j|t}) \\quad \\textrm{for} \\quad t= 0.0] #min_speed (not really needed)\n", "constr += [cp.abs(u[0,:]) <= MAX_ACC] #max acc\n", "constr += [cp.abs(u[1,:]) <= MAX_STEER] #max steer\n", "# for t in range(T):\n", "# if t < (T - 1):\n", "# constr += [cp.abs(u[0,t] - u[0,t-1])/DT <= MAX_ACC] #max acc\n", "# constr += [cp.abs(u[1,t] - u[1,t-1])/DT <= MAX_STEER] #max steer\n", "\n", "prob = cp.Problem(cp.Minimize(cost), constr)\n", "solution = prob.solve(solver=cp.OSQP, verbose=True)" ] }, { "cell_type": "code", "execution_count": 11, "metadata": {}, "outputs": [ { "data": { "image/png": "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\n", "text/plain": [ "
" ] }, "metadata": {}, "output_type": "display_data" } ], "source": [ "x_mpc=np.array(x.value[0, :]).flatten()\n", "y_mpc=np.array(x.value[1, :]).flatten()\n", "v_mpc=np.array(x.value[2, :]).flatten()\n", "theta_mpc=np.array(x.value[3, :]).flatten()\n", "a_mpc=np.array(u.value[0, :]).flatten()\n", "delta_mpc=np.array(u.value[1, :]).flatten()\n", "\n", "#simulate robot state trajectory for optimized U\n", "x_traj=predict(x0, np.vstack((a_mpc,delta_mpc)))\n", "\n", "#plt.figure(figsize=(15,10))\n", "#plot trajectory\n", "plt.subplot(2, 2, 1)\n", "plt.plot(track[0,:],track[1,:],\"b\")\n", "plt.plot(x_ref[0,:],x_ref[1,:],\"g+\")\n", "plt.plot(x_traj[0,:],x_traj[1,:])\n", "plt.axis(\"equal\")\n", "plt.ylabel('y')\n", "plt.xlabel('x')\n", "\n", "#plot v(t)\n", "plt.subplot(2, 2, 3)\n", "plt.plot(a_mpc)\n", "plt.ylabel('a_in(t)')\n", "#plt.xlabel('time')\n", "\n", "\n", "plt.subplot(2, 2, 2)\n", "plt.plot(theta_mpc)\n", "plt.ylabel('theta(t)')\n", "\n", "plt.subplot(2, 2, 4)\n", "plt.plot(delta_mpc)\n", "plt.ylabel('d_in(t)')\n", "\n", "plt.tight_layout()\n", "plt.show()" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "## full track demo" ] }, { "cell_type": "code", "execution_count": 12, "metadata": {}, "outputs": [ { "name": "stderr", "output_type": "stream", "text": [ "/home/marcello/.conda/envs/jupyter/lib/python3.8/site-packages/cvxpy/problems/problem.py:1054: UserWarning: Solution may be inaccurate. Try another solver, adjusting the solver settings, or solve with verbose=True for more information.\n", " warnings.warn(\n" ] }, { "name": "stdout", "output_type": "stream", "text": [ "CVXPY Optimization Time: Avrg: 0.1636s Max: 0.2422s Min: 0.1457s\n" ] } ], "source": [ "track = compute_path_from_wp([0,3,4,6,10,12,14,6,1,0],\n", " [0,0,2,4,3,3,-2,-6,-2,-2],0.05)\n", "\n", "# track = compute_path_from_wp([0,10,10,0],\n", "# [0,0,1,1],0.05)\n", "\n", "sim_duration = 200 #time steps\n", "opt_time=[]\n", "\n", "x_sim = np.zeros((N,sim_duration))\n", "u_sim = np.zeros((M,sim_duration-1))\n", "\n", "MAX_SPEED = 1.5 #m/s\n", "MAX_ACC = 1.0 #m/ss\n", "MAX_D_ACC = 1.0 #m/sss\n", "MAX_STEER = np.radians(30) #rad\n", "MAX_D_STEER = np.radians(30) #rad/s\n", "\n", "REF_VEL = 1.0 #m/s\n", "\n", "# Starting Condition\n", "x0 = np.zeros(N)\n", "x0[0] = 0 #x\n", "x0[1] = -0.25 #y\n", "x0[2] = 0.0 #v\n", "x0[3] = np.radians(-0) #yaw\n", " \n", "#starting guess\n", "u_bar = np.zeros((M,T))\n", "u_bar[0,:] = MAX_ACC/2 #a\n", "u_bar[1,:] = 0.0 #delta\n", "\n", "for sim_time in range(sim_duration-1):\n", " \n", " iter_start = time.time()\n", " \n", " # dynamics starting state\n", " x_bar = np.zeros((N,T+1))\n", " x_bar[:,0] = x_sim[:,sim_time]\n", " \n", " #prediction for linearization of costrains\n", " for t in range (1,T+1):\n", " xt = x_bar[:,t-1].reshape(N,1)\n", " ut = u_bar[:,t-1].reshape(M,1)\n", " A,B,C = get_linear_model(xt,ut)\n", " xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n", " x_bar[:,t] = xt_plus_one\n", " \n", " #CVXPY Linear MPC problem statement\n", " x = cp.Variable((N, T+1))\n", " u = cp.Variable((M, T))\n", " cost = 0\n", " constr = []\n", "\n", " # Cost Matrices\n", " Q = np.diag([20,20,10,0]) #state error cost\n", " Qf = np.diag([30,30,30,0]) #state final error cost\n", " R = np.diag([10,10]) #input cost\n", " R_ = np.diag([10,10]) #input rate of change cost\n", "\n", " #Get Reference_traj\n", " x_ref, d_ref = get_ref_trajectory(x_bar[:,0] ,track, REF_VEL)\n", " \n", " #Prediction Horizon\n", " for t in range(T):\n", "\n", " # Tracking Error\n", " cost += cp.quad_form(x[:,t] - x_ref[:,t], Q)\n", "\n", " # Actuation effort\n", " cost += cp.quad_form(u[:,t], R)\n", "\n", " # Actuation rate of change\n", " if t < (T - 1):\n", " cost += cp.quad_form(u[:,t+1] - u[:,t], R_)\n", " constr+= [cp.abs(u[0, t + 1] - u[0, t])/DT <= MAX_D_ACC] #max acc rate of change\n", " constr += [cp.abs(u[1, t + 1] - u[1, t])/DT <= MAX_D_STEER] #max steer rate of change\n", "\n", " # Kinrmatics Constrains (Linearized model)\n", " A,B,C = get_linear_model(x_bar[:,t], u_bar[:,t])\n", " constr += [x[:,t+1] == A@x[:,t] + B@u[:,t] + C.flatten()]\n", " \n", " #Final Point tracking\n", " cost += cp.quad_form(x[:, T] - x_ref[:, T], Qf)\n", "\n", " # sums problem objectives and concatenates constraints.\n", " constr += [x[:,0] == x_bar[:,0]] #starting condition\n", " constr += [x[2,:] <= MAX_SPEED] #max speed\n", " constr += [x[2,:] >= 0.0] #min_speed (not really needed)\n", " constr += [cp.abs(u[0,:]) <= MAX_ACC] #max acc\n", " constr += [cp.abs(u[1,:]) <= MAX_STEER] #max steer\n", " \n", " # Solve\n", " prob = cp.Problem(cp.Minimize(cost), constr)\n", " solution = prob.solve(solver=cp.OSQP, verbose=False)\n", " \n", " #retrieved optimized U and assign to u_bar to linearize in next step\n", " u_bar = np.vstack((np.array(u.value[0,:]).flatten(),\n", " (np.array(u.value[1,:]).flatten())))\n", " \n", " u_sim[:,sim_time] = u_bar[:,0]\n", " \n", " # Measure elpased time to get results from cvxpy\n", " opt_time.append(time.time()-iter_start)\n", " \n", " # move simulation to t+1\n", " tspan = [0,DT]\n", " x_sim[:,sim_time+1] = odeint(kinematics_model,\n", " x_sim[:,sim_time],\n", " tspan,\n", " args=(u_bar[:,0],))[1]\n", " \n", "print(\"CVXPY Optimization Time: Avrg: {:.4f}s Max: {:.4f}s Min: {:.4f}s\".format(np.mean(opt_time),\n", " np.max(opt_time),\n", " np.min(opt_time))) " ] }, { "cell_type": "code", "execution_count": 13, "metadata": {}, "outputs": [ { "data": { "image/png": "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\n", "text/plain": [ "
" ] }, "metadata": {}, "output_type": "display_data" } ], "source": [ "#plot trajectory\n", "grid = plt.GridSpec(4, 5)\n", "\n", "plt.figure(figsize=(15,10))\n", "\n", "plt.subplot(grid[0:4, 0:4])\n", "plt.plot(track[0,:],track[1,:],\"b+\")\n", "plt.plot(x_sim[0,:],x_sim[1,:])\n", "plt.axis(\"equal\")\n", "plt.ylabel('y')\n", "plt.xlabel('x')\n", "\n", "plt.subplot(grid[0, 4])\n", "plt.plot(u_sim[0,:])\n", "plt.ylabel('a(t) [m/ss]')\n", "\n", "plt.subplot(grid[1, 4])\n", "plt.plot(x_sim[2,:])\n", "plt.ylabel('v(t) [m/s]')\n", "\n", "plt.subplot(grid[2, 4])\n", "plt.plot(np.degrees(u_sim[1,:]))\n", "plt.ylabel('delta(t) [rad]')\n", "\n", "plt.subplot(grid[3, 4])\n", "plt.plot(x_sim[3,:])\n", "plt.ylabel('theta(t) [rad]')\n", "\n", "plt.tight_layout()\n", "plt.show()" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "# Iterative Linearization" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "The goal is to have a more accurate linearization of the diff equations. For every time step the optimization is iterativelly repeated using he previous optimization results **u_bar** to approximate the vehicle dynamics, instead of a random starting guess and/or the rsult at time t-1.\n", "\n", "In previous case the results at t-1 wer used to approimate the dynamics art time t!\n", "\n", "This maks the results less correlated but makes the controller slower!" ] }, { "cell_type": "code", "execution_count": 14, "metadata": {}, "outputs": [ { "name": "stderr", "output_type": "stream", "text": [ ":41: RuntimeWarning: invalid value encountered in true_divide\n", " v /= np.linalg.norm(v)\n" ] }, { "name": "stdout", "output_type": "stream", "text": [ "CVXPY Optimization Time: Avrg: 0.6024s Max: 0.8522s Min: 0.2994s\n" ] } ], "source": [ "track = compute_path_from_wp([0,3,4,6,10,12,14,6,1,0],\n", " [0,0,2,4,3,3,-2,-6,-2,-2],0.05)\n", "\n", "# track = compute_path_from_wp([0,10,10,0],\n", "# [0,0,1,1],0.05)\n", "\n", "sim_duration = 200 #time steps\n", "opt_time=[]\n", "\n", "x_sim = np.zeros((N,sim_duration))\n", "u_sim = np.zeros((M,sim_duration-1))\n", "\n", "MAX_SPEED = 1.5 #m/s\n", "MAX_ACC = 1.0 #m/ss\n", "MAX_D_ACC = 1.0 #m/sss\n", "MAX_STEER = np.radians(30) #rad\n", "MAX_D_STEER = np.radians(30) #rad/s\n", "\n", "REF_VEL = 1.0 #m/s\n", "\n", "# Starting Condition\n", "x0 = np.zeros(N)\n", "x0[0] = 0 #x\n", "x0[1] = -0.25 #y\n", "x0[2] = 0.0 #v\n", "x0[3] = np.radians(-0) #yaw\n", "\n", "for sim_time in range(sim_duration-1):\n", " \n", " iter_start = time.time()\n", " \n", " #starting guess for ctrl\n", " u_bar = np.zeros((M,T))\n", " u_bar[0,:] = MAX_ACC/2 #a\n", " u_bar[1,:] = 0.0 #delta \n", " \n", " for _ in range(5):\n", " u_prev = u_bar\n", " \n", " # dynamics starting state\n", " x_bar = np.zeros((N,T+1))\n", " x_bar[:,0] = x_sim[:,sim_time]\n", "\n", " #prediction for linearization of costrains\n", " for t in range (1,T+1):\n", " xt = x_bar[:,t-1].reshape(N,1)\n", " ut = u_bar[:,t-1].reshape(M,1)\n", " A,B,C = get_linear_model(xt,ut)\n", " xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n", " x_bar[:,t] = xt_plus_one\n", "\n", " #CVXPY Linear MPC problem statement\n", " x = cp.Variable((N, T+1))\n", " u = cp.Variable((M, T))\n", " cost = 0\n", " constr = []\n", "\n", " # Cost Matrices\n", " Q = np.diag([20,20,10,0]) #state error cost\n", " Qf = np.diag([30,30,30,0]) #state final error cost\n", " R = np.diag([10,10]) #input cost\n", " R_ = np.diag([10,10]) #input rate of change cost\n", "\n", " #Get Reference_traj\n", " x_ref, d_ref = get_ref_trajectory(x_bar[:,0] ,track, REF_VEL)\n", "\n", " #Prediction Horizon\n", " for t in range(T):\n", "\n", " # Tracking Error\n", " cost += cp.quad_form(x[:,t] - x_ref[:,t], Q)\n", "\n", " # Actuation effort\n", " cost += cp.quad_form(u[:,t], R)\n", "\n", " # Actuation rate of change\n", " if t < (T - 1):\n", " cost += cp.quad_form(u[:,t+1] - u[:,t], R_)\n", " constr+= [cp.abs(u[0, t + 1] - u[0, t])/DT <= MAX_D_ACC] #max acc rate of change\n", " constr += [cp.abs(u[1, t + 1] - u[1, t])/DT <= MAX_D_STEER] #max steer rate of change\n", "\n", " # Kinrmatics Constrains (Linearized model)\n", " A,B,C = get_linear_model(x_bar[:,t], u_bar[:,t])\n", " constr += [x[:,t+1] == A@x[:,t] + B@u[:,t] + C.flatten()]\n", "\n", " #Final Point tracking\n", " cost += cp.quad_form(x[:, T] - x_ref[:, T], Qf)\n", "\n", " # sums problem objectives and concatenates constraints.\n", " constr += [x[:,0] == x_bar[:,0]] #starting condition\n", " constr += [x[2,:] <= MAX_SPEED] #max speed\n", " constr += [x[2,:] >= 0.0] #min_speed (not really needed)\n", " constr += [cp.abs(u[0,:]) <= MAX_ACC] #max acc\n", " constr += [cp.abs(u[1,:]) <= MAX_STEER] #max steer\n", "\n", " # Solve\n", " prob = cp.Problem(cp.Minimize(cost), constr)\n", " solution = prob.solve(solver=cp.OSQP, verbose=False)\n", "\n", " #retrieved optimized U and assign to u_bar to linearize in next step\n", " u_bar = np.vstack((np.array(u.value[0,:]).flatten(),\n", " (np.array(u.value[1,:]).flatten())))\n", " \n", " #check how this solution differs from previous\n", " #if the solutions are very\n", " delta_u = np.sum(np.sum(np.abs(u_bar - u_prev),axis=0),axis=0)\n", " if delta_u < 0.05:\n", " break\n", " \n", " \n", " # select u from best iteration\n", " u_sim[:,sim_time] = u_bar[:,0]\n", " \n", " \n", " # Measure elpased time to get results from cvxpy\n", " opt_time.append(time.time()-iter_start)\n", " \n", " # move simulation to t+1\n", " tspan = [0,DT]\n", " x_sim[:,sim_time+1] = odeint(kinematics_model,\n", " x_sim[:,sim_time],\n", " tspan,\n", " args=(u_bar[:,0],))[1]\n", " \n", " #reset u_bar? -> this simulates that we don use previous solution!\n", " u_bar[0,:] = MAX_ACC/2 #a\n", " u_bar[1,:] = 0.0 #delta\n", " \n", " \n", "print(\"CVXPY Optimization Time: Avrg: {:.4f}s Max: {:.4f}s Min: {:.4f}s\".format(np.mean(opt_time),\n", " np.max(opt_time),\n", " np.min(opt_time))) " ] }, { "cell_type": "code", "execution_count": 15, "metadata": {}, "outputs": [ { "data": { "image/png": "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\n", "text/plain": [ "
" ] }, "metadata": {}, "output_type": "display_data" } ], "source": [ "#plot trajectory\n", "grid = plt.GridSpec(4, 5)\n", "\n", "plt.figure(figsize=(15,10))\n", "\n", "plt.subplot(grid[0:4, 0:4])\n", "plt.plot(track[0,:],track[1,:],\"b+\")\n", "plt.plot(x_sim[0,:],x_sim[1,:])\n", "plt.axis(\"equal\")\n", "plt.ylabel('y')\n", "plt.xlabel('x')\n", "\n", "plt.subplot(grid[0, 4])\n", "plt.plot(u_sim[0,:])\n", "plt.ylabel('a(t) [m/ss]')\n", "\n", "plt.subplot(grid[1, 4])\n", "plt.plot(x_sim[2,:])\n", "plt.ylabel('v(t) [m/s]')\n", "\n", "plt.subplot(grid[2, 4])\n", "plt.plot(np.degrees(u_sim[1,:]))\n", "plt.ylabel('delta(t) [rad]')\n", "\n", "plt.subplot(grid[3, 4])\n", "plt.plot(x_sim[3,:])\n", "plt.ylabel('theta(t) [rad]')\n", "\n", "plt.tight_layout()\n", "plt.show()" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "## V2 Use Dynamics w.r.t Robot Frame\n", "\n", "explanation here...\n", "\n", "benefits:\n", "* slightly faster mpc convergence time -> more variables are 0, this helps the computation?\n", "* no issues when vehicle heading ~PI in world" ] }, { "cell_type": "code", "execution_count": 37, "metadata": {}, "outputs": [], "source": [ "def compute_path_from_wp(start_xp, start_yp, step = 0.1):\n", " \"\"\"\n", " Computes a reference path given a set of waypoints\n", " \"\"\"\n", " \n", " final_xp=[]\n", " final_yp=[]\n", " delta = step #[m]\n", "\n", " for idx in range(len(start_xp)-1):\n", " section_len = np.sum(np.sqrt(np.power(np.diff(start_xp[idx:idx+2]),2)+np.power(np.diff(start_yp[idx:idx+2]),2)))\n", "\n", " interp_range = np.linspace(0,1,np.floor(section_len/delta).astype(int))\n", " \n", " fx=interp1d(np.linspace(0,1,2),start_xp[idx:idx+2],kind=1)\n", " fy=interp1d(np.linspace(0,1,2),start_yp[idx:idx+2],kind=1)\n", " \n", " # watch out to duplicate points!\n", " final_xp=np.append(final_xp,fx(interp_range)[1:])\n", " final_yp=np.append(final_yp,fy(interp_range)[1:])\n", " \n", " dx = np.append(0, np.diff(final_xp))\n", " dy = np.append(0, np.diff(final_yp))\n", " theta = np.arctan2(dy, dx)\n", "\n", " return np.vstack((final_xp,final_yp,theta))\n", "\n", "\n", "def get_nn_idx(state,path):\n", " \"\"\"\n", " Computes the index of the waypoint closest to vehicle\n", " \"\"\"\n", "\n", " dx = state[0]-path[0,:]\n", " dy = state[1]-path[1,:]\n", " dist = np.hypot(dx,dy)\n", " nn_idx = np.argmin(dist)\n", "\n", " try:\n", " v = [path[0,nn_idx+1] - path[0,nn_idx],\n", " path[1,nn_idx+1] - path[1,nn_idx]] \n", " v /= np.linalg.norm(v)\n", "\n", " d = [path[0,nn_idx] - state[0],\n", " path[1,nn_idx] - state[1]]\n", "\n", " if np.dot(d,v) > 0:\n", " target_idx = nn_idx\n", " else:\n", " target_idx = nn_idx+1\n", "\n", " except IndexError as e:\n", " target_idx = nn_idx\n", "\n", " return target_idx\n", "\n", "def normalize_angle(angle):\n", " \"\"\"\n", " Normalize an angle to [-pi, pi]\n", " \"\"\"\n", " while angle > np.pi:\n", " angle -= 2.0 * np.pi\n", "\n", " while angle < -np.pi:\n", " angle += 2.0 * np.pi\n", "\n", " return angle\n", "\n", "def get_ref_trajectory(state, path, target_v):\n", " \"\"\"\n", " modified reference in robot frame\n", " \"\"\"\n", " xref = np.zeros((N, T + 1))\n", " dref = np.zeros((1, T + 1))\n", " \n", " #sp = np.ones((1,T +1))*target_v #speed profile\n", " \n", " ncourse = path.shape[1]\n", "\n", " ind = get_nn_idx(state, path)\n", " dx=path[0,ind] - state[0]\n", " dy=path[1,ind] - state[1]\n", " \n", " xref[0, 0] = dx * np.cos(-state[3]) - dy * np.sin(-state[3]) #X\n", " xref[1, 0] = dy * np.cos(-state[3]) + dx * np.sin(-state[3]) #Y\n", " xref[2, 0] = target_v #V\n", " xref[3, 0] = normalize_angle(path[2,ind]- state[3]) #Theta\n", " dref[0, 0] = 0.0 # steer operational point should be 0\n", " \n", " dl = 0.05 # Waypoints spacing [m]\n", " travel = 0.0\n", " \n", " for i in range(T + 1):\n", " travel += abs(target_v) * DT #current V or target V?\n", " dind = int(round(travel / dl))\n", " \n", " if (ind + dind) < ncourse:\n", " dx=path[0,ind + dind] - state[0]\n", " dy=path[1,ind + dind] - state[1]\n", " \n", " xref[0, i] = dx * np.cos(-state[3]) - dy * np.sin(-state[3])\n", " xref[1, i] = dy * np.cos(-state[3]) + dx * np.sin(-state[3])\n", " xref[2, i] = target_v #sp[ind + dind]\n", " xref[3, i] = normalize_angle(path[2,ind + dind] - state[3])\n", " dref[0, i] = 0.0\n", " else:\n", " dx=path[0,ncourse - 1] - state[0]\n", " dy=path[1,ncourse - 1] - state[1]\n", " \n", " xref[0, i] = dx * np.cos(-state[3]) - dy * np.sin(-state[3])\n", " xref[1, i] = dy * np.cos(-state[3]) + dx * np.sin(-state[3])\n", " xref[2, i] = 0.0 #stop? #sp[ncourse - 1]\n", " xref[3, i] = normalize_angle(path[2,ncourse - 1] - state[3])\n", " dref[0, i] = 0.0\n", "\n", " return xref, dref" ] }, { "cell_type": "code", "execution_count": 17, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ "CVXPY Optimization Time: Avrg: 0.1593s Max: 0.1842s Min: 0.1461s\n" ] } ], "source": [ "track = compute_path_from_wp([0,3,4,6,10,12,14,6,1,0],\n", " [0,0,2,4,3,3,-2,-6,-2,-2],0.05)\n", "\n", "# track = compute_path_from_wp([0,10,10,0],\n", "# [0,0,1,1],0.05)\n", "\n", "sim_duration = 200 #time steps\n", "opt_time=[]\n", "\n", "x_sim = np.zeros((N,sim_duration))\n", "u_sim = np.zeros((M,sim_duration-1))\n", "\n", "MAX_SPEED = 1.5 #m/s\n", "MAX_ACC = 1.0 #m/ss\n", "MAX_D_ACC = 1.0 #m/sss\n", "MAX_STEER = np.radians(30) #rad\n", "MAX_D_STEER = np.radians(30) #rad/s\n", "\n", "REF_VEL = 1.0 #m/s\n", "\n", "# Starting Condition\n", "x0 = np.zeros(N)\n", "x0[0] = 0 #x\n", "x0[1] = -0.25 #y\n", "x0[2] = 0.0 #v\n", "x0[3] = np.radians(-0) #yaw\n", " \n", "#starting guess\n", "u_bar = np.zeros((M,T))\n", "u_bar[0,:] = MAX_ACC/2 #a\n", "u_bar[1,:] = 0.0 #delta\n", " \n", "for sim_time in range(sim_duration-1):\n", " \n", " iter_start = time.time()\n", " \n", " # dynamics starting state w.r.t. robot are always null except vel \n", " x_bar = np.zeros((N,T+1))\n", " x_bar[2,0] = x_sim[2,sim_time]\n", " \n", " #prediction for linearization of costrains\n", " for t in range (1,T+1):\n", " xt = x_bar[:,t-1].reshape(N,1)\n", " ut = u_bar[:,t-1].reshape(M,1)\n", " A,B,C = get_linear_model(xt,ut)\n", " xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n", " x_bar[:,t] = xt_plus_one\n", " \n", " #CVXPY Linear MPC problem statement\n", " x = cp.Variable((N, T+1))\n", " u = cp.Variable((M, T))\n", " cost = 0\n", " constr = []\n", "\n", " # Cost Matrices\n", " Q = np.diag([20,20,10,20]) #state error cost\n", " Qf = np.diag([30,30,30,30]) #state final error cost\n", " R = np.diag([10,10]) #input cost\n", " R_ = np.diag([10,10]) #input rate of change cost\n", "\n", " #Get Reference_traj\n", " #dont use x0 in this case\n", " x_ref, d_ref = get_ref_trajectory(x_sim[:,sim_time] ,track, REF_VEL)\n", " \n", " #Prediction Horizon\n", " for t in range(T):\n", "\n", " # Tracking Error\n", " cost += cp.quad_form(x[:,t] - x_ref[:,t], Q)\n", "\n", " # Actuation effort\n", " cost += cp.quad_form(u[:,t], R)\n", "\n", " # Actuation rate of change\n", " if t < (T - 1):\n", " cost += cp.quad_form(u[:,t+1] - u[:,t], R_)\n", " constr+= [cp.abs(u[0, t + 1] - u[0, t])/DT <= MAX_D_ACC] #max acc rate of change\n", " constr += [cp.abs(u[1, t + 1] - u[1, t])/DT <= MAX_D_STEER] #max steer rate of change\n", "\n", " # Kinrmatics Constrains (Linearized model)\n", " A,B,C = get_linear_model(x_bar[:,t], u_bar[:,t])\n", " constr += [x[:,t+1] == A@x[:,t] + B@u[:,t] + C.flatten()]\n", " \n", " #Final Point tracking\n", " cost += cp.quad_form(x[:, T] - x_ref[:, T], Qf)\n", "\n", " # sums problem objectives and concatenates constraints.\n", " constr += [x[:,0] == x_bar[:,0]] #starting condition\n", " constr += [x[2,:] <= MAX_SPEED] #max speed\n", " constr += [x[2,:] >= 0.0] #min_speed (not really needed)\n", " constr += [cp.abs(u[0,:]) <= MAX_ACC] #max acc\n", " constr += [cp.abs(u[1,:]) <= MAX_STEER] #max steer\n", " \n", " # Solve\n", " prob = cp.Problem(cp.Minimize(cost), constr)\n", " solution = prob.solve(solver=cp.OSQP, verbose=False)\n", " \n", " #retrieved optimized U and assign to u_bar to linearize in next step\n", " u_bar = np.vstack((np.array(u.value[0,:]).flatten(),\n", " (np.array(u.value[1,:]).flatten())))\n", " \n", " u_sim[:,sim_time] = u_bar[:,0]\n", " \n", " # Measure elpased time to get results from cvxpy\n", " opt_time.append(time.time()-iter_start)\n", " \n", " # move simulation to t+1\n", " tspan = [0,DT]\n", " x_sim[:,sim_time+1] = odeint(kinematics_model,\n", " x_sim[:,sim_time],\n", " tspan,\n", " args=(u_bar[:,0],))[1]\n", " \n", "print(\"CVXPY Optimization Time: Avrg: {:.4f}s Max: {:.4f}s Min: {:.4f}s\".format(np.mean(opt_time),\n", " np.max(opt_time),\n", " np.min(opt_time))) " ] }, { "cell_type": "code", "execution_count": 18, "metadata": {}, "outputs": [ { "data": { "image/png": "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\n", "text/plain": [ "
" ] }, "metadata": {}, "output_type": "display_data" } ], "source": [ "#plot trajectory\n", "grid = plt.GridSpec(4, 5)\n", "\n", "plt.figure(figsize=(15,10))\n", "\n", "plt.subplot(grid[0:4, 0:4])\n", "plt.plot(track[0,:],track[1,:],\"b+\")\n", "plt.plot(x_sim[0,:],x_sim[1,:])\n", "plt.axis(\"equal\")\n", "plt.ylabel('y')\n", "plt.xlabel('x')\n", "\n", "plt.subplot(grid[0, 4])\n", "plt.plot(u_sim[0,:])\n", "plt.ylabel('a(t) [m/ss]')\n", "\n", "plt.subplot(grid[1, 4])\n", "plt.plot(x_sim[2,:])\n", "plt.ylabel('v(t) [m/s]')\n", "\n", "plt.subplot(grid[2, 4])\n", "plt.plot(np.degrees(u_sim[1,:]))\n", "plt.ylabel('delta(t) [rad]')\n", "\n", "plt.subplot(grid[3, 4])\n", "plt.plot(x_sim[3,:])\n", "plt.ylabel('theta(t) [rad]')\n", "\n", "plt.tight_layout()\n", "plt.show()" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "## V3 Add track constraints\n", "inspried from -> https://arxiv.org/pdf/1711.07300.pdf\n", "\n", "explanation here...\n", "\n", "benefits:\n", "* add a soft form of obstacle aoidance" ] }, { "cell_type": "code", "execution_count": 38, "metadata": {}, "outputs": [ { "data": { "text/plain": [ "[]" ] }, "execution_count": 38, "metadata": {}, "output_type": "execute_result" }, { "data": { "image/png": "iVBORw0KGgoAAAANSUhEUgAAA2kAAAI/CAYAAADtKJH4AAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjMuMSwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy/d3fzzAAAACXBIWXMAAAsTAAALEwEAmpwYAACIiklEQVR4nO39fZQcd3nn/X+q+smWLYuxRLTWAMudSMQswXCWZtGwKNklTmJi7+/OwihjvEpIcji5Y4jJYRQnAtsZJrKPdcdozImTwJ5j7sTJHMNkhock5iFZHU5iAS0vbdbBJraxc9gNHilyJI8Vge3unq76/dFTrZqefqie7qr6Vtf7xR8aaUbqMld9u/vq6/peX8t1XVcAAAAAACPYcV8AAAAAAOACkjQAAAAAMAhJGgAAAAAYhCQNAAAAAAxCkgYAAAAABiFJAwAAAACDkKQBAAAAgEGycT3wyZMn43rojnbs2KEzZ87EfRnoghiZjxglA3EyHzEyHzEyHzEyX5pjtGvXro7fo5IGAAAAAAYhSQMAAAAAg5CkAQAAAIBBSNIAAAAAwCAkaQAAAABgEJI0AAAAADAISRoAAAAAGIQkDQAAAAAMQpIGAAAAAAYhSQMAAAAAg5CkAQAAAIBBSNIAAAAAwCAkaQAAAABgEJI0AAAAADAISRoAAAAAGIQkDQAAAAAMQpIGAAAAAAYhSQMAAAAAg5CkAQAAAIBBSNIAAAAAwCAkaQAAAABgkGzcFwAAME+uXFahVFJ9bEyZlRVVJiZUKxbjviwAAFKBJA0AsE6uXNb2qSlZ1arkOJJt69J8XudmZ0nYAACIAEkaAGCdQqkkq1aT5ThyJVmOI1Wretktt0iuq0szGb0wNaUXJyebP0/iBgDA8JCkAQDWqUxM6NJcTnJdyXHk2rZc25blOI2ErV7XJfPz2rKwIEuS6nVdmss1K220SAIAMBiSNADAOrViUWcXFtbtSauPjWnbzIxUqUiuK8t1pVpNkhpfu26j0uY4bVskSdwAAAiOJA0AEsAb5BFVklMrFjc8zuqVV2rL0pK2LCzIrdflZjKypMbXltWstG1okeyQuFUmJiTRLgkAQCuSNAAwXHOQR62mS3M5nV1YiCWhqRWLOlcs6oXJyWZiJalZcds2MyOtDRtpbZHstLet2S7p2+dGsgYASDuSNAAwWK5c1ta5OVnVaiPJUSMpijORaa2yeV+vXnll+xbJDomb1v57LNe9sM9tcZEWSQBA6pGkAYChWkfhu7YtN5drVrBM06lFsm3iVqtdaJes1S7sc6NFEgAAkjQAMFFrBc21bVX27dP56elEJSbdEjcv4Vq3z63b3rYuLZISiRsAYHSQpAGAQXLlcjNp0erqhQpaPp+4BK2T1sTNv89tUy2S/qMA2NsGABgBJGkAYIhme6M35l5KbAWtX/7Ere8WSf9RAG32ttEiCQBIGpI0ADDAuvZG15UrybWskaqgBdV3i2S3vW20SAIAEogkDQBi1nZASDZL255PtxbJXnvb+mmRlEjcAADxI0kDgBiNyoCQOATa29ZPi6Q/ccvlOAoAABAbkjQAiMnF8/ONlrx6XXLdkRsQEod2e9sCt0j6EzfX7XkUADECAISFJA0AYpArl7Xtlluk1dVGsmBZVNCGrO8WSS9xC3gUAC2SAICwkKQBQMSaLY71eiMpkKRMhgQtAkESt0BHAdAiCQAIEUkaAERkwxlortuY4JjJ6Nwdd/BmPiatiVvPowC8IxL6bJEkcQMABDW0JM1xHB06dEiXX365Dh06NKx/FgBGQprPQEuqTkcBbKpFssveNol2SQDAekNL0r74xS9qfHxcL7744rD+SQAYCSaegXb4cEY33hj5wyZerVjcdItkp71t7Y4CIFkDgHQbSpJ29uxZffOb39Q73/lOPfDAA8P4JwFgJJh6BtrttzeStKNHt+rgwfOS1n+N7vpukey0t63dGW6Lizo3Oyu7WtXF+TwtkgCQQkNJ0v7kT/5EBw4coIoGAD4mnoHWmojNzV34vfc1ydrmdWqRbJu4dTrDzdci+TJaJAEglSzXdd1B/oGHH35Y/+t//S+9973v1be//W391V/9Vds9aceOHdOxY8ckSUeOHFG1Wh3kYUORzWa1uroa92WgC2JkPmIkWSdOyJqfV+ZP/7QxWGLtjbYKBa1++cty9+6N5boOH87o9tszG/781lvruu22ugqFvCqVavNX7+/cdlt9w9cYjHXihKwHH5T74z/e+L13v6yuSpYl+Vsk1di/KNuWXFfKZBo/s7oqZTJy3vMeOQcONP6dtX8zrnssbXi+Mx8xMl+aY5TP5zt+b+Ak7f7779eDDz6oTCajarWqF198Uf/hP/wHfeADH+j6906ePDnIw4Zix44dOnPmTNyXgS6IkfnSHiNTB4R41bHx8V2anj6vubmtXX9+evp88+eXlxvP197XtEiGI1cur9vb5rXIqnVvm2VJUnN/oyxLbi7X3NvmcoZbZNL+fJcExMh8aY7Rrl27On5v4CTNr1slrRVJGjaDGJkvzTHy2hsLx483qyCyLLmFgs4uLMTyJvno0UYy1i4p85I1L/HqlLi1JmkkbuHLlcsa+9a3dH5tT1ozcfO1SMprkZR6J26+M9xI2IYnzc93SUGMzJfmGJGkBZTmmyQpiJH50hqj1gEhMmRASGti5f368Y/v1I03nm6bcI2Pd37R8LRW2tr9O9KFhI3ErX+ta8mrtHl70ppn7vmOAuiYuPnaJam0DU9an++ShBiZL80xiixJ6wdJGjaDGJkvjTHaUEEzpL1R6lxBu/POgs6cOdO2AtapUjZIi2S7xA3dBVlLgRK3Nme40SI5HGl8vksaYmS+NMeIJC2gNN8kSUGMzJemGOXK5QtvildXL1TQ8vnY2hsldUyopqcbidHBg+e7xsmfRHVLuIIkbpJokdykza6l1sRt3T43/17JPlokvcmUJG7rpen5LqmIkfnSHCOStIDSfJMkBTEyX1pilIQBIe3aHD1B4xS00tb6Z73QItnbsNfSug8V+mmR9M5zW/sAgr1tF6Tl+S7JiJH50hyjbkmaHeF1AMBIWHf+2drnXK5lyc3nY0vQjh7d2qxseUmS9+vRo1ubVbR++ZMk72v/v9Xp311ePtlMuvzJocd/ba286py/Suf9XLufRzC1YlHnjhzRmcVFnb/5Zp1dXNSZxUW9cOCAlM/LzWTk5nJSLtf4ei1Bs7wDtx1H1toZblvvukvb9+/XZYcOKVcuK1cu69J77lGuXI75vxIARgOVNJ80Z/JJQYzMN+oxStqAkE7VqGHHqVPr4rBbJDvtbRvFqluUa6lri2SnowCk1O9tG/Xnu1FAjMyX5hjR7hhQmm+SpCBG5hvlGCVxQEinxCWqOLVrXQyjRbJXUppEJqwl/9lt644CYG+bJDNihO6IkfnSHKNuSVo2wusAgMS6eH5eL7vlFqleb4wxX9ufE2d7o9Q5OZNkRLLiXYP/Wrq1SEqdjwJobeNsZ25uY3VtlBK3qNWKxQ339+qVVzb3trm+vW2ut7fNdRv73NRI3OS6jbXj29t2qW9v26glbgAwDFTSfNKcyScFMTLfKMYoVy5r+7veJWt1tVk5qPz4j8daQevU3tg6IKQTE+IUtEWy9c966XaGW5JaJE2IUTebHf/vDdkZhaEkpscIxCgJ0hwj2h0DSvNNkhTEyHyjFqNmi+ODD15o58pmdeYzn0l0Bc3kOPXTItlrn1u/LZImJW4mx6iTze5tW5e4uW5iWiSTGKO0IUbmS3OMSNICSvNNkhTEyHyjFKMNQ0IsS24mo3N33KEXDxyI/HqCnH8WVNLi1C1x838ddG9b698xcW9b0mLUTce9bZ0Stx6VNlMSt1GK0agiRuZLc4zYkwYAfVo3Zt+QISGe1vbGuJKJ8umySqdKmrhiQsWd4f5/0mtvm//roHvb/F+3JmXt9ra1+zkE02lvW7vETbXaxhZJx5HWxv932tvmr97FnbwBwKCopPmkOZNPCmJkvqTHaN2Bv6ur6z7FP7uwEMsbv3e9a7tOnChs+PNBBoQMGqfy6bKmvjClmlNTzs5p4dqF0BO1IIbRIulp3dvW+vfDTtySvpY2w19x67tF0r8PLqKjANIYo6QhRuZLc4w4zBoAAvDaG7fMz0trFTStVdDiStAk6cSJwrphIMvLJ5sJRBxVnfLpsuYenlO1XlXdravm1FQ6VYr8OtppV2lrN03S+zn/gdutP+c/GLyVP8HzvvYftM2h25tTKxb1/Ztu0osHDujswoLO/9Zv6fn/9//V+d/6LZ274w65+XwjMVMjQWseuF2vy6rVpFqt8XW1qkvm57V9/37t2L9/w+HbAGA62h0BQC3tjWsDQlzLMmLMvrSxRa/TGPuweRW0ar0qR45s2crZOU1cMRHL9XTTT4uk93Nzc1uH0iLJUQCD67tFstdRAPW6Lpmf15bFRVokARiPdkefNJdbk4IYmS+JMdowIMS25WazzXapuBK0du14e/dW9JnPnB34399MnLwK2vHl480Ebd/4Pk2/adqIVsfNate6GEaLZKejADpJ4lqKQ6CjALzETcNtkSRG5iNG5ktzjJjuGFCab5KkIEbmS1qMmiP2jx83ZkBIa6LQ7xloQfQTp/LpspaeWtLCkwtadVabCVo+kzdmL9qwBZkiGTRxkzofBdBtb1vS1pJJuiZu/qEkliVJF47XsCy5uVzgxI0YmY8YmS/NMSJJCyjNN0lSECPzJSVGJg4IGdYZaEEEjZPX3lipV7T2NnZkKmhBBa20tf5ZL93OcDt6dKvuvLOgD32oQovkkGwYSuJrkVxXaeuVuPnOcNvyylfqhe99j1ZJgyXlNSnN0hwjkrSA0nyTJAUxMl8SYtRsb6xU1rVAxV1B61Q5G3Qvkzcqf6wwppXKiiaumNA1r7smUJwOffWQ5h+fbyZoliwVMoWRraAFFTRx83/dKXHr1CJZqVRVKOQ3tEiyt21wfbdI+hO3dme4ZbOqvP3tkqT6y1++ofLW7mv/WW9hfH9UH6vfa9larWrlqqtIog2WhPcNYSFJCyjNN0lSECPzmR6jDe2NUuOT8kLB2AraoAla66CPfCavoz91VN87+73mwI92552VT5e1/4H9qjpVSVLWyurdV75bk3smU52gddKpdXGzLZKtSVqvvW0kb4MJlLi1tktq7SiA1n/MtqVMRnKcDfveLGl99T6bHf73R/WxNnstMXZIoDfT3zeEiSQtoDTfJElBjMxnaow6tjcaOiBkWO2N9zxyj+4q36W6W2/+mS1btm3LdV1lrIwkqe7WlbEymvrRKU3uaVQB/ENCLFk68NoDOvK2IwNdTxq1q4CF0SI5rMorLmhN3Nqe4WZZzYqbx3tjtaEK19JKGer3R/WxNnMtmYzO33yzvn/TTYJ5TH3fEAWStIDSfJMkBTEyn4kxMrW9MYoBIe0qabZly3GdZvIlqdnOKKmRuLmSI0euXFmylLNzWrxukQrakARpkfQqab0EqbSRuA2Xl7xteeUrVTlxQls+/enmuH/JV11rM4hk5KpbVNIwIBPfN0SFJC2gNN8kSUGMzGdajJLY3igNb0CItHFP2lhhTB858RFV69VmJa3m1NYlaq3ydl6H33q4uadNat8iif50a5Hs1u7YS+s+N1okw+E93+XKZV28tKTcd76jfLncGO/vq9JL8e/NGpXHYk/a6DHtfUOUSNICSvNNkhTEyHwmxcjE88+k8AaE9OPpl57Wl574UjPh+vjff1x//X/+umOi5lXgXHVvkSRxG4520x07tUj22ufWb4skiVtw7Z7v/C2SJAbxM+k1Ce2lOUYkaQGl+SZJCmJkPlNiZOr5Z1I4A0L65cXJfwZap2parxZJrx1S2pi4kaxtXuta6ra3zf910L1trX+HxK1/pjzfoTNiZL40x6hbkpaN8DoAIHTtBoS4a3sS4k7QompvDKrbGWg/+3/9bLM10vt1pjSjmlPb0CLpylXNaezHceWq7tY1//i8Fr+zqNmJWVokh8S7R/z3inf/tH7dK3Hz/977ujURm5u78Hv/1yRsABA+Kmk+ac7kk4IYmS/OGKV5QEi/nn7paf3OV36nOb1R6n0Gmre3zUu4vAqcVz2T1u9to0VyMJtdS0GmSAY9CqDTGW5U2hp4TTIfMTJfmmNEu2NAab5JkoIYmS/OGF126JAumZ9vjl5O24CQoMqny7r+i9erslppTnzM2tlNtSh2S9wsWZtqkZRI3KThrKV+WiT7OcONFskGXpPMR4zMl+YYkaQFlOabJCmIkfniilGuXNb2/fsbQ0IkKZvVD9797tQPCGlVPl1ed/6Z1944/abpoSVE/mmSnVokJfVM3HJ2rtku6bVdpilxC2sttUukuiVu3p+1022KZBqOAuA1yXzEyHxpjhFJWkBpvkmSghiZL44YbRgSYll64cABnTsSz8HLJg0I8fgHhKw6q80ELZ/Jd2xvHNbj9tMi6U/cWgeWeNfr3+c2yglblGspaOI2aItkp6MAkorXJPMRI/OlOUYkaQGl+SZJCmJkvihj1G5ISNwHlyZtQMgwK2j9XE+vxK21XdLTus9tlFsk436+63aGGy2SDXHHCL0RI/OlOUYkaQGl+SZJCmJkvqhiZPKQkLm5rcYMCGltb5Qa1aqLshfp0z/7aWMSmtbEzd8uWa1Xm5U0f2VNGu0WSVOf7wZtkfRLeuJmaoxwATEyX5pjxAh+ACPFa2+0qtXmkBDXsmIds/+ud23XiROF5u/9Y839o9Gj5FXQ/EmONyDkvcX3avdFu2O5rnaKO4vrEinv6ysvv7KZsPmPAvCqgq3j/926q1u+dkvHFsmkJ24m8BKmTuP//YIeBdDv+H+TEzcAGAYqaT5pzuSTghiZL+wYNSto1eqF9sZsVi9MTRkzJESS8QNCkryW/Pvr+mmR7La3TTKvXTKJMRpmi2S/e9viWG9JjFHaECPzpTlGtDsGlOabJCmIkfnCjNGGASGGtDdK5gwJCTogZBTW0mZbJKVgZ7jFnayNQow83Y4CGNbetjiGkoxSjEZVFDHKlcsqlEqqTEzE9lqUZGleRyRpAaX5JkkKYmS+MGJk6oAQqX1ytndvRZ/5zNmoL6mvASGjvJb8RwD4WyQ7JW7tjgIoZAqxt0iOcoykaPa2+R8njMRt1GM0CiLr7qjV5OZysb0mJVma1xF70gAklqkDQrzhIO2GhMSRoEmNKYn+BM2SpXwmH8sExzi17m+TOu9ta3eGmytX1Xq16942U1skkySMvW3tEjpvTxt72xCGQqkkq1aTVa9LjqMtS0s6R5KGISBJA2AsEweEeBU0aeMbw7iHhCw8udBM0LJWVu++8t1GtO2ZoFvi1u4ogNa9bY6cZuLWrUVSInHrlz9JCiNxa6db4tb6NdBNZWJCl2YyUr0uua62LCzohRj3R2N0kKQBMFLrgBDXgAEhJp6BJl0YErLqrEpqVNDefeW7deRt8RzmnRTtJkpO7pkMtLfNcRvJmytXdbeu+cfntfDkgiQSt2Fol7hJF9ZakMTNr1ulzdNuoiSJG3qpFYt6YWpKl8zPNz5MrNdVKJVI0jAwkjQAxllXQTNoQIj3yXtre2OcyVmnISFecoD++BO3flsk/UcBtEvc/Ge4kbBtjrfWgiRug7RIenolboAkvTg5qS2Li1K1KteyVB8bi/uSMALsuC8AADy5clnbDh3Sjv37VTh+/EIFLeb2Rq+CZlp749QXpjT/+LyqTnXdmH3/FEdsXnFnUTe98SYdeO2B5q8L1y7o5uLNWrxuUYvXLerAaw8ob+eVsTLK2Tnl7Ny6QSQ1p6aaU1PdrTfbJe8q36X9D+zXoa8eUvl0WeXTZd3zyD0qny7H/F+cTN0St1bLyyebyVu7A+bHx3e1Xed+/mr64cOZ5tfez/l/vtfXYX9/VB+rn2vxxygstWJR52ZnJduW5TjaNjOjXJn1jMEw3dEnzdNlkoIYmW+zMTJ1QEjrtDn/uPC42xu9M9CkCxMJgyZorKXhaT0KIOgZbpYs5exc8/utLZLfOvctXbXtKhLuAQUZ/+//s2Ge4dbr67C/P6qPtdlrCdOl99yjrXfdJatel2tZeuHAAZ07Qst5EGl+PWK6IwCjJXFASJwJ2tQXptbtlcraWWPO9kqjbnvb2p3h5k3g7LdFMq6jAJKunxZJ7+da25pbE7e5uWBnusEMUTxnM0AEw0YlzSfNmXxSECPz9ROjjuefMSCkrdYKWqcz0IJgLcXDv4/QX2nz9rZJWtcu2TqwpN1RACRsw9FuSEinygySyauAhuWyQ4cuDBChmhZYml+POMw6oDTfJElBjMwXNEamtje2vjmLumWmnW4DQja7/4y1FK/NtkhKaiZu3lEATJEMT9DEzf+1SW2Bo/pY/V6LFH6CJq29ru3f35hKLEn5vM4sLlJN6yHNr0e0OwIwzsVLS7IqFePaG/1tTCYNCPEfUj1IBQ1mCNIi+a1z31K+nu96FAAtkuHqdYYbzOavenrP7WEmaxvG8ddqHG6NTSNJAxC5XLncaHFcS9CUzeoH7353bO2Nkpp7UNrtRYm7vbFar65rhctn8iRoI6g1cbvmddfozJkzHY8C6LS3za27uuVrt3RskSRxG4z/+eDWW+vNr9vtc+v1ddjfH9XHCnotBw+e18c/vlO3355Z92dhenFysvH6Vq2yNw0Dod3RJ83l1qQgRubrFSNvSEjh+PHGGWgx9+37K2itonhB7yTsASGsJfN1i1GnvW29WiS77W2TaJfsF+vIbN32F7M3zRxpXkfsSQsozTdJUhAj83WKUcchIfm8zi4sMCDEZ5gDQjphLZkvSIxa97b5p0h2apH0tO5tkzYeBUCy1h3ryHw7duzQhz5UaT7XszfNPGleR+xJAxArU4eEeFoHhMSZnHUaEEJ7I9ppt7dNUscWyU6Jm+M2kjf/UQCL31mkRRKJd/hwpu3xCexNg+mopPmkOZNPCmJkvtYYbWhvlCTLklsoxFZBe9e7tuvEicKGP4+zghb1gBDWkvmGHSOv6taauNWcWtujAGiR7I11ZD4vRv7OCappZknzOqKSBiAWzQpatSo5jlwDzkCTpBMnCutGMzMgBGnQWnWTLlTc2h0F0Lq3zZGjar2qW752S9cWSSndiRv642/ZDet+6XQYOdU0mIxKmk+aM/mkIEbm82K0oYJmQHujaUNCOrU3DnNASCesJfPFFSN/xa1bi6T/0G2p8cFCzs5JSk/ixjoajNdBUHNqytm5TZ/72I0/RlTTzJTmdUQlDUBkrBMntO3ee9cNCHHXBoTEnaC1S8727q3oM585G/n1cP4ZTOWvuHXa29auRbL1KIBeZ7iNWsKG/pVOlVRzaqq7dTl1R0tPLY12Na1eV6FUIklDICRpAIYmVy4re/31yr70klEDQrxWxtYz0MbHd8WWoNHeiCTot0WyV+LmneHmtUuOeqUN3U1cMaGMlVHdrcuVq4UnF0LrIDh4sJGMRV1Ne3FyUlsWF6VqVa5lqT42FurjYXTQ7uiT5nJrUhAjc5k4IKRXe6MU/ZCQsM8/C4q1ZL4kxaj1KICgZ7glvUUySTEy1aGvHtL84/Ny5cqSpQOvPaAjbxvemWKd2h39wk7WLp6f18tuuaXRWRLjsTOmSvM64py0gNJ8kyQFMTJT64AQGTIgxF8x8/8a55AQ/xuSONsbWUvmS3qMup3h5m/z7bW3zd8iadpRAEmPkQnKp8va/8B+VZ3Gvq28ndfidYuhngnpT9aWl8N/P3rpPfdo6113yarXOdy6jTSvI/akAQiNV0GzqlXjBoRIak5w9H6NK0HzhoR86olPNd+MZu0s7Y0YWd3OcNtMi2SnowBMS9zQn+LOoqZ+dKr54VXNqUW6N817bQizmlaZmNClmYxUr0uuqy0LC3ohxg8wkQxU0nzSnMknBTEyR65c1palpXUDQmTbUqGgM5/+NO2NPu2GhITR1tMP1pL5Rj1Gm22RlIKd4RZFwjbqMYpKmNW0TjGKupp22aFDFwaIUE1bJ83riHbHgNJ8kyQFMTJDs72xUtkwICTzu7+rf9m9O5br6tTe6P0aB29IyPHl4+v24RQyhVDGTQfFWjJfGmPUrUWy01EAHu/PoxxKksYYhcXfCp6xMrq5eLNueuNNA/+73WIURRXNwzj+ztK8jmh3BDA069ob3UZdyLWs5oj9bXv3ShE/2fZqb/SqaFEzZUgIkBTdWiTbHQXQKXHrNf6fFknzTO6Z1OJ3FlWtV2XJ0lghvCmIRozj53Br9EAlzSfNmXxSEKN4BRkQEnWMuk3rkuJpb5Q2VtBMOwONtWQ+YtSd/9Btf+LWaShJrxbJzSRuxGi45h+fb+4/zGfyQ+k26BUjqmnxS/M6opIGYGCmDgjpdP5ZnMmZt7dm1Vld92bQlAQNGAWdznALurfNkaNqvdp1KAmVtmitVFbkypUjR5V6ZfQPt6aahi6opPmkOZNPCmIUvU4DQjqd9RJFjJI0IMS0CpqHtWQ+YrR5w9rb5m+RbJeweTFqrer5H7fT171+dtDvJ/Gxlp5a0v1P3K+6W5ck5eycrv/R69ftLez3WqqZqq7adlXH59+oD7emmrZRmp/rGBwSUJpvkqQgRtHqNiCkUwUtihiZeP6ZqQNCOmEtmY8YDV+nFslOiVtrwta6lnfs2KEvf/vLbfeeStpQzfO+9lfZ2/3soN9P+mO1ytv5ga6lU+tkXIdbM+lxvTQ/19HuCGBTLl5aklWptB0QEueIfcmc888kBoQASdGpRbJd4lZzautbJJ1Gdab175dOlVRzauvaKP3nvDmu0/brXj876PeT/Fitqk5jmMgg19IudgcPNpKxqKtpL05ONrpTqlXOTUNHJGkA2sqVy40XkbUETdmsfvDudzcHhETN9AEh/gTNxPZGAO31Sty8hC1n55qtdH4TV0woZ+fk1t2Rrm7FWUnzfn5T12LZHWMnsTcN5qLd0SfN5dakIEbR8IaEFI4fbwwJ6aMdI4wYeVUy084/6zQgxMT2xlasJfMRIzP497exJy2ax3rs7GP61BOf0qq7KqmxN+32t96+YQpnkGvptSfNw960+KT5uY49aQGl+SZJCmIUrn6HhLQz7Bi9613bdeJEYcOfMyBkMKwl8xEj8xGj8PgPt7Zk6cBrD+jI2/rftxUkRuxNi1ea11G3JM2O8DoAGMwbErJlfl5aG7OvtSEhQRO0MHgJmlcxW14+2XzhjCtB89ob/WcxMWIfAIZncs+kcnZOUmN/2cKTCyqfLofyWAcPnm++tnii2pvm5nKNV5K1vWm5cjj/jUgekjQAkqRCqSSrVpO1VlyPe0jIu961vTkURDJrQIj/gOq8ndeB1x5IRIsjACRFcWdRUz861TyQvObUtPTUUmiP125v2vj4rnUDq4bN25sma+2/sl5XoVQK7fGQLCRpACRJlYmJxid6mYzcfF4/OHAgtgra0aNb27Y47t1bMW5AyOJ1izrytiMkaAAwZHFX05aXT0ZTTSsU5Nq2XMtSfWws1MdDcpCkAZDU+ETv7MKCzt98s84uLupfjxyJLUHzXhT9Q0GWl0/qM585G/n1lE+Xdeirh7T/gf3rK2i0NwJAqOKupo2P74qkmnZudlaybVmOo20zM7Q8QhJJGgCfWrGo7990U2zJmfcC2XoG2t69lcivR7rQ3jj/+LyqzvoKGu2NABC+NFTTMisrkuvKchxZlYq2LIWXiCI5SNIAGGFubmMFzXuxjKOCJklLTy2tm+DIgBAAiFZrNa3u1lU6Fe6+LX9SFmYVzVOZmGhsNZAYIIImkjQAsfIqaJI2VNDiGhLitTh+6olPNRO0rJVlQAgAxGByz6QKmYJs2bJkaawQ3r6to0e3rhtaFcsAkbXDrZFuJGlAyuTKZV16zz1GfErntTe2nk8zPX0+kvHH7fhbHL2DVC1ZeveV72ZACADEoLizqNmJWdmWLcd1NFOaCb3l0b8nmnH8iANJGpAi3lloW++6S9unpmJ9AWg3IMT71bQz0AqZgib3TEZ+PQCAhpXKily5cuSoUq+EPkCEahriRpIGpMjFS0uyKhVZ9bqsWi2W81i6DQg5enTrug3bUeIMNAAw18QVE8pYGUkcbo10IEkDUiJXLmvLwoLkrtWIMhlVJiYiv45uA0JMqKBxBhoAmCfucfxU0xA1kjQgBXLlsrbOzclaXW088VuWXpiainTUvskDQjgDDQDMF/c4fqppiBJJGjDivH1ohePHJceRa9tyCwW9MBndHivTB4RwBhoAmI9qGtKEJA0Ycc19aI4j2bYq+/bp7MJCZFW0JA0IoYIGAGajmoa0IEkDRtiGfWjZrM5PT0eSoDEgBAAwbFTTkBYDJ2lnzpzR7OysPvjBD2p6elpf/OIXh3FdAIbg4qUlWbVaLPvQGBACAAgD1TSkwcBJWiaT0S/8wi/o7rvv1h133KG//uu/1jPPPDOMawMwgA1VtFwukn1ohw9nGBACAAhNKqtp9Xosx+YgPgMnaWNjY/rhH/5hSdLFF1+s8fFxPffccwNfGIDBxFFFO3p0q26/PcOAEABAqOKupi0vn4ymmlYoNAZ+WZbqY2OhPh7MMtQ9ac8++6y++93vavfu3cP8ZwH0Ka4qmocBIQCAMMVdTRsf3xVJNe3c7Kxk27IcR9tmZmh5TBHLdV13GP/QSy+9pJmZGb3zne/UW97ylg3fP3bsmI4dOyZJOnLkiKrV6jAedqiy2axWV1fjvgx0QYyCyfz6r8u+915Zrtv49O2975XzB38Q2uMdPpzR7bdnNvz5rbfWJUm33VYP7bE7OfHMCV3zqWtUWa00qmeWrayd1Xte/x4deP0B7X3F3sivySSsJfMRI/MRo3ideOaEfur+n1K13nhPWcgU9Dc3/M265/dhx8j/elephP9e1v6931NmZkbW2hE69dlZOb/1W6E/bpTSvI7y+XzH72WH8QCrq6s6evSo9u3b1zZBk6Srr75aV199dfP3Z86cGcZDD9WOHTuMvC5cQIx6y5XL2n7ffeuqaCvXXadaiP+/3Xij9MILFz5lXF4+qaNHt+rGGxvVs6hD5lXQmgmabO3btW9d9Szt9xFryXzEyHzEKF67L9qtqdc02tlduVp1VvWlJ76k3Rdd6OgadoxuvFG6/fbGPusPfagSepfIxfm8XuY4jddzx9H5fF4vjtg9l+Z1tGvXro7fG7jd0XVdfeITn9D4+Liuu+66Qf85AAPIlcvaOjcna3U1sr1oR482NlC3toHEgQEhAJAuk3smVcgUZMuWJUtjhfD2bXmvd54oBohkVlYa7Y6SZFnKP/ZYaI8FswycpD355JN68MEH9dhjj+nmm2/WzTffrG9+85vDuDYAfciVy9o+NaXC8ePSWluEWyiEvhft4MHz6zZT33prPZIN1a0YEAIA6VPcWdTsxKxsy5bjOpopzYQ+QMTbby2FP46/MjEhN5tlFH8KDdzueOWVV+rP//zPh3EtAAZQKJUa0xzXErTKvn2hH1zdupFakm6/PaMXXoh21D4DQgAgvVYqK3LlypGjSr2ipaeWQnvebzeOf25ua2jJmjeK/5L5+cY+87WDrc9FdOYp4jPU6Y4A4lMfG5Msq1FBy+dDT9CkjVW06enzqlSqkSdoU1+YWt/eaOd14LUHqKABQApMXDGhjNUY5jGKh1tzsHU6kaQBIyBXLmvbzEyzzfHc7GwkZ6K17kWbm9uqw4c3TnkM09JTS6rUK+vaGxevW9SRtx0hQQOAFIh7HH/Ye9M2HGy9Vk3DaCNJA0bAxUtLsioVWY4jy3UbG40j0NqXv7x8MrJx+96QkE898almi2PWztLeCAApFPfh1lTTMGwkaUDCbTi4OpNRZWIi1Mf0PkVsnXIV5oQrqZGY3fPIPZp/fL45JGTVbZytYsnS1I9OkaABQApRTcOoIUkDEu7ipaXGwBApkpH7fl4lzauihfkporf37Pe+8Xv60Fc/pEq9sm5ISCFT0OSecCdZAgDM1a6aduKZE6E8FtU0hI0kDUiwDVW0XC7Ukfut+9CiPA9t6aklvVR/Sc7a/1y5DAkBADS1q6bNPzof2uNRTUOYSNKAhIrj4Grvk0OP9yli2NMcy6fL+tQTn1r3Z5YshoQAANZprab96aN/yt40JBJJGpBAcRxc7VXR/NWzKCpp84/P69eO/Vpz75mnkCkwJAQAsE5rNa1ar7I3DYlEkgYkkH+ao9YOrj67sBBpFS2KfWjzj8/rt7/62zr1wql1f/7Gl7+R9kYAQFtMesQoIEkDEmbDPrRsNpKDqyWt+2QwigOrP/Xkpzb8Wd7Oa3ZilgQNANBW6iY91usqlEqhPBbiQ5IGJEwc0xzbHVwd5guQ1NiH9tiZx9b92TX/9hotXrdIggYA6CrualrYnSYvTk7KLRQa2x0sS/WxsdAeC/EgSQMSJOppjn6tA0PCfgFaempJdffCwdjX/Ntr9Mmf/iQJGgCgp7irad4e7jCraedmZyXbluU42jYzQ8vjiCFJAxIkripa68HVUVTRFp5caJ6DlrfzuvENN4b2eACA0TO5Z1K5zOhW0zIrK5LrynIcWZUKA0RGDEkakBBxVtGkaA+uXnpqSTWnJqkxan/qR6eooAEA+lLcWdR7Xv+eZjWt7tZVOhXu3i3/a2OYH2ZKUmViQm4mwwCREUWSBiRE1FW0uA6ubq2i5eycJvdEl4wCAEbHgdcfUCFTkC1bliyNFcLbu+W9bnoYx49BkKQBCRBHFe3gwfMb2jaiOLi6dKrU3ItGFQ0AMIi9r9ir2YlZ2ZYtx3U0U5oJveWx9bgaxvFjM0jSAMPlymVtnZuTtboaWxVNiq6SNlYYkyVLtmwVMgWqaACAgaxUVuTKlSNHlXol9AEiVNMwDCRpgMFy5bK2T02pcPy45DiNUbuFQuRVtCj2oUmNVseZ0owc15Ft2ZyHBgAY2MQVE8pYGUkcbo3kIEkDDHbx0pKsSkWW40i2rcq+fTq7sBB5FW1ubmvoG6DLp8uae3hO1XpVjhy5crVSWQn1MQEAoy/ucfxU07AZJGmAoTbsQ8tmdX56OvSR+3FU0cqny5r6wpSOLx+XI0e2bOXsnCaumAjtMQEA6RH34dZU09AvkjTAUIVSSVa9HvmZaHFU0ZaeWlKlXmkmaPvG92nh2gVaHQEAQ0E1DUlDkgYYqj42JllWZPvQPK1TqaKoovlH7mftrKbfNE2CBgAYKqppSBKSNMBAuXJZ22ZmmsNCzs3ORlJF8z7p80RVRePgagBA2KimIUlI0gAD+QeGWK6rzEp0AzS8SlocVTQOrgYAhIlqGpKCJA0wzIaBIZmMKhPhDdBo3YcW1XloElU0AEC0UldNq9dVKJVCeSyEiyQNMEgcB1e3TnP0PvWL4kw0qmgAgKjFXU0Lu0vlxclJuYVCY0+7ZTX2uCNxSNIAQ8RxcHW7aY5RVNK8M9FWnVVJVNEAANGJu5o2Pr4r9GraudlZybZlOY62zczQ8phAJGmAIeI4uNr7hM8T15lohUyBKhoAIDKjXk3LrKxIrtvY216pMEAkgUjSAAPEcXC1V0WLY5ojZ6IBAOLUWk2ru3WVToW7d8uflIX9WluZmJCbyTBAJMFI0gADXLy0JKtWi/Tg6riqaJyJBgAwweSeSRUyBdmyZcnSWCG8vVveB6MexvGjF5I0IGYbqmi5XCQHV7e+MIQ9KERimiMAwBzFnUXNTszKtmw5rqOZ0kzoLY+tH44yjh+dkKQBMYujitbu4OowP9GTmOYIADDPSmVFrlw5clSpV0IfIEI1DUGRpAExiquK5vE+0fM+3QvzEz2qaAAA00xcMaGMlZHE4dYwC0kaEKOoq2idDq4OewMzVTQAgIniHsdPNQ2dkKQBMYmjihbXwdWlUyXV3bokqmgAALPEPY6fahraIUkDYpArl7V1bk7W6mpsVTQpmoOrJWmsMCZLFmeiAQCMQzUNJiJJAyKWK5e1fWpKhePHJceRa9tyC4XIq2hRjNyXGq2OM6UZOa4j27I1OzFLFQ0AYBSqaTANSRoQsYuXlmRVKrIcR7JtVfbt09mFhciraFEcXF0+Xdbcw3Oq1qty5MiVq5XKSqiPCQBAv6imwTQkaUCENuxDy2Z1fno6koOro66ilU+XNfWFKR1fPi5HjmzZytk5TVwxEdpjAgCwWVTTYBKSNCBChVJJVr0e+ZlocVTRlp5aUqVeaSZo+8b3aeHaBVodAQBGopoGk5CkARGqj41JlhXZPjSPdx6aFF0VzT9yP2tnNf2maRI0AIDRqKbBFCRpQERy5bK2zcw0h4Wcm52NpIrmfTLniaqKxsHVAICkSV01rV5XoVQK5bEwGJI0ICL+gSGW6yqzEt0ADa+SFkUV7cQzJzi4GgCQWHFX08J+nX5xclJuodDo6rGsRpcPjEOSBkRgw8CQTEaVifAGaLTuQ4vqPDRJmn90nioaACCx4q6mjY/vCr2adm52VrJtWY6jbTMztDwaiCQNCFkcB1e3TnP0PqWL4ky0+x69jyoaACDRRr2alllZkVy30d1TqTBAxEAkaUCI4ji4ut00xygqad6ZaKv1VUlU0QAAydVaTau7dZVOhbt3y5+Uhb13vDIxITeTYYCIwUjSgBDFcXC194mcJ64z0QqZAlU0AEBiTe6ZVCFTkC1bliyNFcLbu+V9wOphHD9I0oCQxHFwtfckH8c0R85EAwCMkuLOomYnZmVbthzX0UxpJvSWx9YPWRnHn14kaUBILl5aklWrRXpwdVxVtHXTHDM5zkQDAIyElcqKXLly5KhSr4Q+QIRqGjwkaUAINlTRcrlIDq5ufSIPe1CItPFMtF98/S+SoAEARsLEFRPKWBlJHG6NaJGkASGIo4rW7uDqMD+Bk9pU0eycDrz+QGiPBwBAlOIex081Lb1I0oAhi6uK5vHaHb3e9jA/gWutok396JT2vmJvaI8HAEDU4h7HTzUtnUjSgCGLuorW6eDqsIeFtKuiMc0RADBqqKYhDiRpwBDFUUWL6+DqdlU09qIBAEYR1TREjSQNGJJcuaytc3OyVldjq6JJ0R1cTRUNAJAWVNMQNZI0YAhy5bK2T02pcPy45DhybVtuoRB5FS2KkfuSVDpVUt2tS6KKBgBIB6ppiBJJGjAEFy8tyapUZDmOZNuq7NunswsLkVfRoji4uny6rOXvLytjZZSxMipkClTRAAAjz6umeVadVZVOlUJ7vNirafW6CqXw/vvQHUkaMKAN+9CyWZ2fng595L6kWA6unvrClO5/4n5J0g1X3qCFaxeoogEAUuHHtv9Y82tHjsYKY6E9VrtqWtiv8y9OTsotFBodQZal+lh4/33ojiQNGJApZ6JFUUVbempJlXpFdbeuulvX+KXjJGgAgNRYqazIXnv7bMnSY2cfC/XxWqtp4+O7Qq+mnZudlWxbluNo28wMLY8xIUkDBmDKmWhRVdH8w0IyVkYTV0yE9ngAAJhm4ooJZe2spPD3pUnxVNMyKyuS68pyHFmVCgNEYkKSBgygUCrJqtdjPxMtCozcBwCkXeuUx7pbD3VfmseflIXdNVOZmJCbyTBAJGbZuC/ARLlyWYVSSfWxMWVWVlSZaFQLCqXSuq+T/n2TriXo9613vEO555835/r+9V8bVTTLkjIZVX/sx5r3T7+xCJLceU/SXpK2vHxSR49uDX2aIyP3AQBomNwzqcXvLKpar8qSFeq+NKn9AJG5ua2hTXv0BohcMj8vy3Xlro3jPxfBXntcYLmu68bxwCdPnuz9QxHbsWOHzn35y9o+NSWrWpXWJvW52Wxzyo2byTS+Xl1N9vdNupY+vq/s2ucKJlyfZclaXV13D7n5/OZikcv1nAbZ+iTtieLg6kNfPaT5x+flypUlSwdee0BH3nak7c/u2LFDZ86cCfV6MDjiZD5iZD5iZL6wYjT/+Lxu+dotclxH+Uw+siFaXgdN2K/9uXJZ2/fvb7wflqR8XmcWF0PpFkrzOtq1q3NHFO2OLQqlUmMIhONIUqMft1aTarVGW5v3ddK/b9K19PF9mXR9awmatXbvWNJAseg15jauM9GoogEAsN5KZUWuXDlyVKlXQj3YWrqw3cHD4dajjyStRWVionGQn934v8a1bbm5nJTLNfpzva+T/n2TrqWP78uE6/P6tNd4X7uWNVAsvPbHduI8E23u4TmtOl5Cyl40AAAmrphQxspIim+ACIdbjzb2pLWoFYs6u7Bg1D4s9qRd+P7F73iHno95T9qlH/+4Lvryl2WpkZitvvrVevEd75Auu2ygWHRrIWjdixZFi6N3Jlq1XpUjR7Zs5TN5qmgAgNTzBoh4WwFqTk1LTy2F+iEme9PShT1pPmnuiU2KuGMUZY+2J669aP59aLZs7Rvfp+k3Tfd8AYo7RgiGOJmPGJmPGJkvzBiVT5e1/4H9qjqN9wR5O6/F6xZD7zbxvy8Yhb1paV5H7EkDhiSOg6u9FgdPHGeiZe1soAQNAIC0aB3H71XTwtSumsbetNFEkgYEFMfB1d5etNbNwmHvReNMNAAAepvcM6mcnZPE3jQMF0kaEFBcVTRJzUpaHFU0pjkCANAe1TSEhSQNCCCOKpqkDU+4YQ8LkaiiAQDQD6ppCANJGhBA1FW01pH7XrtjFCP3qaIBABBcKqtp9XrP810xGJI0oIc4qmitB1cvL5+M5OBqqmgAAPTPhGpa2O8TXpyclFsoNM59tSzVx8ZCeyyQpAE9FUolWfV6bFU0SaF+OuahigYAwOaYUE3zBo2FWU07Nzsr2bYsx9G2mRlaHkNEkgb0UJmYaPRhZzJyC4XIq2hRDQuZe3hOq86qJKpoAAD0Kw3VtMzKiuS6shxHVqXCAJEQkaQBPdSKRZ1dWND5m2/W2YWFyKtoYY/cL58ua+oLUzq+fFyOHNmyVcgUqKIBANCH1mpa3a2rdCr8fVv+pCzsrpvKxETjQ2uJASIhI0kDAqgVi/r+TTeFPnJfUuQHV5dOlVRzas0Ebd/4Pi1cu0AVDQCAPk3umVQhU5AtW5YsjRXC3bflfbjrYRz/6CBJAwzh9ZZHfXD1WGFMlizZspXP5DX9pmkSNAAANqG4s6jZiVnZli3HdTRTmomk5bH1A17G8ScfSRpgmKgPrp4pzchxHdmWrdmJWRI0AAAGsFJZkStXjhxV6pVIBohQTRs9JGlAzDqdiRaFpaeWVKlX5MiRK1crlZXIHhsAgFE0ccWEMlZGEodbY/NI0oCYtTsTLewnV2njyP2MldHEFROhPiYAAKPOhHH8VNOSbyhJ2iOPPKLf+I3f0E033aTPf/7zw/gngVTodCZaFDi4GgCAcJgwjp9qWrINnKQ5jqNPfvKT+vCHP6y7775bX/va1/TMM88M49pi5X3y4P8Eot3XSf++SdeSxu/HcSaaxMHVAACEiWoaBmW5rusO8g985zvf0eLiom655RZJ0uc+9zlJ0n/9r/+16987efJk1+/HYceOHTpz5oykRjVjeflk81f/n43S9026liDfr1SqOnPmjLHX18/3p6fPr3sy9YT9yZd3cLV3LpolSwdee0BH3nZkKP++fx3BXMTJfMTIfMTIfHHGqHy6rP0P7FfVqUqS8nZei9ctht614k/Wwn5PkSuXtX3/flnVxn+j8nmdWVzs68iiNK+jXbs6d08NXEl77rnntH379ubvt2/frueee27QfxYYeV5rgieqaY4cXA0AQPiopmEQA1fSSqWS/v7v/16/9mu/Jkl68MEH9fTTT+tXfuVX1v3csWPHdOzYMUnSkSNHVPUyboPccUdOv/u7VtyXgRS79da6brutHtq//+tf+nXd+8i9cuXKlq23/19v121vu017X7F3aI+RzWa1uro6tH8P4SBO5iNG5iNG5os7RieeOaGfuv+nVK033vcWMgX9zQ1/M9TX3XYOH87o9tsbEybDfm9hnTih7E/9lOS9ty8UtPo3fyN3b7D/xrhjFKd8Pt/xe9lB//Ht27fr7Nmzzd+fPXtWY2MbT1e/+uqrdfXVVzd/b2JZ85Zbduj/+X9odzT5+6PU7tja+uhV0MJaGuXTZd33rfua+9CydlY3vf4m7b5o91DXY5rbFpKEOJmPGJmPGJkv7hjtvmi3pl4zpfnH5+XKVbVe1b3le7X7ot2hPWZrNe322xsJW2itj7t367KpKV0yPy/LdeVWq6ree6/O7Q723xh3jOIUarvjj/zIj+jUqVN69tlntbq6qq9//esq9tGHCkChDwqRmOYIAEAcmPSIzRg4SctkMvqVX/kV3XHHHfrgBz+oiYkJvfKVrxzGtcXKu7Fbb/BR+75J15L274eJaY4AAMQjlXvT6nUVSqVQHistBt6TtlmmT3eEmYjR5hz66qFmq8Wwpzm2IkbJQJzMR4zMR4zMZ0qMTJj06B9WFoZcuaztU1OyqlW5tq1zd9yhFw8c6Pn3TIlRHEJtdwRgNqpoAADEy4Rq2vj4rtCraedmZyXbluU42jYzQ8vjAEjSgBHHXjQAAOJnwt60sI/6yaysSK4ry3FkVSqM4x8ASRowwqiiAQBghtZqWt2tq3Qq/H1b/qQsrCqapzIxITeTYYDIEJCkASOsdKqkuts4G4UqGgAA8ZrcM6lCpiBbtixZGitsPLZqmI4ebQwM8XC4dXKQpAEjbOKKCeXsnDJWRoVMgSoaAAAxKu4sanZiVrZly3EdzZRmIml59A8NYRx/MpCkASOsuLOohWsXdHPxZi1cu0AVDQCAmK1UVuTKlSNHlXolkgEiVNOShyQNGHHFnUXd9MabSNAAADDAxBUTylgZSRxujc5I0gAAAICImDCOn2qa+UjSAAAAgAiZMI6faprZSNIAAACACFFNQy8kaQAAAEDEqKahG5I0AAAAIGJU09ANSRoAAAAQA6pp6IQkDQAAAIhBKqtp9boKpVIojzVKSNIAAACAmJhQTVtePhl+Na1QkGvbci1L9bGx0B5rVJCkAQAAADExoZo2Pr4r9GraudlZybZlOY62zczQ8thDNu4LMFH5dFmlUyWNFca0UlnRxBUTkqTSqdK6r5P+fZOuJej333HlO/T8ueeNvb5BYlHcWWy9FQEAQApM7pnUwpMLqjrVZjVtcs9kaO8NDh5s7EPzJ2vLyydDeSxPZmVFcl1ZjiNVKtqytKRzRd77dEKS1qJ8uqypL0ypWq/KkSNbtrJ24/+multXxspIklad1UR/36Rr6ef7c9+ck1xzr2+zscjZOS1cu0CiBgBACnnVtPnH5+XKVd2tq3SqFPr7goMHzzeTtKNHt4ba8liZmNClmYxUrzcHiLwwOSldc01oj5lktDu2KJ0qqebU5MiRJDlyVHNqqjk11d168+ukf9+ka+nr+3XDr2+AWJROsYkWAIC0mtwzqUKmIFu2LFkaK4S7b+vo0cbAEA/j+M1CktZi4ooJ5eyc7LX/a2zZytk55eycMlam+XXSv2/StfT1/Yzh1zdALLz2RwAAkD7FnUXNTszKtmw5rqOZ0kwkA0T8bY5xjOO3TpwI7fGSjHbHFsWdRS1cu2DEPiX2pLEnDQAApMdKZUWuXDlyVKlXtPTUUqjvD9qN45+b2xpasuZV0y6Zn5flunJrNVnz89JHPjL0x0o6y3VdN44HPnky3M2Jm7Fjxw6dOXMm7stAF8TIfMQoGYiT+YiR+YiR+ZIWo/LpsvY/sF9VpypJytt5LV63GPoHuf5kLexqWq5c1vb9+2VVG/+NKhR05s//XLUUDhHZtWtXx+/R7ggAAAAYwIRx/JHvTatW2ZvWBkkaAAAAYAgTDreOY28a56atR5IGAAAAGCKV1TQmPW5AkgYAAAAYhGoaSNIAAAAAg1BNA0kaAAAAYJi0VNNENa0tkjQAAADAMGmppjnveQ/VtDZI0gAAAAADpaGa5hw4wN60NkjSAAAAAAOloZrm7t27fm9ava5CqRTKYyUJSRoAAABgKBOqacvLJ8Of9FgoyLVtuZal+thYaI+VFCRpAAAAgKFMqKaNj+8KfW/audlZybZlOY62zcykvuWRJA0AAAAwWBqqaZmVFcl1ZTmOrEol9QNESNIAAAAAg7VW0+puXaVT4e/b8idlYVXRPJWJCbmZDANE1pCkAQAAAIab3DOpQqYgW7YsWRorhLtv6+jRxsAQD4dbR4skDQAAADBccWdRsxOzsi1bjutopjQTScvj8vLJ5p9Fcbg14/gbSNIAAACABFiprMiVK0eOKvVKJANEqKbFgyQNAAAASICJKyaUsTKSRvdwa6ppDSRpAAAAQAKYMI6falo0SNIAAACAhDBhHD/VtPCRpAEAAAAJQTUtHUjSAAAAgAShmjb6SNIAAACABKGaNvpI0gAAAICEoZo22kjSAAAAgIRJZTWtXlehVArlsUxDkgYAAAAkkAnVtOXlk+FX0woFubYt17JUHxsL7bFMQpIGAAAAJJAJ1bTx8V2hV9POzc5Kti3LcbRtZiYVLY8kaQAAAEBCpaGalllZkVxXluPIqlRSMUCEJA0AAABIqNZqWt2tq3Qq/H1b/qQsrCqapzIxITeTSdUAEZI0AAAAIMEm90yqkCnIli1LlsYK4e7bOnq0MTDEwzj+4SNJAwAAABKsuLOo2YlZ2ZYtx3U0U5qJpOVxeflk888Yxz9cJGkAAABAwq1UVuTKlSNHlXolkgEiVNPCQ5IGAAAAJNzEFRPKWBlJHG49CkjSAAAAgIQzYRw/1bThIUkDAAAARoAJ4/ippg0HSRoAAAAwAqimjQ6SNAAAAGBEUE0bDSRpAAAAwIigmjYaSNIAAACAEUI1LflI0gAAAIARQjUt+bJxX4ApyqfL+tZ3vqWrtl0lSSqdKmniionm12OFMa1UVtb9Waevw/rZfv9ecWcxrP+7AAAAYLDJPZNaeHJBVafarKZN7pkM7f3hwYONypk/WYuimrZlYUGqVpvVtBcmJ1UrJv89MEmaGgna1BemVHNqzUMA6269+fWqsypHjmzZytrZDd+P4mf7/Xs5O6eFaxdI1AAAAFLIq6bNPz4vV26zmhbme8N21bS5ua2hJWteNe2S+XlZriu3XlehVBqJJI12RzUqTzWnprpbV82pbfjakSNJcuS0/X4UP7uZv1c6VYrn/1AAAADEzoS9acvLJ8Pfm1YoyLVtuZal+thYaI8VJZI0SRNXTChn55SxMsrZuQ1f22v/N9my234/ip/dzN/z2h8BAACQPibsTRsf3xX63rRzs7OSbctyHG2bmRmJASK0O6pxAy9cu6BvnWNPGgAAAEZHFHvTyqfLzfefBw8WN+xNW14+ObTHaiezsiK5rizHkSoVbVla0rmEtzxaruu6cTzwyZPhBmszduzYoTNnzsR9GcbwLzhTEj5iZD5ilAzEyXzEyHzEyHzEqOHQVw8196ZlrIxuLt6sm95408D/bvl0WUtPLWnhyYW2MxHGx3dJ6j5AZBgxypXL2r5/v6xqtfEH+bzOLC4avzdt165dHb9HuyPa8oap3FW+S1NfmAq1fxkAAADhmdwzqUKmIFu2LFkaKwy2b6t8uqxDXz2k/Q/s1/zj86o61XUzEY4e3dpM0CTG8W8GSRra8g9Tqdarmnt4jkQNAAAggYo7i5qdmJVt2XJcRzOlmb7f15VPl3XPI/do/vF5TX1hqpmcuY3jpGXJas5E8AaI+NscOdy6PyRpaMsbpmLLliNHx5ePa/8D+3Xoq4dI1gAAABJmpbIiV64cOarUK4EHiPirZneV79ItX7tF1fr65Cxv53XgtQfWtTpSTRsMSRra8oap7Bvf10zUqk5V84/Pk6wBAAAkzMQVE80zdXuN4+9UNau7dTmuI9uylbEyzeRs8bpFHXnbkXUzDNqN46eaFhxJGjoq7ixq+k3TymfyzdGtrtxmssZeNQAAgGQIMo4/UNUsk9cd//EO3Vy8uW1y5tfucGuqacGQpKErr6J24LUHlLdbkjX2qgEAACRGp8OtOw0CaVc1894X3vTGm3pO/6aatnmM4PdhTGt3/jGrq86qHDmyZStrZzX1o1NDP3OjHWJkPmKUDMTJfMTIfMTIfMRoI/84fkl6y795i/7+X/5elXql+WdSo2pWyBQ0OzHbPJt3M+/zWqtpHi9ZCyNGlx06pEvm52W5rlzL0gsHDujckSNDfYxhYAQ/hqK4s6gjbzuixesW2+5Vo/0RAADAbD+2/ceanVGS9NA/P7QuQWsdBBK0atYJ1bTNIUlD3zruVaP9EQAAwEheS+NtX79NjpwN3+81CGQQ7E3rH+2OPpTE+9Op/TGfyQ9cGu+EGJmPGCUDcTIfMTIfMTJf2mNUPl1W6VRJY4UxzZRmNrQ0ejLK6IbX3hD61hV/shZmu6Mk5cplbd+/X1a12viDfF5nFhdVK4a7Nacf3dodsxFeB0ZMcWdRxZ1FTe6Z1NzDczq+fLzR/liv6pav3SJXrnJ2bt2ZGQAAAAiX/4P0uluXJUuO66xrabSsxp9JalbWokrQpEY1bW5uq269ta4bbxz+43nVtObetHpdhVLJqCStG9odMTB/+2PGyjRPs6+7dVogAQAAItDv2WZ3/sc7lbfzknqfmzYM7famLS+f1G231UN7zBcnJ+UWCnIzGbm5nCoTE6E91rBRScNQeKP6/SX1ar0qR46OLx9X6VQpsgmQAAAAaRGkatZpK8pjZx9rTnr0zk2Lspo2Pt5o95ue3hrKIJFasaizCwsqlEqqTEwkpoomsSdtnbT3LQ9T+XR5XQuk1HiSyNm5gZI1YmQ+YpQMxMl8xMh8xMh8oxwjf3JWc2rNpMyWLduy5cpVxsp0fd9VPl3W/gf2q+o09m3l7bwWr1sM/QN1L1lbXj450jHqhRH8iFzHCZCM6wcAANiUTi2NrVWzO/7jHbq5eHPPKY3FnUVN/ehU871a3a2rdKoU+n+HVzULa7rjKBio3fHP/uzP9PDDDyubzWrnzp163/vep0suuWRY14aE81ogWz/l8Y/rn37TNO2PAAAAXQRpadxst9LknkktfmdR1XpVliyNFcbC+s/oMDwkvHbHJBuoknbVVVfp6NGj+uhHP6orrrhCn/vc54Z1XbE4fDjT/Nqf2Xtft/uzqH92kL8XB/8B2Adee0B5O988BPv48nHtf2C/Dn31EFU1AACAFt7ZZvsf2N9zEMhmzzYr7ixqdmK2OfhtpjQT2vsyb3jI8vKFbU+33lonQWtjaHvS/uf//J86ceKEPvCBDwT6eRP3pI2P72reNO2+7vX9KH52s3/v6FEzPqHotFetkCkEGtWf5r7lpCBGyUCczEeMzEeMzJfEGPU628x73zTMM2nveeQe3VW+q1mlO/DaAzrytiOD/qe01VpN83jnpqVJJOekfeUrX9Fb3/rWYf1zGLK5OTOSNG+v2kP//FDzSYf2RwAAkHZhtjT2MnHFhDJWRnW33hzHH+ZEbq/Y4P891utZSTt8+LCef/75DX9+/fXX681vfrMk6bOf/az+8R//Ub/5m78py7La/jvHjh3TsWPHJElHjhxR1Tv9O2aHD2d0++2Z3j84Am69tXEORZjnUQR14pkTmn90Xvc9ep9WndVG2V62cpmcfvH1v6gDrz+gva/Yu+HvZbNZra6uxnDFCIoYJQNxMh8xMh8xMp/pMTrxzAk9+E8P6vKLL9dvHvtNvbT60oUpjdbalEbXVdbOdn1/NAy//qVf172P3CtXrixZeu8b36s/eMcfDOXfPnw403z/WSjkdeut9bbvv2+9tW7E+9So5PP5jt8buN3xb//2b/U//sf/0O/8zu+oUCgE/nu0O4bf7titnCzJiMpav+2PSWxbSBtilAzEyXzEyHzEyHymxqhT1az1vdAwWxqDXNOwx/F7222CvDc14X1p1EIbwf/II4/oL/7iL/Tbv/3bfSVoiIZ3s3vJm/frwYPn2y6QOHQc1b/W/shAEQAAMCr6GQSycO2CDrz2gG56402RbAVpHcfvHW69Gd7gutaDq1vff5pUODDNQHvSPvnJT2p1dVWHDx+WJO3Zs0e/+qu/OpQLi4PXDihduGn8X7f7s6h/djN/z1soXu+v96v353EvjNZR/avOanP6Y+lUKZTeawAAgCgEGQSSz+QjrZp1MrlnUgtPLjTPXutnb5p/SF1rctbK6wg7ePC8tmzZMrz/gBEytOmO/TKx3dHUkvgwtPtEw2PSpxid2h+9jbLvLb5Xuy/aHfNVoptRXkejhDiZjxiZjxiZL84YBWlpDGsQyCAOffWQ5h+fb+5N6zXpsd+WxtbJ42leR6G1OyI5Dh48H6j90YRz1dq2PzpVzT8+r2s+dQ0tkAAAwFhRnG0Wpsk9k8rZOUlqVtNa33v53y/229JoUnHAZCRpKdOr/dGEvWpe+6N3+LU/WavUK+xVAwAARimfLuueR+7R/OPzmvrCVDM584/Pz2fyuuM/3qGbizcbmZx5uu1Na+3Man1P6ecvBvi34pCcBUO7o0+ayq1Jan9s3atmy1bWzhrXHoCGNK2jJCNO5iNG5iNG5gs7RkltaeylddJjxi3os//3n+v//vf/vw1nnPl1amnsJs3rqFu7I0maTxpvkvHxXZqebj/t0bRkrZ9R/YhPGtdREhEn8xEj8xEj84URo26DQGytnW0mVxkrk7jkzO8df3ibHs3/ceO/rZ7R22q36qtHPtL2Z1uPhgqSnHnSvI7Yk4aO/OdSJGFUfyFbYFQ/AACInH+v2V3lu3TL125RtZ7MlsZuvG6rb/3pe1XIFGS5GcnJ66vzP7Pu56anzzffM3q/95jwAX/SUUnzSXMmn5T2x6dfelr3lu/d0P5oyuhapHsdJQlxMh8xMh8xMt8wYuRvaaw5tZGsmkkbpzSOj++SXlGSXv230v/+T9IzE5LU7MDaTNWsnTSvo26VtIHOScPoaF1c/mStNXGLM1nb+4q92n3Rbk3umVzX/litV3XL126RK1c5O0cLJAAA2LQknW02iJ5nmz0z0UzO/Geb+ZnwIf4oopLmk+ZMvpX/U5R2v8bFH6Py6bKmvjClmlNbt1HXlq194/s0/abpRD5hJh3rKBmIk/mIkfmIkfn6jdGoDgJpNejZZsOU5nXE4JCA0nyTtDK1/bE1Rq2fdFXrVSZAxox1lAzEyXzEyHzEyHxBY5SGlkZ/grWupbGNYbc0dpPmdUS7I/qWlPbH4s5i84nyysuvXN8CuXYA9sKTC4l+UgUAAMOXtpbGubnGr73ONqOl0QxU0nzSnMn3EqT9McxPWTy9YuS1QLZ7omVcfzRYR8lAnMxHjMxHjMzXLkZpbWkc5tlmw5TmdcQI/gTKlcu69J57lCubMVp+enrjJy/er91aI6NW3FnUwrULOvDaA8rbecb1AwAAlU+Xdc8j92j+8XlNfWFK84/Pq+pUVXfrclxHtmUrY2WUt/M68NoDiR+fLzXel/WqmkkXqmQmTfMGlbR1TMnkc+Wytk9NyarVpExGL0xN6YXJSdWK8T9R9ErIwv4Epp8Y+T8p84/rZ69auExZR+iOOJmPGJmPGJnPf3RPp6pZIVMYmZZGEwaB9CvN64jBIQGZcpNces892nrXXbLq9UbDnmVJuZxRyVqQ0rk0/E9jNhOj8unyur1qEu2PYTJlHaE74mQ+YmQ+YmS28umyrv/i9Xpp9aWRHAQi9dfSGNUgkH6leR0xOCRhKhMTujSXkxxHcl1Zriu3WtWW+XldvLioswsLsSdq/lPlvQXvf4LwnjBMeAIo7ixq+k3TeuifH2ruVfO3PzKqHwCA0eJ9QFtZvbBHfdQGgUgdzjbzGZVBILlyWYVSSZWJidjfA0eFStqaXLmssW99SytXXSVJzRvB+7o+NqbMysq6P+v09TB+NvvEE9ryqU8p99hjslZXJUmWJNeytPrqV+vFd7xDuuyyro8RxU3sPVF0K6tLw3syGOTTFtofo5HmT8SShDiZjxiZjxiZZdSP5UlyS2M3ndaRl5jVx8a0bWZGVq0mN5czolgxLLQ79tC6B8yVZNXrF75eXW1UtWxbymY3fj/Mn7VtqV5v/Fzbi8/JtawNfy+OmziKs9WG8YLYqf1xFCY5mYA3LclAnMxHjMxHjMzQbVqjbdnat2tfYrtmTD3bbJha11GuXNbFS0vasrDQeH9rWZLjyHIcuZmMzt98s75/000xXvHwMN2xh0KpJKtWa9wItdrGr9cSJMtx2n8/zJ9dXW20PPqu1/L/2uHvWbWaCqVSZP8fSo0EzHsy8J4g/JODvOTNP3koDl77Yz7TMv1x7Vy1qS9MMQESAACDBZ3WWMgUEpmgtX7wHXRKo387ShISNL9cuazLDh3S9v37dcn8vKxqtfH+1nHk2rbcTEZuLtfsHBt17EmTbw+Y1KxGyVeZ0lrFy/VVvNZ9P4qf9apqtZo2lD4tq/Fn2axcy5LWKmlx3cS9xvV7hynGyRvV733yVnNq7FUDAMBwnapmnfadvePKd2j3RbtjvurgWg+eltonZv6WRu/3UjITM/tb39LF+XyjpbFSaRYnXDW2+bj5vM7Nzja3B41Kq2MvtDuuMW1PWqevm3vVHn20UYFraaN86eqrVX/5y/WiAVMgw2h/DKO1hL1qw0X7TzIQJ/MRI/MRo+j4X6u9D1al3tMakxCj1pZGr22xHa/dMWktja26tjRKRk42DwN70gJKwkL2eJspM8vL2nL//caP6+/0hNNvshZmjBjVPxxJWkdpRpzMR4zMR4zC1ToIxJvQ7AlyxpnJMRrVQSDdrEvOarULVTPblmvbslzXuDOCw0SSFpDJC7mT5tCTlvKwLEtuoWDEBJx2Z3i0+zWIsGNUPl3W1Bem1r0Q2LK1bzy5m46jlsR1lEbEyXzEyHzEKBzdBoFI/Q37MjFGo3C2WT82TGns8J41jS2NnJM2wmrFos4uLDQ/lZD3qYTrStWqts7N6fz0dKw3u/eE0muvmv9n49K6V81rfzy+fFylUyXaHwEACEmvlkZL1kgcQJ2ms83atjS6bnO/mXI51d/zHq1cd11qErOgqKT5mPhpSz/WLYaW8f4mlY0H2asWZYxof9ycpK+jtCBO5iNG5iNGgxtGS2M3psQoyLmyo9DS2LVq1qGlcds11xgRozjQ7hiQKQt5ULlyWVvn5lQ4fnzdBkxT2h89m2l/jDpGtD/2b1TW0agjTuYjRuYjRps3zJbGbuKOkb+1sZ1RamnsNQikU0tj3DGKE0laQKN0k7Tdq2bbquzbF3v7o2czFbU4YtRp+qN/xG+/n+yNslFaR6OMOJmPGJmPGPWnW9Ws15TGzYojRp0OoPYSsdY/S2piJg1nEEia1xFJWkCjdpOMYvtjnDFqbX8M6wUl6UZtHY0q4mQ+YmQ+YhRMkKrZIC2N3UQZo6DTGiUlOjkb9iCQNK8jkrSARvUmGZX2x6NHt+rOOwuxxshrf6w5tY4vMmnfrzaq62jUECfzESPzEaPuNnu22TBFEaN+pjV6+9KSmpyFcbZZmtcRSVpAo3yTjEL749zcVlUq1dhj1KtdI+371UZ5HY0S4mQ+YmQ+YrRR2INA+hVWjAY5gDppwj7bLM3riCQtoFG/SUah/fHWW+t64YUXjPkEqtN+taydTW3746ivo1FBnMxHjMxHjC6IahBIv4Ydo7QcQB3l2WZpXkckaQGl5Sbp1P64mRJ1mLp9MmVaywDj+i9IyzpKOuJkPmJkPmJkRktjN8OKUVoOoA6rpbGbNK8jkrSA0nSTtG1/lIzaq9buCbFSqapQyG+YkGQCxvU3pGkdJRlxMh8xMl9aY2RaS2M3g8Rosy2NSUzM+j3bbJjvEdO6jiSStMDSdpN06zFOyl41yawJSbQ/pm8dJRVxMh8xMl/aYmRqS2M3m4lRWloaJd+H9rVaX2ebDVPa1pEfSVpAab1JkrRX7c47CyoU8m2/3+lstTikuf0xresoaYiT+YiR+dIQozjONhumoDHqdLZZO0lvafRs2P4SQdWsnTSso05I0gJK800iJWNU/44dO9q2O7Y7LDJuaW1/TPs6SgriZD5iZL5RjlGcZ5sNU68Y9Xu2WZKrZp5OH867+XzoVbN2Rnkd9dItSctGeB0wXK1Y1PnpaeUfekjy+pFdV6pWtXVuzpj2R69i5rVBep90eb96fx73k2dxZ1EL1y5saH88vnxcpVMlIz9xBACkW69BIJYsY6tm/fCSrLm59RW0Vv6WRu/3UvzvMfrVa9+ZSdtc0EAlzSfNmbyfye2PrTHqdbaaZMYTaaf2R9N694eBdZQMxMl8xMh8oxKjJA0C6Zc/RoOcbZbUylmQaY1xd0yNyjraDNodA0rzTdKOie2PnWLUqe3RpLaEdu2P0ujtVWMdJQNxMh8xMl/SY5TEQSD92rFjhz70oUpqBoF4wj6AepiSvo4GQZIWUJpvkk7ajurPZPSDG26QMz4eac+y1DlGvSpq/g2+cerWRjIqe9VYR8lAnMxHjMyX1BiZfrbZMHgJln8vexoGgUR1APUwJXUdDQNJWkBpvkm62VAqz2TkSs2vo/wUJsgGYCkZ7Y+jOqqfdZQMxMl8xMh8SYrRKLc0+rUOAvn4x3fq9tszbX/WtI6bzYrjAOphStI6GjaStIDSfJME4X1Ck1le1pb775dVr0e++IPGqFuvuWnJ2qiN6mcdJQNxMh8xMl8SYpSGlkZpY3LWrWo2Ci2NcR9APUxJWEdhIUkLKM03ST/atkBKkexX6/e8k1571UwwaqP6WUfJQJzMR4zMZ2qMkn62WVAMAuk8CMS0lsZuTF1HUSBJCyjNN0m/um1IDXOMa78xov0xeqyjZCBO5iNG5jMtRqNytlkvQc82m54+rzvvLDT3pCU1MZOSNQikX6atoyiRpAWU5ptks6Ie17/ZGCUpWUt6+yPrKBmIk/mIkflMiVEaBoFI/bU0eoNA/NMdkyapg0D6Zco6igNJWkBpvkkGFdW4/kFjRPtj+FhHyUCczEeMzBdnjNI2CETqr6XRP90xaeso6YNA+pXEGA0LSVpAab5JhqHtXrUhtz8OGqMkVdTatT/mM3njX3BZR8lAnMxHjMwXR4zSOghks2ebJWkdjXJLYzdJitGwkaQFlOabZFjCbn8cVoySlKz52x+T0LrCOkoG4mQ+YmS+KGOUhpbG1qrZMM42M30dpaWlsRvTYxQmkrSA0nyTDFtY7Y/DjlGv9kcTNhl77Y81p9ZxE7hJ+9VYR8lAnMxHjMwXdozS1tLYq2om9X+2manrKG0tjd2YGqMokKQFlOabJAxhtD8OO0a9Kmr+T+ni1Gucskn71VhHyUCczEeMzBdWjNLa0hjG2WYmraNROttsmEyKUdS6JWnZCK8DKVMrFnV2YaH5SZHW2h8Lx4+rUCoZ8QTU+iTvT9a8r71ELs6KWnFnsfkifOXlV27Yr3Z8+bhKp0qJf8EGgLQKcraZJWukWhr9r7ntEjQvcfN+3qTtCP3oWDVzGxF2LUtuPj/SLY3oH5U0nzRn8mHr1P7Ybyk/7Bh1mxzlfZJnQgukZO64ftZRMhAn8xEj8w0jRpxttt4gVbN24lxHaR0E0q80P9fR7hhQmm+SKLRtf5T62qsWdozatV60juhnXH93rKNkIE7mI0bmGyRGaRgEIm3ubDP/3xtU1OuIQSD9S/NzHe2OMMKG9kfvUyXXlapVbZ2bG9qo/s3yt1R4bY7eC0rrC4sJFbXizqIWrl2g/REAEiDIIJAkHLXSyyAtjZ64X1/7FaSlMS2DQDAcVNJ80pzJR22zo/qjjpH/E8B2TOqPN6X9kXWUDMTJfMTIfEFjlNZBIFG1NHYT9jqipXFwaX6uo90xoDTfJHHpd1R/XDFq1+7YrhUybia0P7KOkoE4mY8Yma9XjNLQ0hjG2WbDFMY6oqVxuNL8XEe7I4xVKxZ1fnpa+YcekrwnOYPaHz1exaxTC6QJEyAl2h8BIG5pa2mcm9vaHKol0dJISyOGhUqaT5oz+bgFbX80IUa9zlaTzHjh6dT+GHZLjQkxQm/EyXzEyHz+GKW1pTGMs82GadB1xNlm4Uvzcx3tjgGl+SYxRa/2x23XXGNMjDq1Pcb9guTXrv1RCnevGusoGYiT+YiR+Z5+6Wl96YkvdT3bbBRbGjsdVSNpwzaAuF8LN7uOOlbNWt6b0NI4uDQ/15GkBZTmm8QkbUf1ZzL6wQ036KLXvEYrV11lxBNhr4qav+8+Tt32RISxV411lAzEyXzEyGzl02Vd/8XrVa1XOdvMkKpZO/2uIwaBRC/Nz3UkaQGl+SYxzYZPsDIZuVLza5OeHJPU/ti6V82WraydHeonvKyjZCBO5iNG5mptJx+lqpkU/9lmwxRkHTEIJF5pfq4jSQsozTeJqbwnzszysrbcf7+ser35hGna5txuLSCmJWthjupnHSUDcTIfMTJPpw+7RmkQiNRfS6OJiZlft3UUpKXRtPcaoyjNz3UkaQGl+SYxXdsWSKnruP6otfvkMY2j+llHyUCczEeMzNBtWqNt2dq3K7ojTsIwCi2N3bSuIwaBmCfNz3UkaQGl+SZJgly5rMsfeEDWffdt6BOv7NtnzLj+tLc/so6SgTiZjxjFK8i0xouyF+nTP/vpxCVopp9tNkzeOmIQiLnS/FxHkhZQmm+SpNixY4fOffnLgcb1xy1Jydow2x9ZR8lAnMxHjKLXtWrWZt/Ze4vv1e6Ldsd81cEFrZpJyWpp7OblTz+tyr33MgjEYGl+riNJCyjNN0lS+GPUa1y/KU+0aWt/ZB0lA3EyHzGKTpCqWbtpjUmJUdLONhuUv6XxZR/5iPTSSwwCMVhS1lEYuiVp2QivAxiqWrGo89PTyj/0kOT1lLuuVK1q69ycMe2P09Pnm1U174XR+9X787hfBIs7i1q4dmFD++Px5eN66J8fSvyGeABop9sRJbZly5KV2GmN/gTLXy1rl6B5iZv38yZ1e/SjY0uj24isyyAQJAiVNJ80Z/JJ0S5G656UaX8c2KCjpVlHyUCczEeMwtGtpVHq74wzE2M06oNA2ul2tplsW6Kl0WgmrqOo0O4YUJpvkqToNUp3FNofTXih9Nofa06tY9tPp/1qrKNkIE7mI0bDFaSlMWfn+qqamRijUR8E4gl6tplz9Khe+N73aGk0mInrKCq0OyIVRqX9cW4u/hdMr/2x3afNrlxV61XNPTyX6LHTANJhlFsa/bzXFSlYS6Mn7tebfvXb0rjtmmv0/ZQmAEg2kjSMlFqxqLMLC80ncK21PxaOH1ehVDKi1aH1BdHfhuJ9bcJeteLOYvPNypWXX9l2v1rpVCnxb2wAjJ4gLY2jdAB1kJZG7/dSMhOzXmebybJoacRIod3RJ83l1qToJ0ad2h9N2zQ8Pr6r2X7SynuBNaUdJci4ftZRMhAn8xGj/oXR0thNXDFq3XcmdW6l9/980gzjbDPWkfnSHCP2pAWU5pskKfqNUa5c1vapqY696ibsVWs3Grn1BTZJ4/qved01rKME4PnOfMQomH7PNhtm5T/KGPV7ALWUvIqZp9sgkH7PNmMdmS/NMSJJCyjNN0lSbCZG3Z7sK/v2GbNXrdv0R0nGDBWR1n9a7bU/2rKVtbN6z1Xv0XWvui6RrUNpwvOd+YhRd5s922yYoohRvwdQm/I60a+gg0D6PduMdWS+NMeIJC2gNN8kSTFIjJI0qt+/h6CVSZ+QBml/hJl4vjMfMWqv1yCQsKpm7YQZo80eQJ00QVoaB9mmwDoyX5pjRJIWUJpvkqQYRoySNqrf/3W7Vsi49Wp/JFEzE8935iNGFwzzbLNhGnaMWlsaO+1XlpT4fWfDbGnshnVkvjTHiBH8gE+SRvVL6jquX4q/ouaN62+2P7qrclymPwIYXKeWRi9BG/YgkLh4CZZ3BEun9vdO0xql+F8LgujV0uhaltx8vu+WRmAUUUnzSXMmnxTDjFFS2h+l7vvVTGt/vOfRe/SV734ltGlqGA6e78yX5hiZ1NLYzaAx6qelMckHUIfd0thNmtdRUqQ5RrQ7BpTmmyQpwohRt/ZH0z7N69T26N9QHvcL99MvPa2fuf9nOrYjsVfNDDzfmS9tMTK1pbGbzcRosy2NJjy/b0bbKctDbmnsJm3rKInSHCOStIDSfJMkRVgx6vUi4uZyRuxX61VR83/SGpcdO3boy9/+csdPwdmrZgae78yXlhhFfbbZMPUTo6BTGlsHgSQ5OSuUSsosL2vL/ffLqtdj+RA0LesoydIcI5K0gNJ8kyRFmDHq2o6RoHH9cbc/+mPUbVS/iW+40oTnO/ONcoziPNtsmHrFqN+zzZLc0ujZ8FqayciVml9HvZ1glNfRqEhzjEjSAkrzTZIUUcRow8bmatXY/WrdWmXiStbaxYhR/ebh+c58oxgjE842G6ZOMer3bLOkV82kLtMaMxn94IYb5IyPx7J1YBTX0ahJc4xCT9L+8i//UvPz87r33nt12WWXBfo7JGnYjKhjZPq4/nabzuMe1d8pRozqNwvPd+YbpRglZRBIv1pjtNmzzZKanAU9gDrO18tRWkejKs0xCnUE/5kzZ/Too49qx44dg/5TgHFMH9fvvahPT59P3qj+tfZHRvUDoynIIJB8Jp+Yqlkn/gTLXy1rl6B5iZv/uVuK//m5Xx23B7huc5R+WNMagbQYuJJ29OhRvetd79Jdd92lO++8k0oaQhVXjJIyrt+EvWpBYtSp/dHU4QCjiOc78yU1RkkeBNKPo0e36s47CyoU8qkYBCJFdwD1MCV1HaVJmmMUWrtjuVzWo48+ql/+5V/W+9//fpI0hC7uGJne/uiJc1R/0Bi1a3+U2KsWlbjXEnpLWoxGtaXRr3UQSKVSVaGQb/uzozQIJEhLo2lH1niSto7SKM0xGihJO3z4sJ5//vkNf3799dfrc5/7nG699VZt2bKlZ5J27NgxHTt2TJJ05MgRVavVPv4TopHNZrW6uhr3ZaALE2JknTih7DXXSC+9tO5TROftb5dz221y9+6N9fok6fDhjCTp9tszG75366113X57RpVKOGuwnxideOaE5h+d132P3qda/cKbuoyV0a+84Vf0qm2v0o+/6se19xXx/386akxYS+guCTE68cwJPfhPD+ryiy/Xbx77Tb20+tKGD10uyl6kj179UT334nOJXc+HD2d02211FQp5VSpVHT6cafv8KqmZuHk/d9tt9YivdjisEydkz8/Lvu8+qdMB1Pm86r/4i3IPHDDita+dJKyjtEtzjPL59h/ySANU0v7pn/5Jv/u7v6tCoSBJOnv2rMbGxnTnnXfqZS97Wc+/TyUNm2FKjGh/7GwzMWptj8pYjTc/3tdJ/uTdVKasJXRmcozS1NLIIBDzWxq7MXkdoSHNMYpkBD/tjoiCaTHq1P5o2obpKEf1DxIjb9DA8veXdf8T96vuNj6BpgVy+ExbS9jItBiNytlmvbS2NHZ67pQuVM1GoaWx4zmhkvEtjd2Yto6wUZpjFOp0RyDNOk1/dKtVbZmf18WLi0bsVfM+5fX2R/g/FfY+/TXhjUVxZ1HFnUWVT5e1+J1FOXVH7tr/qvWq5h6eY1w/ELFOVTMvQRu1KY1zc41fO3Ui+Ktm3u89JjyP9qPXIBBZVqKqZsAo4TBrnzRn8klhaoy6vdBV9u2LfVS/J4r2x2HFyP/G0BvXb8tW1s4m+lN6U5i6lnBB3DFKwyAQqb+WxtZBIHfeWUjcOkr6IJB+xb2O0FuaY0QlDQhZrVhUrVjUi5OTzWRNa3vVCsePq1AqGfFJZGsC5k/W/F97nyLH+amwV1Wb3DO5blx/1alq/vF5LX5nkfZHYMg426z32Waexu8LoV7nMHG2GZAsVNJ80pzJJ0VSYpT0Uf3+7/UrjBi1G9dvy9a+8X20P25SUtZSmkUZo7QOAhn0bLMkrKMknm02TEmIUdqlOUaRDA7pF0kaNiNJMcqVy9o+NbVhOlZS2h8lbWpKWVgxov1xuJK0ltIqihiloaWxdRBIvy2N3Z7/TF1HaWtp7MbUGOGCNMeIdkcgBrViUWcXFhLT/ujfCO9p/b3J7Y8LTy4k+o0kEJW0tTS2DgLpv6UxOWhpBEYHlTSfNGfySZHUGCWt/dH/deuvJnyy3K79UWJUfz+SupbSZNgxSmtLY5hnm5mwjkbxbLNhMiFG6C7NMaKSBsSs06h+VavaOjdnTPujN+Gx9RNn71dv/0bcny4Xdxa1cO3ChjYtRvUD6wU528ySNVItjf0OAhn2WZFRCVI1c/P5VLQ0AqOISppPmjP5pEh6jNa9qK61P8q2pWzWuE84NzuuP+oYsVdtc5K+ltJg0IPhe1XNCpnCyLQ0DmsQSL/iWEdpHwTSL57rzJfmGDE4JKA03yRJMSox6tb+aNqnnuPju5qb6Vu1S9biilH5dHndXjWJ9sduRmUtjbLNxCgNg0Ckwc42G2bFLKp1xCCQzeO5znxpjhHtjoBhurU/brvlFlmuq0tzOSP2q3mfQHtvdPxvirw3SSa0CRV3FjX9pmk99M8PNVu6aH9EGqRtEIg06NlmycEgECC9qKT5pDmTT4pRi1HHF2DHSdS4fn9FLe4Y0f4YTNxxQm+9YpTWQSBRtzR2E9Y6oqVxeHiuM1+aY0S7Y0BpvkmSYlRjtKGVpVo1dr9ar2Rty5YtuvHG01Ff1ga0P3Y3qmtplHSKURpaGsM822yYhrmOaGkMB8915ktzjEjSAkrzTZIUaYhR0sb1d/rVBO1G9duytW98X+rbH9OwlpLOH6MgLY1pGgQiqa+jQcIyjHXUtaNCavyelsZN47nOfGmOEUlaQGm+SZIiLTHKlcvaPjW14bybJLY/xo32x/bSspaSbMeOHfryt7+cypbGMM82G6bNriPONosOz3XmS3OMSNICSvNNkhRpilFSxvUnKVlr1/44Cm9wNyNNaympnn7paf3M/T/T9myzUWxp7DRFVtKGKn3cyZmn33UUpGpGS+Nw8VxnvjTHiCQtoDTfJEmRxhiNSvujCW+q2rU/Suncq5bGtZQUXmvj2dpZ/X9///+p7tYlpa+l0bSqWTtB1xGDQOLDc5350hwjkrSA0nyTJEVaYzQK7Y/+jf1x6jR0IWNldMOVN2j80vHEvvntR1rXkslapzVm7axc11XdrSe+aiaZc7bZMHVbRwwCMQPPdeZLc4xI0gJK802SFGmOUVLaHz/+8Z164YUXEtH+6H9DnLEykjQyb4h7SfNaMs0of3Cw2ZZGkxMzv3briEEgZuG5znxpjhFJWkBpvkmSghh1bn805UXfi1G3N2SmJWulUyUtf39Z9z9x/4bWslFtgWQtxSvItMaLshfp0z/76UTef6PU0tiNt44YBGIunuvMl+YYkaQFlOabJCmIUUPb9kfJiL1qXozatTaZOqpfSt+4ftZSPPo5gPq9xfdq90W7Y77i4JJyttkwvfzpp1W5914GgRiM5zrzpTlGJGkBpfkmSQpidEG3jehx7lVrjVFSpj9K6RrXz1qKTreqWbdpjUmJUdLONhsG7/n3koUFiUEgRkvKOkqzNMeIJC2gNN8kSUGMNjJtr1qnGPVK1g4ePG/Mm7ZO4/pHqf2RtRS+IFWzbtMaTY9RUs822ywGgSST6esI6Y4RSVpAab5JkoIYdWbKqP5eMerW9mhSC+Sotz+ylsLTaRBIv2ecmRijUTjbrF8MAkk2E9cR1ktzjEjSAkrzTZIUxKg7E0b194pRt4qaJKM+aR/l9kfW0nAFGQTS7xlnJsZo1AeB+AU62yyb1Qs///MkZwYzcR1hvTTHiCQtoDTfJElBjHqLu/0xaIz8rVLtmLRfrVP7ozfgIYnJGmtpOPoZBNLvfWJSjIKs11EYBNJvS+PF73iH/mV3coa7pJFJ6wjtpTlGJGkBpfkmSQpiFFxc7Y/9xqhdu2Prrya84WvX/igld68aa2kww2pp7MaEGAWpfJu0Tjdrsy2NJsQI3REj86U5Rt2StGyE1wEgQrViUeenp5V/6CHJ+zTYdaVqVVvn5mKb/tjKq5h5bwa9T+q9X722qrjf/BV3FrVw7cKGN+auXFXrVc09PDcSe9XQWZCWxnwm31dLo4n8yZZXHfN+bf1QRTKr6t2PIGebybKY0gggFlTSfNKcyScFMepf1O2Pg8QoKeP6R2GvGmspuDBbGruJOkb9HkCd1MpZkKpZ0CmNrCPzESPzpTlGtDsGlOabJCmI0eZ1a38c5sjoYcSo29Q405K1pI7qZy11t9mzzYYpihj1ewC1ZMba24xAg0D6rJqxjsxHjMyX5hiRpAWU5pskKYjRYDpNf/TeoLi53MD71YYRo3bnL3Ua2x+3pI7qZy21N+jZZsMUZow2ewB10oR9thnryHzEyHxpjhFJWkBpvkmSghgNrmurzxDG9Q8zRrQ/hoe1tF4Ug0D6FUaM0nIAdVRnm7GOzEeMzJfmGJGkBZTmmyQpiNHwbPiEuVodyn61sN5YSslI1pLS/shaCudss2EaVozSdAB1GC2N3bCOzEeMzJfmGJGkBZTmmyQpiFE4hjmuP8wY0f44PGleS3ENAunXoDHqdxBIkqtmYbY0dpPmdZQUxMh8aY4RSVpAab5JkoIYhafTfrV+2x/D3kcjJaOiZnr7YxrXkoktjd1sNkb9tDQm/QDq5vNWrRZaS2M3aVxHSUOMzJfmGHFOGoCeasWizi4sNFuFtDauv3D8uAqlkhHnBLW+gfQna62JW5xvNos7iyruLGpyz+S69seqU9X84/NaeHLBmERg1KX1bDNPuwTNS9xa10gSE7Stc3OyqtXmnlrONgMwKqik+aQ5k08KYhSNQdofo4xRr/ZHEyoD7dofpfj3qo36WkpKS2M3QWKUlpZGT7e9tG4+H0pLYzejvo5GATEyX5pjRLtjQGm+SZKCGEVns+2PUcaoV/ujv5UrTt3a7OLaqzaKa8mEs82GqVOM+j3bLOktjVL4U2k3axTX0aghRuZLc4xI0gJK802SFMQoWuveGK21P/aa/hhHjJK+Vy2OdrtRWksmnW02TK0x2uzZZklNzKRg0xqHcb7jZo3SOhpVxMh8aY4RSVpAab5JkoIYxaNT+2O7TflxxqjbeHHTkjX/XjV/lSdn5yJpgRyFtZS0QSD98mKUlrPNPHFOa+zXKKyjUUeMzJfmGJGkBZTmmyQpiFF82rY/Shv2qsUZo3ZvZk0f1V9zausqP1G1QCZ1LZl+ttmwHD26VXfeWdCZM2dG/mwzT1QHUA9TUtdRmhAj86U5RiRpAaX5JkkKYhSvbq1H3p6QbddcE3uMktT+6E84qvVqZOP6k7aWRmEQSBD+Dxoqlao+9KHKSA8CkaI/gHqYkraO0ogYmS/NMSJJCyjNN0lSECMzdNurVn/Pe7Ry3XVGvJFKSrImbWyBlMKdAJmUtTTqLY1SegeBJKWlsZukrKM0I0bmS3OMSNICSvNNkhTEyCyDjOqPUhLaH6X24/rDan80eS2lqaUx1YNAEtLS2I3J6wgNxMh8aY4RSVpAab5JkoIYmWezo/qj1KuidvDgeWPe+HaaADns9kcT11IaWxq7Vc1uvbWuG288nfjkrGvVLAEtjd2YuI6wHjEyX5pjRJIWUJpvkqQgRmbazKj+OHRL1iQZ9Ua4U/vjsJIUU9bSqJ1t1klrS2OQQSCVSnXddMekCVI1S0JLYzemrCN0RozMl+YYkaQFlOabJCmIkdly5bIuv+ce2V/5SqLaH9v9mQlvjNu1P0rD2asW91oa1bPNWgVtaWw3CMSb7pg0SR4E0q+41xF6I0bmS3OMSNICSvNNkhTEyHwvf/ppZX7mZ4xvf/TeELfTOpwhTt0GZwyyVy2utZSGQSBS8JbGboNAkvR8NyqDQPqVpBilFTEyX5pjRJIWUJpvkqQgRubbsWOHzn35y4lpf/T2o5k+AXLYe9WiXEtpGwQiBW9p7Fa1TcLz3agNAulXEmKUdsTIfGmOEUlaQGm+SZKCGJnPH6NO0x9NfNPW7U21acnaMEb1R7GW0joIpJ+Wxm73lMnPd2lqaezG5BihgRiZL80xIkkLKM03SVIQI/O1xqjt9EfJuL1q7drTTB3XP4xR/WGupTS0NEZxtplpz3dpbWnsxrQYYSNiZL40x4gkLaA03yRJQYzM1y5GHT91z2T0gxtukDM+bswbuqQcgD1o++Ow11LaWhqjONvMlOe7tLc0dmNKjNAZMTJfmmNEkhZQmm+SpCBG5usWow1v9jIZuVLza5Pe5CUpWdtM++Ow1lJaWxq7Vc36aWnsJs7nu1E+22yYeE0yHzEyX5pjRJIWUJpvkqQgRuYLEiPvDWBmeVlb7r9fVr1uZAuktHE0f1JG9fdqfxxkLXG22UatLbHDuC/ieL5Lw9lmw8RrkvmIkfnSHCOStIDSfJMkBTEyXz8xartfzcBx/VLnipqJo/qDtD9uZi1xttl6w6yatRPl8x2DQDaH1yTzESPzpTlGJGkBpfkmSQpiZL5+Y7TuzaHh4/ql5LY/trYc9hOnNAwCkYZzttkwhf18xyCQwfGaZD5iZL40x4gkLaA03yRJQYzMt9kYJWVcfxJG9bdrf5TW71W75nXXdI1T2gaBSMM522yYwnq+YxDI8PCaZD5iZL40x4gkLaA03yRJQYzMN0iMkjCuPymj+rtVv/aN79Pvvv13tfui3V3/XpoGgcTV0tjNsJ/vaGkcPl6TzEeMzJfmGJGkBZTmmyQpiJH5Bo1RtzeSSdqrJsVfUZM671UrZAv6yN6PNKtgkka+pTGKs82GaRjPd7Q0hovXJPMRI/OlOUYkaQGl+SZJCmJkvmHFiL1qw9W6V8227GaVLGtnZclal5xJo9fSGMXZZsM0aFWalsbw8ZpkPmJkvjTHiCQtoDTfJElBjMwXRotWu71qprQ/ekxvf5Qu7FWrOTVJUt2tt/25UW1pjOJss2HazBAezjaLFq9J5iNG5ktzjLoladkIrwMA+lYrFnV+elr5hx6SvDedritVq9o6N2dM++P09PlmVc1LBrxfvT+P+41/cWdRC9cuaOmpJX3j2W/oibNPbPgZW7Z++t/+tG58w42JTM78CZa/WtYuQfMSN+/nTap89qNj1cxt1EVdy5Kbz9PSCAAJQpIGwHi1YlFnFxaab0S11v5YOH5chVLJiKpA6xt7f4LQ2loXRxLgn9a4+J1FVevVtj/nytVXvvcVvXzLyyUpMYmal5zNzTV+7dSG6q+aeb/3JDo5azMIRJZF1QwAEop2R580l1uTghiZL4qznUal/TGKtrpu0xpt2bpqx1X6h+f+oeN+tIVrF4xO1Ew722yY2q0lBoGYhdck8xEj86U5RrQ7AhgZo9L+6K/6hKHXAdTevrPZt85K2jjZ0ZWrar2quYfnNP2maaMStUFaGj2mJ2itgrQ0MggEAEYHlTSfNGfySUGMzBdVjEZh+qOkoQ6q6OcA6mqmqqu2XbUu+eo0rj9rZ40YIpKEs82GaceOHTr35S9ztpnBeE0yHzEyX5pjxHTHgNJ8kyQFMTJf1DHq1P5oWlUhSDuetLkKz2YOoO4Wp9Zx/d6/EUf7Y9LONhsGr6VxyytfKfvgQVoaDcZrkvmIkfnSHCPaHQGMrE7tj261qi3z87p4cdGIvWr+ARVeEuFPOrzKT79JhTdW318187c0buYA6uLOoqbfNK2H/vmh5r8bdftjp0EgtDSa9eEDACAcJGkAEm/D9EevLcygvWqtY96HNa6/dKq0bs+ZJUv5TH7gA6j94/r97Y/Hl4/roX9+KLSKWrv9eu0Ss05TGpOYmPU624wpjQCQPiRpAEZCrVhUrVjUi5OTiRjV708mBhnXP3HFhHJ2TnK0qapZN8WdRRV3FjW5Z3Jd+2PNqal0qhRKksbZZr6qWaGgcx/5CC2NAJBC7EnzSXNPbFIQI/OZEqOkjOqXgo3r78YbGNJP1azfOHltlTWnppydG2olzauejfogEKn32Wb+QSD5975X/7J7d9yXjC5Meb5DZ8TIfGmOEYNDAkrzTZIUxMh8JsUoVy5r+9TU+hayTEY/uOEGOePjxlQnuk2ADKtStJk4bSYZ7MY/rbGdURsE0u/ZZiatJbRHjMxHjMyX5hgxOARAKm3Yq1avS5lMs8VsqyH7fFoTj0HaH8PktT8Oqt2+s07DVPySlqAxCAQAsFlU0nzSnMknBTEyn6kx8qoZmeVlbbn/fln1urEtkL3aH4dRUYo6Tq2j9L0qWTtJbmkMMggk6Nlmpq4lXECMzEeMzJfmGFFJA5B63mCRXLmsixcXG4dfGzYB0jM9vXHkvH/6o78CZbpOo/RbEzRv31m/0y1NEaRq5ubznG0GAAiESppPmjP5pCBG5ktCjNa9oV6bACnblrJZo1rPwtyrFmacBjmAOmn6GQTS732VhLWUdsTIfMTIfGmOEZU0APDxj+tfNwFy7QDsLQsLRiRrXqIzN7d1Q3ugSXvVPMM4gDoJeg0CoWoGABiUHfcFAEBcasWizk9Py83nG0McpGb745b5eW2fmlKuXI75Ki+0AkoXBmx4v3pJUZzaVfzGx3e1bWn0V8ySdsZZrlzWZYcOafv+/dp611162S23yKpWG/eM1gaB5PN64cABnV1Y0IsHDuj7N91EggYA6BuVNACptmECpNeyZtBeNf/Bzd32qvl/Nmz+lsZRP4C6V0ujLGvTLY0AALRDkgYg9fztj81kbW2vWuH4cRVKJSPegJswqr/fQSBe0uYlZmFeWxjanrUnWhoBAOFicIhPmjcuJgUxMt8oxChXLq/fqyYlclR/N/3GyX/wdD+DQJI+Sr/dkQ1RnW02Cmtp1BEj8xEj86U5RgwOAYA+eHvV8g89JHkVFIPaHz1htz8O0tLoSVqCtmGUfiYjN5NpfJOWRgBAREjSAKCNDXvVUtT+OGhLYxITs27TGl+44QY54+O0NAIAIkO7o0+ay61JQYzMN4oxGqX2Ry8Ba43TIGebJbmlse0B1IbEeBTX0qghRuYjRuZLc4y6tTsOPIL/S1/6kn7jN35D09PTmp+fH/SfAwDjdBrVb621P5owpl8K1v7YWg1r/fNeZ5tJjUpZUgeBSOtH6V8yP98Yo1+vS47TmNiYyawbpW9KEg4ASI+B2h0fe+wxlctlffSjH1Uul9O5c+eGdV0AYJRRaH/0//7w4YxuvFHNlkapfWKWlpZGpjUCAEwyULvj3Nycrr76al111VV9/13aHbEZxMh8aYhRp/bHqKb+BdWrbXHv3opOnCi0/V6nNsmkCdLSaFrcPGlYS0lHjMxHjMyX5hiF1u546tQpPfHEE/rwhz+smZkZPf3004P8cwCQCJ3aH1Wtasv8vLZPTRnRAulvSVxePtlMuLw/b03QpqfPrxvdn5aWxjOLizp35IhRCRoAIN16VtIOHz6s559/fsOfX3/99fr0pz+t173udfrlX/5l/eM//qPuvvtu/cEf/IGstTctfseOHdOxY8ckSUeOHFG1Wh3Of8EQZbNZra6uxn0Z6IIYmS9NMbJOnJA9Py/7vvukWu1C+5xty3n72+XcdpvcvXvjvkwdPpzRbbfVdfhwRrffntnw/Vtvrev22zOqVKrrfj5prBMnZD34oHT55cr85m9KL720rqVRliVddJHqH/2o9Nxzcn/8x42ITydpWktJRYzMR4zMl+YY5fP5jt8bqN3xjjvu0M/93M/pda97nSTppptu0h133KHLLrus59+l3RGbQYzMl8YYrWupW9urJtuWslnj2ujaHUq9vHwyse2MUrJbGrtJ41pKGmJkPmJkvjTHKLTDrN/85jfrscce0+te9zqdPHlSq6ur2rp1a++/CAAjpFYsqlYs6sXJyfV71dbaHy9eXDRmSmBrIjaSg0BsW65tN5IzDqAGACTQQEna29/+dv3RH/2RDh48qGw2q/e///1tWx0BIA28vWr5hx6SvKTBdaVaTRcvLalQKhkzNfDWWxvtjElMztpWzVyXKY0AgJExUJKWzWb1gQ98YFjXAgCJt2FUf70uZTLNpGKrIZWd226rK0ndJeuSs5b9f1TNAACjZqAkDQCwkb/9sVAqKbO8rC333y+rXpdbrxvXAmkqzjYDAKQVSRoAhMRL1nLlsi5eXGwMFPFaIKtVbZ2b0/npaRKLFkFaGpM4CAQAgKBI0gAgZBtaINcmQBaOH1ehVCLZWENLIwAADSRpABCBXhMgtywspDL5oKURAICNSNIAIEKdJkCaOK4/TLQ0AgDQGUkaAERsQ/uj19o34nvVONsMAIBgSNIAIAb+9sdR36vG2WYAAPSHJA0AYtRrr1qS2x8ZBAIAwOaQpAGAATrtVUta+yODQAAAGBxJGgAYIsmj+hkEAgDA8JCkAYBBktb+SEsjAADDR5IGAAbq2P5Yq6lQKsWa7NDSCABAuEjSAMBQG9of63W5uZwqExOxXA8tjQAARIMkDQAM5m9/LJRKkVelONsMAIDokaQBQAJ4yVqUcuWytk9NNfaacbYZAACRIUkDALRVKJVk1Wqy6nWqZgAARIgkDQDQVmViQpfmcpIkN5ejagYAQERI0gAAbXmDS+LYCwcAQJqRpAEAOopjLxwAAGlnx30BAAAAAIALSNIAAAAAwCAkaQAAAABgEJI0AAAAADAISRoAAAAAGIQkDQAAAAAMQpIGAAAAAAYhSQMAAAAAg5CkAQAAAIBBSNIAAAAAwCAkaQAAAABgEJI0AAAAADAISRoAAAAAGIQkDQAAAAAMQpIGAAAAAAYhSQMAAAAAg5CkAQAAAIBBSNIAAAAAwCAkaQAAAABgEJI0AAAAADAISRoAAAAAGMRyXdeN+yIAAAAAAA1U0nwOHToU9yWgB2JkPmKUDMTJfMTIfMTIfMTIfMSoPZI0AAAAADAISRoAAAAAGIQkzefqq6+O+xLQAzEyHzFKBuJkPmJkPmJkPmJkPmLUHoNDAAAAAMAgVNIAAAAAwCDZuC/ABI888oj++I//WI7j6Cd/8if1cz/3c3FfElqcOXNGf/iHf6jnn39elmXp6quv1s/+7M/GfVlow3EcHTp0SJdffjkTmwz0gx/8QJ/4xCf0ve99T5Zl6cYbb9RrXvOauC8LPg888IC+8pWvyLIsvfKVr9T73vc+5fP5uC8r9f7oj/5I3/zmN7Vt2zYdPXpUkvT9739fd999t/7lX/5FL3/5y/XBD35Ql156acxXml7tYvRnf/Znevjhh5XNZrVz5069733v0yWXXBLzlaZXuxh5/vIv/1Lz8/O69957ddlll8V0heZIfSXNcRx98pOf1Ic//GHdfffd+trXvqZnnnkm7stCi0wmo1/4hV/Q3XffrTvuuEN//dd/TZwM9cUvflHj4+NxXwY6+OM//mO98Y1v1Mc+9jHdddddxMowzz33nL70pS/pyJEjOnr0qBzH0de//vW4LwuS/tN/+k/68Ic/vO7PPv/5z+v1r3+9fv/3f1+vf/3r9fnPfz6ei4Ok9jG66qqrdPToUX30ox/VFVdcoc997nMxXR2k9jGSGh/GP/roo9qxY0cMV2Wm1CdpTz/9tP7Nv/k32rlzp7LZrN761rfqG9/4RtyXhRZjY2P64R/+YUnSxRdfrPHxcT333HMxXxVanT17Vt/85jf1kz/5k3FfCtp44YUX9Pjjj+vtb3+7JCmbzfKJsoEcx1G1WlW9Xle1WtXY2FjclwRJ/+7f/bsNVbJvfOMb+omf+AlJ0k/8xE/w/iFm7WL0hje8QZlMRpL0mte8hvcOMWsXI0m677779N/+23+TZVkxXJWZUt/u+Nxzz2n79u3N32/fvl1PPfVUjFeEXp599ll997vf1e7du+O+FLT4kz/5Ex04cEAvvvhi3JeCNp599llddtll+qM/+iP9n//zf/TDP/zD+qVf+iVddNFFcV8a1lx++eX6L//lv+jGG29UPp/XG97wBr3hDW+I+7LQwblz55pJ9NjYmP71X/815itCN1/5ylf01re+Ne7LQItyuazLL79cr371q+O+FKOkvpLWbrglWby5XnrpJR09elS/9Eu/pC1btsR9OfB5+OGHtW3btmbFE+ap1+v67ne/q5/+6Z/W7/3e76lQKNCeZZjvf//7+sY3vqE//MM/1H//7/9dL730kh588MG4LwtIvM9+9rPKZDLat29f3JcCn0qlos9+9rOampqK+1KMk/okbfv27Tp79mzz92fPnqW1xFCrq6s6evSo9u3bp7e85S1xXw5aPPnkkyqXy3r/+9+vj33sY3rsscf0+7//+3FfFny2b9+u7du3a8+ePZKkvXv36rvf/W7MVwW/Rx99VD/0Qz+kyy67TNlsVm95y1v0ne98J+7LQgfbtm3TysqKJGllZYVhB4b627/9Wz388MP6wAc+wAfxhjl9+rSeffZZ3XzzzXr/+9+vs2fP6rd/+7f1/PPPx31psUt9u+OP/MiP6NSpU3r22Wd1+eWX6+tf/7o+8IEPxH1ZaOG6rj7xiU9ofHxc1113XdyXgzZuuOEG3XDDDZKkb3/72/qrv/or1pJhXvayl2n79u06efKkdu3apUcffVSveMUr4r4s+OzYsUNPPfWUKpWK8vm8Hn30Uf3Ij/xI3JeFDorFov7u7/5OP/dzP6e/+7u/05vf/Oa4LwktHnnkEf3FX/yFZmdnVSgU4r4ctHjVq16le++9t/n797///brzzjv5wEMcZi1J+uY3v6n77rtPjuPoP//n/6x3vvOdcV8SWjzxxBP6nd/5Hb3qVa9qfgr27ne/W//+3//7mK8M7XhJGiP4zfO///f/1ic+8Qmtrq7qh37oh/S+972PkeGG+fM//3N9/etfVyaT0atf/Wr92q/9mnK5XNyXlXof+9jH9A//8A86f/68tm3bpp//+Z/Xm9/8Zt199906c+aMduzYoenpadZTjNrF6HOf+5xWV1ebcdmzZ49+9Vd/NeYrTa92MfKGWUkkaX4kaQAAAABgkNTvSQMAAAAAk5CkAQAAAIBBSNIAAAAAwCAkaQAAAABgEJI0AAAAADAISRoAAAAAGIQkDQAAAAAMQpIGAAAAAAb5/wNmi3jh9MSRhAAAAABJRU5ErkJggg==\n", "text/plain": [ "
" ] }, "metadata": {}, "output_type": "display_data" } ], "source": [ "def generate_track_bounds(track):\n", " \"\"\"\n", " in world frame\n", " \"\"\"\n", " width = 0.5\n", " bounds_low=np.zeros((2, track.shape[1]))\n", " bounds_upp=np.zeros((2, track.shape[1]))\n", " \n", " for idx in range(track.shape[1]):\n", " x = track[0,idx]\n", " y = track [1,idx]\n", " th = track [2,idx]\n", " \n", " \"\"\"\n", " trasform the points\n", " \"\"\"\n", " bounds_upp[0, idx] = 0 * np.cos(th) - width * np.sin(th) + x #X\n", " bounds_upp[1, idx] = 0 * np.sin(th) + width * np.cos(th) + y #Y\n", " \n", " bounds_low[0, idx] = 0 * np.cos(th) - (-width) * np.sin(th) + x #X\n", " bounds_low[1, idx] = 0 * np.sin(th) + (-width) * np.cos(th) + y #Y\n", " \n", " return bounds_low, bounds_upp\n", "\n", "track = compute_path_from_wp([0,3,4,6,10,12,14,6,1,0],\n", " [0,0,2,4,3,3,-2,-6,-2,-2],0.05)\n", "\n", "lower, upper = generate_track_bounds(track)\n", "\n", "plt.figure(figsize=(15,10))\n", "\n", "plt.plot(track[0,:],track[1,:],\"b+\")\n", "plt.plot(lower[0,:],lower[1,:],\"g.\")\n", "plt.plot(upper[0,:],upper[1,:],\"r.\")" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "the points can be used to generate the **halfplane constrains** for each reference point.\n", "the issues (outliers points) should be gone after we are in vehicle frame...\n", "\n", "the halfplane constrains are defined given the line equation:\n", "\n", "**lower halfplane**\n", "$$ a1x_1 + b1x_2 = c1 \\rightarrow a1x_1 + b1x_2 \\leq c1$$\n", "\n", "**upper halfplane**\n", "$$ a2x_1 - b2x_2 = c2 \\rightarrow a2x_1 + b2x_2 \\leq c2$$\n", "\n", "we want to combine this in matrix form:\n", "\n", "$$\n", "\\begin{bmatrix}\n", "x_1 \\\\\n", "x_2 \n", "\\end{bmatrix}\n", "\\begin{bmatrix}\n", "a_1 & a_2\\\\\n", "b_1 & b_2\n", "\\end{bmatrix}\n", "\\leq\n", "\\begin{bmatrix}\n", "c_1 \\\\\n", "c_2 \n", "\\end{bmatrix}\n", "$$\n", "\n", "becouse our track points have known heading the coefficients can be computed from:\n", "\n", "$$ y - y' = \\frac{sin(\\theta)}{cos(\\theta)}(x - x') $$" ] }, { "cell_type": "code", "execution_count": null, "metadata": {}, "outputs": [], "source": [] } ], "metadata": { "kernelspec": { "display_name": "Python 3", "language": "python", "name": "python3" }, "language_info": { "codemirror_mode": { "name": "ipython", "version": 3 }, "file_extension": ".py", "mimetype": "text/x-python", "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython3", "version": "3.8.5" } }, "nbformat": 4, "nbformat_minor": 4 }