{ "cells": [ { "cell_type": "code", "execution_count": 1, "metadata": {}, "outputs": [], "source": [ "import numpy as np\n", "from scipy.integrate import odeint\n", "from scipy.interpolate import interp1d\n", "import cvxpy as cp\n", "\n", "import matplotlib.pyplot as plt\n", "plt.style.use(\"ggplot\")\n", "\n", "import time" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "### kinematics model equations\n", "\n", "The variables of the model are:\n", "\n", "* $x$ coordinate of the robot\n", "* $y$ coordinate of the robot\n", "* $\\theta$ heading of the robot\n", "* $\\psi$ heading error = $\\psi = \\theta_{ref} - \\theta$\n", "* $cte$ crosstrack error = lateral distance of the robot from the path \n", "\n", "The inputs of the model are:\n", "\n", "* $v$ linear velocity of the robot\n", "* $w$ angular velocity of the robot\n", "\n", "These are the differential equations f(x,u) of the model:\n", "\n", "* $\\dot{x} = v\\cos{\\theta}$ \n", "* $\\dot{y} = v\\sin{\\theta}$\n", "* $\\dot{\\theta} = w$\n", "* $\\dot{\\psi} = -w$\n", "* $\\dot{cte} = v\\sin{-\\psi}$\n", "\n", "The **Continuous** State Space Model is\n", "\n", "$ {\\dot{x}} = Ax + Bu $\n", "\n", "with:\n", "\n", "$ A =\n", "\\quad\n", "\\begin{bmatrix}\n", "\\frac{\\partial f(x,u)}{\\partial x} & \\frac{\\partial f(x,u)}{\\partial y} & \\frac{\\partial f(x,u)}{\\partial \\theta} & \\frac{\\partial f(x,u)}{\\partial \\psi} & \\frac{\\partial f(x,u)}{\\partial cte} \\\\\n", "\\end{bmatrix}\n", "\\quad\n", "=\n", "\\quad\n", "\\begin{bmatrix}\n", "0 & 0 & -vsin(\\theta) & 0 & 0 \\\\\n", "0 & 0 & vcos(\\theta) & 0 & 0 \\\\\n", "0 & 0 & 0 & 0 & 0 \\\\\n", "0 & 0 & 0 & 0 & 0 \\\\\n", "0 & 0 & 0 & vcos(-\\psi) & 0 \n", "\\end{bmatrix}\n", "\\quad $\n", "\n", "\n", "$ B = \\quad\n", "\\begin{bmatrix}\n", "\\frac{\\partial f(x,u)}{\\partial v} & \\frac{\\partial f(x,u)}{\\partial w} \\\\\n", "\\end{bmatrix}\n", "\\quad\n", "=\n", "\\quad\n", "\\begin{bmatrix}\n", "\\cos{\\theta_t} & 0 \\\\\n", "\\sin{\\theta_t} & 0 \\\\\n", "0 & 1 \\\\\n", "0 & -1 \\\\\n", "\\sin{(-\\psi_t)} & 0 \n", "\\end{bmatrix}\n", "\\quad $\n", "\n", "discretize with forward Euler Integration for time step dt:\n", "\n", "* ${x_{t+1}} = x_{t} + v_t\\cos{\\theta}*dt$\n", "* ${y_{t+1}} = y_{t} + v_t\\sin{\\theta}*dt$\n", "* ${\\theta_{t+1}} = \\theta_{t} + w_t*dt$\n", "* ${\\psi_{t+1}} = \\psi_{t} - w_t*dt$\n", "* ${cte_{t+1}} = cte_{t} + v_t\\sin{-\\psi}*dt$\n", "\n", "The **Discrete** State Space Model is then:\n", "\n", "${x_{t+1}} = Ax_t + Bu_t $\n", "\n", "with:\n", "\n", "$\n", "A = \\quad\n", "\\begin{bmatrix}\n", "1 & 0 & -v\\sin{\\theta}dt & 0 & 0 \\\\\n", "0 & 1 & v\\cos{\\theta}dt & 0 & 0 \\\\\n", "0 & 0 & 1 & 0 & 0 \\\\\n", "0 & 0 & 0 & 1 & 0 \\\\\n", "0 & 0 & 0 & vcos{(-\\psi)}dt & 1 \n", "\\end{bmatrix}\n", "\\quad\n", "$\n", "\n", "$\n", "B = \\quad\n", "\\begin{bmatrix}\n", "\\cos{\\theta_t}dt & 0 \\\\\n", "\\sin{\\theta_t}dt & 0 \\\\\n", "0 & dt \\\\\n", "0 & -dt \\\\\n", "\\sin{-\\psi_t}dt & 0 \n", "\\end{bmatrix}\n", "\\quad\n", "$\n", "\n", "This State Space Model is not linear (A,B are time changing), to linearize it the **Taylor's series expansion** is used around $\\bar{x}$ and $\\bar{u}$:\n", "\n", "$ \\dot{x} = f(x,u) \\approx f(\\bar{x},\\bar{u}) + A(x-\\bar{x}) + B(u-\\bar{u})$\n", "\n", "So:\n", "\n", "$ x{t+1} = x_t + (f(\\bar{x},\\bar{u}) + A(x-\\bar{x}) + B(u-\\bar{u}) )dt $\n", "\n", "$ x_{t+1} = (I+dtA)x_t + dtBu_t +dt(f(\\bar{x},\\bar{u}) - A\\bar{x} - B\\bar{u}))$\n", "\n", "The Discrete linearized kinematics model is\n", "\n", "$ x_{t+1} = A'x_t + B' u_t + C' $\n", "\n", "with:\n", "\n", "$ A' = I+dtA $\n", "\n", "$ B' = dtB $\n", "\n", "$ C' = dt(f(\\bar{x},\\bar{u}) - A\\bar{x} - B\\bar{u}) $" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "------------------\n", "NB: psi and cte are expressed w.r.t. the track as reference frame.\n", "In the reference frame of the veicle the equtions would be:\n", "* psi_dot = w\n", "* cte_dot = sin(psi)\n", "-----------------" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "### Kinematics Model" ] }, { "cell_type": "code", "execution_count": 2, "metadata": {}, "outputs": [], "source": [ "# Control problem statement.\n", "\n", "N = 5 #number of state variables\n", "M = 2 #number of control variables\n", "T = 20 #Prediction Horizon\n", "dt = 0.25 #discretization step\n", "\n", "x = cp.Variable((N, T+1))\n", "u = cp.Variable((M, T))" ] }, { "cell_type": "code", "execution_count": 3, "metadata": {}, "outputs": [], "source": [ "def get_linear_model(x_bar,u_bar):\n", " \"\"\"\n", " \"\"\"\n", " \n", " x = x_bar[0]\n", " y = x_bar[1]\n", " theta = x_bar[2]\n", " psi = x_bar[3]\n", " cte = x_bar[4]\n", " \n", " v = u_bar[0]\n", " w = u_bar[1]\n", " \n", " A = np.zeros((N,N))\n", " A[0,2]=-v*np.sin(theta)\n", " A[1,2]=v*np.cos(theta)\n", " A[4,3]=v*np.cos(-psi)\n", " A_lin=np.eye(N)+dt*A\n", " \n", " B = np.zeros((N,M))\n", " B[0,0]=np.cos(theta)\n", " B[1,0]=np.sin(theta)\n", " B[2,1]=1\n", " B[3,1]=-1\n", " B[4,0]=np.sin(-psi)\n", " B_lin=dt*B\n", " \n", " f_xu=np.array([v*np.cos(theta),v*np.sin(theta),w,-w,v*np.sin(-psi)]).reshape(N,1)\n", " C_lin = dt*(f_xu - np.dot(A,x_bar.reshape(N,1)) - np.dot(B,u_bar.reshape(M,1)))\n", " \n", " return A_lin,B_lin,C_lin" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Motion Prediction: using scipy intergration" ] }, { "cell_type": "code", "execution_count": 4, "metadata": {}, "outputs": [], "source": [ "# Define process model\n", "def kinematics_model(x,t,u):\n", " \"\"\"\n", " \"\"\"\n", "\n", " dxdt = u[0]*np.cos(x[2])\n", " dydt = u[0]*np.sin(x[2])\n", " dthetadt = u[1]\n", " dpsidt = -u[1]\n", " dctedt = u[0]*np.sin(-x[3])\n", "\n", " dqdt = [dxdt,\n", " dydt,\n", " dthetadt,\n", " dpsidt,\n", " dctedt]\n", "\n", " return dqdt\n", "\n", "def predict(x0,u):\n", " \"\"\"\n", " \"\"\"\n", " \n", " x_bar = np.zeros((N,T+1))\n", " \n", " x_bar[:,0] = x0\n", " \n", " # solve ODE\n", " for t in range(1,T+1):\n", "\n", " tspan = [0,dt]\n", " x_next = odeint(kinematics_model,\n", " x0,\n", " tspan,\n", " args=(u[:,t-1],))\n", "\n", " x0 = x_next[1]\n", " x_bar[:,t]=x_next[1]\n", " \n", " return x_bar" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Validate the model, here the status w.r.t a straight line with constant heading 0" ] }, { "cell_type": "code", "execution_count": 5, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ "CPU times: user 3.81 ms, sys: 0 ns, total: 3.81 ms\n", "Wall time: 3.75 ms\n" ] } ], "source": [ "%%time\n", "\n", "u_bar = np.zeros((M,T))\n", "u_bar[0,:] = 1 #m/s\n", "u_bar[1,:] = np.radians(-10) #rad/s\n", "\n", "x0 = np.zeros(N)\n", "x0[0] = 0\n", "x0[1] = 1\n", "x0[2] = np.radians(0)\n", "x0[3] = 0\n", "x0[4] = 1\n", "\n", "x_bar=predict(x0,u_bar)" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Check the model prediction" ] }, { "cell_type": "code", "execution_count": 6, "metadata": {}, "outputs": [ { "data": { "image/png": "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\n", "text/plain": [ "
" ] }, "metadata": { "needs_background": "light" }, "output_type": "display_data" } ], "source": [ "#plot trajectory\n", "plt.subplot(2, 2, 1)\n", "plt.plot(x_bar[0,:],x_bar[1,:])\n", "plt.plot(np.linspace(0,10,T+1),np.zeros(T+1),\"b-\")\n", "plt.axis('equal')\n", "plt.ylabel('y')\n", "plt.xlabel('x')\n", "\n", "plt.subplot(2, 2, 2)\n", "plt.plot(np.degrees(x_bar[2,:]))\n", "plt.ylabel('theta(t) [deg]')\n", "#plt.xlabel('time')\n", "\n", "plt.subplot(2, 2, 3)\n", "plt.plot(np.degrees(x_bar[3,:]))\n", "plt.ylabel('psi(t) [deg]')\n", "#plt.xlabel('time')\n", "\n", "plt.subplot(2, 2, 4)\n", "plt.plot(x_bar[4,:])\n", "plt.ylabel('cte(t)')\n", "\n", "plt.tight_layout()\n", "plt.show()" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "the results seems valid:\n", "* the cte is correct\n", "* theta error is correct" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Motion Prediction: using the state space model" ] }, { "cell_type": "code", "execution_count": 7, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ "CPU times: user 404 µs, sys: 4.79 ms, total: 5.19 ms\n", "Wall time: 1.54 ms\n" ] } ], "source": [ "%%time\n", "\n", "u_bar = np.zeros((M,T))\n", "u_bar[0,:] = 1 #m/s\n", "u_bar[1,:] = np.radians(-10) #rad/s\n", "\n", "x0 = np.zeros(N)\n", "x0[0] = 0\n", "x0[1] = 1\n", "x0[2] = np.radians(0)\n", "x0[3] = 0\n", "x0[4] = 1\n", "\n", "x_bar=np.zeros((N,T+1))\n", "x_bar[:,0]=x0\n", "\n", "for t in range (1,T+1):\n", " xt=x_bar[:,t-1].reshape(5,1)\n", " ut=u_bar[:,t-1].reshape(2,1)\n", " \n", " A,B,C=get_linear_model(xt,ut)\n", " \n", " xt_plus_one = np.dot(A,xt)+np.dot(B,ut)+C\n", " \n", " x_bar[:,t]= np.squeeze(xt_plus_one)" ] }, { "cell_type": "code", "execution_count": 8, "metadata": {}, "outputs": [ { "data": { "image/png": "iVBORw0KGgoAAAANSUhEUgAAAagAAAEYCAYAAAAJeGK1AAAABHNCSVQICAgIfAhkiAAAAAlwSFlzAAALEgAACxIB0t1+/AAAADl0RVh0U29mdHdhcmUAbWF0cGxvdGxpYiB2ZXJzaW9uIDMuMC4zLCBodHRwOi8vbWF0cGxvdGxpYi5vcmcvnQurowAAIABJREFUeJzt3XeUFMX2wPFv9S45iLCCJAEzmMD8zAERfSr61CuKAQwYCGIERCUoCs8AKCYUBBTDNYL+EHN6PiMqovhUjEQxIKJkun5/9KDLssvusrPTE+7nnD0709PTc6kzzd2urqrrvPcYY4wx6SaIOwBjjDGmOJagjDHGpCVLUMYYY9KSJShjjDFpyRKUMcaYtGQJyhhjTFqyBGWMMSYtWYIyxhiTlixBGWOMSUv5cQdQSWx5DJMsLu4A0pCdXyYZSj23sjVBMX/+/L8eFxQU8PPPP8cYTfqxNtlQ0TZp0qRJjNGUnYh0BEYBecB9qjqsyOvVgInAHsAvwCmq+l3itf7AOcBaoLeqPl+Wzyx8fq1j36mItUNkY+1Q1nPLuviMyWAikgfcARwFtAFOFZE2RXY7B1isqtsCI4Dhife2AToDOwEdgTsTxzMmLViCMiaz7Q3MVtVvVHUV8AjQqcg+nYAJicePA4eLiEtsf0RVV6rqt8DsxPHKzc//gZXv/2eT/gHGlCRru/iMyRFNgTmFns8F9ilpH1VdIyJLgAaJ7e8UeW/T4j5ERLoD3RPHoKCgYL3Xl0y6i99ee47qh/2TOmdfTFCr9qb/izJcfn7+Bu2Ti5LRDpagjDGlUtUxwJjEU1/03oKXc6nVYAv+fPJBVnz8LsFZvXFt2qY8znRg96Aidg/KGDMPaF7oebPEtmL3EZF8YDOiwRJleW+ZuCpVqH36BQT9hkPVaoQjriWcdDd+5YpNOZwxgCUoYzLd+8B2ItJKRKoSDXqYUmSfKcBZiccnAa+oqk9s7ywi1USkFbAd8F5FgnFb70BwzUhc+074158jHNwb/9WsihzS5DBLUMZkMFVdA/QEngc+jzbpZyIyRESOS+w2FmggIrOBS4F+ifd+BigwC5gG9FDVtRWNyVWtRnDKOQSXDQXvCW/qT/jY/fjVqyp6aJNjXJaWfPc2D2rjrE02VMI8KJuouyFf1nlQfsVy/GP349+YBo2bE5zdB9dyuxSFGQ87tyJluAdV6rllV1DGmErjqtcgOOMigosHwfJlhDdeQTh5En7N6rhDMxnAEpQxptK5nXcnGHw7bp+D8c8+SnjD5fi538UdlklzlqCMMSnhatYmOPsSgh5XwW+/El5/KeHUx/BrK3zby2QpS1DGmJRybfclGHwHru0++KceIBzeF79wbtxhmTRkCcoYk3KuTl3c+VfizrscFi0gHNKH8KUp+DCMOzSTRixBGWNi4Zwj2PsggkG3Q+vd8I/eR3jL1fifFsYdmkkTlqCMMbFy9eoT9Lwa17U3/PA14eCLCd+YRpZOgTHlYAnKGBM75xzB/u0JBo2GrbfHP3An4ahB+MW/xB2aiZElKGNM2nANtiDoMxh32vnw1SzCQT0J33nVrqZyVEasZi4izYkqgjYiKjc9RlVHxRuVMaYyuCDAHfpP/E7tCO8fhR87Av/h2wSnX4SrWy/u8EwKZcoV1BrgMlVtA+wL9CimaqgxJou4hk0IrrgBd1I3mDmdcGBP/PS34g7LpFBGJChVXaCqHyYeLyVaFLPYwmrGmOzhgjyCI08guHoENGhIePdwwntvxv+5NO7QTApkRBdfYSLSEmgHvFtke4kVP63C5YasTTZkbZK+XNOtCPr9G//c4/j/exT/xacEZ/bA7bpX3KGZSpRRq5mLSG3gdWCoqj65kV1tNfNSWJtsyFYzL7Myr2ZeKR/+/deE94+Eed/jDjgCJ+fgatSs9M8tKzu3Ijm1mrmIVAGeACaVkpyMMVnMtdiGYMCtuKNOxL/1MuGgXvjPZ8QdlqkEGZGgRMQRFV37XFVvjTseY0y8XJUqBP86i6DvMKhSlfDWawgfusdKzGeZTLkHtT9wBjBTRD5ObLtKVafGGJMxJmZumx0JrhmJf2oi/uVn8J99SNCtD27b1nGHZpIgIxKUqv4HuxdgzHpEpD7wKNAS+A4QVV1cZJ+2wF1AXWAt0f3bRxOvjQcOBpYkdu+qqh+TYVy1arjO5+Hb7kM4/jbCf/fHdeiE69QFV6Vq3OGZCsiILj5jTLH6AS+r6nbAy4nnRS0DzlTVnYCOwEgRKTzb9QpVbZv4ybjkVJjbcVeCQbfhDmiPf/4pwusuwX8/O+6wTAVYgjImc3UCJiQeTwCOL7qDqn6pql8lHs8HFgFbpCzCFHPVaxKc2ZOg90BY/ifhDZcTTnkIv2ZN3KGZTZARXXzGZBoRKQDOBP4J7AZsRtSVNgN4Dpigqj9V8GMaqeqCxOOFREuBbSymvYGqwNeFNg8VkWtJXIGp6soS3lviPMN10moe2aFHEu71D5beN4IVzzxC3mcfslnva8hvsU2lf3RatUOMktEOlqCMSTIRGQZ0AaaSGH0KLAXqAK2J7vt8KCKTVLW4brnCx3oJ2LKYlwYUfqKqXkRKnNQoIo2BB4CzVHVdVcD+RImtKjAG6AsMKe79qjomsQ+AL25+S1rO/zm9B0Gb3Vnz4J38cnk33HFdcEcejwvyKu0j07IdYlCGeVClsgRlTPLNBbYt4WrkI+AhEakOnFvagVS1fUmviciPItJYVRckEtCiEvarC/wfMEBV3yl07HVXXytF5H7g8tLiyURu938QbNeG8ME78U9OwM94l6DrxbgtbbW0dGf3oIxJMlUdvS45iUhxVz8A9VR1dAU/agpwVuLxWcDkojuISFXgKWCiqj5e5LXGid+O6P7VpxWMJ225OpsRXNAPd+5lsGAO4XUXE778rJWYT3N2BWVM5fqSaIh3UbOA+hU89jBAReQc4HtAAERkT+ACVT03se0goIGIdE28b91w8kkisgXRFI6PgQsqGE9ac87h9jkYv8POhBNG4x8Zg//obYKuvXEFG719Z2KSUWvxlcNfa4WF990CM6f/XfDMAVWqQbVqULU61KqNq7MZ1K0X/RQ0ir6sWzSCOvVwLjunX1k/+YYqYy0+EVmqqnWKbKsLfKOqmXonPda1+JLBe4//z4v4R8cC4E45J1rXLwnneya1Q2VKxlp82X8FteOu1NiiEcuXL4+eew+rV8HKFdGyKH/+gZ/zLfz+Gyz/M9pl3Xtr1oImLXDNWkCzVritd4CmW1XqDVaTHURkDtFXqYaI/FDk5QbAw6mPyqzjnMMd2AHfejfC8bfhJ46OiiKe1RNXr0Hc4ZmErE9QwQFHUKeggJVl+IvGr1wJvy6Cnxbif1oIC+bg532Pf/d1eO25KHFVqwFbb4/bfmdcm7bQYltcniUss4HTif5CnEq0TNc6HvhRVb+IJSqzHlfQiODS6/CvTsU/OZ5wYC/caefj9j4oa3tPMknWd/FBxS+5vfdR0vrmf/D1F/jZn8Pcb6MXa9SKElW7fXG77ImrWauisaeEdUNsqJK6+Gqq6rIKhpZuMr6Lrzh+4byojMc3X8Du+xGcfmHU/V9Omd4OyWJdfCninIOGjXENG8O+hwLgly7B/+8TmPUx/pP3Yfpb+Lx8aL0bbp+Dce32xVWrHnPkJg4i0hu4R1VXlpScRKQacL6q3pba6ExJ3JZNCfoOw7/wNH7yJMKBnxGcfhFu93/EHVrOsgS1iVydzXB7HQh7HRgNVf3mC/xH7+A/+A9+7K34ajVwu++LO+hI2Ka1dRfkli2B2SIylajA5hf8PVF3e+AQ4ChgYlwBmuK5IA/X8UT8LnsSjhtBeNeNuH0PwXXujqtVO+7wco518SX7g8MQvpqFf/c1/Af/geXLoFlL3CFHR1/0NLmqsm6IDSWziy+x1FFXokS0C1APWAx8QnRfaqKq/lKxiGOTlV18Rfk1a/BTFf9/CnXrEZzZC7fLHqW+L9vaYVMlo4vPElRlBrFiOf691/GvToW530HtOrjDjsUdejSudnFTY1LHTqINWcn3MsuJBLWO/3424biRMP8H3IEdcHI2rnrJJeaztR3Ky+5BpTlXvQbuoI74A4+Er2YRvvAUfspD+GlPRFdUHU/E1Yk3URljNs612Jbg6lvxkx/Cv/AUftbHBN0uxu2wS9yhZT1LUCngnIPtdyJv+52iYevTnsC/OBn/xjRc+064IzplzOg/Uz6JSbmDiBaILaDQX42qulVMYZlyclWq4k7qGhVFvH8k4c0DcIcfizvhTFy1anGHl7VsLb4Uc01bEJxzKcGg26BNO/yzjxBefQHhG8/jw7Vxh2eS705gd6JVwusDvYAfgBFxBmU2jdu2NcG1o3CHHYN/+RnCIRfjv/5f3GFlrYxJUCLSUUS+EJHZIrLREgWZwDXZirwL+xEMuAUaNcE/cAfh9ZfiZ8+KOzSTXB2AE1V1MrA28fsU1p+8azKIq1ad4NTuBJdeB2tWEw7vR/jkBPzq1XGHlnUyIkGJSB5wB9GIqDbAqSLSJt6oksO13I7gymG48y6HP5ZGX/YH78Qv+zPu0ExyBESFCgH+EJHNgAXAtvGFZJLBtd6NYNDtuP0Pxz/3BOHQS/E/fF36G02ZJSVBicgIEWmbjGOVYG9gtqp+o6qrgEeIyl1nBeccwd4HEQy5A9f+OPwbLxAO7IGf8X7coZmKm0F0/wngTaIuv7uIVjk3Gc7VqElwVi+C3tdGf2DecDl/PDrOSswnSbIGSeQBz4vIT0RVOyep6twkHRugKTCn0PO5wD5leeO119blq6/yWb06UxaA7Itf3hs+nAvTVsJmK6JVLILkXuxWqZJJbZIae+yRR//+ST/sefw9MOJi4AaiOVFnJv2TTGzcLnsSDL4d/9AY/nzkPnj7NYKz++Ca2DiYikhKglLV3iJyCVEXXBfgahF5l2im/JOq+kcyPmdjRKQ70D0RDwUFUSWDGjXycM5RpUqVyg4heapUwdduzdpF8wl/XoRbvoy85i0JapQ896K8Mq5NUiAI3F/fmyTaQlXfBVDVRSSq6IrI3sn+IBMvV6sO7rzLqH1IB5bcOZzwuktwx5+OO+I4q4CwiZI2zFxV1wLPAs+KyE7AQ8B44E4ReQQYqKrzNvHw84DmhZ43S2wr/PljgDGJp37dBLH+/TN54lwe/otfCMfdCr//Fi23ctCRVrOmkpQwUbeiXqT4goXTqHjBQpOGqv/jUJY2ak74wJ34x+/Hf/xONG+qYVK+TzklaQkqMd/jZKIyA7sCTwAXEQ2pvQx4LrF9U7wPbCcirYgSU2fgtIrGnAncDjsTXDOScOyt+AfvhNmfwxkX4ara3It0JiIBUdeeS5RUL/xXxTaA3aTIYq5uPYKL+kdLnj08hnDwxbiTuuIOPirp3fXZLCkJSkQeB44E3gDuBp5W1ZWFXr+Uv0cylZuqrhGRnsDzRPe7xqnqZxWLOnO42nUJel0brQs25WH8wrkEPQbg6tkf4GlsDX/XviyajEJgaEU/QETqA48CLYHvAFHVxcXstxaYmXj6g6oel9jeimjAUQNgOnBGYhCSSQLnHG7fQ/E77Eo48Xb8Q/fgP3qH4KzeuAZbxB1eRkjWFdQ7QE9VXVjci6oaikijinyAqk4lWmQzJ7kgwB3TGd+sJeF9txLecDlBz6txW20dd2imeK2IrppeBw5KPPaJn59UdXkSPqMf8LKqDkvMDewH9C1mv+WqWtwo2+HACFV9RETuBs4hGmFoksht3oCg90D8my/gdRzhoJ64U87F7d/eqhyUIlmDJG4uwz7ZVrQtFq7tvgRXDiMcfT3hv/sT9LgK13q3uMMyRajq94mHLeCvLr9GqrogiR/Tiah0B8AE4DWKT1AbSHQ7HsbfXeUTiJZksgRVCZxzuIOOxLdpG5WYn3B7VGL+zJ7WE7IRthZfBnJbbU1w1U2EIwcR3jaY4NzLcXvsF3dYphgiUo9o7tNJwGqglogcB+ytqldX8PCFE95CoKReiuoi8gFRV+MwVX2aqFvvN1Vd1/04l2g6R0n/jmJHyRaWn59fGaMgM85G26GgAH/DXSyf+jhLH7gTP7gXdbpfTrUDsu9qKhnfB0tQGcrVa0BwxY2Eo68jvGc47qzeBPsfHndYZkN3E9WBagGsW8fqbeAWoNQEJSIvERVALGpA4Seq6kWkpNo5LVR1nohsDbwiIjMp5z3hkkbJFmYjQyNlaod9DyNouT3h/aNYcutAeP15gi6bVmI+XZWh3EapLEFlMFerNkGfIYR3DsVPuI0QLEmln8OBJqq6el0CUdWfRKRhWd6squ1Lek1EfhSRxqq6QEQaA4tKOMa8xO9vROQ1oB3RKNt6IpKfuIraYOqGqVxuy2YEVw6LSnhMeYjwy88IzuiBa7dv3KGlDRvvmOFctWoEPQZA692iJPXWy3GHZNa3hKjMxl9EZCui9fgqagpwVuLxWcDkojuIyOYiUi3xuADYH5ilqh54lajrscT3m8rl8vIIjjqJYMCtUK8+4Z03EI4dgV9W6WsbZARLUFnAVU0kqR13/evmq0kb9wFPiMihQCAi/yAakHB3Eo49DDhCRL4C2ieeIyJ7ish9iX1aAx+IyAyihDRMVdd1NfYFLhWR2UT3pMYmISazCVyzlgRX3RyN1H3vdcKBvfCffhh3WLGzku9ZxK9cQXjL1TDnW4I+gzZa8TNX2qQ8KqPke2K0XG/gfKL7UD8A9wCjElcxmSinSr6XV0XbwX/3VVRifsEc3EEdcSd33WiJ+XSVjJLvlqCyjP/jd8J/94fFPxP0v6nExSpzqU3KqjISVJayBLURyWgHv3oV/ulJ+BefhgYNCbpejNth5yRFmBrJSFA2SCLLuNp1CfoMxj/3GGxR3OAvk2oisgOwG1C78HZVHRdPRCbduSpVcSd3+7vE/C3rSsyfkVPLnFmCykKufgGuy4Vxh2EAEbkKuJaoLlThyeoesARlNspt14Zg4G34J8bjX5qC/3Q6Qbc+uK13iDu0lLAEZUzl6kM0KfeTuAMxmclVq4477QJ8230JJ9xGOKwv7qgTccd0xmV5yRwbxWdM5VoO/C/uIEzmc23aEgy8HbffYfipjyVKzH8Td1iVyq6gjEmyxLp761wD3C4ig4AfC++nqmEq4zKZz9WshevaG9/uH4QPjCa84bLoSuqok3B52VcU0RKUMclXuNQGRKOVzi3y3BOVjjGm3NxuexFsczv+4TH4yZPwM96LSsw3bl76mzOIJShjkq9V4rcjKuKpRV53wIkpjchkHVe7Lu68y/Ht9iWcdBfhkD64E07Htc+eEvOWoIxJskKlNhCRa1T1pqL7iMgAogVjjakQt+cBBNvvRDjxDvxj9+M/ejdRYr5x3KFVmCUoYyqBiByWeJifWOao8KTErYGlqY/KZCtXd3OCHgPwb7+Kf+RewsG9cSd1wx3cMaNLzFuCMqZyrFvXrhrrz3fyRLWbeqU8IpPVnHPRCL8ddyGcMBr/0N34j97O6BLzlqCMqQSq2gpARCaq6plxx2Nyh6u/BUGfQfg3nsc/No5wcC/cKefh9jss44oipn2CEpGbgGOBVcDXQDdV/S3eqIwpG0tOJg7OOdzBHaMS8/ePxI8fFV1NndEDt9nmcYdXZpnQOfkisLOq7gp8CfSPOR5jjMkIbostCS6/ASfnwGcfEQ7sSfj+m3GHVWZpfwWlqi8UevoOfxdYM8YYUwoXBLgjOuF33iO6mhpzE+GHb+NOuwBXp27c4W1U2ieoIs4GHi3uBRHpDnQHUFUKCv4uYpqfn7/ec2NtUhxrE5PNXONmBH2H46c9gX/mEfyXn0Zdfm33iTu0EqVFPSgReQkorjbEAFWdnNhnALAn8K8yFHrL2XpQZWVtsqFMqwclIvWJ/mBrCXwHiKouLrLPocCIQpt2BDqr6tMiMh44mKgsPUBXVf24DB9t9aA2IhPawc/5NiqKOPdb3H6H4045F1ezVlI/I2vqQalq+429LiJdgWOAwzO4CqkxydYPeFlVh4lIv8TzvoV3UNVXgbbwV0KbDRTuNr9CVR9PUbwmTbjmrQgG3Ix/9lH8c4/j/zcjGo7epm3coa0n7QdJiEhH4ErgOFVdVtr+xuSQTsCExOMJwPGl7H8S8JydRwbA5VchOP50gn43QdXqhCOuJZx0F37F8rhD+0vaJyhgNFAHeFFEPhaRu+MOyJg00UhVFyQeLwQalbJ/Z+DhItuGisgnIjJCRHKnVKv5i2u1HcE1I3Adjse/Po1wyMX4Lz+LOywgTbr4NkZVt407BmPisrH7s4WfqKoXkRK7v0WkMbAL8Hyhzf2JEltVYAxR9+CQEt5f4iCkdWyQSSRj2+HCK1l1cAd+v+161t58FTWPPYXap52Pq7Zpf7ckox3SYpBEJbBBEqWwNtlQBg6S+AI4RFUXJBLQa6pabC1wEbkY2ElVu5fw+iHA5ap6TBk+2gZJbESmt4NfsTwqMf/ac7Bls6iMR6vty32cZAySyIQuPmNM8aYAZyUenwVM3si+p1Kkey+R1BARR3T/6tNKiNFkGFe9BkGXCwkuGQwrVxAOu5LwqQfxa1anPBZLUMZkrmHAESLyFdA+8RwR2VNE7lu3k4i0BJoDrxd5/yQRmQnMBAqA61MRtMkMrk07gkG34fY5BD9VCYdejp/zbWpjsC6+3GRtsqFM6+KLkXXxbUQ2toP/+F3CB+6AP//AHdsZ1/HEUkvMWxefMcaYSufa7kMwaDSu3b74px8kHN4Xv2BupX+uJShjjDGlcnXqEpx/Ja77FbBoAeF1fQhfnIwPw0r7TEtQxhhjyizY60CCwaOh9W54HUt4ywD8Twsr57Mq5ajGGGOylttsc4KeV+O6XgxzviUc3Jvw9Wkke0yDJShjjDHl5pwj2P9wgoG3w9Y74B+8k3DkIPyvyRsgYgnKGGPMJnMNtiC4ZAiuywUwexbhoF6E/30lKVdTlqCMMcZUiHOO4JCjCQbeBk1b4O8fyZJh/fC/Ly71vRtjCcoYY0xSuIaNCa4Yijv5bFZ98gH88lOFjpf2i8UaY4zJHC7Iw3U4nvrHCr+uXFWhY9kVlDHGmKQL6tSt+DGSEIcxxhiTdJagjDHGpKWsXSw27gBM1rDFYjdk55dJhpxdLNYV/hGR6UW35fqPtUmZ28RsyL5T5f8e5dxPGdqhVNmaoIwxxmQ4S1DGGGPSUq4kqDFxB5CGrE02ZG1SMdZ+EWuHSIXbIVsHSRhjjMlwuXIFZYwxJsNk/VJHItIRGAXkAfep6rCYQ4qdiHwHLAXWAmtUdc94I0o9ERkHHAMsUtWdE9vqA48CLYHvAFHViq12mSNy9Tyz71FERJoDE4FGRNMQxqjqqIq2RVZfQYlIHnAHcBTQBjhVRNrEG1XaOFRV2+ZickoYD3Qssq0f8LKqbge8nHhuSpHj59l47HsEsAa4TFXbAPsCPRLfgQq1RVYnKGBvYLaqfqOqq4BHgE4xx2TSgKq+AfxaZHMnYELi8QTg+JQGlbly9jyz71FEVReo6oeJx0uBz4GmVLAtsj1BNQXmFHo+N7Et13ngBRGZLiLd4w4mjTRS1QWJxwuJuitM6ew8W19Of49EpCXQDniXCrZFticoU7wDVHV3oi6ZHiJyUNwBpRtV9diSPqaCcu17JCK1gSeAPqr6e+HXNqUtsj1BzQOaF3reLLEtp6nqvMTvRcBTRF00Bn4UkcYAid+LYo4nU9h5tr6c/B6JSBWi5DRJVZ9MbK5QW2T7KL73ge1EpBXRCdMZOC3ekOIlIrWAQFWXJh53AIbEHFa6mAKcBQxL/J4cbzgZw86z9eXc90hEHDAW+FxVby30UoXaIusn6orI0cBIouGv41R1aMwhxUpEtia6aoLoD5SHcrFNRORh4BCgAPgRGAg8DSiwFfA90ZDYojfATTFy9Tyz71FERA4A3gRmAmFi81VE96E2uS2yPkEZY4zJTNl+D8oYY0yGsgRljDEmLVmCMsYYk5YsQRljjElLlqCMMcakJUtQxhhj0pIlKGOMMWnJEpQxxpi0lO1LHZlCRGQbomVp2qvqhyLSBJgBnKyqr8UanDHGFGErSeQYETkPuATYk2jJo5mqenm8URljzIasiy/HqOq9wGyiNbIaAwPijcgYY4pnCSo33QvsDNyuqivjDsYYY4pjXXw5JlFQbAbwKlHBwl2yfaVlY0xmsiuo3DMK+EBVzwX+D7g75niMMaZYlqByiIh0AjoCFyY2XQrsLiJd4ovKGGOKZ118xhhj0pJdQRljjElLlqCMMcakJUtQxhhj0pIlKGOMMWnJEpQxxpi0ZAnKGGNMWrIEZYwxJi1ZgjLGGJOWLEEZY4xJS5agjDHGpCVLUMYYY9KSJShjjDFpyRKUMcaYtGQJyhhjTFqyBGWMMSYtWYIyxhiTlvLjDqCSWBVGkywu7gDSkJ1fJhlKPbeyNUExf/78YrcXFBTw888/pzia9GPtENlYOzRp0iTF0aSeiIwDjgEWqerOZX1fceeXfaci1g6RZJxb1sVnTG4bD3SMOwhjipO1V1DGlMavWc2Kd9+AbdrEHUpsVPUNEWlZ0eP4hfNYNf87/JIlxe9QvQbUrgu16kCNmjhnPaemdJagTE7yc78jvH8kS374huCakbitto47pLQmIt2B7gCqSkFBwXqv//7URBZPfbxsB8vLI6izGa7OZgSbbU7+lk3Ja9qC/KZbkddkK/IaNcHlZ+5/Tfn5+Ru0Ty5KRjtk7rfAmE3g167Fv/AUfvJDULMWm/W9kT8sOZVKVccAYxJPfdF7C37/9my+36EsKe4KygMrluP//B3++B3+WIr/43fCP5eydsliVr/zerR9nbw8KNgSmrXAbdMat21raN4Kl1+lsv55SWX3oCLJuAdlCcrkDL9wHuH9I+GbL2D3/QhOv5DqrbbhD/vPpMJcwyZULSjAbaQtN9ap5/9cCgvn4X+c9/fv72bjp/83GjJYpSq03DZKWNvsCDvugqteM9n/DJNmLEGZrOfDEP/Ks/gnJ0KVqrhzL8PtfZDdB0kjrlYd2GbHKPkU4hf/At/8Dz/7f/ivP8e/OBk/7QnIy4cddsHtthdut71xDRrGFLmpTJagTFbzPy0kHH8bfPkp7LInwZlX6sYpAAAdcElEQVQ9cPUaxB1W2hCRh4FDgAIRmQsMVNWx8Ub1N7d5A9hjf9we+wPgV62Eb7/Cz3wfP+M9/MNj8A+PgWYtcbvujWu3D7TY1v74yBKWoExW8t7j33wer/eDA3dmT9wBR9h/XEWo6qlxx1Aermo12GFn3A47w0nd8Avn4T95Dz/jffy0x/FTFRo3x+1/OG6fQ3D16scdsqkAS1Am6/jFvxBOuA0++wh23JWga2/rAspSbsumuC1PgA4n4P9civ/wbfxbL+EfHx916e60O8H+h8Oue+OqZMYgC/M3S1Ama3jv8e++FnX5rFmNO+183MFH4QKbj54LXK06uAM7wIEdoiur/76Mf/tVwruHQ83a0VXV4cfhGmwRd6imjCxBmazgf/+N8ME74aN3YJsdCbr1wTXK/qWKTPHclk1x/zoTf3wX+PwT/H9exL/8DP7lZ3B7HoDrcDyuxbZxh2lKYQnKZDw//b9RclqxDHdSV9wRnXBBXtxhmTTggjzYqR1up3b4X37Cv/IM/o3n8e+9AdvvTNDheNhlT7vKTlMpS1Ai0hEYBeQB96nqsCKvjwAOTTytCTRU1XqJ19YCMxOv/aCqx6UmapPO/J9L8Q+Nwb/3Omy1DcHZl+CabhV3WCZNuQZb4E4+G//PU/D/eQH/8jOEo6+HLZvijumM2+tAS1RpJiUJSkTygDuAI4C5wPsiMkVVZ63bR1UvKbR/L6BdoUMsV9W2qYjVZAY/8wPCCaPhjyW4Y0/FHX1yRi+PY1LH1ayF63AC/rBj8dPfwj/3OP6+W/DTniA4/nTYdS8b7ZkmUnVG7w3MVtVvAETkEaATMKuE/U8FBqYoNpNB/PJl+MfG4d98AZpsRdDrGlyLbeIOy2Qgl5+P2+dg/F4H4t9/Ez/loeiKausdCE44A7fjrnGHmPNSlaCaAnMKPZ8L7FPcjiLSAmgFvFJoc3UR+QBYAwxT1aeLed9GF7NcxxZyjGRiO6yaOZ0ltw/F/7KImiecTu1Tz8VVqVqhY2ZiO5jkckEQJao99o9G/j3zCOEtV0Pr3Qj+dSau5XZxh5iz0rFPpDPwuKquLbStharOE5GtgVdEZKaqfl34TaUtZrmOLeQYyaR28CtX4p+cgH/lWWjYhOCKG1m5bWtWLvm99DeXItcLFpq/ufx83EFH4v9xKP615/BTHyO84fJogvcJZ+DqbBZ3iDknVXcE5wHNCz1vlthWnM7Aw4U3qOq8xO9vgNdY//6UyWJ+9ueEQy7Gv/Is7vBjCa4dFa1ubUwlcVWqEhzRieCGMbgOx+P/+zLh1RcQvvp/+LVrSz+ASZpUXUG9D2wnIq2IElNn4LSiO4nIjsDmwNuFtm0OLFPVlSJSAOwP/DslUZvY+NWr8VMewj//FNQvILjsersnYFLK1aiJO6kbfv/2hA+PwT90D/6NFwi6nI/bNneLXKZSSq6gVHUN0BN4Hvg82qSficgQESk8ZLwz8Iiq+kLbWgMfiMgM4FWie1AlDa4wWcB//zXh0Evx057AHdCeYNBtlpxMbFzj5gSXDCG4oC8sW0o4vB/h2BH43xfHHVrWc9770vfKPH7+/PnFvpBJ914qUzq2g1+zBj/1sWjBzzqbEZzZC7fLHpX6mWW4B2XjjTdU7PmVjt+pZPMrV+CnPo5/4UmoXgN36vnR/KlCw9JzoR3KIhnnVjoOkjA5yM/7gXDcCPjha9y+h+A6d8fVqh13WMasx1WrjjvhdPy+BxPePwp/78346W8RdLkAV3fzuMPLOpagTKx8uBb/wtP4yZOgRi2CC/vhdt8v7rCM2SjXuDlB3+H4lybjn55E+EVP3KndcXsfFHdoWcUSlImN/3F+VIL96//B7v8g6HIhrm69uMMypkxcXh7uyH/hd90rupq67xb89LdY22tA3KFlDVt4yqScD0PCl58lHNIbFszBnXMpwQX9LDmZjOQaNyfoNxx3UleYOZ1fenfBf/xu3GFlBbuCMinlf1lEeP8o+GIm7Lx7NBBicyvBbjKbC9ZdTe1NMH4ka+4Yijv8WNyJXa1QYgVYgjIp4b2PavLoWPBWgt1kJ9e4GfWHjeGne26J6k99NYug+xVWm2wTWYIylc7/9gvhxDtg5gewwy5RCfaCRnGHZUylcFWqEnQ+D7/jroTjbyO87hLc6RcS7HtI3KFlHEtQptJ47/HvvYF/6B5YswrX+Tzcof+0mjsmJ7i2+xBcO5Lw3lvwY28l/HxGNNKveo24Q8sYlqBMpfBLlxA+eBd8+N+ofEG3Prgtm8YdljEp5epvQXD5UPyzj+D/T/HffknQcwCuoXX5lYX9KWuSzn/0DuHAnvDJe7h/nUVw5TBLTiZnubw8gk5dCPoMhqW/EQ69DP/p9LjDygiWoEzS+D//IBw7gvDOG2DzBgRXjyA46kRcXl7coRkTO9emLcFVt0D9hoS3DSF87nGydKm5pLEuPpMU/tMPCSfcDr8vxh3bGXe0WAl2Y4pwW2xJ0G84fsLt+CcnwvdfQ7eLcdWqxx1aWrL/QUyF+BXL8I/dj3/jeWjcPOpfb7Ft3GEZk7Zctepw3uXQYhv8ExPxC+cS9BiA22LLuENLO5agzCbzX8yMJt3++hPuyBNwnbpUuAS7MbnAORdN7G3WinDMTYTXX0pwUX/cDrvEHVpasQRlys2vXIl/aiL+5WegYWOCK2+0Am6VQEQaAkcCuwH1gN+AGcCLqrowzthMcrid2hEMuIVw9PWEIwbiuvYi2PfQuMNKG2VOUCLSnCIniqrOqazATHryX/8vumr6cV40p+nEs6z/PMlEpDVwHXAoMJ2oyOdCoA5wBjBSRF4FrrXinZnPNWxM0G844Z034seOIPz5R9w/T7FVViglQYlIFeD8xM/WwGxgKdGJsq2IfAvcDYxR1VWVHKuJkV+9Gv/Mw/hpT0Yj9C69Dtd6t7jDylbjgZuALqq6suiLIlINOA4YC/wjtaGZyuBq1iboMwg/YTR+8kPw8yI4/aKcH2hU2r9+BvAKUYJ6V1XXrntBRPKAvYEuwEfAThs7kIh0BEYBecB9qjqsyOtdiU7KeYlNo1X1vsRrZwFXJ7Zfr6oTSv2XmaTxP3xNOG4kzPs+Wj9PzsHVqBl3WFlLVfcp5fWVwGOJH5MlXH4VOLsPFDSKJvYu/jla5T+Hz7XSEtQhqrqouBcSyept4G0R2WJjB0kkszuAI4C5wPsiMqWY7olHVbVnkffWBwYCewIemJ547+JSYjcV5NeswU97HP/so1C7LkGva3C77hV3WDlFRCaraqditj+pqv+KIyZTeZxzuE6nERY0xD9wB+HwvgS9r8XV3+h/sVlroxN1CycnEbm8uH1E5FJV/amUz9kbmK2q3yS6Ah8BNjjpSnAk0U3hXxNJ6UWgYxnfazaRn/8D4bAr8ZMfwu1xAMHg0Zac4lHSHfNDUhmESa1g//YEvQfCrz8R3nglfv4PcYcUi/J0cF4L3FzM9quBW0t5b1Og8ICKuUBx3RgnishBwJfAJYlBGMW9d4N1c0SkO9AdQFUpKCgoNpD8/PwSX8slJbWDX7uWZc8+yh+TxuCq16DuFddTfb/DYogwNdL1+yAiQxIPqxZ6vM7WwPcpDsmkmGvTluDKGwlHDiK8qT/BxYNwLbeLO6yUKjVBici6/53yRORQoPDQkq2JBk0kwzPAw6q6UkTOByYAZf6fUVXHAGMST/3PP/9c7H4FBQWU9FouKa4d/KL5hPffBrNnQdt9cGdcxB91N+ePLG6vjX0fmjSJdUHP5onfQaHHEHVzzwEGpTogk3quWasoSd16LeEtVxP0vAa3w85xh5UyZbmCGpv4XR0YV2i7Jxr62qsMx5jH+idZM/4eDAGAqv5S6Ol9wL8LvfeQIu99rQyfacrIhyH+9efwj4+HvHxctz64fxxqw1xjpKrdAETkv6p6b9zxmPi4hk0I+g4nHHEt4ahBBOf3xe2WG93tpSYoVW0FICITVfXMTfyc94HtRKQVUcLpDJxWeAcRaayqCxJPjyOa+wHwPHCDiGyeeN4B6L+JcZgi/C8/EU64DT6fAW3aEZzVC1c//bq8comINFLVHwE2lpwK72eym9u8AcEVNxKOGkR41w24bn0I9jk47rAqXZnvQVUgOaGqa0SkJ1GyyQPGqepnib71D1R1CtBbRI4D1gC/Al0T7/1VRK4jSnIAQ1T1102NxUS894RvvYR/9D4IQ9wZF+EOPNKumtLDKyLyOvAA0fSOcN0LIhIQDTo6EzgIqHB/T2lTQEx6cHXqElx2PeHo66MCiMuXERxyVNxhVSq3seXeReR9oq62ycVNxBWRqsDxwGWlzd1IMT9//vxiX7B7UOB/+5X8R+9l1QdvwfY7RyXYc3ShyjLcg0p5xk6cV92BC4BWwDf8PUG+FdGE+XuAsRWdIJ+YAvIlhaaAAKeWskJFseeXnVuRym4Hv2ol4T3/hk/ex53UleDI9JxtkIxzq7QrqLOAIcBdIvIh8AV/nyjbA7sTTeTtWtagTbzC99/ET7qbVatX4k45F3fYMVaCPc0kks5oYHRiibFdiJYYWwx8oqrzNvb+cvprCgiAiKybAmJLKKUpV7UawYX98eNG4B8fT+g9QccT4w6rUmw0QSX+ijpJRLYk+gtrF6CA6ESZCJxR0kRek1780t/xk+7CT38LWm1Pg8sG81u1WnGHZUqRmGpRmWtelnUKiEkjLj8fzrkUAP/EBEIPwVHZl6TKdA8qsXLyA5Uci6kk/uN3CCfeAcv+xP3rTFyHE8hv1AisOybtJdbduxY4FWigqpuJSAdge1UdncI4Sp1nmK5zylItle3g+w7l91HXseLJCdSoWYNaJ27yUIGkS0Y7lLZY7EGq+kbicYlzklT1lQpFYSqFX/YH/pF78W+/Cs1bEVw6BNesVdxhmfIZQXSV0wV4LrHts8T2ZCSoUqeAQNnmGdo9qEiq28F3uQi3chV/PHg3fy5bRnDUSSn77I1JxhzD0q6g7uTvUUJjS9jHE03YNWnEf/ZRVIJ9ya+4Y07B/VOixShNpjkB2FZV/xSREEBV54nIBqupbKJSp4CY9Oby8qJFZgH/5MTontTRJ8ccVXKUdg9q50KP7U/vDOBXLMc/fj/+9WlRCfYLb8K1yq3lUbLMKoqcp4nFmX8pfvfyKWkKSDKObVJnvST11ANRkvqnxBxVxW1ysZHEskdr13UBmvj5Lz+Nign+sgjX4QTc8VaCPQs8BkwQkUsgmtAOjCRacDkpVHUqMDVZxzPxcHl5cE4iST39IGGVqgQdjo85qoop8/hiEXldRPZPPO5LdII8LCJXVVZwpmz8qpWEj44lvHkAOEdwxY0EJ3ez5JQdrgK+BWYSDTX/CphPNP3DmPW4IA93Th/YYz/8Y+MI33wh7pAqpDxXUDsD7yQen0dUBmAp8BZwQ5LjMmXkv/mC8P6RsHAe7pCjoxLs1WvEHZZJksScqEuASxJdez+rasmz603Oc0EewbmXEa5cEdWUql6DYK8D4w5rk5RnhmYAeBHZBnCqOisxR2PzUt5nKoFfvZrwqQcIh/WFVSsJLhlC0OUCS05ZRkT+WtZLVX9al5xExOYfmhK5/CoEF/SHbVvjx96Kn/F+6W9KQ+VJUP8hGtZ6M/AUQCJZ2bjSFPNzviW84TL81Mdw+x1KMPB2XJu2cYdlKscGQy9FpArRgAZjSuSqVSPodS00a0V49zD8/z6JO6RyK08XX1fgMmARcFNi245Ei0yaFPBr1+KnPYF/5hGoVZug59W43faOOyxTCUTkTaIpHNVFpOhApGbA26mPymQaV6MmQZ9BhDddRTh6aDQXcusd4g6rzMqToJYCa4HTgStEZD7wKHB9ZQRm1ucXzCEcNxK++wq35wG4LhfgateNOyxTee4jWkxzL9afg+iBH4GX4wjKZB5Xuy7BJUMI/92PcNRggiuGZsyE/fIkqLuIFojtRVRuugXRCKMmwNnJD80A+HAt/qVn8E89ANWq47pfkbE3PE3ZqeoEABE5HfhKVf+77jUR2Y+oq71PTOGZDOPq1U8kqf6EIwcR9Ps3rqBR3GGVqjwJ6nhgG1X9LfF8loi8S7T0vyWoSuB/WhiN0PtqFuy2N8EZPXCb2ZiUHLMb8EGRbdOBp7EEZcrBbbElwSWDCYf3jSrz9h2e9r0w5RkksRCoWWRbDWBBMfuaCvDeE772HOHg3jD3O1y3iwl6DLDklJs8Gw6IyKN8564xALgmWxH0vAZ+XkR4+3X4lSvjDmmjynMF9QAwTURuJ1qSvznQA5hYeCHZkhaOLa1qp4hcCpxLVFH3J+BsVf0+8dpaoomKAD+o6nHliDuj+F9/itbQm/UxtGmbKMG+Rdxhmfi8CVwnIleqapioqDsosd2YcnPbtSE47zLCu4cT3nsTwYX9o1Uo0lB5EtT5id9FV464IPEDJSwcm6jaeQeFqnaKyJQiVTs/AvZU1WUiciFRJd9TEq8tV9WsHkftvce//Qr+kXujEuxdLsQd3NFKsJuLgWeBBSLyPbAVUa/FsbFGZTKa230/3Knn4x+6Gz/pLjijR1r+X1PmBFXBxWJLrdqpqq8W2v8dotGCOcEvWUz4wB0w4z3Ytg1Bt4txDRvHHZZJA6o6V0R2JzqHmhMVF3xPVcN4IzOZLjj0aMLffsFPfQzqNcAdd2rcIW1gkxeLLafyVu08h79r30A0F+QDou6/Yar6dPJDjEf4/n+iv2BWrsCdfDau/bG4ID0vt008EsnoHf5easyYpHDHnw6Lf8E/8zBhvfoEBx0Zd0jrSVWCKrPEsNo9gYMLbW6RqIGzNfCKiMxU1a+LvK/Uip+QPlU/w9+X8Pu9N7PyPy+Tv21rNut9DfnNW6bs89OlHeJm7WBymXMOzuyJX/ob/sG78PXq43bdK+6w/pKqBFWmqp0i0h4YABysqn8NL1HVeYnf34jIa0A7YL0EVZaKn5AeVT/9jPeiLr0/luKOP52w44n8lpeX0hLs6dAO6SAZVT+NyWQuP5/g/L7RahNjbiboOwzXPD0m8qZqqOpfVTtFpCpR1c4phXcQkXbAPcBxqrqo0PbNRaRa4nEBsD+F7l1lEr/sT8LxowhHXw91NiMYcAvBPyVtR9AYY3KDq16DoOfVUKNmNPz8t19Lf1MKpCRBqeoaYF3Vzs+jTfqZiAwRkXVDxm8CagOPicjHIrIugbUGPhCRGcCrRPegMi5B+VkfEw7uhf/vq7ijTyYYcEva/JVijDFu8wYEva6GZX8Qjr4+LeZIOe+zsrSMnz9/frEvpLpry69cgX98PP61qbBlU4JufdJisUbr4ouUoYsv/cbexq/Y88u+U5FMbwc/4z3CO4ZCu30Jzu+LCzbtOiYZ55bNRq9E/qtZhIN7419/Dte+E8E1I9MiORljTEncbnvjTj4bPnw7WgM0Rmk3ii8b+NWr8E8/iH9xMjRoSHD5UNz2O8cdljHGlIlrfxz8OA8/7QnCho0JDuwQSxyWoJLMf/tVtMDrgjnRShAndbMqt8aYjOKcg87d8T/9iJ90F76gEa71bimPw7r4ksSvWU04eRLhsCtgxXKCPoMJTr/IkpMxJiNFw8+vhIZNooq8i4q/r1+ZLEElgZ/7HeENl+OffRS3zyEEg27D7dQu7rCMMaZCXM1aBL2ugSAgHD0Uv3xZSj/fElQF+LVrCac+Rnj9pfDbrwQ9riI4uw+uZu24QzPGmKRwW2xJ0P1K+HEe4dhb8WHqloG0BLWJ/MK5hMP74p96ANd2H4LBd+Da7ht3WMYYk3Su9W44ORdmvId/5uGUfa4NkignH4b4V57FPzkRqlazEuzGmJzgDvsnzPkG/+yj+GYtcXvsX+mfaQmqHPxPC6Nigl/MhF33ikqw16sfd1jGGFPpnHPQ5UL8gjmE40YSNGqCa1a5q+FYF18ZeO8J35hGOPhi+OFrXNfeBD2vtuRkjMkprkoVggv7Q81a0aCJpb9X6udZgiqF//VnwlGD8A/cCVtvTzDwdoL926dl9UljjKlsrl59gouugiWLCe8Zjl+zptI+yxJUCbz3hG+/SjioF3w1C3faBQR9BuMabBF3aMYYEyvXanvcGT3gi5n4x8ZV2ufYPahi+N8XEz5wJ3z8bqIEe29cQ6sNZIwx6wT7HUY45xv8S1MIt96BYJ+DS39TOVmCKsJPf4vwwbtgxXLcyd1w7Y+zEuzGGFMMd2JX/Hez8RNHRyP7mrZI6vGtiy/B/7mU8N6bCe8eHi3wes0Igg4nWHIyxpgS/LUcUo2ahHfeiF/2Z1KPbwkK8J+8TziwF376W7hOpxH0+zeuyVZxh2WMMWnP1asfrTTx80LC+0eRzBqDOZ2g/PJlhONvI7z9Oqhdh+CqmwmO6YzLt55PY4wpK7f9TriTu8HH7+CnPZm046bsf2IR6QiMAvKA+1R1WJHXqwETgT2AX4BTVPW7xGv9gXOAtUBvVX2+ovH4z2cQjr8NFv+CO+ok3LGn4qpUqehhjTEmJ7nDj4NvvsQ/9QC+5bZw4OEVPmZKrqBEJA+4AzgKaAOcKiJtiux2DrBYVbcFRgDDE+9tA3QGdgI6AncmjrdJ/IrlhA/dQ3jrNVClKkHfYQT/OtOSkzHGVIBzDndmT9iyKeG9N7P25x8rfMxUdfHtDcxW1W9UdRXwCNCpyD6dgAmJx48Dh4uIS2x/RFVXquq3wOzE8crNz/6cXy49C//q/+EOPzYqwb7Njpv0DzIm04nIySLymYiEIrJn3PGYzOeq14hWmli1iiU3XY1fvbpCx0tVF19TYE6h53OBfUraR1XXiMgSoEFi+ztF3tu06AeISHege+L9FBQUbBDE4rsns3btWja/bjRVd9590/81WSA/P7/YNso1Od4OnwL/Au6JOxCTPVzjZgTdLmb1mJsIvpgJFfi/NmtGA6jqGGBM4qn/+eefN9jHn3YBDRo35tc/l0Mxr+eSgoICimujXLOxdmjSJLsnZ6vq5wAiEncoJsu4PfajweiH+a1K9QodJ1VdfPOA5oWeN0tsK3YfEckHNiMaLFGW95aJq1uPoEatTXmrMcaYcshv3Kzix0hCHGXxPrCdiLQiSi6dgdOK7DMFOAt4GzgJeEVVvYhMAR4SkVuBJsB2wHspituYjCYiLwFbFvPSAFWdXI7jlNqFnuPdpX+xdogkox1SkqAS95R6As8TDTMfp6qficgQ4ANVnQKMBR4QkdnAr0RJjMR+CswC1gA9VHVtKuI2JtOpavskHafULnTrNo5YO0SS0X3ukjnrN41k5T/KxCLr66qIyGvA5ar6QRnfYueXSYZSz61sXUnClfQjItM39nqu/Fg7lLkdspaInCAic4F/AP8nImWdAG/fqYp9p3LiJxnnVtaM4jPGlI+qPgU8FXccxpQkW6+gjDHGZLhcTFBjSt8lJ1g7RKwdksfaMmLtEKlwO2TrIAljjDEZLhevoIwxxmQAS1DGGGPSUk6N4iutJlW2EpFxwDHAIlXdObGtPvAo0BL4DhBVXRxXjKkgIs2Jao41IprLM0ZVR+ViWySbnVt2blEJ51bOXEGVsSZVthpPVEursH7Ay6q6HfBy4nm2WwNcpqptgH2BHonvQC62RdLYuWXnFpV0buVMgqJsNamykqq+QbR8VGGF629NAI5PaVAxUNUFqvph4vFS4HOi0i051xZJZufW+nLu+1RZ51YuJajialJtUFcqhzRS1QWJxwuJLs1zhoi0BNoB75LjbZEEdm6tL6e/T8k8t3IpQZkSqKonh9ZXE5HawBNAH1X9vfBrudYWpnLl2vcp2edWLiWopNWVyhI/ikhjgMTvRTHHkxIiUoXoBJqkqk8mNudkWySRnVvry8nvU2WcW7mUoP6qSSUiVYnKeUyJOaY4rau/ReJ3mWsDZSoRcURlXT5X1VsLvZRzbZFkdm6tL+e+T5V1buXUShIicjQwkr9rUg2NOaSUEJGHgUOAAuBHYCDwNKDAVsD3RMM/i97szSoicgDwJjATCBObryLqK8+ptkg2O7fs3KISzq2cSlDGGGMyRy518RljjMkglqCMMcakJUtQxhhj0pIlKGOMMWnJEpQxxpi0ZAnKGGNMWrIEZYwxJi39P/YIBx9+w2CFAAAAAElFTkSuQmCC\n", "text/plain": [ "
" ] }, "metadata": { "needs_background": "light" }, "output_type": "display_data" } ], "source": [ "#plot trajectory\n", "plt.subplot(2, 2, 1)\n", "plt.plot(x_bar[0,:],x_bar[1,:])\n", "plt.plot(np.linspace(0,10,T+1),np.zeros(T+1),\"b-\")\n", "plt.axis('equal')\n", "plt.ylabel('y')\n", "plt.xlabel('x')\n", "\n", "plt.subplot(2, 2, 2)\n", "plt.plot(x_bar[2,:])\n", "plt.ylabel('theta(t)')\n", "#plt.xlabel('time')\n", "\n", "plt.subplot(2, 2, 3)\n", "plt.plot(x_bar[3,:])\n", "plt.ylabel('psi(t)')\n", "#plt.xlabel('time')\n", "\n", "plt.subplot(2, 2, 4)\n", "plt.plot(x_bar[4,:])\n", "plt.ylabel('cte(t)')\n", "\n", "plt.tight_layout()\n", "plt.show()" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "The results are the same as expected" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "------------------\n", "\n", "the kinematics model predictits psi and cte for constant heading references. So, for non-constant paths appropriate functions have to be developed.\n", "\n", "-----------------" ] }, { "cell_type": "code", "execution_count": 9, "metadata": {}, "outputs": [], "source": [ "def calc_err(state,path):\n", " \"\"\"\n", " Finds psi and cte w.r.t. the closest waypoint.\n", "\n", " :param state: array_like, state of the vehicle [x_pos, y_pos, theta]\n", " :param path: array_like, reference path ((x1, x2, ...), (y1, y2, ...), (th1 ,th2, ...)]\n", " :returns: (float,float)\n", " \"\"\"\n", "\n", " dx = state[0]-path[0,:]\n", " dy = state[1]-path[1,:]\n", " dist = np.sqrt(dx**2 + dy**2)\n", " nn_idx = np.argmin(dist)\n", "\n", " try:\n", " v = [path[0,nn_idx+1] - path[0,nn_idx],\n", " path[1,nn_idx+1] - path[1,nn_idx]] \n", " v /= np.linalg.norm(v)\n", "\n", " d = [path[0,nn_idx] - state[0],\n", " path[1,nn_idx] - state[1]]\n", "\n", " if np.dot(d,v) > 0:\n", " target_idx = nn_idx\n", " else:\n", " target_idx = nn_idx+1\n", "\n", " except IndexError as e:\n", " target_idx = nn_idx\n", "\n", "# front_axle_vect = [np.cos(state[2] - np.pi / 2),\n", "# np.sin(state[2] - np.pi / 2)]\n", " path_ref_vect = [np.cos(path[2,target_idx] + np.pi / 2),\n", " np.sin(path[2,target_idx] + np.pi / 2)]\n", " \n", " #heading error w.r.t path frame\n", " psi = path[2,target_idx] - state[2]\n", " \n", " # the cross-track error is given by the scalar projection of the car->wp vector onto the faxle versor\n", " #cte = np.dot([dx[target_idx], dy[target_idx]],front_axle_vect)\n", " cte = np.dot([dx[target_idx], dy[target_idx]],path_ref_vect)\n", "\n", " return target_idx,psi,cte\n", "\n", "def compute_path_from_wp(start_xp, start_yp, step = 0.1):\n", " \"\"\"\n", " Interpolation range is computed to assure one point every fixed distance step [m].\n", " \n", " :param start_xp: array_like, list of starting x coordinates\n", " :param start_yp: array_like, list of starting y coordinates\n", " :param step: float, interpolation distance [m] between consecutive waypoints\n", " :returns: array_like, of shape (3,N)\n", " \"\"\"\n", "\n", " final_xp=[]\n", " final_yp=[]\n", " delta = step #[m]\n", "\n", " for idx in range(len(start_xp)-1):\n", " section_len = np.sum(np.sqrt(np.power(np.diff(start_xp[idx:idx+2]),2)+np.power(np.diff(start_yp[idx:idx+2]),2)))\n", "\n", " interp_range = np.linspace(0,1,section_len/delta)\n", " \n", " fx=interp1d(np.linspace(0,1,2),start_xp[idx:idx+2],kind=1)\n", " fy=interp1d(np.linspace(0,1,2),start_yp[idx:idx+2],kind=1)\n", " \n", " final_xp=np.append(final_xp,fx(interp_range))\n", " final_yp=np.append(final_yp,fy(interp_range))\n", " \n", " dx = np.append(0, np.diff(final_xp))\n", " dy = np.append(0, np.diff(final_yp))\n", " theta = np.arctan2(dy, dx)\n", "\n", " return np.vstack((final_xp,final_yp,theta))" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "test it" ] }, { "cell_type": "code", "execution_count": 10, "metadata": {}, "outputs": [], "source": [ "track = compute_path_from_wp([0,5],[0,0])\n", "\n", "u_bar = np.zeros((M,T))\n", "u_bar[0,:] = 1 #m/s\n", "u_bar[1,:] = np.radians(-10) #rad/s\n", "\n", "x0 = np.zeros(N)\n", "x0[0] = 0\n", "x0[1] = 1\n", "x0[2] = np.radians(0)\n", "_,psi,cte = calc_err(x0,track)\n", "x0[3]=psi\n", "x0[4]=cte\n", "\n", "x_bar=np.zeros((N,T+1))\n", "x_bar[:,0]=x0\n", "\n", "for t in range (1,T+1):\n", " xt=x_bar[:,t-1].reshape(5,1)\n", " ut=u_bar[:,t-1].reshape(2,1)\n", " \n", " A,B,C=get_linear_model(xt,ut)\n", " \n", " xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n", " \n", " _,psi,cte = calc_err(xt_plus_one,track)\n", " xt_plus_one[3]=psi\n", " xt_plus_one[4]=cte\n", " \n", " x_bar[:,t]= xt_plus_one" ] }, { "cell_type": "code", "execution_count": 11, "metadata": {}, "outputs": [ { "data": { "image/png": "iVBORw0KGgoAAAANSUhEUgAAAagAAAEYCAYAAAAJeGK1AAAABHNCSVQICAgIfAhkiAAAAAlwSFlzAAALEgAACxIB0t1+/AAAADl0RVh0U29mdHdhcmUAbWF0cGxvdGxpYiB2ZXJzaW9uIDMuMC4zLCBodHRwOi8vbWF0cGxvdGxpYi5vcmcvnQurowAAIABJREFUeJzs3Xd4FNX6wPHvmSSEXoP0JqCAIIgKYkOuqNhARV+KKCiKDRDsoNIUxXKpgspFiijisSF6VVSE++NexYqoWAFFAWmC0pQ25/fHLBpiQhKy2dndvJ/nycPu7Mzsu4dM3p1TjXMOpZRSKt54YQeglFJKZUcTlFJKqbikCUoppVRc0gSllFIqLmmCUkopFZc0QSmllIpLmqCUUkrFJU1QSiml4pImKKWUUnEpNewAColOj6GixYQdQJzRa0tFS67XVrImKNauXfvn44yMDDZt2hRiNIUrmT9fmJ+tevXqobxvfolIB2AckAJMsdaOyvJ6OvAkcCzwC9DFWvtD5LVBQG9gH9DfWjsvt/fLfG1llsy/h/mh5RA4WDnk9drSKj6lEpiIpAATgbOBJkA3EWmSZbfewBZrbQNgDPBA5NgmQFfgKKADMClyPqXigiYopRJbK2C5tXaltXY3MBvolGWfTsCMyOPngdNFxES2z7bW7rLWfg8sj5wv39zH/2Pvz6sP6QMolZOkreJTqoioAfyU6flqoHVO+1hr94rIb0ClyPbFWY6tkfUNRKQP0CdyPBkZGQe87nbtYtOzU9g8bRyle95AibMuxHhF97tvamrq38qoKIpGOWiCUkodlLV2MjA58tRl265wx4OkzXqMbZP/ybZFb+P17I+pVDmWYcYNbYMKaBuUUmoNUCvT85qRbdnuIyKpQDmCzhJ5OTZPTMXKlB86FtPjelj5Df7wfvj/extdb04VhCYopRLbh0BDEaknIsUIOj3MzbLPXKBn5PHFwDvWWhfZ3lVE0kWkHtAQ+OBQAzHG4LXtgDd0PNSqh5s+Hv+Re3G/bj7UU6oiThOUUgnMWrsX6AvMA74KNtllIjJCRDpGdnsCqCQiy4GbgDsixy4DLPAl8AZwg7V2X0FjMpWr4t08EtOlN3y1FH9YP/z3/6N3UyrfTJL+0jgdB5Uc4mAclA7UPZDLzzgot241/tSx8P23cOyJeJdehylTLhZxhiaZr8f8yEMbVK7Xlt5BKaUKjalaE+/2BzAXXQ5LP8Af2hf3yXthh6UShCYopVShMikpeGdfjHfXGKhQCf/R+/GfGI3bsT3s0FSc0wSllIoJU6MO3qCHMed3xX24CH9YX9znH4cdlopjmqCUUjFjUlPxOnbHG/QwlCyNP344/pOP4H7fGXZoKg5pglJKxZypUx/vrjGYDp1x/30bf1g/3FdLww5LxRlNUEqpUJi0NLzOPfFuHwWpafij78af9Thu1x9hh6bihCYopVSoTP1GeEPGYU4/H7fg3/gjbsQt/zLssFQc0ASllAqdSU/H63o13i0jYd8+/AcH4T83Dbdnd9ihqRBpglJKxQ1zZDO8YeMxp5yJe/Ml/HsG4r7/LuywVEgSIkGJyFQR2SAiX4Qdi1KqcJniJfEuuwHvxqHw+078Ubfiv/w0bu+esENTMZYQCQqYTrDip1KqiDBNj8UbPgHTui3u1Wfx77sFt/r7sMNSMZQQ60FZa/9PROoeyrFuxdfsfP9n/O07st/B8yA9HZNeHNKLQ7HIv+npULIUlC6L8XQVbKXCYEqWxlw5ENeyDf6TE/HvvRlzfldMh86YFL0uk11CJKi8yGnVz+3zlrHt+RkHOxSAHKfMNQZTphxeuQqklK+IifzrVaxMStXqpFQJfrxSZaL0SfIvmVfwTObPpvLOtDgBr34T3KzHcHOewi39AO+KAZhqNcMOTRWihJnNPHIH9aq1tmkedv9zxmW3axeVypTml82/ZL+nvw927YJdf/z1s/sP3K5dsHM7bP0Ntv2K2/orbPvtz+dkHflesjRUrgoZh2Gq1cLUqAM16sJh1Qr9m14yz56ss5nHnXzNZl4Y/A8X4Z5+DHbvwlzQA9P+/Liq5Ujm6zE/ojGbedLcQeXEpKfjlS2H2Z2/BtbcSs7t3AGb1sOmdbhN62HjetymdbB6Fe6TxTjnBzumpkH1SMKqWRdTtyHUaYhJTz+kz6NUUecdfwruiKb4MyfinpuKW7IY74obMYdVCzs0FWVJn6AKiylZCmofDrUP/1syc3t2w88/4VavgjWrcGt+CKZxeW9BUJWYkgI162EOPwIOb4Sp3wgyqmCMfllXKi9MuQp4N9yJe28Bbva/8If3x1x8BaZtB4yXKH2/VG4SIkGJyDPAaUCGiKwGhlprnwg3qpyZtGJQuz6mdv0Dtrttv8HKb3Erv8at+Br37juw4LUgaZUtj2l0NDRpgWncAlNR212UOhhjDObEf+AaHY0/Y0LQPrXkPbye/TGVKocdnoqChGmDyqeEWFHX+ftgzY+4FV/Dd1/ivvo0aOcCqFojSFRNWkCjZpjiJXM8T7x+vmjQNqiciUhF4FmgLvADINbaLVn2aQE8CpQF9gEjrbXPRl6bDrQFIr909LLWfprL24beBpUd5xxu0TycnQaewUhvzEntQ6mVSObrMT+0DSrBGS8FatXD1KoHp52Ncw7W/ID7cinuq09x/3sLt+DfkJoKjZpjjjkB06IVpmyFsENX8eEOYL61dpSI3BF5fnuWfXYCl1trvxOR6sDHIjLPWvtr5PVbrbXPxzDmQmGMwZzaAde4Bf708bgZE3CfvId3eV9M+Yphh6cOkSaoOGKMCdqmataDMy/A7dkDK7/GLf0At2QxbuZE3FOToH5jzDGtMce0wVSuGnbYKjydCKq+AWYAC8mSoKy132Z6vFZENgCVgV9JQqZyVbyb78W98yruxSfxh/bFdL8G0+pUbeNNQJqg4phJS4Mjm2GObIa75Mrg7uqTxbhPF+Oem4Z7bhrUbcjO9ufhmrTElCkXdsgqQkQygMuBc4HmQDmCqrSlwOvADGvtxgK+TRVr7c+Rx+uAKrnE1AooBqzItHmkiAwB5gN3WGt3ZXNctmMMs4qrMWtdr2TvKaezdfy97JnyT4ot+4Sy19yCV67wax/iqhxCFI1y0DaoBOU2rsMteQ+3eCH89H3QM7DpsXgnnAbNWwUdNZJAIrZBicgo4FLgNeA/wFfANqAM0Jig3ecc4Glr7R25nOttILvb5DsJklz5TPtusdZm+xdYRKoR3GH1tNYuzrRtHUHSmgyssNaOyOXjxWUbVE6cvw83bw5u7tNQohRej+sxLdsU6nvGYzmEQdugijBTuSrmzAvhzAspt+M3trz+Iu79/+Av/QBKlMIcfzKm7dmY2oeHHWpRtBpokN3dCLAEmCUixYGrcjuRtbZ9Tq+JyHoRqWat/TmSbDbksF9Z4N/AnfuTU+Tc++++donINOCW3OJJNMZLwZzdGXf0cfhTx+A/ej/mhNMwXftgSpUOOzyVCx0wkATS6tTHu/gKvAeewBs4AtO8FW7xAvx7BrBv1G34ixcG7VkqJqy1j+xPTiKSUyNheWvtIwV8q7lAz8jjnsDLWXcQkWLAS8CTWTtDRJIaImKAC4CkXS3A1KiDN+hhzPndcB8uwh/WF/f5x2GHpXKhd1BJxHgpwTiqJi1wXa/GvTsft/B13BOjcfYJzMntMad2wGQctKlCRde3BF28s/oSKGj3slGAFZHewCpAAETkOOBaa+1VkW2nApVEpFfkuP3dyZ8WkcoEVS2fAtcWMJ64ZlJTMR274Zq3Cu6mxg/HnHIm5pIrMSVyHsahwqNtUEngYJ/P+T58vRR/weuw9APAYVqeiDm7M6ZOg9gGeggSsQ0qMxHZZq0tk2VbWWCltTYRW9ITqg0qJ27PHtwrs3BvvAQVKuH16o9p3Dwq506kcihM2galcmU8D5ocQ0qTY3CbN+IWvhbcVX38P2jcHK9DZ2jcXLvgRpmI/EQwSX4JEfkxy8uVgGdiH5Xaz6SlYS7qiWveGn/aOPzRd2PanYPp3CtYekfFBU1QRYipWDm4KM++BPd/b+Demos/ZkgwLVOHzphj28TVrNAJrgfBN8TXgMsybXfAemvtN6FEpQ5g6jfCu3ss7qUncfNfwX3xCd6VAzANmoQdmkKr+JLCoX4+t2cPbvEC3Bsvwoa1UK0WXqfucEybuJlwMwmq+Epaa3fmvmfCSIoqvuy4b77Anz4OftmAOaNTsJTHIQzXSPRyiJZoVPHFx18hFQqTloZ3ypl490zEu+Y2APzHHsAfeTPu849J0i8vhU5E+otIOkBOyUlE0kWkf2wjUwdjjmyKN3Qc5pSzcG/Owb9nIO7778IOq0jTKj4VVOsddzJeyza4xf/BvfIM/vjh0KAx3gWXYY7MyxqRKpOqwHIR2T9Q9xv+Gqh7BMH0RGcDT4YVoMqeKV4Sc9n1wRLzMybgj7oV0+FizPldMKlpYYdX5OgdlPqT8VLwTvwH3j2TMJdeB5vW4z88mH3jhuN+Xh12eAnDWjsYOAb4DuhNMLXRFwTtUVcCXwPHWGvvCi1IdVDmqGPwho3HtD4N95rFH3kL7qfvww6ryNE2qCRQWJ/P7d6FW/Aa7t/PBstrtzsv+CZZMnYj8BO9DSoJJW0bVE7cp+/jz5wIO7Zjzu8adChKybkzUbKWQ35pN3NVqEyxdMxZF+LatMO9/DRu/lzc4gVB4/EpZ2iPP1UkmBat8Ro0xs16HDfnKdyn7wc9/arVCju0pKcJSuXKlC2PuewGXNsO+M9OwT01CbfwdbxufTBHHBV2eHEtMih3GMEEsRlk+tZora0dUlgqn0zpspg+t+If0wY361H8EQMwF/bAtO+oX9QKkbZBqTwztevj3XJf0ONv53b8hwbhz5yI27k97NDi2SSgJTCCYGqjfsCPwJgwg1KHxjv+ZLxhj8BRx+Cem4b/0J24DT/nfqA6JJqgVL4YYzDHnYw3YiLmzAtwi97CH9IX9/G72i09e2cCna21LwP7Iv924cDBuyqBmHIV8G64E3PFAFizCn94f/wFrwXTiqmoSpgqPhHpAIwDUoAp1tpRIYdUpJn04phLrsS1OjXojvvYKGjRGq/7tZgKlcIOL554BAsVAmwXkXLAz0D8T4SocmSMwZz4D1yjo/FnTMDNegy35D28nv1BFyuMmqjcQYnIGBFpEY1z5XD+FGAiwdiRJkA3EdG5SOKAqdMAb/A/MZ17wrIl+EOux1/0pt5N/WUpQfsTwCKCKr9HCWY5VwnOVMzAGzAMc9n1sPJb/GF9+f3tV/X3P0qidQeVAswTkY3ATIKVQqM5cKYVsNxauxJARGYDnQiWLDioIUPK8t13qezZk7zf6tPS4uHz9cHt7gXr18DCHVB6B1SpgUkt2K9YrD9bkyZ7GDFiazRPeTV/dYy4EbgPKE+wHLxKAsYYzKkdcI1b4E8fz9aJ90Gz4/Au74spX9AVVYq2qCQoa21/ERlIcIdzKXCXiLxPMFL+RWttQVvRawA/ZXq+GmideQcR6QP0icRDRuQ2u0SJFIwxpKUl7yjwuPl8aWm4ekfg/7KBfevXwqrlpNSojVem3CGfMtafrUSJVDIy8j//2kFUtta+D2Ct3UBkFV0RaRXNN1HhM5Wr4t18L6U+WMi2mZPwh/bFdL8G0+pUXS3gEEWtDcpauw94FXhVRI4CZgHTgUmRO56h1to10Xq/bN5/MjA58tTtHyA2aFDyD5yLx8/nVv+BP+WfsGYVpm2HYFG4Q1jGIIzPtv/tIoMJC+otsl+w8A0KvmChijPG8yh5nrCj7pH408bipvwT98l7eD2uwxTgi1pRFbUEFRnvcQnBMgNHAy8A1xN0qb2ZYLqXow/x9GuAzKPiaka2qThlatbFu3N0MLDxrTm4rz/Hu+Y2TK16YYcWEyLiEVTtmciS6pm/QtcH9oYSmIoJU7UG3u2jcG/Owb38NP7QZUGSanli2KEllKgkKBF5HjgL+D/gMWCOtXZXptdv4q+eTIfiQ6ChiNQjSExdge4FOJ+KAZOWhrnkClyzY/GfGI1//62YS6/DO+n0sEOLhb0Eaz/tf5yZD4ws6BuISEXgWaAu8AMg1tot2ey3D/g88vRHa23HyPZ6wGyCBRQ/Bi6z1u4uaFwqYLwUTIfOuGbH4U8di//oKEzrtphu12BKxW66sEQWrXFQi4GG1tpzrbXPZk5OANZaH6hyqCe31u4F+gLzgK+CTXZZQQJWsWMaHY139xio3wg3fVzQLXf3rtwPTGz1CO6UVgOHRx4fHtle1lo7LArvcQcw31rbEJgfeZ6d3621LSI/HTNtfwAYY61tAGwhmNhWRZmpUQdv0EOY87vhPvov/tC+uM8/CjushBCtThIP52GfAi3aZq19jWA2aJWATNkKeAOH415+Bveaxf2wHO+62zGHRaWdJ+5Ya1dFHtaBP6v8qlhrozntQCeCpTsAZgALgdvzcmCk2vEf/FUTMYNgSqZHoxifijCpqZiO3XDNW+FPG4s/fgTm5DMw0htTomTY4cWthBmoqxKf8VIwF/bA1T8S/4kx+PfehHflQEyL1rkfnKBEpDzB2KeLgT1AKRHpCLSKwnIbmRPeOnKupSguIh8RVDWOstbOIajW+zVSOwHBnV6NHD5Dtj1ks0pNTc3xtaLkoOWQkYE7egbbZz/BzjlPY775jDJ97yT96ONiG2QMROP3QROUijlz9PF4d48JVu+ddB/mossxZ12UrF1xHyOoPqvDX+P23gP+CeSaoETkbYIFELO6M/MTa60TkZxGh9ax1q4RkcOBd0Tkc/LRJpxTD9ms4rE3aRjyVA5nX4J3RDP8aeP4dWh/TLtzMJ17HVJP13iVh+U2cqUJSoXCZFTBu/V+3PRxuBdmwLrV0OP6ZFy19HSgurV2z/4EYq3dKCKH5eVga237nF4TkfUiUs1a+7OIVAM25HCONZF/V4rIQoLFFF8AyotIauQuSnvGxpip3wjv7rG4OTNxb8/FffFJsIxHA50kZz+dLFaFxqSnY/rcijm/K+5/8/FH343bFtVZHOLBbwTLbPxJRGoTzMdXUHOBnpHHPYGXs+4gIhVEJD3yOAM4CfjSWuuABQRVjzkerwqXSU/H63IV3i33gXP4Dw7Cf24qbo92pgRNUCpkxhi8jt0xV98C33+Hf/8tuLU/hh1WNE0BXhCRdoAnIm0IOiQ8FoVzjwLOEJHvgPaR54jIcSIyJbJPY+AjEVlKkJBGWWv3VzXeDtwkIssJ2qSeiEJM6hCYI5viDR2HOeUs3Jtz8O8ZiPv+u7DDCp0u+Z4EkuXzuZXf4E8cCXv24PW9C3PEUQm/5Hukt1x/4BqCdqgfgceBcZG7mERT5JZ8z6+CloNbtgR/xgT4bTOmw8WY87skZNV3NJZ81wSVBJLp87lfNuKPHQK/bMS75jYqn35OQieoJKQJKhfRKAe3cztu9hTce+9AzXpB21SCzcISjQSlnSRUXDGVKuPd9gD++OH4k+7jdwMcndjzqorIkUBz4IDpA6y1U8OJSMU7U7I05soBuJZt8GdOxB95M+b8rpgOnTEpRWeJeW2DUnHHlCmLd/M9cGQztk64F3/eS2GHdMhEZDDBmlA3E6yiu/+nR5hxqcRgWrTGG/4IpmUb3Jyn8Efdhvv5p9wPTBJ6B6XikileEq/fENKemsiu56fhb/sN07lnIo6VGkAwKPezsANRicmULovpcyv+MW1wsx7FHzEAc2EPTPuOGC+576Y0Qam4ZdLSKHfTcDYWS8fNexH27QXpnWhJ6nfg67CDUInPO/5k3JFH4c+chHtuGm7J+3hX3Ig5rFrYoRUaTVAqrpmUFEz3ayElFff23GBjnCepyLx7+90NTBCRYcD6zPtFJlFWKs9M2Qp41w/GLV6Ie2Yy/vD+mIuvCNZc85KvxUYTlIp7xhjochVAoiSpzEttQNBb6aoszx2Q3PUzqlAYYzBt2uEaHY3/5ATcrMdwS97D69kfU6ly2OFFlSYolRASLEnt7w9sCBbxtFleN0DnmEakko6pUAmv/1Dcojdxdir+sL6YLldhTmofr9dFvmmCUgnj70nKgFwZdxdjpqU2EJG7rbUPZd1HRO4kmDBWqUNmjMGcehauSQv86eNxMyYES8xffgOmfKWwwyswTVAqoRyYpF6GUqUw53UNOaq/E5F/RB6mRqY5ypxFDwe2xT4qlaxMRhW8m+7BLfg37sUZ+EP7Ybpfg2l1atx9gcsPTVAq4RhjQHrDzh24l2fhly6Hd9rZYYeV1f557dKBzANyHcHaTf1iHpFKasbzMKefjzuqJf70cbgp/8R98i7epddhypYPO7xDoglKJSTjeXB5X9yObUEjcekymONODjusP1lr6wGIyJPW2svDjkcVHaZqDbzb7se9OQf38tP4332J1+M6TMsTww4t3+I+QYnIJQRLUTcmGPD4UbgRqXhhUlPx+tyGP3Yo/pTReCVLY5q0CDusA2hyUmEwXgqmQ2dcs+Pwp47Ff3QUplVbTPc+mFJlwg4vzxKh4/wXwEXA/4UdiIo/Jj0dr+9dULUG/qT7cT/oEgVK7Wdq1MEb9BCmY3fcx//FH9oP99mHYYeVZ3GfoKy1X1lrvwk7DhW/TKnSeAOGQekyuP+8EXY4SsUVk5qKd35XvEEPQ+ky+BPuCXr8/b4z7NByFfdVfErlhSlfCe+OB6BMYjYGK1XYTJ36eHeOxr0yC/fGS7ivluL16o9p3Dzs0HIUFwlKRN4Gqmbz0p3W2jwtQy0ifYA+ANZaMjL+WmU7NTX1gOfJJpk/X74+W5KWQU5EpCLwLFAX+AEQa+2WLPu0A8Zk2tQI6GqtnSMi04G2BMvSA/Sy1n5ayGGrEJm0NMxFPXHNW+NPG4c/+m5Mu3MwnXth0ouHHd7fxEWCsta2j8I5JgOTI09d5oWykn0htWT+fHGwom48uwOYb60dJSJ3RJ7fnnkHa+0CoAX8mdCWA29m2uVWa+3zMYpXxQlTvxHe3WNxc57CzZ+L++KTYFHEBk3CDu0Acd8GpZTKUSdgRuTxDOCCXPa/GHjdWhv/jQ+q0Jn0dLwuvfFuGQnO4T84CP+5qbg9u8MO7U9xn6BE5EIRWQ20Af4tIvPCjkmpOFHFWvtz5PE6oEou+3cFnsmybaSIfCYiY0QkPeoRqrhnjmiKN3Q8pm0H3Jtz8O8ZiPs+PnrDxkUV38FYa18CEndJVaUK4GDts5mfWGudiLhs9tt/nmpAMyDzF7xBBImtGEH1+O3AiGyOzbF9N7NkbgvNj4QthxvvZlfbs9j6yH34o26j1EU9KCVXYtLSDul00SgH41yOv9OJzK1du/bPJ8ncRgPJ/fnioA0qbicyE5FvgNOstT9HEtBCa+2ROex7I3CUtbZPDq+fBtxirT0vl7c94NrKLJl/D/Mj0cvB7dyBs1Nw/5sPNesFbVO16uV+YBYHK4e8XltxX8WnlMrRXKBn5HFP4GA9XruRpXovktQQEUPQfvVFIcSoEowpWQqv1414fe+Gbb/ij7wZ/9Vncfv2xTwWTVBKJa5RwBki8h3QPvIcETlORKbs30lE6gK1gP9kOf5pEfkc+BzIAO6NRdAqMZjmx+MNm4Bp2SaY0+/+W3Frf4xtDFrFl/iS+fNpFV/c0Sq+XCRjObiP/ov/9KPwxx+YC3pgzuiI8Q6+ILRW8SmllCp05riT8YY/Ak2PxT0/Df+hwbgN2X9RiSZNUEoppXJlylbAu34Q5sqBsOZH/OE34r/zKs73C+09NUEppZTKE2MMXpt2eMMmQMMmuGcm448ZgvtlQ6G8nyYopZRS+WIqZuDdOAxz2fXw/Xf4w/rhL3qTaPdp0ASllFIq34wxeKd2wBs2Huo0wD35CP74Ebhff4nae2iCUkopdchMRhW8m+7BdO0D336OP7Qv/uIFUbmb0gSllFKqQIzn4Z1+Ht6Q8VCtFu6JMfz2wGDc1l8LdF5NUEoppaLCVKmOd9v9mIt7sXvpB7ClYOPB4n6yWKWUUonDeCmYsy6iYseubN5VsKU79A5KKaVU1Hllyhb8HFGIQymllIo6TVBKKaXiUtJOFht2ACpp6GSxB9JrS0VLkZ0s1mT+EZGPs25Lpp9k/nxx8NnUgeL5/youfrQc8lwOuUrWBKWUUirBaYJSSikVl4pKgpocdgCFLJk/XzJ/tmSj/1cBLYdAgcshWTtJKKWUSnBF5Q5KKaVUgkn6qY5EpAMwDkgBplhrR4UcUlSISC3gSaAKQdffydbaceFGFV0ikgJ8BKyx1p4Xdjwqe8l6jeWFiEwFzgM2WGubRrZVBJ4F6gI/AGKt3RJWjLGQ09+jgpZFUt9BRf7ATQTOBpoA3USkSbhRRc1e4GZrbRPgBOCGJPps+90IfBV2ECpnSX6N5cV0oEOWbXcA8621DYH5kefJLqe/RwUqi6ROUEArYLm1dqW1djcwG+gUckxRYa392Vr7SeTxNoI/5DXCjSp6RKQmcC4wJexY1EEl7TWWF9ba/wM2Z9ncCZgReTwDuCCmQYXgIH+PClQWyZ6gagA/ZXq+miT6I76fiNQFjgHeDzmUaBoL3Ab4YQeiDqpIXGP5VMVa+3Pk8TqCaq8iI8vfowKVRbInqKQnIqWBF4AB1tqtYccTDSKyv07/47BjUaogrLWOIjQ91MH+Hh1KWSR7gloD1Mr0vGZkW1IQkTSCX4anrbUvhh1PFJ0EdBSRHwiqjP4hIk+FG5LKQVJfY4dovYhUA4j8uyHkeGIih79HBSqLZO/F9yHQUETqEVw0XYHu4YYUHSJigCeAr6y1o8OOJ5qstYOAQQAichpwi7W2R6hBqZwk7TVWAHOBnsCoyL8vhxtO4TvI36MClUXSD9QVkXMI2jNSgKnW2pEhhxQVInIysAj4nL/aaQZba18LL6roy5SgtJt5nErWaywvROQZ4DQgA1gPDAXmABaoDawi6FqdtSNFUsnp7xFBO9Qhl0XSJyillFKJKdnboJRSSiUoTVBKKaXikiYopZRScUkTlFJKqbikCUoppVRc0gSllFIqLmmCUkopFZc0QSmllIpLyT7VkcpEROoTTE3T3lr7iYhUB5YCl1hrF4YanFJKZaEzSRQxInI1MBA4DngJ+Nxae0u4USml1N9pFV+NSnIjAAAgAElEQVQRY639F7CcYI6sasCd4UaklFLZ0wRVNP0LaApMsNbuCjsYpZTKjlbxFTGRBcWWAguAs4FmyT7TslIqMekdVNEzDvjIWnsV8G/gsZDjUUqpbGmCKkJEpBPQAbgusukmoKWIXBpeVEoplT2t4lNKKRWX9A5KKaVUXNIEpZRSKi5pglJKKRWXNEEppZSKS5qglFJKxSVNUEoppeKSJiillFJxSROUUkqpuKQJSimlVFzSBKWUUiouaYJSSikVlzRBKaWUikuaoJRSSsUlTVBKKaXikiYopZRScUkTlFJKqbiUGnYAhURXYVTRYsIOIM7otaWiJddrK1kTFGvXrs12e0ZGBps2bYpxNPFHy+EvOZVF9erVQ4gmtkRkKnAesMFa2zQvx+i1dXBaDoGDlUNery2t4lOqaJsOdAg7CKWyk7R3UErlhfviY/zWJ4cdRmistf8nInULeh63/Et2ry2J++23v7/oeVCiFJQuA6XLYoqlF/TtVBGhCUoVSW7nDtyzU3Dvzmdn16vg9I5hhxS3RKQP0AfAWktGRsbf9tk4aAxbNq3P2wmLpeOVKRf8VMwgtXotUmrUJrV6bVKq18arVBljErfpLzU1NdsyKmqiUQ6aoFSR475cgj9jAmzZjDnnEkpd1IM/ftsadlhxy1o7GZgceeqybVe4+hYqlCrJb9ndQfk+7NyO274NdmyD7Vtx27exd8c22LiO3V98Art3/bV/enGoUh1Tuz40aIyp3wiq1EiYpKVtUIFotEFpglJFhvvjd9wL03ELX4eqNfEGPYipdwQmrVjYoSU8c/iRFMvIwBzkD3NO6cU5B1t+gfVrcOvWBP/+vBr3yXvw37eCboOlykD9Rpj6jTANGsPhjTCp+ucr2en/sCoS3Ldf4E8fD5vWY87ohLmgh7aFxAljDFTMgIoZmMbN/9zufD9IVsu/ghVf41Z+g/vswyBhlSyFOaolNG+FaXosplTp0OJXhUcTlEpqbvcu3EtP4ebPhYwqeLfchzniqLDDihsi8gxwGpAhIquBodbaJ8KNKmA8D6rVwlSrBaecCYDbsQ2++QL32Qe4zz6CDxfhPA8aHoU5+njMMSdgKlcNOXIVLZqgVNJyK7/BnzYW1q3BnHYOpnNPTPESYYcVV6y13cKOIT9MqTLQsg2mZZvgDuv7b4O7qqUf4J6bintuKhzRFHPi6ZhjT9T/7wSnCUolHbdnD+6VZ3BvvAgVKuINHIFp0iLssFSUGc/7s12KCy/DbVyH++D/cO/Ox00fh3vmccyxJ2FOPB0aNgn2VwlFE5RKKu7HFfhTx8KaVZiT2mOkN6ZkqbDDUjFgKlfFnCu4cy6BFV/h3n0H9+Ei3LvzoXJVTNuzMaecqb8PCUQTlEoKbu9e3BvP4159FkqXxet3N+bo48MOS4XAGAMNmmAaNMF1uRq35F3cordwz0/DvTobc/KZmPbnYyodFnaoKheaoFTCc2t+DNqaVi3HtDoV060PpnTZsMNSccCkp2NOaAcntMOtWoF7cw7unVdw77wSVP+dcQGmXsOww1Q5iFmCEpEOwDggBZhirR2V5fUxQLvI05LAYdba8pHX9gGfR1770Vqrw/4Vzt+He+tl3JynoHhJvGtvxxx7UthhqThl6tTHXH0zrvPluPmv4hbNw324CI5oitepO+aIPM2Vq2IoJglKRFKAicAZwGrgQxGZa639cv8+1tqBmfbvBxyT6RS/W2u1lVv9ya1fG9w1rfgajjkBr8f1mLLlww5LJQBTsTLmkitw53XBLXoT9+Yc/IcGw1HH4F3QA1NX76jiRazuoFoBy621KwFEZDbQCfgyh/27AUNjFJtKIM73cQtew704HVLTML1vwrRumzDT4Kj4YUqUxJx5Aa7t2biFr+Fefx5/5M3Qsg1ep0sx1WuHHWKRF6sEVQP4KdPz1UDr7HYUkTpAPeCdTJuLi8hHwF5glLV2TjbH5TqhJehEjvslYjns2/Azv00YyZ4vPqFYyzaUvf4OUipVLvB5E7EsVPSY9HTMWRfiTj0L99Yc3Fsv4y9ZjGl9GqZTd0xGlbBDLLLisZNEV+B5a+2+TNvqWGvXiMjhwDsi8rm1dkXmg/I0oSU6keN+iVQOzrmgKsZOBQPm8r7sPfkMtjgDUfgMRXnBQvUXU6IkpmN3XLvzcG+8gFvwb9zH/8N0uAjTobNOjRWCWI1cWwPUyvS8ZmRbdroCz2TeYK1dE/l3JbCQA9unVBJzW37BHz8cN3Mi1GuIN2wC3ilnapWeKjSmTFm8S67Au/cxTIvWuFdm4w+5Affp4mBiWxUzsbqD+hBoKCL1CBJTV6B71p1EpBFQAXgv07YKwE5r7S4RyQBOAh6MSdQqNM453OKFuNmTYe9eTPdrgoGWOhuAihFTMQPT51Zc2w74sx7Hn3gfNG2J1+VqTNUaYYdXJMTkarfW7gX6AvOAr4JNdpmIjBCRzF3GuwKzrbWZv6Y0Bj4SkaXAAoI2qJw6V6gk4LZuwZ90P27qGKheG2/oOLx252pyUqEwRzbDu3sspstVsOJr/GH98F+cgdu1K/eDVYGYJL1ldWvXrs32hURqeylM8VoO7qP/4j/9KPzxR7AkxhkdMV5Kob5nLm1QWpd4oCJ9bbmtW3AvPBlMn3RYNbye/f82O35RKIe8yMOChbleW/HYSUIVQW77Vtysx4OBk3Ua4F05QLv5qrhjylbAXHEj7sR/4E8fj//wYMw/zsNceBkmvXjY4SUdTVAqdG7pB/gzJ8L2bZhOl2LOvhiTUrh3TUoVhDmyGd7Q8biXZuLmv4L77MPgbupInY0imrRSX4XG7dyBP20c/iP3QplyeIMfxjuviyYnlRBM8RJ43frg3XIfAP7Dg4POFL/vDDmy5KF3UCoUbtkS/BkT4LfNmHMEc34XTGpa2GEplW/myKYH3E1t/nIJrvfNOgltFOgdlIop98fv+E9Nwh87FNLT8e54EO/CHpqcVEIz6cXxul6Nd+t9uH378B+4Df/Nl4JVf9Uh0zsoFTPu2y/wp42DXzZgzugU9NLT0fkqiZgjmlJx9Aw2jhmGe24a7qvPgg4/ZcqFHVpC0jsoVejc7l34zz6B//CdYAzeLffhSW9NTiopeWXK4l03CNP9Wvj6M/zhN+K+Whp2WAlJ76BUoXIrvwmWxVi3BnPaOZjOPTHFS4QdllKFyhiDaXcOrkFj/MkP4o8ZgjnnEsz53bQTUD5oglKFwu3Zg3vlGdwbL0KFingDR2Ca6JJeqmgxterh3TUG98xk3L8tbvlXeNfcplV+eaQJSkWd+3EF/tSxsGYV5qT2GOmNKVkq7LCUCoVJL47p1R//yGa4mRPx770J7/rBmDr1ww4t7mkblIoat3cv/iuz8e+7BbZvxet3N16v/pqclAK8Nu3wbh8FOPwHbsdfvDDskOKe3kGpqHBrfgzamlYtx7Rqi+neB1OqTNhhKRVXTJ0GeHeOxn/8QdwTo/FXrcBc3EvbpXKgCUoViPP34d6cg3v5aShRCu/aOzDHnhh2WErFLVO2PN7AEbjnpuLefhm3+nu8PrdhypQNO7S4owlKHTK3bg3+9HGw4mto2Qbv0uswZcuHHZZScc+kpmK69cGvUx83cxL+yJvw+t2NqVEn7NDiiiYolW/O94PlsF+cAalpmKtuxrQ6VVe5jTIROQw4C2gOlAd+BZYCb1lr14UZm4oO78TTcdVq408cif/A7UENhPZ2/VOeE5SI1CLLhWKt/amwAlPxyW1ajz99PHzzOTQ7Du/yGzDlK4UdVlIRkcbAPUA74GOCRT7XAWWAy4CxIrIAGKKLdyY+U68h3uCH8MePwB8/HHPZDXgntQ87rLhw0AQlImnANZGfw4HlwDaCC6WBiHwPPAZMttbuLuRYVYicc7hFb+LsVDBgLu+LOfkMvWsqHNOBh4BLrbV/W7ZVRNKBjsATQJvYhqYKg6lYGe+2UfiPP4CbPh5/03pMx+5F/vrK7Q5qKfAOQYJ631q7b/8LIpICtAIuBZYAR2V7hr/27wCMA1KAKdbaUVle70VwUa6JbHrEWjsl8lpP4K7I9nuttTNy/WQqatyWX/CfnABffAKNjg66jlc6LOywkpa1tnUur+8Cnov8qCRhSpbC6zcE99Qk3KvPwqb1cHk/TFrRnUg5twR1mrV2Q3YvRJLVe8B7IlL5YCeJJLOJwBnAauBDEZmbTfXEs9bavlmOrQgMBY4DHPBx5NgtucSuCsg5h1u8EDd7Muzdi+l+Dabt2RhPh8/Fioi8bK3tlM32F621F4URkyo8JjUVevaDylVxc57CbfklmNevVOmwQwvFQf/SZE5OInJLdvuIyE3W2o25vE8rYLm1dmWkKnA28LeLLgdnETQKb44kpbeADnk8Vh0it3UL/qT7cFPHQPXaeEPH4bU7V5NT7LXLYftpsQxCxY4xBu9cwfS+CVZ8hf/A7bgtv4QdVijy04tvCPBwNtvvAkbncmwNIHOHitVAdtUYnUXkVOBbYGCkE0Z2x9bIeqCI9AH6AFhrycjIyDaQ1NTUHF8rSg5WDn/87x22Pv4Q/PE7pXv2peT5yb3KbTz+TojIiMjDYpke73c4sCrGIakY8044DVehEv4j9wY9/G66B3NYtbDDiqlcE5SI/CPyMEVE2gGZW+0OJ+g0EQ2vAM9Ya3eJyDXADOAfuRzzJ2vtZGBy5KnbtGlTtvtlZGSQ02tFSXbl4LZvxc16HPfhIqjTAO/KAfxevTa/b0nu2tScfieqV68eQjR/qhX518v0GIJq7p+AYbEOSMWeObIZ3s334o8bhv/gHXgDhmFq1gs7rJjJyx3UE5F/iwNTM213BF1f++XhHGs48CKryV+dIQCw1ma+h50CPJjp2NOyHLswD++p8sEt/QB/5kTYvg3TqTvm7EuS+q4p3llrrwAQkXettf8KOx4VHlO3YdDDb/QQ/IcG4/UfiqnfKOywYiLXBGWtrQcgIk9aay8/xPf5EGgoIvUIEk5XoHvmHUSkmrX258jTjgRjPwDmAfeJSIXI8zOBQYcYh8rC7dyBe3YK7t35ULNu8Mtf+/CwwyrSRKSKtXY9wMGSU+b9VHIz1Wrh3T4Kf8wQ/NF3490wGNPkmLDDKnR5boMqQHLCWrtXRPoSJJsUYKq1dlmkbv0ja+1coL+IdAT2ApuBXpFjN4vIPQRJDmCEtXbzocai/uKWLcGfMQF+24w5RzDnd8GkFt0urXHkHRH5DzCTYHiHv/8FEfEIOh1dDpwKNC3om+U2BETFB5NRJbiTGjsUf/w9eFffkvTzXhrnXI4visiHBFVtL2c3EFdEigEXADfnNnYjxtzatWuzfUHboMD98Tvpr87m93kvQbVaeFcMwNRrGHZYocmlDSrmIyUj11Uf4FqgHrCSvwbI1yMYMP848ERBB8hHhoB8S6YhIEC3g8xQoddWLgq7HNyO7fgTRsDKbzG9+uOdmOem+pg6WDnk9drK7Q6qJzACeFREPgG+4a8L5QigJcFA3l55DVqFy33zBf70cfz+ywbMmRdiLrgUk1Ys7LBUJpGk8wjwSGSKsWYEU4xtAT6z1q452PH59OcQEAAR2T8ERKdQilOmVGm8gSPwJ47ETR+Hj8M78fSwwyoUB01QkW9RF4tIVYJvWM2ADIIL5UngspwG8qr44nbvwr00Ezf/FcioQoV7J7H1sL/11ldxJjLUojDnvMzrEBAVR0x6cby+d+E/cm8wNZID76TkS1J5aoOKzJw8s5BjUYXErfgaf9o4WL8G0+5cTOeeFKtRE7Q6Ju5F5t0bAnQDKllry4nImcAR1tpHYhSDjjHMh1iWgxs6ll/vv43dM8ZTqnQpSpx+XkzeNy+iUQ65TRZ7qrX2/yKPc6zotNa+U6AoVKFwe/bgXpmFe+MlqFApGOjXuHnYYan8GUNwl3Mp8Hpk27LI9mgkqLwMAdExhvkQ63JwfW6DifexdeL9bNu2De/kM2L23geThzaoXOV2BzWJv3oJPZHDPo5gwK6KI+7HFfhTx8KaVcGs49IbU6Jk2GGp/LsQaGCt3SEiPoC1do2IRKt+NtchICq+mWLpeDcMDqYme/IRfIibJFVQubVBNc30uOgMX05gbu9e3GvP4V6zULpcsErn0ceHHZY6dLvJcp1GJmeOyuRsOQ0Bica5VewESerOoOPEjAn4zuGdcmbYYRXYIa+oG5n2aN/+KkAVPrfmR/ypY+DHFZjWbTHd+mBKlQk7LFUwzwEzRGQgBAPagbEEEy5HhbX2NeC1aJ1PhcOkFQuS1P47qdQ0vDY5zTWcGPI8NbWI/EdEToo8vp3gAnlGRAYXVnAqb5y/D//1F/DvHQCbN+JdewfeVTdrckoOg4Hvgc8Jupp/B6wlGP6h1AFMWjG86wdDo6Nx08fhPnkv7JAKJD93UE2BxZHHVxMsA7AN+B9wX5TjUnnk1q3Bnz4OVnwNLdvgXXodpmz5sMNSURIZEzUQGBip2ttkrc15dL0q8v68kxozBH/yQ3h978I0bRl2WIckP4v7eIATkfqAsdZ+GRmjUSGX41QhcL6P//Zc/HtuhJ9/wvS+Ce/aOzQ5JRkR+XNaL2vtxv3JSUR0/KHKkSleAq//UKheC//R+3DfJea46/wkqP8SdGt9GHgJIJKstF9pjLmN6/BH3417dgoc0Qxv2CN4J5yGMTGflUcVvr9NjigiaQQdGpTKkSlVGm/AcKhYGX/CCNyq5WGHlG/5qeLrBdwMbAAeimxrRDDJpIoB5xxu0TycnQYGzOV9gy7kmpiSjogsIhjCUVxEsnZEqgkkduOCiglTtjzewHvwH7wDf+xQvFvvx1SvHXZYeZafBLUN2Af0AG4VkbXAs8C9hRGYOpDbvAn/yQmwbAk0bo7Xsx+m0mFhh6UKzxSCyTSP58AxiA5YD8wPIyiVeEzFDLyb7sF/cBD+6CF4t92fMCvz5idBPUowQWw/guWm6xD0MKoOXBn90BRE7preW4Cb/S/YtxfT/VpM2w4YLz+1syrRWGtnAIhID+A7a+27+18TkRMJqtoHhBSeSjDmsGrBBLMPDwrupO54AFM2/rsP5CdBXQDUt9b+Gnn+pYi8TzD1vyaoQuB+2xKscrv0A2jQBO+K/pjDQl2GXMVec+CjLNs+BuagCUrlg6lRG6//UPyH78QfNwLv1pGY4vE9u0x+voavA7J+mhLAz9nsqwrIffRf/GF9YdkSzCVXBr9MmpyKIsffO0SkkL9rVykATL0j8K69HVZ/j//oA7i9e8IO6aDycwc1E3hDRCYQTMlfC7gBeDLzRLI5TRyb26qdInITcBXBirobgSuttasir+0jGKgI8KO1tmM+4k4obvtW3KzHcR8ugroN8a4cgKlWK/cDVbJaBNwjIrdZa/3IirrDItuVyjfT7DjM5X1x08fjZkyAKwbEbZNBfhLUNZF/s84ccW3kB3KYODayaudEMq3aKSJzs6zauQQ4zlq7U0SuI1jJt0vktd+ttS3yEWtCcks/wH/yEdixHXNBD0yHzpgU7U1cxN0IvAr8LCKrgNoEtRbnhxqVSmjeSe3xf92Mm/MUlKuIubhX2CFlK88JqoCTxea6aqe1dkGm/RcT9BYsEtzO7bjZU3DvvQM16+INGI6ppXPzKrDWrhaRlgTXUC2CxQU/sNb64UamEp055xL4dTNu3ov45SvitY+/iqlDniw2n/K7amdv/lr7BoKxIB8RVP+NstbOiX6I4XDLluDPmAC/bcacK5jzumBS/zY2UxVhkWS0mL+mGlOqwIwx0O1q3NYtOPsEfrmKeMefHHZYB4hVgsqzSLfa44C2mTbXiayBczjwjoh8bq1dkeW4hFr10/99B9unT+T3N+eQUrMu5QaNIq1hk5i9f7yUQzzQslBFlfFS8HrfhD9mKG7qaFzZ8pgjm+Z+YIzEKkHlumongIi0B+4E2lprd+3fbq1dE/l3pYgsBI4BDkhQibTqp/vmi2CC1182YM68EHfBpfyWViymS7DHQznEi5zKIq+rfiqVyEyxdLy+d+GPug1/0n14gx7CVI3WepgFE6uuG3+u2ikixQhW7ZybeQcROQZ4HOhord2QaXsFEUmPPM4ATiJT21Uicbt24c/+F/7Dg8EYvFvvx7vkCkxasbBDU0oVYaZUabz+Q8Dz8Cfcg9u+NeyQgBglKGvtXmD/qp1fBZvsMhEZISL7W+YeAkoDz4nIpyKyP4E1Bj4SkaXAAoI2qIRLUG7F1/j3DMDNfwXT7hy8oeMxMazSU0qpgzGVq+LdcCds3oj/6P24PeGPkTLOJeXSMm7t2rXZvhDrqi23Zw9u7izcvJegQiW8Xv0xjZvH7P1zolV8f8mlik9n4j1Q3Fxb8SrRy8F//z+4Kf/EtGmHuWLAIU9GfbByyOu1FXedJJKJW7UCf9pYWLMqmHVcemNKxPfUIkqpos1r3RZ/48+4l2dBlRqYcyW0WDRBFQK3dy/utedwr1koXQ6v/xBMs+PCDksppfLEnNsF1q/FzXkK/7BqeMefEkocmqCizK1ZhT91LPy4AtO6LaZbH0ypMmGHpZRSeWaMgcv74TZtwE0di6tYGVO/UczjiM8JmBKQ8/fhv/4C/r0DYcsmvOsG4V11syYnpVRCMmlpeNcPhgqV8CeOxP2yMeYxaIKKArduDf4Dd+BenAFHt8Ib/gimZZuww1JKqQIxZcoG3c/37sGfNBK3a1fuB0WRJqgCcL6P//Zc/HtuhHVrMFfdjHft7Zgy5cIOTSmlosJUrYl39S3w0/e4GeOJZc9vbYM6RG7jumAOvW8+h2bH4V1+A6Z8pbDDUkqpqDPNjsNceHlQS1SrHubsi2Pyvpqg8sk5h1s0D2engQHTsx/mpPaHPFZAKaUSgelwEaz+HvfSTFz1Opjmxxf6e2qCyge3eRP+kxNg2RJo3ByvZ39Mpcphh6WUUoXuz55969bgT3kYb/DDhb6YqrZB5YFzDv/dd/CH9YPvvsR0vzZYs0mTk1KqCDHp6Xg3DIa0YviPjMTt2F6o76cJKhfuty1BF8tpY6FGHbyh4/DanRO3SyQrpVRhMhUr410/CH7ZgP+vh3D+vkJ7L/0rexD+h//FH9YXli3BXHIl3q0jMYfpEgxKqaLNNGiC6X4NLFuCe3Fmob2PtkFlw23bipv1GO6j/0LdhnhXDij0ulallEok3qln4f+0EjfvRVy9IzDHnhj199AElYX7dDH+zEmwYzvmgh6YDp0xKSlhh6WUUnHHdLkK9+NK/Gnj8KrXxlSrGdXzaxVfhNu5HX/qGPyJ90HZCnh3/hPvXNHkpJRSOTCpaXjX3A7FigVrSP2xM6rn1wQFuC8+wR/aD/f+fzDndcG782FMrXphh6WUUnHPVMwIZppYtwY3fUJUZ5oo0gnK/bETf+ZE/HHDoERJvEEP4XW6FJOaFnZoSimVMEzj5piLLsN9/D/cWy9H7bwxa4MSkQ7AOCAFmGKtHZXl9XTgSeBY4Begi7X2h8hrg4DewD6gv7V2XkHjcd98jj9tHGzeiDnrQkynSzFpxQp6WqWUKpLMWRfhVn6De2E6rk4DyDitwOeMyR2UiKQAE4GzgSZANxFpkmW33sAWa20DYAzwQOTYJkBX4CigAzApcr5D4nb9gT/7X/gP3wkpKXi33Y938RWanJRSqgCMMXhXDIDK1fAff4B9UVieI1ZVfK2A5dbaldba3cBsoFOWfToBMyKPnwdOFxET2T7bWrvLWvs9sDxyvnxzK77ml5t64ea/gml3Lt6QcZgGWfOkUkWDiFwiIstExBcRXfJZFZgpURLvukGwexe/PXwXbu+eAp0vVlV8NYCfMj1fDbTOaR9r7V4R+Q2oFNm+OMuxNbK+gYj0AfpEjicjI+NvQfz6r1fYu2c3FYaPp9jRRft6TE1NzbaMiqIiXBZfABcBj4cdiEoepkZtTM9+7JkyGu+7L6Fx80M+V9KMg7LWTgYmR566TZs2/W0f17UPlapUZfPO3yGb14uSjIwMsiujoiinsqhePblnDbHWfgUgImGHopKMd/wplG9xPL+mFS/YeaIUT27WAJmnYqgZ2ZbtPiKSCpQj6CyRl2PzxJQph1ey1KEcqpRSKh9SozBoN1Z3UB8CDUWkHkFy6Qp0z7LPXKAn8B5wMfCOtdaJyFxgloiMBqoDDYEPYhS3UglNRN4Gqmbz0p3W2jz1B85L9TkU6arSA2g5BKJRDjFJUJE2pb7APIJu5lOttctEZATwkbV2LvAEMFNElgObCZIYkf0s8CWwF7jBWlt40+cqlUSste2jcI5cq89Bq43303IIHKwc8lp9bmK5vnwMJeWHUqFI+qWSRWQhcIu19qM87K7XloqWXK+tZJ1JwuT0IyIfH+z1ovKj5ZDnskhaInKhiKwG2gD/FpG8DIDX36mC/T4VmZ88lEOukqYXn1Iqf6y1LwEvhR2HUjlJ1jsopZRSCa4oJqjJue9SJGg5/EXLIjq0HANaDoECl0OydpJQSimV4IriHZRSSqkEoAlKKaVUXCpSvfhyW5MqWYnIVOA8YIO1tmlkW0XgWaAu8AMg1totYcUYCyJSi2DNsSoE43kmW2vHFcWyiKaiel2BXlv7Fda1VWTuoPK4JlWymk6wllZmdwDzrbUNgfmR58luL3CztbYJcAJwQ+R3oCiWRVQU8esK9Nrar1CurSKToMjbmlRJyVr7fwTTR2X2/+3doU7EUBCF4R8BCklCMIRXwCPQKNR5DjQGhSW8AoKQTAIhvAIKg0GsRi2LBA+I24UNhYSEdtvunM+0ac3N5J5M2t10ZudvnQH7c11UByJiHBH31fkrMKKMbklXiwalzRU4W1NtZStTg/ppJlVtrlQi6xExrs6fKI/maUjaAraBO5LX4p+cq7rU+6nJbGVqUPaLiHgn0TfWJK0Cl8BBRLzM3stWC2tXtv3UdLYyNajG5kotiImkDYDq+NzxeuZC0jIlQOcRcVVdTlmLhjhXdSn3U/2iTQwAAACrSURBVBvZytSgPmdSSVqhjPO46XhNXZrO36I6/mk20JBJWqKMdRlFxMnMrXS1aJBzVZduP7WVrVRfkpC0B5zyNZPquOMlzYWkC2AXWAMmwBFwDQSwCTxS/v75/cfehSJpB7gFHoC36vIh5V15qlo0KWuuwNmaaitbqRqUmZkNR6ZXfGZmNiBuUGZm1ktuUGZm1ktuUGZm1ktuUGZm1ktuUGZm1ktuUGZm1ksf6yHm+I8x09oAAAAASUVORK5CYII=\n", "text/plain": [ "
" ] }, "metadata": { "needs_background": "light" }, "output_type": "display_data" } ], "source": [ "#plot trajectory\n", "plt.subplot(2, 2, 1)\n", "plt.plot(x_bar[0,:],x_bar[1,:])\n", "plt.plot(track[0,:],track[1,:],\"b-\")\n", "plt.axis('equal')\n", "plt.ylabel('y')\n", "plt.xlabel('x')\n", "\n", "plt.subplot(2, 2, 2)\n", "plt.plot(x_bar[2,:])\n", "plt.ylabel('theta(t)')\n", "#plt.xlabel('time')\n", "\n", "plt.subplot(2, 2, 3)\n", "plt.plot(x_bar[3,:])\n", "plt.ylabel('psi(t)')\n", "#plt.xlabel('time')\n", "\n", "plt.subplot(2, 2, 4)\n", "plt.plot(x_bar[4,:])\n", "plt.ylabel('cte(t)')\n", "\n", "plt.tight_layout()\n", "plt.show()" ] }, { "cell_type": "code", "execution_count": 12, "metadata": {}, "outputs": [], "source": [ "track = compute_path_from_wp([0,2,4,5,10],[0,0,3,1,1])\n", "\n", "u_bar = np.zeros((M,T))\n", "u_bar[0,:] = 1 #m/s\n", "u_bar[1,:] = np.radians(10) #rad/s\n", "\n", "x0 = np.zeros(N)\n", "x0[0] = 2\n", "x0[1] = 2\n", "x0[2] = np.radians(0)\n", "_,psi,cte = calc_err(x0,track)\n", "x0[3]=psi\n", "x0[4]=cte\n", "\n", "x_bar=np.zeros((N,T+1))\n", "x_bar[:,0]=x0\n", "\n", "for t in range (1,T+1):\n", " xt=x_bar[:,t-1].reshape(5,1)\n", " ut=u_bar[:,t-1].reshape(2,1)\n", " \n", " A,B,C=get_linear_model(xt,ut)\n", " \n", " xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n", " \n", " _,psi,cte = calc_err(xt_plus_one,track)\n", " xt_plus_one[3]=psi\n", " xt_plus_one[4]=cte\n", " \n", " x_bar[:,t]= xt_plus_one" ] }, { "cell_type": "code", "execution_count": 13, "metadata": {}, "outputs": [ { "data": { "image/png": "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\n", "text/plain": [ "
" ] }, "metadata": { "needs_background": "light" }, "output_type": "display_data" } ], "source": [ "#plot trajectory\n", "plt.subplot(2, 2, 1)\n", "plt.plot(x_bar[0,:],x_bar[1,:])\n", "plt.plot(track[0,:],track[1,:],\"b-\")\n", "plt.axis('equal')\n", "plt.ylabel('y')\n", "plt.xlabel('x')\n", "\n", "plt.subplot(2, 2, 2)\n", "plt.plot(x_bar[2,:])\n", "plt.ylabel('theta(t)')\n", "#plt.xlabel('time')\n", "\n", "plt.subplot(2, 2, 3)\n", "plt.plot(x_bar[3,:])\n", "plt.ylabel('psi(t)')\n", "#plt.xlabel('time')\n", "\n", "plt.subplot(2, 2, 4)\n", "plt.plot(x_bar[4,:])\n", "plt.ylabel('cte(t)')\n", "\n", "plt.tight_layout()\n", "plt.show()" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "### MPC Problem formulation\n", "\n", "**Model Predictive Control** refers to the control approach of **numerically** solving a optimization problem at each time step. \n", "\n", "The controller generates a control signal over a fixed lenght T (Horizon) at each time step." ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "![mpc](img/mpc_block_diagram.png)\n", "![mpc](img/mpc_t.png)" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "#### Linear MPC Formulation\n", "\n", "Linear MPC makes use of the **LTI** (Linear time invariant) discrete state space model, wich represents a motion model used for Prediction.\n", "\n", "$x_{t+1} = Ax_t + Bu_t$\n", "\n", "The LTI formulation means that **future states** are linearly related to the current state and actuator signal. Hence, the MPC seeks to find a **control policy** U over a finite lenght horizon.\n", "\n", "$U={u_{t|t}, u_{t+1|t}, ...,u_{t+T|t}}$\n", "\n", "The objective function used minimize (drive the state to 0) is:\n", "\n", "$J(x(t),U) = \\sum^{t+T-1}_{j=t} x^T_{j|t}Qx_{j|t} + u^T_{j|t}Ru_{j|t}$\n", "\n", "This accounts for quadratic error on deviation from 0 of the state and the control inputs sequences. Q and R are the **weight matrices** and are used to tune the response.\n", "\n", "Becouse the goal is tracking a **reference signal** such as a trajectory, the objective function is rewritten as:\n", "\n", "$J(x(t),U) = \\sum^{t+T-1}_{j=t} \\delta x^T_{j|t}Q\\delta x_{j|t} + u^T_{j|t}Ru_{j|t}$\n", "\n", "where the error w.r.t desired state is accounted for:\n", "\n", "$\\delta x = x_{j,t,ref} - x_{j,t}$\n", "\n", "#### Non-Linear MPC Formulation\n", "\n", "In general cases, the objective function is any non-differentiable non-linear function of states and inputs over a finite horizon T. In this case the constrains include nonlinear dynamics of motion.\n", "\n", "$J(x(t),U) = \\sum^{t+T}_{j=t} C(x_{j|t},{j|t})$\n", "\n", "s.t.\n", "\n", "$ x_{j+1|t} = f(x_{j|t},{j|t}) t= MIN_SPEED]\n", "constr += [cp.abs(u[1, :]) <= MAX_STEER_SPEED]\n", "\n", "\n", "prob = cp.Problem(cp.Minimize(cost), constr)\n", "solution = prob.solve(solver=cp.ECOS, verbose=False)" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Print Results:" ] }, { "cell_type": "code", "execution_count": 15, "metadata": {}, "outputs": [ { "data": { "image/png": "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\n", "text/plain": [ "
" ] }, "metadata": { "needs_background": "light" }, "output_type": "display_data" } ], "source": [ "x_mpc=np.array(x.value[0, :]).flatten()\n", "y_mpc=np.array(x.value[1, :]).flatten()\n", "theta_mpc=np.array(x.value[1, :]).flatten()\n", "psi_mpc=np.array(x.value[1, :]).flatten()\n", "cte_mpc=np.array(x.value[1, :]).flatten()\n", "v_mpc=np.array(u.value[0, :]).flatten()\n", "w_mpc=np.array(u.value[1, :]).flatten()\n", "\n", "#simulate robot state trajectory for optimized U\n", "x_traj=predict(x0, np.vstack((v_mpc,w_mpc)))\n", "\n", "#plot trajectory\n", "plt.subplot(2, 2, 1)\n", "plt.plot(track[0,:],track[1,:],\"b*\")\n", "plt.plot(x_traj[0,:],x_traj[1,:])\n", "plt.axis(\"equal\")\n", "plt.ylabel('y')\n", "plt.xlabel('x')\n", "\n", "#plot v(t)\n", "plt.subplot(2, 2, 2)\n", "plt.plot(v_mpc)\n", "plt.ylabel('v(t)')\n", "#plt.xlabel('time')\n", "\n", "#plot w(t)\n", "plt.subplot(2, 2, 3)\n", "plt.plot(w_mpc)\n", "plt.ylabel('w(t)')\n", "#plt.xlabel('time')\n", "\n", "#plot theta(t)\n", "#plt.subplot(2, 2, 4)\n", "#plt.plot(cte_mpc)\n", "#plt.ylabel('cte(t)')\n", "#plt.xlabel('time')\n", "#plt.legend(loc='best')\n", "\n", "plt.tight_layout()\n", "plt.show()" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "full track demo" ] }, { "cell_type": "code", "execution_count": 19, "metadata": {}, "outputs": [ { "name": "stderr", "output_type": "stream", "text": [ "/home/marcello/.local/lib/python3.5/site-packages/ipykernel_launcher.py:18: RuntimeWarning: invalid value encountered in true_divide\n" ] }, { "name": "stdout", "output_type": "stream", "text": [ "CVXPY Optimization Time: Avrg: 0.2452s Max: 0.2904s Min: 0.2282s\n" ] } ], "source": [ "\n", "track = compute_path_from_wp([0,5,7.5,10,12,13,13,10],\n", " [0,0,2.5,2.5,0,0,5,10])\n", "\n", "sim_duration =100 \n", "opt_time=[]\n", "\n", "x_sim = np.zeros((N,sim_duration))\n", "u_sim = np.zeros((M,sim_duration-1))\n", "\n", "MAX_SPEED = 1.25\n", "MIN_SPEED = 0.75\n", "MAX_STEER_SPEED = 1.57/2\n", "\n", "# Starting Condition\n", "x0 = np.zeros(N)\n", "x0[0] = 0\n", "x0[1] = -0.5\n", "x0[2] = np.radians(-0)\n", "_,psi,cte = calc_err(x0,track)\n", "x0[3]=psi\n", "x0[4]=cte\n", "\n", "x_sim[:,0]=x0\n", " \n", "#starting guess\n", "u_bar = np.zeros((M,T))\n", "u_bar[0,:]=0.5*(MAX_SPEED+MIN_SPEED)\n", "u_bar[1,:]=0.01\n", "\n", "for sim_time in range(sim_duration-1):\n", " \n", " iter_start=time.time()\n", " \n", " # Prediction\n", " x_bar=np.zeros((N,T+1))\n", " x_bar[:,0]=x_sim[:,sim_time]\n", "\n", " for t in range (1,T+1):\n", " xt=x_bar[:,t-1].reshape(5,1)\n", " ut=u_bar[:,t-1].reshape(2,1)\n", "\n", " A,B,C=get_linear_model(xt,ut)\n", "\n", " xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n", "\n", " _,psi,cte = calc_err(xt_plus_one,track)\n", " xt_plus_one[3]=psi\n", " xt_plus_one[4]=cte\n", "\n", " x_bar[:,t]= xt_plus_one\n", "\n", "\n", " #CVXPY Linear MPC problem statement\n", " cost = 0\n", " constr = []\n", "\n", " for t in range(T):\n", "\n", " # Tracking\n", " if t > 0:\n", " idx,_,_ = calc_err(x_bar[:,t],track)\n", " delta_x = track[:,idx]-x[0:3,t]\n", " cost+= cp.quad_form(delta_x,10*np.eye(3))\n", " \n", " # Tracking last time step\n", " if t == T:\n", " idx,_,_ = calc_err(x_bar[:,t],track)\n", " delta_x = track[:,idx]-x[0:3,t]\n", " cost+= cp.quad_form(delta_x,100*np.eye(3))\n", "\n", " # Actuation rate of change\n", " if t < (T - 1):\n", " cost += cp.quad_form(u[:, t + 1] - u[:, t], 5*np.eye(M))\n", " \n", " # Actuation effort\n", " cost += cp.quad_form( u[:, t],1*np.eye(M))\n", " \n", " # Constrains\n", " A,B,C=get_linear_model(x_bar[:,t],u_bar[:,t])\n", " constr += [x[:,t+1] == A*x[:,t] + B*u[:,t] + C.flatten()]\n", "\n", " # sums problem objectives and concatenates constraints.\n", " constr += [x[:,0] == x_sim[:,sim_time]] # starting condition\n", " constr += [u[0, :] <= MAX_SPEED]\n", " constr += [u[0, :] >= MIN_SPEED]\n", " constr += [cp.abs(u[1, :]) <= MAX_STEER_SPEED]\n", " \n", " # Solve\n", " prob = cp.Problem(cp.Minimize(cost), constr)\n", " solution = prob.solve(solver=cp.ECOS, verbose=False)\n", " \n", " #retrieved optimized U and assign to u_bar to linearize in next step\n", " u_bar=np.vstack((np.array(u.value[0, :]).flatten(),\n", " (np.array(u.value[1, :]).flatten())))\n", " \n", " u_sim[:,sim_time] = u_bar[:,0]\n", " \n", " # 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: {:0.4f}s Max: {:0.4f}s Min: {:0.4f}s\".format(np.mean(opt_time),\n", " np.max(opt_time),\n", " np.min(opt_time))) " ] }, { "cell_type": "code", "execution_count": 17, "metadata": {}, "outputs": [ { "data": { "image/png": "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\n", "text/plain": [ "
" ] }, "metadata": { "needs_background": "light" }, "output_type": "display_data" } ], "source": [ "#plot trajectory\n", "grid = plt.GridSpec(2, 3)\n", "\n", "plt.figure(figsize=(15,10))\n", "\n", "plt.subplot(grid[0:2, 0:2])\n", "plt.plot(track[0,:],track[1,:],\"b*\")\n", "plt.plot(x_sim[0,:],x_sim[1,:])\n", "plt.axis(\"equal\")\n", "plt.ylabel('y')\n", "plt.xlabel('x')\n", "\n", "plt.subplot(grid[0, 2])\n", "plt.plot(u_sim[0,:])\n", "plt.ylabel('v(t) [m/s]')\n", "\n", "plt.subplot(grid[1, 2])\n", "plt.plot(np.degrees(u_sim[1,:]))\n", "plt.ylabel('w(t) [deg/s]')\n", "\n", "plt.tight_layout()\n", "plt.show()" ] }, { "cell_type": "code", "execution_count": null, "metadata": {}, "outputs": [], "source": [] } ], "metadata": { "kernelspec": { "display_name": "Python 3", "language": "python", "name": "python3" }, "language_info": { "codemirror_mode": { "name": "ipython", "version": 3 }, "file_extension": ".py", "mimetype": "text/x-python", "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython3", "version": "3.5.2" } }, "nbformat": 4, "nbformat_minor": 2 }