{ "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 **non-linear** (A,B are time changing), to linearize it the **Taylor's series expansion** is used around $\\bar{x}$ and $\\bar{u}$:\n", "\n", "$ \\dot{x} = f(x,u) \\approx f(\\bar{x},\\bar{u}) + A(x-\\bar{x}) + B(u-\\bar{u})$\n", "\n", "So:\n", "\n", "$ x_{t+1} = x_t + (f(\\bar{x},\\bar{u}) + A(x_t-\\bar{x}) + B(u_t-\\bar{u}) )dt $\n", "\n", "$ x_{t+1} = (I+dtA)x_t + dtBu_t +dt(f(\\bar{x},\\bar{u}) - A\\bar{x} - B\\bar{u}))$\n", "\n", "The Discrete linearized kinematics model is\n", "\n", "$ x_{t+1} = A'x_t + B' u_t + C' $\n", "\n", "with:\n", "\n", "$ A' = I+dtA $\n", "\n", "$ B' = dtB $\n", "\n", "$ C' = dt(f(\\bar{x},\\bar{u}) - A\\bar{x} - B\\bar{u}) $" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "------------------\n", "NB: psi and cte are expressed w.r.t. the track as reference frame.\n", "In the reference frame of the veicle the equtions would be:\n", "* psi_dot = w\n", "* cte_dot = sin(psi)\n", "-----------------" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "-----------------\n", "[About Taylor Series Expansion](https://courses.engr.illinois.edu/ece486/fa2017/documents/lecture_notes/state_space_p2.pdf):\n", "\n", "In order to linearize general nonlinear systems, we will use the Taylor Series expansion of functions.\n", "\n", "Typically it is possible to assume that the system is operating about some nominal\n", "state solution $\\bar{x}$ (possibly requires a nominal input $\\bar{u}$) called **equilibrium point**.\n", "\n", "Recall that the Taylor Series expansion of f(x) around the\n", "point $\\bar{x}$ is given by:\n", "\n", "$f(x)=f(\\bar{x}) + \\frac{df(x)}{dx}|_{x=\\bar{x}}(x-\\bar{x})$ + higher order terms...\n", "\n", "For x sufficiently close to $\\bar{x}$, these higher order terms will be very close to zero, and so we can drop them.\n", "\n", "The extension to functions of multiple states and inputs is very similar to the above procedure.Suppose the evolution of state x\n", "is given by:\n", "\n", "$\\dot{x} = f(x1, x2, . . . , xn, u1, u2, . . . , um) = Ax+Bu$\n", "\n", "Where:\n", "\n", "$ A =\n", "\\quad\n", "\\begin{bmatrix}\n", "\\frac{\\partial f(x,u)}{\\partial x1} & ... & \\frac{\\partial f(x,u)}{\\partial xn} \\\\\n", "\\end{bmatrix}\n", "\\quad\n", "$ and $ B = \\quad\n", "\\begin{bmatrix}\n", "\\frac{\\partial f(x,u)}{\\partial u1} & ... & \\frac{\\partial f(x,u)}{\\partial um} \\\\\n", "\\end{bmatrix}\n", "\\quad $\n", "\n", "Then:\n", "\n", "$f(x,u)=f(\\bar{x},\\bar{u}) + \\frac{df(x,u)}{dx}|_{x=\\bar{x}}(x-\\bar{x}) + \\frac{df(x,u)}{du}|_{u=\\bar{u}}(u-\\bar{u}) = f(\\bar{x},\\bar{u}) + A_{x=\\bar{x}}(x-\\bar{x}) + B_{u=\\bar{u}}(u-\\bar{u})$\n", "\n", "-----------------" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "### Kinematics Model" ] }, { "cell_type": "code", "execution_count": 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": "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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": "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", "\n", "![mpc](img/mpc_t.png)" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "#### Linear MPC Formulation\n", "\n", "Linear MPC makes use of the **LTI** (Linear time invariant) discrete state space model, wich represents a motion model used for Prediction.\n", "\n", "$x_{t+1} = Ax_t + Bu_t$\n", "\n", "The LTI formulation means that **future states** are linearly related to the current state and actuator signal. Hence, the MPC seeks to find a **control policy** U over a finite lenght horizon.\n", "\n", "$U={u_{t|t}, u_{t+1|t}, ...,u_{t+T|t}}$\n", "\n", "The objective function used minimize (drive the state to 0) is:\n", "\n", "$\n", "\\begin{equation}\n", "\\begin{aligned}\n", "\\min_{} \\quad & \\sum^{t+T-1}_{j=t} x^T_{j|t}Qx_{j|t} + u^T_{j|t}Ru_{j|t}\\\\\n", "\\textrm{s.t.} \\quad & x(0) = x0\\\\\n", " & x_{j+1|t} = Ax_{j|t}+Bu_{j|t}) \\quad \\textrm{for} 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": 22, "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.2550s Max: 0.3976s Min: 0.2298s\n" ] } ], "source": [ "\n", "track = compute_path_from_wp([0,5,7.5,10,12,13,13,10],\n", " [0,0,2.5,2.5,0,0,5,10])\n", "\n", "sim_duration =100 \n", "opt_time=[]\n", "\n", "x_sim = np.zeros((N,sim_duration))\n", "u_sim = np.zeros((M,sim_duration-1))\n", "\n", "MAX_SPEED = 1.25\n", "MIN_SPEED = 0.75\n", "MAX_STEER_SPEED = 1.57/2\n", "\n", "# Starting Condition\n", "x0 = np.zeros(N)\n", "x0[0] = 0\n", "x0[1] = -0.5\n", "x0[2] = np.radians(-0)\n", "_,psi,cte = calc_err(x0,track)\n", "x0[3]=psi\n", "x0[4]=cte\n", "\n", "x_sim[:,0]=x0\n", " \n", "#starting guess\n", "u_bar = np.zeros((M,T))\n", "u_bar[0,:]=0.5*(MAX_SPEED+MIN_SPEED)\n", "u_bar[1,:]=0.01\n", "\n", "for sim_time in range(sim_duration-1):\n", " \n", " iter_start=time.time()\n", " \n", " # Prediction\n", " x_bar=np.zeros((N,T+1))\n", " x_bar[:,0]=x_sim[:,sim_time]\n", "\n", " for t in range (1,T+1):\n", " xt=x_bar[:,t-1].reshape(5,1)\n", " ut=u_bar[:,t-1].reshape(2,1)\n", "\n", " A,B,C=get_linear_model(xt,ut)\n", "\n", " xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n", "\n", " _,psi,cte = calc_err(xt_plus_one,track)\n", " xt_plus_one[3]=psi\n", " xt_plus_one[4]=cte\n", "\n", " x_bar[:,t]= xt_plus_one\n", "\n", "\n", " #CVXPY Linear MPC problem statement\n", " cost = 0\n", " constr = []\n", "\n", " for t in range(T):\n", "\n", " # Tracking\n", " if t > 0:\n", " idx,_,_ = calc_err(x_bar[:,t],track)\n", " delta_x = track[:,idx]-x[0:3,t]\n", " cost+= cp.quad_form(delta_x,10*np.eye(3))\n", " \n", " # Tracking last time step\n", " if t == T:\n", " idx,_,_ = calc_err(x_bar[:,t],track)\n", " delta_x = track[:,idx]-x[0:3,t]\n", " cost+= cp.quad_form(delta_x,100*np.eye(3))\n", "\n", " # Actuation rate of change\n", " if t < (T - 1):\n", " cost += cp.quad_form(u[:, t + 1] - u[:, t], 25*np.eye(M))\n", " \n", " # Actuation effort\n", " cost += cp.quad_form( u[:, t],1*np.eye(M))\n", " \n", " # Constrains\n", " A,B,C=get_linear_model(x_bar[:,t],u_bar[:,t])\n", " constr += [x[:,t+1] == A*x[:,t] + B*u[:,t] + C.flatten()]\n", "\n", " # sums problem objectives and concatenates constraints.\n", " constr += [x[:,0] == x_sim[:,sim_time]] # starting condition\n", " constr += [u[0, :] <= MAX_SPEED]\n", " constr += [u[0, :] >= MIN_SPEED]\n", " constr += [cp.abs(u[1, :]) <= MAX_STEER_SPEED]\n", " \n", " # Solve\n", " prob = cp.Problem(cp.Minimize(cost), constr)\n", " solution = prob.solve(solver=cp.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: {:.4f}s Max: {:.4f}s Min: {:.4f}s\".format(np.mean(opt_time),\n", " np.max(opt_time),\n", " np.min(opt_time))) " ] }, { "cell_type": "code", "execution_count": 23, "metadata": {}, "outputs": [ { "data": { "image/png": "iVBORw0KGgoAAAANSUhEUgAABDAAAALICAYAAACJhQBYAAAABHNCSVQICAgIfAhkiAAAAAlwSFlzAAALEgAACxIB0t1+/AAAADl0RVh0U29mdHdhcmUAbWF0cGxvdGxpYiB2ZXJzaW9uIDMuMC4zLCBodHRwOi8vbWF0cGxvdGxpYi5vcmcvnQurowAAIABJREFUeJzs3Xl0XPd52P3vbwACBAmSIAguIEiRhERam5fYlvc0cuyocmLVUtP3xq5T1n6dumGbxF1yUneJnCqpnTQ5VXy6OHVRN4LrmL2xm9eR40R2vMQJRTGR5VWWqIWiuBMEiI0ACZKY3/vHDCiQBEgsM3MHg+/nHJwZzNy597mXJDjz4Pk9T4gxIkmSJEmSVM1yWQcgSZIkSZJ0PSYwJEmSJElS1TOBIUmSJEmSqp4JDEmSJEmSVPVMYEiSJEmSpKpnAkOSJEmSJFU9ExiSJEmSJKnqmcCQJEmSJElVzwSGJEmSJEmqevVZBzAPMesAJEmStGCFrAOoEN8zS1oorvtzeSEnMDh27FjFj9nW1kZvb2/Fj7tYeH3Ly+tbXl7f8vL6lpfXt7y8vuU12+u7cePGMkZTfebynrmW/87W8rlBbZ9fLZ8b1Pb5Xe/cZvpz2SUkkiRJkiSp6pnAkCRJkiRJVc8EhiRJkiRJqnomMCRJkiRJUtUzgSFJkiRJkqqeCQxJkiRJklT1KjpGNUmSTwHvBHrSNL29+NhvA/cA54HngfenaTpQybgkSZIkSVJ1q3QFxu8Dd1/x2FeA29M0fQXwDPCvKxyTJEmSJEmqchVNYKRp+k3g9BWPfTlN04vFbx8DNlUyJkmSJEmSVP0quoRkBv5f4P9M92SSJB8EPgiQpiltbW2ViuuS+vr6TI67WHh9y8vrW15e3/Ly+paX17e8vL7l5fWVpMWhahIYSZL8W+Ai8JnptknT9JPAJ4vfxt7e3kqEdpm2tjayOO5i4fUtL69veXl9y8vrW15e3/Ly+pbXbK/vxo0byxiNJKlcqiKBkSTJ+yg093xbmqYx43AkSZIkXUfM54lf/iM4M3TN7cIr7iDsuL1CUUmqZZknMJIkuRv4FeDH0jQdzToeSZIkSTPw4nPEzz8E9fWQm6a13nie+NUvkvvnDxB23FbZ+CTVnEqPUf0scCfQliTJEeAjFKaONAJfSZIE4LE0TX++knFJkiRJmp148FkAcr/x3wlr1k69zZkh8r/1r8j/198g9yu/Rei4oZIhSqoxFU1gpGn6nike/p+VjEGSJElSCRx8DlasgtbpG6iG5pXkPvRr5H/zV8h//NfI/ZvfJrSsqWCQkmpJRceoSpIkSaoN8eCzsHU7IYRrbhfa1pP7pY/AwGniX/xZhaKTVItMYEiSJEmalXjuLBw/Qthy04y2Dzd0wvqNxCMvljkySbXMBIYkSZKk2Tl0AGKesHX7zF/TcQMcPViuiCQtAiYwJEmSJM1KfPG5wp2tM6vAAAgdW6H3JHHsXHmCklTzTGBIkiRJmp2Dz8LqNsKq1TN+SejYAjHCscNlDExSLTOBIUmSJGlW4sHnYIb9Ly7p2FJ4rctIJM2RCQxJkiRJMxZHz0DPMcIslo8AsHY9NDTAURt5SpobExiSJEmSZu7F5wGYVQNPIOTqoP0GogkMSXNkAkOSJEnSjMWDzxbuzLYCg2IfDBMYkubIBIYkSZKkGYsHn4W1GwjLV8z+xR1bYGiAODxY+sAk1TwTGJIkSZJm7sXnCbNt4FkUNhUaeXLkYOnikbRomMCQJEmSNCMxn4eBvkJDzrnYWJxEcuxQCaOStFiYwJAkSZI0M6NnYHwcVrbM7fWrVkPzCvtgSJoTExiSJEmSZmZooHC7cvWcXh5CgI6tRJeQSJoDExiSJEmSZqaYwAhzrcAAwsYb4NjhwnIUSZoFExiSJEmSZiQO9hfuzCOBwaYtMHYW+npKE5SkRcMEhiRJkqSZGZ5YQjKPCowNmwt3Th4rQUCSFhMTGJIkSZJmZmgA6upgWfPc97F6DQBx8HSJgpK0WJjAkCRJkjQzQwOwYhUhN4+PES2thdv+vtLEJGnRMIEhSZIkaUbi0OCcJ5BMCEsaYPkKsAJD0iyZwJAkSZI0M0MD82vgOaGllThgAkPS7JjAkCRJkjQzQwPzGqF6SUurS0gkzZoJDEmSJEnXFWMsWQVGaFnjEhJJs1afdQCSJEnSYpckyaeAdwI9aZrePsXz7wX+FRCAYWBXmqbfrWiQo2dg/GLJlpAwOEAcHyfU1c1/f5IWBSswJEmSpOz9PnD3NZ5/AfixNE1fDvw68MlKBHWZoYHCbUkSGGsg5mF4YP77krRomMCQJEmSMpam6TeBaddUpGn6aJqm/cVvHwM2VSSwyYoJjFL0wAiXRqm6jETSzLmERJIkSVpYPgD86XRPJknyQeCDAGma0tbWNusD1NfXX/W6c0+PMwis3rKN+jnsc7ILWzs5DazIX2DpPPc1W1OdWy2p5fOr5XOD2j6/Up2bCQxJkiRpgUiS5K0UEhhvmW6bNE0/yUtLTGJvb++sj9PW1saVr8sfPQxA/ziEOexzskih78XQoYOcufHWee1rtqY6t1pSy+dXy+cGtX1+1zu3jRs3zmg/JjAkSZKkBSBJklcAXcA70jSt/AzSoQHI5WB58/z3tXJVYV8DLiGRNHP2wJAkSZKqXJIkNwD/F/gHaZo+k0kQQwOwooWQm/9HiJCrg5WrYbDyeRhJC5cVGJIkSVLGkiT5LHAn0JYkyRHgI8ASgDRNfw+4H1gD/LckSQAupmn62krGGAf7YVUJJpBMaGkl2sRT0iyYwJAkSZIylqbpe67z/M8BP1ehcKY2NFCaEaoTWtbAqeOl25+kmucSEkmSJEnXNzxAWFG6BEZoaYV+l5BImjkTGJIkSZKuKcZYhgqMVhg9Qzw/Vrp9SqppJjAkSZIkXdvZEbh4sfRLSMBJJJJmzASGJEmSpGsbGijcljCBEVa3Fu6YwJA0QyYwJEmSJF1bMYERVq0u3T5XFSow4qAJDEkzYwJDkiRJ0jXFwdJXYNBSrMCwkaekGTKBIUmSJOnayrCEhGXLoaEBrMCQNEMmMCRJkiRd29AA5HKwfEXJdhlCgFWOUpU0cyYwJEmSJF3b8ACsWEXIlfjjw+o19sCQNGMmMCRJkiRdUxwqJDBKLViBIWkWTGBIkiRJuraRM9C8svT7Xb0GBk8TYyz9viXVHBMYkiRJkq5tZBiWN5d+v6tWw/nzcHa09PuWVHNMYEiSJEm6tpFhQgkbeF4yMdVkeLD0+5ZUc0xgSJIkSZpWjLGwhKQMCYywopjAmBjTKknXYAJDkiRJ0vTGzsH4xbIkMC5VYJjAkDQDJjAkSZIkTW9kuHBbjh4YxckmcdgEhqTrM4EhSZIkaXrFBEZZemCsWAUhWIEhaUZMYEiSJEma3siZwm05emDU1RX2awJD0gyYwJAkSZI0vUtLSMpQgQGwYhXRKSSSZsAEhiRJkqRpxTNl7IEBhUaeVmBImgETGJIkSZKmV84mnkAwgSFphkxgSJIkSZre6BloaCQsaSjP/le2gEtIJM2ACQxJkiRJ0xsZhuYy9b+AwiSSs6PEC+fLdwxJNcEEhiRJkqRpxTPDsKyMCYyVLYVbl5FIug4TGJIkSZKmN3KmfA08KfbAABhyGYmkazOBIUmSJGl6I8PlG6EKVmBImjETGJIkSZKmN3qGUO4eGEAc6i/fMSTVBBMYkiRJkqYUY4Qzw2VdQnKpAsNJJJKuwwSGJEmSpKmNnYPxi2VdQhIaGmFpk0tIJF2XCQxJkiRJUxs5U7hdVsYKDCgsI7ECQ9J1mMCQJEmSNLWRYQBC88ryHmdlC9EKDEnXYQJDkiRJ0tSKCYyy9sAAWNHiEhJJ12UCQ5IkSdLULiUwyjiFBAgrW1xCIum6TGBIkiRJmlKc6IFR7gqMlS1wZog4Pl7e40ha0ExgSJIkSZpahSowWLkKYoQzQ+U9jqQFzQSGJEmSpKmNDENDI2FJQ1kPE1a2FO4M2wdD0vRMYEiSJEma2shw+asvoNDEE2zkKemaTGBIkiRJmlIcOVP+/hdQWEICjlKVdE0mMCRJkiRN7UyFKjAmlpAMOYlE0vRMYEiSJEmaWqWWkDQth/p6l5BIuiYTGJIkSZKmNnqGUIElJCGEQh8MExiSrsEEhiRJkqSrxBgrV4EBsLKFOOwSEknTM4EhSZIk6Wpj5+Dixco08QRYtRpOn6rMsSQtSCYwJEmSJF1t5EzhtkIVGOGGTjh+hDh2riLHk7TwmMCQJEmSdLWRYQBCpRIYW7dDzMOhAxU5nqSFxwSGJEmSpKsVExgV64GxdTsA8eCzlTmepAXHBIYkSZKkq11KYFSmB0ZYtRpa2+CFZypyPEkLT30lD5YkyaeAdwI9aZreXnysFfg/wFbgIJCkadpfybgkSVrMTp7M8TM/U89//s851q3LZx2OpCoRK9wDA4CtO6zAkDStSldg/D5w9xWPfRj4apqm24GvFr+XJEkV8ru/28yjjwYefLBCkwYkXSVJkk8lSdKTJMkPpnn+5iRJ9iZJMpYkyS9XJKgzQ4Xb5solMMLW7XDqBHHi2JI0SUUTGGmafhM4fcXD7wIeKt5/CLi3kjFJkrRYdXa209Gxke7uZvL5QHd3Mx0dG+nsbM86NGkx+n2u/kXfZKeBXwJ+pyLRAAwPwtImwpKGih0ybCv0weDgcxU7pqSFo6JLSKaxPk3T48X7J4D1022YJMkHgQ8CpGlKW1tbBcK7XH19fSbHXSy8vuXl9S0vr295eX1Lb//+C3z4w3V84Qs5zp4NNDVF3vWuPL/1W+Ne6xLz72951cL1TdP0m0mSbL3G8z1AT5IkP1WxoIYHYcWqih0OgC03QQjEg88Qbn91ZY8tqepVQwLjkjRNY5Ik8RrPfxL4ZPHb2NvbW5nAJmlrayOL4y4WXt/y8vqWl9e3vLy+pbdkCSxZsopz55axdGnk3Dn42tcip0+fpr7eXhil5N/f8prt9d24cWMZo8leKX7pV19fz5KzI8Q1a2mtcHKot2MLdccOsbpMx62FhNe11PL51fK5QW2fX6nOrRoSGCeTJGlP0/R4kiTtQE/WAUmStFj09ubYuXOEX/iFRn72ZyP79y/hwQeb+djHXH8uLVSl+KVfW1sb50/3wtr2iiff8pu3Mf7ktzl16hQhhJLvv9YTirV8frV8blDb53e9c5tpYrkaxqj+MfAPi/f/IfCFDGORJGlR6erqZ/fu5dxxxxL2728A7IUhqWhogLCywktIALbtgKEB6K/ND3KS5q6iCYwkST4L7AVeliTJkSRJPgD8JvATSZI8C7y9+L0kSaqQvXtP8u53j9PUVFg20tSU5777RnnssZMZRyYpK3F8HM4Mw8qWih87bJ1o5Ok4VUmXq+gSkjRN3zPNU2+rZBySJOkl69fnWbECzp0LNDZGzp0L1NdHdu1azSc+0c+6dfbDkMqt+Iu+O4G2JEmOAB8BlgCkafp7SZJsAB4HVgL5JEn+GXBrmqZlWe8Vhwch5ivfxBNg0zaoqye+8Czh1W+q/PElVa1q6IEhSZIy1tMDO3eO8N73jvKZzyzj619v5PDhevthSBVyjV/0TTx/AthUoXDID/YX7qzIoAJjyRLYuJl4+EDFjy2pupnAkCRJpOk4vb1DdHa2Mzb2UtO87u5murubaWyMHDhw/Bp7kFRLJhIYmfTAAMKmbcQffjuTY0uqXtXQxFOSJFWJvXtPcu+9o/bDkBa58cHThTsZ9MAAYPM2GOwnDg1kc3xJVckEhiRJuqTQDyNe1g9jz56GrMOSVGFxYGIJSVYVGFsLd468kMnxJVUnExiSJOkyvb05du4c4eGHT7FjxwV6eup48MHmrMOSVEH5wX7I5WBZRv/2N28DIB4+mM3xJVUle2BIkqTLdHX109nZzkMPvfTBxV4Y0uIyPtgPK1oIuWx+3xmaV0LLGiswJF3GCgxJknSVK3thLF0aWbNmnC9+8VTGkUmqhPxgf2bLRy7ZvI142ASGpJeYwJAkSVe5uhcG9PXl+PSnl2UdmqQKiIP9kNEEkglh01Y4cYR44UKmcUiqHiYwJEnSlHp7c4RAcaxq4au7u5mOjo10drZnHZ6kMsoP9hOqoAKD8XE4fjjbOCRVDRMYkiRpSl1d/Tz+uGNVpcVofOB0diNUi8KmYiNP+2BIKjKBIUmSpjXVWNX6+siuXavp6fFthFSL4tg5GDsHK7JNYLC+HRoawEkkkop85yFJkq5p8ljVnTtH2LevgX37GhytKtWqoYHCbdY9MHJ1sHGLFRiSLnGMqiRJuqaurn4AOjvbi/0wChytKtWoYgIjZLyEBCBs3kb89l5ijIQQrv8CSTXNCgxJkjQjV45WtR+GVKOGBwu3WTfxBNi0Fc4Mw8DprCORVAVMYEiSpBmZqh/Gnj0NWYclqcTipQRGFVRgFBt54jISSZjAkCRJszC5H8aOHRfo6amzF4ZUa6qkBwYA7ZsAiD0nMg5EUjWwB4YkSZqxrq5+Ojvbeeihl5IW9sKQaszwIGHZcsKSKqiwal4JDY3Q51I1SVZgSJKkWbIXhlTjhgbIrVqddRQAhcada9YR+3qyDkVSFTCBIUmSZsVeGFJti8ODVZPAAGDNOug1gSHJBIYkSZoDe2FINWxogNyq1qyjuCS0rQMrMCRhAkOSJM1BV1c/u3cv56671rF/fwMQ6O5upqNjI52d7VmHJ2k+qrECY2SYeHY060gkZcwEhiRJmhN7YUi1J+bH4cxQlSUw1hdurcKQFj0TGJIkaU6m6oVRXx/ZtWs1PT2+xZAWpDPDECO5lupJYIS2dYU70yQw4sljxIHTFYxIUlZ8dyFJkuZsci+MnTtH2LevgX37GuyHIS1UQwMAVdUDgzWFBEacopFnvHCe/H/8MPmP//tC9YikmlafdQCSJGnh6urqB6Czs52xsXDp8e7uZrq7m2lsjBw4cDyr8CTN1sgZCLnqWkKyYhU0NMDpKRIYe79eSLoMDRAf+wbhTW/LIEBJlWIFhiRJmjf7YUi1IbzsdnK/93mW3PKKrEO5JIQAreuuqsCI+TzxK1+AGzph63bi//cZ4thYRlFKqgQrMCRJ0rxN1Q9jz56GrMOSyipJku4ZbjqWpuk/KmswJRRydYS6uqzDuNxUo1S//y04cYTwc/+SsHoN+d/+N8Q//wLhp5JsYpRUdlZgSJKkkpjcD2PHjgv09NTZC0O17meA52fw9TNZBVgrwpp10Hd5RVf+y38ErWsJr3kzYcft8MrXEf/s88RiHw9JtccKDEmSVBJdXf10drbz0EMvJS3shaEadzhN039/vY2SJHlPJYKpaWvWw5lh4rlRwtJlxBeehWd+QEg+QKgvfKTJ/fT7yH/kF4hf/iPC33t/xgFLKgcrMCRJUsnYC0OLSZqmN81wu5vLHUvNuzRK9RQA8WtfhKZlhLf8xKVNQvsmwqvfSPzml4nnzmYRpaQyM4EhSZJKxl4YUkGSJJ1JkmzNOo5aEYqjVOntIZ47S3ziUcIdP0poWnb5dj/xLjg7Qtzz1QyilFRuJjAkSVJJ2QtDi1GSJJ9NkuRNxfvvB54EnkyS5APZRlYjihUYse8k8Ym9cH6M8Ma3XrVZuPFmuPFm4lf/mJgfr3SUksrMBIYkSSqprq5+du9ezl13rWP//gYg0N3dTEfHRjo727MOTyqXtwGPF+//C+DtwOuAD2cWUS1Z0QJLGqCvh/jY12HtBrjxlik3zf3Eu+DUCfjOX1c4SEnlZgJDkiSV3FS9MN7xjrPcdtt5enp8+6Ga1JCm6fkkSTqA1jRN96Rp+iSwPuvAakEIAdasJT73FDz9PcIb7iw8NpVXvQHWrCP/lS9UNkhJZec7CEmSVHJT9cJ4/vk6vv3tBpeTqFZ9J0mSfw38KvAnAMVkxlCmUdWSNevgwH6IkfCGq5ePTAh1dYS33wPP/ZB49FAFA5RUbiYwJElSWUz0wsjnIcbAM880EKPLSVSzPgC8HGgC/l3xsTcCn8ksohoT1hSLWW68mbDu2j8/wq0/AkA8fKDcYUmqoPqsA5AkSbWpq6sfgA996AwPPLCSRx5ZytmzOZqa8tx99znuv99fTGvhS5Lk54AvpWn6PPD3Jz+XpunngM9lElgtKjbyDG/88etvu7YdQg5OHClzUJIqyQSGJEkqK0erqsa9FvjVJEn6KSwd+RLwaJqmMduwak+45ZXE7bcS7njL9bddsgTWrocTRysQmaRKcQmJJEkqO0erqlalafrzaZpuAf4BhX4XHwNOFMeq/mySJG3ZRlg7wtbt1P3KbxKWzfBnx/oOohUYUk2xAkOSJJVdV1c/nZ3tPPTQSx88urub6e5uprExcuDA8Qyjk+YvTdPvA98HfitJklXA3wZ+EvjtJEleBD6SpukjWca42IT2TcSnv0fMjxNydVmHI6kETGBIkqSK2Lv3pL0wtCikaToIpMUvkiS5I9uIFqkNm+DCeeg7BWs3ZB2NpBIwgSFJkirCXhiqdUmS/CjwI8BlaxzSNP1oNhEtbmF9BxHg5FETGFKNsAeGJEmqGHthqFYlSfKfKUwc+VvALZO+bs4yrkWtfROAfTCkGmIFhiRJqhh7YaiGvRe4PU3TY1kHoqLmlbCs2UkkUg2xAkOSJFXU3r0nuffeUZqa8gA0NeW5775RHnvsZMaRSfNyGBjLOgi9JIQA7ZuIJjCkmmEFhiRJqqipemHU10d27VrNJz7Rz7p1+axDlObiA8D/SJLks8Bl2bg0Tb+ZTUgK6zuIT3476zAklYgJDEmSVHETvTDe+95RPvOZZXz9640cPlzPgw8287GPOZVEC9JrgHdQ6IFxdtLjEbghk4hUmETy6FeJZ0cJTcuyjkbSPJnAkCRJFdfV1Q9AZ2c7Y2Ph0uP2w9AC9lHgnjRN/zzrQPSSsKE4ieTEUdi2PetwJM2TPTAkSVJm7IehGjICuFSk2mxwEolUS6zAkCRJmZmqH8aePQ1ZhyXNxf3A7yZJ8gDQM/mJNE2v29glSZJPAe8EetI0vX2K5wPwceAngVHgfWmaPlGKwGva2vWQyzmJRKoRVmBIkqRMTfTDePjhU+zYcYGenjoefLD5+i+UqsungJ8HjgIXil8Xi7cz8fvA3dd4/h3A9uLXB4FPzDXQxSTUL4G17VZgSDXCBIYkScpUV1c/u3cv56671rF/fwMQ6O5upqNjI52d7VmHJ83UtuJX56Svie+vqzip5PQ1NnkX0J2maUzT9DGgJUkS/4HMxIYOOGkFhlQLXEIiSZIyt3fvSR54YCWPPLKUs2dzNDXlufvuc9x/vxNJtDCkafpimQ/RARye9P2R4mNXdbtNkuSDFKo0SNOUtra2WR+svr5+Tq+rRsPbtjP65LdZs3o1oa6ups5tKrV8frV8blDb51eqczOBIUmSMmcvDC1ESZL8epqmvzqD7f59mqYfqURMAGmafhL4ZPHb2NvbO+t9tLW1MZfXVaP8qla4eIHe/U8S1m2sqXObSi2fXy2fG9T2+V3v3DZu3Dij/ZjAkCRJVWGiF8Z73zvKL/5iC/v3L+HBB5v52MeswlDV+mfF5pvhOtv9EjDfBMZRYPOk7zcVH9N1hPbNhVGqx4/Aupl9SJJUnUxgSJKkqtDV1U9nZzsPPfRSA8/u7ma6u5tpbIwcOHBVpbyUteXAc1w/gXGuBMf6Y+AXkiTZDbweGEzT1H8UM9FeyPvE44cJr3xdxsFImg8TGJIkqWrYC0MLSZqmJWuInyTJZ4E7gbYkSY5QqNhYUjzO7wFfojBC9TkKY1TfX6pj17qwbDmsaoVjh6+/saSqZgJDkiRVjal6YdTXR3btWs0nPtHPunX5rEOUyiJN0/dc5/kI/NMKhVN72jc5SlWqAY5RlSRJVWWiF8bDD59i584R9u1rYN++Bh58sPn6L5akKYT2TXD8MDHGrEORNA9WYEiSpKrS1dUPQGdnO2NjL7UWsB+GpDlrvwHOnYWB07B2bdbRSJojKzAkSVJV2rv3JPfeO0pTU2HZSFNTnvvuG+Wxx05mHJmkhSa0byrcOX4o20AkzYsVGJIkqSpN1Q9jz56GrMOSppUkSTPQAgykaXom63g0yaVJJPbBkBYyExiSJKlqTfTDeO97R/nFX2xh//4lPPhgMx/7mFNJVB2SJLkd+MfATwFbKIxUjUmSHAT+FPjvaZp+P7sIBcDKFli2HI47iURayFxCIkmSqlZXVz+7dy/nrrvWsX9/AxDo7m6mo2MjnZ3tWYenRS5Jkt3AHwDHgZ8F2oCG4u0/AI4CnylupwyFEKB9sxUY0gJnBYYkSapqe/ee5IEHVvLII0s5ezbH0qWR5cvz7N7dl3Vo0v9O0/SLUzzeDzxa/PpYkiTvrGxYmkpo30z87l9nHYakebACQ5IkVbWre2FAX1+OT396WdahaZGbnLxIkuT1U22TJMnrpklyqNLaN8HwIPmhwawjkTRHJjAkSVLV6+3NEQLFsaqFL5eSqMp8ZZrH/6yiUWhaodjI8+KRg9kGImnOXEIiSZKqXldXPydP5i5bStLUlOfuu89x//029FR2kiTJUcyqJUkykWGbcCNwMZPAdLUNhVGqF48chHUd2cYiaU6swJAkSQvCVGNV6+sju3atpqfHtzTKzEXgPLCseP/CpK8fAv8tu9B0mTXroKGBcSswpAXL/+0lSdKCMTFW9eGHT7Fz5wj79jWwb18DDz7YnHVoWry2Uai0OAJ0TvraBqxM0/TXsgtNk4VcDjZscgmJtIC5hESSJC0YXV39AHR2thf7YRR0dzfT3d1MY2PkwIHjWYWnRShN0xeLd7dkGohmpm094z3+jJAWKiswJEnSgrN370nuvXeUpqY8AE1Nee67b5THHjuZcWRaTJIk+U9Jkmy4zjYbkiT5T5WKSdcWVrWS73cEs7RQWYEhSZIWnKn6YezZ05B1WFp89gN/nSTJU8BfFL8fBlYAO4A7gZcBv5FVgLpCSytxZJg4NkZobMw6GkmzZAWGJElakCb3w9ix4wI9PXX2wlBFpWn63yn0v/gfxdt/BfwX4Fco9MH4PeCmNE27MgtSl1vVWrgdPJ1tHJLmxAoMSZK0IHV19dPZ2c5DD72UtLAXhiotTdMLwOeKX6pyoaV2A+1vAAAgAElEQVSVCDDYD+vasw5H0ixZgSFJkhYse2GoWiRJ8rtJktyRdRy6jpZCBUYcsAJDWoiswJAkSQuWvTBURQLwhSRJRoA/AP4gTdP9GcekK61aXbgdtJGntBBZgSFJkhY0e2GoGqRp+iFgE/BPgM3AY0mSfCtJkn+RbWS6zPIVUL8EBvqzjkTSHFiBIUmSFjR7YahapGmaB74CfCVJkl8F/hfw24BjVKtECIFcaxvRJp7SglQ1CYwkSf458HNABL4PvD9N03PZRiVJkhaCvXtP8sADK3nkkaWcPZujqSnP3Xef4/77h7IOTYtIkiTLgfuA91AYofoXwD/MMiZdrW71Gi7YA0NakKpiCUmSJB3ALwGvTdP0dqAOeHe2UUmSpIXCXhjKWpIkfwicBD4IfBHYkqbpT6Zp+r+zjUxXyrW2FaaQSFpwqiKBUVQPNCVJUg8sA45lHI8kSVpA7IWhjP0NcGuapn8rTdNPpGnam3VAmlqutQ2swFAVyP/xZ4kvPJt1GAtKiDFmHQMASZJ8CPgPwFngy2mavneKbT5IIatNmqavOX/+fGWDBOrr67l48WLFj7tYeH3Ly+tbXl7f8vL6lletXN9Vq5Zw7ly46vGlSyODgxcyiKigVq5vtZrt9W1oaIDC1JDFIB47NvvfC7a1tdHbW5s5mKa/+BJn/vfvkfsvf0hobMw6nJKr5T+7Wjq3ePIY+X/384Q3v43c+z4E1Nb5Xel657Zx40aYwc/lquiBkSTJauBdwDZgAPjDJEl+9sqSuzRNPwl8svhtzOIPt5b/UlUDr295eX3Ly+tbXl7f8qqV6/voo7lpe2H09uYzi6tWrm+1mu31Lb5R1iKVW91WuDN4Gta1ZxuMFq34/b8p3B5+4fLH+/uIe79GeNs9hMalWYRW1aplCcnbgRfSND2VpukF4P8Cb8o4JkmStMBM1Qujvj6ya9dqenqq5W2PpCzlWosJDJeRKEPxe48X7hw7RLz4UoVg/NoXiX/0afL/8cPE/r6Moqte1fI/+SHgDUmSLEuSJABvA57KOCZJkrQATe6FsXPnCPv2NbBvX4P9MCQBhSkkANFGnspIPHcWnnkS1qyDixfhxJGXnjuwH1rWwMnj5D/6L4kvPp9hpNWnKhIYaZruAz4HPEFhhGqOl5aKSJIkzVhXVz8f/egQ99yzloceaubQoSXEGOjubqajYyOdnZaMS4tZrnVt4c6gv91WRp76LoxfJNz9dwGIhw4UbscvwsFnCa95E7kP/yaEHPlPPZhlpFWnKnpgAKRp+hHgI1nHIUmSasPevSen7YchafEKzSugfolLSJSZ+P3HoWkZ4c1vJ/7hp6DYB+PioQNwfgy27SBs2kZ489uIf/KHxAvnCUscDQ5VUoEhSZJUalP1w9izxzeA0mIXQoBVq8ElJMpAjLGQwLj1VYWkRMfWS408L+x/EoDQ+bLCxhs2QczDydlPEqpVJjAkSVLNmtwPY8eOC/T01NkLQxK0tBKtwFAWDh+AgdOEl98BQNjcCYcPEGPkwjNPwopV0La+8Fz7ZgDi8SPT7m6xMYEhSZJqVldXP7t3L+euu9axf38DYC8MSUBLq0tIlImJ6SPh5a8uPHBDJ4yOwOlTXHjmB9D5skKVEMCGDggBjh/OKNrqYwJDkiTVtL17T3LvvaM0NeUBWLo0smbNOF/84qmMI5OUlbCq1SUkykR8+nuw5SbCytUAhM3bCo8/9V3Gjx4i3HjzpW1DQ2NhUskJKzAmmMCQJEk17epeGNDXl+PTn16WdWiSstLSCmdHiGPnso5Ei83pU4QNHS9937EVQo74zUeASf0vJrRvdgnJJCYwJElSzevtzRECjI0FoPDlUhJpEVtV+O03gy4jUeXEGKG/F1a3XXosNDbC+o3wwjOQy8GWmy57TdjQASePEvPjlQ63KpnAkCRJNa+rq5/HH798KUlTU5777hvlscdOZhydpEoLLa2FOwMuI1EFDQ/CxYuwes1lD4cbOgGov+FGwtKmy1/TvhkunIc+lz2CCQxJkrRITDVWtb4+smvXanp6fEskLSqrCh8goxUYqqT+PgDCpAoMAIp9MJbsuO2ql4T2TYU7NvIETGBIkqRFZPJY1Z07R9i3r4F9+xocrSotNi3FJSROIlEl9fcWbq+swNhcqMBY8rKrExg4SvUy9VkHIEmSVCldXYVy8c7O9mI/jILu7ma6u5tpbIwcOHA8q/AkVcqyZmhogNO9WUeiRSQWKzC4sgLj5lcQ/v4/Zumb387I8PBlT4XlK2DFKieRFFmBIUmSFp0rR6vaD0NaXEII0LGVeOj5rEPRYtLfC3V1hYTEJKGujtxbf6rQ0HMq7ZuJLiEBTGBIkqRFaKp+GHv2NGQdlqQKClu3w4vPO91BldPfBy1rCLnZfQwP7Zvg+JHCFJNFzgSGJElalCb3w9ix4wI9PXX2wpAWk63bYewsHD+adSRaJGJ/71X9L2ZkwyYYPQPDA6UPaoExgSFJkhalrq5+du9ezl13rWP//gYg0N3dTEfHRjo727MOT1KZhW3bAYgHn804Ei0a/X1XTyCZgVBs5ImNPE1gSJKkxcteGNIitr4DljaBCQxVQIwRBuZYgVEcpWofDBMYkiRpEbMXhrR4hVwOttxUdRUYMUbyj36VODJ8/Y21cIyegfPn55bAWN0GjU1WYGACQ5IkLXL2wpAWr7D1JjjyAvHihaxDecmh54n/6+PEr38p60hUSv2Fkb1zWkISAmzeRnzhmVJHteCYwJAkSYuavTCkxSts2wEXL8KRg1mHckn8wROF22d/mHEkKqn+vsJtyxwqMIBw0y1w6ADx/FgJgyqtODZGPPwC8UL5EoL1ZduzJEnSArF370keeGAljzyylLNnczQ15bn77nPcf/9Q1qFpEUmS5G7g40Ad0JWm6W9e8fwW4FPAWuA08LNpmlpTPh9bX2rkGYr3sxZ/+J3CneefJo6PE+rqsg1IJRGLFRjMoQIDCgmM+Gefh4PPwY7bShhZCR18hvzv/FtyH/o1uP3VZTmEFRiSJGnRm6oXRn19ZNeu1fT0+HZJ5ZckSR3wX4F3ALcC70mS5NYrNvsdoDtN01cADwAfq2yUNah1LaxYBS9URx+MeG4Unn8K1m4ojHg98kLWIalU+vsg5GDV6rm9vvNmAOLzT5UwqNKKxw4V7nRsKdsx/B9ZkiSJy3th7Nw5wr59Dezb12A/DFXK64Dn0jQ9kKbpeWA38K4rtrkV+Frx/teneF6zFEKArdurp5Hn09+H8XHCPe8BID77ZMYBqWRO98Kq1XOuqAkrVsKGDuJz1ZvA4OiL0LQcWlrLdggTGJIkSRR6YXz0o0Pcc89aHnqomUOHlhCj/TBUMR3A5BmJR4qPTfZd4O8W798HrEiSZG4L6nVJ2HoTHD9CPHc261CIP/w2NDQSXvsWaFtvH4waEvvnOEJ1knDjLYWlRfl8iaIqrXjsEHTcUEgMlok9MCRJkiaxH4aq2C8D/yVJkvcB3wSOAuNXbpQkyQeBDwKkaUpb2+zX3NfX18/pdQvBlec29srXMvDwblYN9tKw6UcyjAx6n/4edS9/Davb2xm8/dWMPbGXNWvWzOoD4WL6s1tIeocGqL9hGy3XiP9653f2Va9jaM+fs3pslPrNW8sQ5dzFGDl1/DBL3/TjrJziHEr1Z2cCQ5IkaZKp+mHs2dOQdViqfUeBzZO+31R87JI0TY9RrMBIkqQZ+Ok0TQeu3FGapp8EPln8Nvb29s46mLa2NubyuoXgynOLKwrl7gNPP0lu/ebpXlZ28dQJ8sePkP+xd9Db20v+hhuJ3/hTep/8LmHDphnvZzH92S0UMUbyvSfJ3/yKa8Z/vfOL6wt/D04//ii5pupa3hgHThPPDHOudT3npziH653bxo0bZ3Qcl5BIkiRdYXI/jB07LtDTU2cvDJXb3wDbkyTZliRJA/Bu4I8nb5AkSVuSJBPv3/81hYkkmq+WVqhfAj3HMw0jPvltAMJthSqQsL3Qw9VlJDXg7CiMnZvzBJJLNnRA84pCo9dqU2zgGTaWNwloAkOSJOkKXV397N69nLvuWsf+/Q2AvTBUXmmaXgR+AXgEeKrwUPpkkiQPJEnyd4qb3QnsT5LkGWA98B8yCbbGhFwO1m4gnqqCBMaadbC+2PpkfUdhQoqNPBe+/r7C7Xx7YIQAN95CfO7pEgRVWvHYi4U7ZZxAAi4hkSRJmpK9MFRpaZp+CfjSFY/dP+n+54DPVTquRWFde+YVGDz/FOHlr73U7yKEANtvtQKjFvQXlk6E1vn3gAg33kL87l8ThwcJK1bNe38lc+wwNK8krGwp62GswJAkSZqCvTCkxSOs3QCnThBjzOT48cwQDA9Cxw2Xx7X9Vug9STy98Po+6CWxmMCY9xISINx4c+FOlS0jiUdfhI03XH/DeTKBIUmSNA17YUiLxLp2OD8Gg/3ZHP9EoV/rlc06w82vACA+9Z2Kh6QSmlhCsmr1/Pe1bTvU1xOfrXwCIw4PEb/1KPH73yI++0Pi+bHC4zHC8cOEjvInMFxCIkmSNI2urn46O9t56KGXkhbd3c10dzfT2Bg5cCDjknNJJRHWbiACnDpRaOpZYfHEkcKdK6eNdGyFVa3wgyfgzW+veFwqkYE+WNlCqF8y712FJQ2wbQcxg94o8U/+D/GrD7/0wI7byP3yRwtLZM6OWoEhSZKUtb17T3LvvaM0NeUBaGrKc999ozz22MmMI5NUMusKzXljVn0wThyF+npoW3fZwyEEwu0/Qvzhd4jj49nEpnmL/b0lWT4yIWy/HV58jnjubMn2OROx9yRs6CD34f9IeOfPwDNPFpJrRycmkJS3gSeYwJAkSbqmqXph1NdHdu1aTU+Pb6WkmtC6DnI5yGgSSTxxBNZtJOTqrn7yttfA6Bk4+GzlA1Np9PfNewLJZGHHbZDPw4EKTyMZOA1tGwg33kz4qQTWrCP/hc9MmkBiBYYkSVLmJvfC2LlzhH37Gti3r8F+GFKNCPX1hRGmWVZgXLl8pCjc+koIOeIPnqhwUCqZ/j5CCRMY3PgyyOWIz1R4GcnAaUJxiVWoX0K45z2FSpCv/QmsaiUsX1H2EOyBIUmSdB1dXYXGfp2d7YyNhUuP2w9DqiFrNxBPnaj4YePFi9B7gvCaN0/5fFi+Ajp3EJ98At719yscneYrjp0rVNC0lLACY+kyuOHGivbBiOPjMDRwWY+Y8IY7iX/6OTh5FG55ZUXisAJDkiRphq7sh7F0aWTNmnG++MVTGUcmab7CuvZsKjBOnYDxcdjQMe0m4bZXw8FnicODFQxMJTExgaSEPTCguIzkwDPEC+dLut9pDQ1AzF+WiAl1dYR73l24X4EGnmACQ5Ikacau7ocBfX05Pv3pZVmHJmm+1m6A0TPEkeHKHrc4geTKEaqThdtfDTESfzj3carx4gXi0Rcr3vhx0evvBSjtEhIgbL8NLl6AFyrUG2XgdOG4V0zpCXe8hfC37yO86W0VCcMEhiRJ0iz09uYIgeJSksJXd3czHR0b6exszzo8SXMUipNI6KnsMpKXRqhOX4HBlpugeWVh4sNs9//4XzH+6/+c/C/+DPlf+0Xi539/boFqTmLxg3+pKzDYfmth/5VaRjJYrCS5MoGRqyP3995PuKGzImGYwJAkSZqFrq5+Hn/c0apSzVlbHKVa6UkkJ45CSyuhafpKrpDLEW79EeKTT8x6nGr+z/8YBvsJb/s7sHkb8bmn5huxZqNYgVHKHhhQ7I3SsaVijTxjfzERU+LzmC0TGJIkSbM01WjVPXsasg5L0ny0bSjcVrgPRjxxBNZfo/qiKLzmjTA8CE/NfBlJzOfhyEHCa95E7u+9j/DyO+DYIeL5sfmErNno74NlzYTGxpLvOuy4DZ5/atZJrTkZOF0YNbxiZfmPdQ0mMCRJkuZg8mjVHTsu0NNT51hVaQELjY2F8vgKTiKJMcKJI4T26ftfXPLyO2BZM3HvN2Z+gN4TMHYONm8DIGy9CfJ5OPzCnOLV7MX+Xihx/4sJYcfthT/f558uy/4vM9gHK1cTcnXlP9Y1mMCQJEmag66ufnbvXs5dd61j//4G7IUh1YB17cRKVmAMD8LoCFyjgeeEsGQJ4XU/SvzOXuLZ0Zntv5ioCJuL/Qm23AhAPPT8nMLVHAycLn3/iwm3vxqWNBAf/6vy7H+S2H+6bImY2TCBIUmSNEdXjlW1F4a0sIW1GypagTGTCSSThTe8Fc6fJz7x6Iy2j4deKJT9b9xceGB1G6xYBS8+N6dwNQf9vSWfQDIhLF0Gr3gt8Vt7iPkyLyMZPA2rWq+/XZmZwJAkSZqjqXph1NdHdu1aTU+Pb7OkBWdtOwyeJo6dq8jhZjSBZLLOlxWqRPZ+fWb7P3wA2jcTlhR69IQQYMuNxIMmMCohXrwAQwNlbXyZu+NHC8fY/4OyHQOAgdNXjVDNgv+zSpIkzcPkXhg7d46wb18D+/Y12A9DWoDC+o2FOyePVeaAx49CQ8OMlxiEEAhvfCvs/z6xr+f6Lzj8AqHY/+LSPrbcBMcP28izEi6NUC3j0ovbXwuNS4l/85dlO0Q8PwYjw1eNUM2CCQxJkqR56Orq56MfHeKee9by0EPNHDq0hBjthyEtSMVKiHjyaEUOF08dh7XthNzMP5aF199ZeO1j37j2voeHYKDvUgPPS6/fYiPPihnoAyCUqwcGheaz4ZWvJz6xl3jxYnkOMthfuM14hCqYwJAkSSoJ+2FINWDdRggBTlQmgUFfD7Stn9VLwtoNsON24l9++dofWI8UG3huujyBcamRp30wyi72FxIY5W5+Ge54S6FC4qnvlucAxUoSl5BIkiTViKn6YezZ05B1WJJmITQ0QuvaS801y66vh9C6dtYvy911L/T1EB+fftlAPHygcOeKCoyXGnk6iaTs+nsLt+We3nHbq6FpedmWkcRiJYlLSCRJkmrI5H4YO3ZcoKenzl4Y0kKzoYNYgQqMOHoGzo5C27rZv/jlr4WNNxD/9PPEfH7qbQ6/AC1rCCtWXfZwoZHnTVZgVEJ/HzQuhablZT1MWLKE8KrXE7+zjzhehmkkE708XEIiSZJUO7q6+tm9ezl33bWO/fsbgEIvjMbGBnthSAtE2LAJTh4lxljeA/WdKhxvzewTGCGXI9z903DsEHz/W1NuEw+/cHX1xcTrt9wIxw4Tx2zkWVb9fYUkUgjlP9bLXwtnR+Dgs6Xf98BpWNIAy8qbiJkJExiSJEklNFUvjHe/e9xeGNJCsaEDxs4VPnyWU1/xZ0LrHCowgHDHj0LrWvJ/9rmrnosXzsOJI1dNILn02i03Qcxf6pOh8ogDfeVfPlIUbn4FhEB86jul3/lAH7S0ViYRcx0mMCRJkkpoql4Y3/iGb7mkhSKsL0wiocyTSGKxAoM1s++BARDq6wl33QfPPUV85snLnzx2GMbHp01gsGlrIYZjh+Z0bM1Qfy+hUgmMFSthcyexDI0848BpWJV9/wswgSFJklRyV/bCOHECe2FIC0X7JgBiuRt59vVAQ0OhoeYchbf8BKxsIf+5/3VZL4z4/FOFO5s7p37hytWF2zNDcz62ri3mxwtLL8o4QvVK4ZZXwvP7iefOlnbHA6crloi5HhMYkiRJJTZdL4yOjo32wpCq3apWaGwq+yjV2HcKWtfNqyw/NDYS/p/3wwvPEP/yywCM954kfuEPYOt2WLth2tfR0GACo5yGBiGfr2jjy3DrK2H8Ijz75PU3nqEYY2EJiRUYkiRJtWuqXhj33TdqLwypyoUQipNIKlCBMcflI5OF198JL3s58f92Ewf7Gfz4r8P4RXL/6F8Sctf4uNe8EoZNYJRNsYdKRSsXbroV6pcQf1jCZSRnR+H8WFWMUAUTGJIkSWUxuRfG0qWF2/r6yK5dq+np8S2YVM3Cho6yV2DQ10NYs37euwkhkHvvz8PYWfIf/WUu/OAJwnv+MWHdxmu/sHklcWR43sfXNAaKTWAr+ME/NDTC9ltL28hzcGKEqgkMSZKkmjbRC+Mv//IiO3eOsG9fA/v2NdgPQ6p2GzbB6VNlGzMax84Vlm+UoAIDILRvJtx1L5w+ReOb30Z4049f/0XNK11CUkZx4trOo8fJXIRbXglHXyQO9pdmhwOFBEao4FKYa6nPOgBJkqRa1dVVeAN5443tnDu35NLj3d3NdHc309gYOXDgeFbhSZpG2NBBhMIkkhumaYQ5H309hds1cxuhOpXwzndD6zpW/uTf5fTo9Zs4huUriL0uaSubM8XqluUrKnrYcMsriUB86ruEN9w57/3FU8X/o1or14z0WqzAkCRJKrOnn75gPwxpIdlQGKUayzVKtThCNZSoAgMKywdyd76D3LLlM3uBFRjlNTIE9fXQuLSyx72hs5A0+eG3S7O/A/sLf1fa5r/cqRRMYEiSJJVZezuX+mE0NhZu9+xpyDosSdNZtxFCgOPlaeQZL1VgZPihsHkljI4Qx8ezi6GWnRmG5SvnNWVmLkKujvCq1xG/9Shx5My89xefexpuvLni5zEdExiSJEkVMNEP4+GHT7FjxwV6eurshSFVqdDQCK1rC0tIyuF0D9TVw6rV5dn/TKxYWbi1kWdZxJFhaK7s8pEJ4cfvgfNjxL/6yrz2E4eH4ORRwo23lCiy+TOBIUmSVAFdXf3s3r2cu+5ax/79DUCgu7uZjo6NdHa2Zx2epCu1byrfKNXeHmhtu/aY03Kb6M3gMpLyODNc8f4XE8INnbDjNuLX/2R+FTYHni7s78abSxTZ/JnAkCRJqpC9e09e1gtj6dLImjXjfPGLpzKOTNKVwrqNcOoEMcaS7zuePlXSBp5zEZqLFRhnrMAoiwwrMAByb7un0Cz2u/vmvI/43FOFSqGtN5UwsvkxgSFJklQh69fnr+iFAX19OT796WVZhybpSm3r4exoeZZY9PWUtIHnnFxKYFiBURZnhggZVWAA8KrXw5p15L/68Jx3EZ9/Cm7oLCypqhImMCRJkiqotzdHCDA2FoDCl0tJpOoT1hYbbJ4q7bSgeOECDJyG1mwrMCYSGNEERsnFGGH0TKYVGCFXR3jrT8EzTxIPPT/r18eLF+Dgc1XV/wJMYEiSJFVUV1c/jz9+0rGqUrVr2wBA7C3xv8v+4pKxjJeQXPpwbQKj9M6Owvg4LF+ZaRjhR38CGhqIf/HI7F986ABcOE+4yQSGJEnSonb1UpJAfX1k167V9PT49kyqCm3FCozeE6Xdb18hgRHaMu6B0dAIDY1OISmHiWuaYQUGQFjWTHjVG4mP/1Wh8mcW4vOFBp5UUQNPMIEhSZKUicljVXfuHGHfvgb27WtwtKpUJcLSJlixCkpcgXGpoqM14x4YUFhGMmwFRskVG6Nm2gOjKLzxzsJylu//zaxeF597CtrWE1payxPYHNVnHYAkSdJi1NXVD0BnZ3uxH0ZBd3cz3d3NNDZGDhw4nlV4kgDa1hNPlbgCo7cHcjlY3Vba/c5F8wp7YJTDSPGaZlyBAcAtr4KVLeQf+wZ1r37TjF4SY4TnnyLc/IoyBzd7VmBIkiRl6MrRqvbDkKpHaFtf8goMek9A61pCfRX8Lrl5pT0wyiBOjKbNuAcGQKirI7zux+B7jxNnulzoe4/DYD/cdGt5g5sDExiSJEkZmqofxp49DVmHJQkKfTBOnyKOj5dsl/HUCVi7oWT7m4/QvNIeGOVQJT0wJoQ33gnjF4l/81fX3TYePUS+63cK41Pf+OPlD26WTGBIkiRlbHI/jB07LtDTU2cvDKkarN1QmCbR31u6ffaeJFRJAsMKjDKZqMBYViU/xzd3Qvtm4mNfv+ZmcXiI/H/9DWhcSu6f/jtCY2OFApw5ExiSJEkZ6+rqZ/fu5dx11zr2728AAt3dzXR0bKSzsz3r8KRFK1yaRFKaZSTx3CgMD14a0Zq55StgdKSkFSai0ANj2XJCXV3WkQAQQiC88a3w/NPEnql7K8UYyf+P34b+PnL/5N8QWqugR8sUTGBIkiRVAXthSFWomMAoWSPPU4V/z2Ht+tLsb75WFHs0uIyktM4MF5JDVSS87scAiN96dOoNvr0XnvouIfkAofNlFYxsdkxgSJIkVQF7YUhVqHVtYWJIqRp5TiRCqmkJCbiMpMTiyPBL17ZKhDVrYet24rf2XPVcvHiR/Oe7oX0z4W/97QyimzkTGJIkSVXCXhhSdQl1dYUkRqmWkPQWExhVsoQkmMAojyqswAAIr34TvPgcsa/nssfjXz4CPcfI/fT7qmbZy3RMYEiSJFUJe2FIVWjthhIuITkBy5oJy6skMTnxIdsERmmNDBOqZALJZOE1bwQgPrH30mPx7Cjx4d3wspfDK16bVWgzVgXDhyVJkjRh796TPPDASh55ZClnz+Zoaspz993nuP9+P2DUuiRJ7gY+DtQBXWma/uYVz98APAS0FLf5cJqmX6p4oItMaFtP/M6+kuyrmkaoApeWOcQz/z97dx4fV13vf/z1nayTTNJmb5ICbdqmC0spKIsoIG7FDar1KCL1Xpd6UXC9ItyreC9XQVQs/NxrFAmgeAQVi0JVBBdoC5Y10IaW0tIlTTJtmn2f7++PM2mbNm2TNDNnMvN+Ph59JDM5M+fz/Z40yXzm8/182zE+h5JUErUCo7QCps/EPvU4vOUSAOwffw3trQSW/hvGJP53gSowRERERBKIemGkJsdx0oDvAxcDC4DLHMdZcMhhXwZc13UXAR8AfhDfKFNUcRm0t2J7uo//uZobD+xskghCqsCYaHagH3q7D8xtgjFnngubN2D37cE+vx67+jeY896MmTHH79BGRQkMERERkQSjXhgp6Sxgs+u6W1zX7QPuAS455BgLDHUGnALsimN8qWuoYuI4+2DYyCDsaUqoCgyTmQVZ2UpgTKSO6I4uuYnVxHOIOfM8AOyff0+k5haoPAlz2Sd8jmr0EmYJieM4U4Ea4BS8H84fcaDHh20AACAASURBVF13zdEfJSIiIpJ8ampaqKoq5447DiQtamtD1NaGyMqybNnS4GN0EiOVwPaDbu8Azj7kmP8B/uQ4ztVALvDmkZ7IcZzlwHIA13UpLi4eczDp6enjetxkMNax9c+ay14gr6+b7OOYk8Hm3YQHBwjNnEVODOd2rONrzp9CZn8fUybB9Z4M35cDXW3sAfLLK8b8/RKX8RUXE54+g8E//RaTE6Lwv75JenllbM/JxI0tYRIYeOv9HnJdd6njOJlAjt8BiYiIiPhFvTBkBJcBP3dd9xbHcc4F7nQc5xTXdSMHH+S67kpgZfSmDYfDYz5RcXEx43ncZDDWsdmMbADatrxER9X8cZ/X1r8IQGcwj64Yzu1YxxcJhujZ00z/JLjek+H70u54FYD2CHSMMdZ4jS+y6BzYsRXzkc+yLyMb4nDOY42toqJiVM+TEEtIHMeZApwP/BTAdd0+13X3+RuViIiIiH9G6oWRnm658soCmpoS4k84mVg7gRMOuj09et/BPgq4ANFK5Wwgsd+OTgahPMgKQrjp2Mcexf6dTBKpBwZ4jTy1hGTiDC0hSdAeGABm8XsJXH8bZuFZfocyZolSgTETaAZudxxnIbAe+Izrup0HHzQR5XDHazKULU1mmt/Y0vzGluY3tjS/saX5ja3xzm9bWxrLl0f42Mci1NQEWL06yKuvGn74wxK++93BGEQ6OSXJ9++TwBzHcWbiJS4+AHzwkGNeBd4E/NxxnPl4CYzmuEaZgowxUFKGbTrOpVvhRggEoLBkYgKbICaUh23WsrSJYjsTuwcGRHufnDDT7zDGJVESGOnAGcDVruuucxznNuBa4CsHHzQR5XDHazKULU1mmt/Y0vzGluY3tjS/saX5ja3xzu8PontMVFWV09vrbW/3/um/I+PhvWRlfUT9MKLGOr+jLVWOJ9d1BxzHuQpYjbdF6s9c133BcZwbgH+5rvt74AvATxzH+Rxez7h/c13X+hd1Cikth13bj33c0TTvhqJSTFraxMQ0UUL5B6oG5PhNggqMySxREhg7gB2u6w5tsHwvXgJDREREJOUd3A/jjILneW/lH+k59QKu+mqu36HJBHJd94/AHw+57/qDPn8ROC/ecQmYkmnY557ERgYxgfElIGzz7sRbPgJeAqO7EzswgElPlJeHk1hnG2RkQmaW35EkpYRYQOm67m5gu+M4c6N3vQl40ceQRERERBLGwf0wfrDt40RsgNfs+rnfYYmkjpJyGBiAlr3jf47wbkxJ+cTFNFFC0aUOXarCmBAd7ZCb5y09kgmXEAmMqKuBux3HeQ44HbjR53hEREREEkY4HGDZsk5+cm+A+9uWcnHRQ/ziW41+hyWSEkxpNPEwzl4RtqvTe2FbkngVGCYvmsBo1R4KE8F2tmv5SAwlTI2Q67rPAK/xOw4RERGRRFRT00JVVTl33BFiSvpHWfzG37PgpZ9RWXmbemGIxFrJNABsUwNm3mljf/zuHYC3FCXhDC1r2dM4aRs7JpRoBYbERiJVYIiIiIjIUaxZ08ill3bRlxHi+y//G28qfYwvXvIYa9eqEkMkpgqLIS3da8Q5Dvb59WACUH3KBAc2AYaSM836OTIhVIERU0pgiIiIiEwSB/fC+EWDQ0NPKW9s+TFYbUQhEksmkAbF499K1T69BmbPw+RNmeDIJkBOCII5407OyCE62jAJvIXqZKcEhoiIiMgkMtQL497727m77WOcEnqR1Tc/7XdYIsmvtHxcPTBsUwPs3IZZdG4Mgjp+xhgvORNWBcbxstZCV4cqMGJICQwRERGRSaSmpoV77snlrW8t5fvr381L7VWc3VDDidNLqapKwB0ORJKEKZkGzbu9F6ljYJ9Z5z3+9LNjEdbEiI5NjlN3JwwOqgdGDCmBISIiIjLJDPXCyMwOcHP9J5kVepX/W3wfJ5/cR1OT/rwTiYmSadDTDe2tY3qYfWYtTJ+RmA08o0zxNNjThI1E/A5lcmv0KnRMcanPgSQv/YYTERERmWQO7oXx99bzearlVN46UEvdM4YVK0J+hyeSlA5spTr6SgXbtg82b8QsOidGUU2QkjLo74O2Fr8jmdTsjle8T6bP8DWOZKYEhoiIiMgkNNQLIxIxfGfTckozGnlf5Spqa0NUVlZoOYnIRCvx/k+NpZGnfe5JsBHM6YmdwDBDW6lqJ5Ljs3MbZGZBceJW20x2SmCIiIiITEI1NS3ceGMb69Y1UnjeaTzVeipXzf4Z+Tk9LFnSpa1VRSZacRkYM6ZGnvbptVBUCifMjGFgE6B4aCtV9cE4HnbHVqg8CRPQy+xY0cyKiIiITGJlZRHy8uE7Ly2nMtjIu4sf4LHHMv0OSyTpmIwMKCge9RISu2MrvPA0ZtE53k4fiayo1EvOhJXAGC9rLezcitHykZhSAkNERERkkguHA8y8+BS6yufz2bm3sy88qF4YIrFQMm1US0hsfx+RmlsgN4R5+/viENjx8ZIzRVpCcjxa90JHu/pfxJgSGCIiIiKTXE1NC/f8KsTH7/8UpRmNONPVC0MkFkxp+agqMOx9d8DObQT+7TOYvClxiGwCFE/DhpXAGLcdWwFUgRFjSmCIiIiIJIE1axopOu9Unmo9jatm3a5eGCKxUFIO7a3Y7q4jHmLr1mMfXoW56J2YU8+MY3DHxxSXaQnJcbDRBAaVM/wMI+kpgSEiIiKSBIZ6YdxSv5yKYCOXlKxSLwyRCXZgK9XDl5FYa4n87SEi378RKk7EvPfDcY7uOJWUwb692L5evyOZnHZug4JiTK6W78WSEhgiIiIiSSIcDlD19pPpqljAZ6p/zt5mq14YIhOpJLpbx+6dw+62XZ3Yld/C3vUDmHsKgS98DZOZ5UeE4ze09eeeJn/jmKTsjq3qfxEHSmCIiIiIJImhXhif+v3HKc1o5B3lD6sXhshEKquEvCnYX/wY++LTANjNG4jc8BnsU49j3vNhAp/+KiZ/qs+Bjp2JJmdGu8uKHGAH+qFhB2b6SX6HkvSUwBARERFJImvWNJJ/7iJe7pzB8pl3EgwOqheGyAQxWVkErr0ZphYSufV/GfzRN4h88zowhsA13yBw8XsxgUn6EqukDECNPMdj904YHFD/iziYpP+7RERERGQkZWURQvmGlVsu59Qp9ZyRs570dMuVVxbQ1KQ//USOlymtIHDtN+GMc2D945izLyBw/W2YWfP8Du345E2FzCxtpToOdv8OJDP9DSQF6LeYiIiISJIJhwPkvPF8BnKm8j9vqGXdukzWrctUPwyRCWKygwQ+8SUCN64k8NHPYYI5fod03IwxUFyG1U4kY7dzG6SnQ1mF35EkvXS/AxARERGRiVVT0wLAty/6AJ+b9SOy976KtbOorQ1RWxsiK8uyZcvhuyiIyOgZY/Y39UwaJdNg+ytE1j7idyQj6g7lEelo9zuMw9gNz8K0EzDpenkda5phERERkSS17Kfn03fj7fzH7Lv4/DNfJRiMsHhxD9df3+Z3aCKSgMwJM7HPPoH96Qq/QxlRIv/kMhcs9juElKAEhoiIiEiSKp0Z4rGsi3nXtD9wS94n2dVRzGOPZfodlogkKPOuyzDnXgRYv0MZUUFBIS0te/0OY2RFZX5HkBKUwBARERFJYg/0vJ+zAvez6gs/57Jffob6+gxWrAhx002J/F6miPjBBAJQmrhbLqcXF2Mysv0OQ3ykJp4iIiIiSeymmlz+0nQBgX8+xCubAAy1tSEqKyuoqkrcFyoiIiKHUgJDREREJMmd/cWLKMxs5Z3TvcZ8wWCEJUu6WLtW2yWKiMjkoQSGiIiISJIreN1ptATKWFK2iqwsS0+PUS8MERGZdJTAEBEREUlyJhDgn4Pv4A0l63jw7jqqq/tpakpjxYqQ36GJiIiMmhIYIiIiIingkpvPAwurrnuc+vpM1AtDREQmGyUwRERERFKAKSphYM7pfHjO/eQG+wH1whARkclFCQwRERGRFJH9prdQSBOvCT25vxdGerrlyisLaGrSn4UiIpLY9JtKREREJFUsPJsOO4Uvvf43rFrVzLJlnaxbl8m6dZnqhyEiIglPCQwRERGRFGEyMsh7ywWcMvBPPvyedO64I8Srr2ZgrfphiIhI4lMCQ0RERCSFmNe/BQYHePjm+7j00i6CwQgA2dmWoqJBHnig2ecIRURERqYEhoiIiEgKMZUnQfkJhLasJS/P64Ph9cOAPXsC3Hlnjt8hioiIjEgJDBEREZEUY04/C16qozPciTHQ22sA75+WkoiISKJK9zsAEREREYkvs/Bs7IP3cdvHH+bLX38jN9yQz+rV2XR3BwgGIyxe3MP117f5HaZMkIqKirg+bjJI5rFBco8vmccGyT2+iRibKjBEREREUs3MasibAs8+QVlZ5JClJIYHHggSDuvPxCRhxvPPcZz1431sov9L5rEl+/iSeWzJPr5Rju2Y9JtJREREJMWYQACz8Cxs3XrsQD/hcIBlyzpZtaqZ/PwI/f3wqU9N9TtMERGRYZTAEBEREUlB5vSzobsL6uuoqWnhjjtyeetbS2ltTQMML72USWVlBZWV6oUhIiKJQQkMERERkVQ0fyFkZmKfWQfA6tXNVFYOADZ6gGX69AH+/Gdtq5qiVvodQAwl89gguceXzGOD5B7fhIzNWGuPfVRisrt27Yr7SYuLiwmHw3E/b6rQ/MaW5je2NL+xpfmNLc1vbCXq/A5+/+uw7WUCN/8UYwwXXljCpk0HerxXV/fzyCOJF/ehxjq/0UZyo1pvLSIiiUO7kIiIiIikKLPwLK8CY+c2mD6DtrYAs2YNYAxYS3Q5iYiISGLQEhIRERGRFGXmngqA3fQCAE891ch55/Xy8svpnHdeL0891ehneCIiIsOoAkNEREQkVRWXQUExvPQCVR/9GL29B1ZV1NaGqK0NkZVl2bKlwccgJZ4cx1kM3AakATWu637D55DGzXGcE4BaoAyvuctK13VvcxynEPgVMAPYCjiu67b4FefxchwnDfgXsNN13Xc6jjMTuAcoAtYDV7iu2+dnjOPhOM5UoAY4Be/6fQSoJ0muneM4nwM+hje254F/B8qZpNfOcZyfAe8EmlzXPSV634j/1xzHMXg/Z94OdAH/5rruU6M5jyowRERERFKUMQYz52TsphdY8/huLr20i2AwAkAwGGHJki7WrlUVRqqIvhD+PnAxsAC4zHGcBf5GdVwGgC+4rrsAOAf4VHQ81wIPu647B3g4ensy+wyw4aDbNwMrXNedDbQAH/UlquN3G/CQ67rzgIV4Y0yKa+c4TiXwaeA10Rf7acAHmNzX7ufA4kPuO9L1uhiYE/23HPjhaE+iBIaIiIhIKpt7MrS2UGp2kpdn6ekxGON9zMuLUFoa8TtCiZ+zgM2u626Jvut7D3CJzzGNm+u6DUPv6rqu2473ArgSb0x3RA+7A7jUnwiPn+M404F34FUqEH1n+yLg3ughk3J8juNMAc4Hfgrgum6f67r7SKJrh7caIug4TjqQAzQwia+d67p/B/YecveRrtclQK3rutZ13bXAVMdxRrVntxIYIiIiIinMzDkFAPtSHeFwgOrqfqz1diBpblYTzxRTCWw/6PaO6H2TnuM4M4BFwDqgzHXdoXVRu/GWmExWtwLXAEOZxiJgn+u6A9Hbk/UazgSagdsdx3nacZwax3FySZJr57ruTuDbwKt4iYtWvCUjyXDtDnak6zXunzVKYIiIiIiksmmVkDeF+25+hQcfDFJfnwkY6uszefDBIFVVo3pTTCRhOY4TAu4DPuu6btvBX3Nd1+L1IJh0HMcZ6jew3u9YYiAdOAP4oeu6i4BODlkuMsmvXQFeFcJMoALI5fDlF0lloq6XEhgiIiIiKcwYA3NO5pL5/1IPDNkJnHDQ7enR+yYtx3Ey8JIXd7uu+5vo3Y1D5erRj01+xXeczgPe7TjOVrzlPhfh9Y2YGl2WAJP3Gu4Adriuuy56+168hEayXLs3A6+4rtvsum4/8Bu865kM1+5gR7pe4/5ZM+oEhuM4KxzHOX20x4uIiIjI5GCqTyZtXyPTc3bT02PIylIPjBT1JDDHcZyZjuNk4jUV/L3PMY1btB/ET4ENrut+56Av/R74cPTzDwP3xzu2ieC67nWu6053XXcG3rX6q+u6lwOPAEujh03K8bmuuxvY7jjO3OhdbwJeJEmuHd7SkXMcx8mJfp8OjW/SX7tDHOl6/R5Y5jiOcRznHKD1oKUmRzWWbVTTgNWO4zQDd+JlMXeM4fEiIiIikoDM7PlYYErLRpYuLWPjxgzmz1cPjFTjuu6A4zhXAavx/vb/meu6L/gc1vE4D7gCeN5xnGei9/0X8A3AdRzno8A2wPEpvlj5EnCP4zhfA54m2ghzEroauDuaTNuCt81ogCS4dq7rrnMc517gKbzdcp4GVgJ/YJJeO8dxfglcCBQ7jrMD+CpH/r/2R7wtVDfjbaP676M9j7F29MtQolsrXQxcjrfH6zq8vZV/47pux6ifaGLYXbt2xfmUUFxcTDgcjvt5U4XmN7Y0v7Gl+Y0tzW9saX5jK9Hn1/b3Ebn6/Zi3vZf/fuKT3HlnLldc0clNN7Ud+8EJYKzzW1FRAWBiFpCIiMTEmHpguK476LruA67rXoa3l3IJ3n6vu6OdYSd7l1QRERGRlGMyMtm4byZ/+fkuamtDWGuorQ1RWVmhJp4iIpIwxrKEBMdx8oH3AR8CTsNriPNJvDU8XwAejN4vIiIiIpPIjDecwLRnnicYjNDdHSAYjLB4cQ/XXz85qjBERCT5jTqBEV2j8zbg78CPgN+5rtt70Nc/j7d/rYiIiIhMMsE5M8l+5hFyIy30mEI18RQRkYQzlgqMtcBV0Y6wh3FdN+I4TtnEhCUiIiIi8WROmIkF3jJ/A7985jzmzlUTTxERSSyjTmC4rvvtURzTdXzhiIiIiIgfzrjkXP51AeS3bgFeT319JvX1UFWVzZYto9rdTkREJKbG1MRTRERERJLTQ//oYS9lnFZQD0AwGGHJki7Wrm30OTIRERGPEhgiIiIiQllZhMaM2cwLvURWllUPDBERSThj2oVERERERJLXtr4ZvDn0BHOre5k3f1A9MEREJKGoAkNEREREALj4Q3mk00/jpjaysy01NS1+hyQiIrKfEhgiIiIiQlVVOVd8dj4A07MbqK0NUVlZQVVVuc+RiYiIeJTAEBERERHWrGlk7usKAJie06AmniIiknCUwBARERERysoi9OeVATA9uEtNPEVEJOGoiaeIiIiIANCwJ4eWyFSmBxuoru5XE08REUkoSmCIiIiICFVV5fT2Gq58XQXTgw3U12VSXw9VVdls2dLgd3giIiJKYIiIiIiI1wPjhhvyadhRTnXOJoLBCIsX93D99W1+hybHx/odgIjIKJljHaAEhoiIiIhQVhYhL8/yakc5FxX9g54e1AMjSezatWvMjykuLiYcDscgGv8l89gguceXzGOD5B7fscZWUVExqudRE08RERERASAcDjBt3hSy0vpYtrRJPTBERCShKIEhIiIiIgDU1LTQm+ltpVqUsYeamhafIxIRETlACQwRERERoaqqnMrKCn77sFfG+9hDPVRWVlBVVe5zZCIiIh4lMERERESENWsaufTSLtqNV4FRGQqzZEkXa9c2+hyZiIiIR008RURERGR/E8+d7UUATAm0MKgmniIikkBUgSEiIiIigNfEs2RGDgORNKrLm9XEU0REEooqMERERESEqqpyensNAHsrpxJob+XBNUGqqrLZsqXB5+hERERUgSEiIiIiHOiBEQxGaO4roixnj3pgiIhIQlECQ0RERET298Do6THs7S+kIH0veeqBISIiCUQJDBEREREBvB4YS5d2MZCdz4kFe9UDQ0REEooSGCIiIiICQE1NC8Gg5eWmYkLso6amxe+QRERE9lMTTxEREREZ1sTzU7MKyLLdVJ1QCBlZauIpIgnPdndh1z4CAwMT/+QZGZjXvQmTmTXxzy1jklAJDMdx0oB/ATtd132n3/GIiIiIpIo1axq54YZ8Vq/OJtxbAMDl727g6q8GfY5MROTY7Lq/YX/x49idIC0d84a3xu75ZVQSKoEBfAbYAOT7HYiIiIhIKhnexHMqAKXBPZSWVvgcmYjIKOxtgrQ0ArfcCcZM4BNbIl+9Gl58BpTA8F3CJDAcx5kOvAP4OvB5n8MRERERSTnhcIDq6n7CjYUADOxr9zkiEZFR2huGqUWY3NCEP7WZvxD7/JPYSAQTUBtJPyVMAgO4FbgGyDvSAY7jLAeWA7iuS3FxcZxCOyA9Pd2X86YKzW9saX5jS/MbW5rf2NL8xtZkmN8pUzLo6fHetTwpx0tgvPJcJ7NmldPa2u9naMc0GeZXRGLLtoShIEY/BxacDmv+Ctu3wEmzY3MOGZWESGA4jvNOoMl13fWO41x4pONc110JrIzetOFwOB7hDVNcXIwf500Vmt/Y0vzGluY3tjS/saX5ja3JML+PPx44rAfGBWc08uUbGgmHIz5Hd3Rjnd+KCi2LEUk6LXswM6tj8tRmwUIsYF98BqMEhq8Spf7lPODdjuNsBe4BLnIc5y5/QxIRERFJHQf3wBhID9IzmElh5j5KSxM7eSEiYiMRaAlDQVFMnt/kF8D0GdgXn4nJ88voJUQFhuu61wHXAUQrMP7Tdd0P+RqUiIiISIoJhwMsXdrFxo0Z9KRPIdDV5ndIIiLH1tHmbZ9aUBKzU5j5C7GP/AHb24vJ0naqfkmUCgwRERER8VlNTQvBoKWuLoOuwBRef3qz3yGJiBxbi7eEzBTGrheOWXC6lyTZ/GLMziHHlhAVGAdzXfdR4FGfwxARERFJKVVV5fT2Hth6cPPuIhrCXXzgO+Vs2dLgY2QiIsewN9oDJ0ZLSACYcwqkp3t9ME5eFLvzyFGpAkNEREREWLOmkUsv7SIY9HpetEamcGLhXtaubfQ5MhGRo7PRCgxiWYGRlQWz5qsPhs+UwBARERGRYU08jbE0dxcQQk08RWQS2BuGtHQITYnpacz8hbDjFWxXR0zPI0emBIaIiIiIAF4Tz+rqfqyFQH4+QduJHRjwOywRkaOL7kBiAjF+eVsQrfDoaI/teeSIEq4HhoiIiIjE36E9MF7aVQSFcM4pQdZt7PcxMhGRo7Mt4ZguHxlisoNYgJ7umJ9LRqYKDBERERE5rAdGB14p9h/dl/0MS0Tk2PaGMVNjn8AgO+h9VALDN0pgiIiIiMiwHhhZWZbdnQUAFGa0+ByZiMiR2UgE9u2NSwXG/gRGrxIYftESEhEREREBvB4YS5d2sXFjBmdVZ0E30Km13iKSwNpbYXAgtluoDokmMGxPN+YYh0psqAJDRERERACoqWkhGLTU1WUwEMwHwKpZnYgksr3eFqomnhUYWkLiG1VgiIiIiMhhTTx/cncF114Mt9wAX7zQv7hSmeM4acC/gJ2u677TcZyZwD1AEbAeuMJ13T4/YxTxXYuXwKCgJPbnUgLDd6rAEBEREZHDmnimZ6fRQw5XXrHL58hS2meADQfdvhlY4brubKAF+KgvUYkkELs/gRGHJSRZSmD4TQkMERERERnWxNMY72N3IJ+cSJvfoaUkx3GmA+8AaqK3DXARcG/0kDuAS/2JTiSB7A1DegbkTYn5qUxaGmRmKoHhIy0hERERERHAa+JZXd1PfX0Gc+f20zY4hQI18fTLrcA1QF70dhGwz3XdgejtHUDlSA90HGc5sBzAdV2Ki8feGyA9PX1cj5sMknlskNzjG2ls+7raGSgupbgkDktIgOZgLllY8mMwx6l27cb1PBMQi4iIiIhMcof2wKivz2RrfgEt/+zgzE/7GFgKchznnUCT67rrHce5cKyPd113JbAyetOGw+Exx1BcXMx4HjcZJPPYILnHN9LYBnfvhPyCuI05kplFz74W+mJwvlS7dgerqKgY1fNoCYmIiIiIHNYDIxiMkFsW4tSZe3yOLCWdB7zbcZyteE07LwJuA6Y6jjP0BuR0YKc/4YkkkJY98dmBZEh2ENurJSR+UQJDRERERIb1wMjK8j72Z+aT1qMeGPHmuu51rutOd113BvAB4K+u614OPAIsjR72YeB+n0IUSQg2Mgj79sSngeeQ7KB6YPhICQwRERERAbweGEuXdlFd3c/73tdFc/dU6OrEDg76HZp4vgR83nGczXg9MX7qczwi/mrbB4OD8dlCdUh2jhIYPlIPDBEREREBoKamheuuy6euLoNFi/q45N0Z2F8Ane2QP9Xv8FKS67qPAo9GP98CnOVnPCIJpakBAFNcFrdTmuwgNnpeiT8lMERERETksCaetbUhWv58Et9fBHS0KYEhIgnH7tzmfVJ5UvxOqiUkvtISEhEREREZsYnngrOC3hc7tJWqiCSgHdsgmBvfHhhZSmD4SQkMERERERnWxNMY76PNzfO+2KFGniKSeOzOrVB5EsaYYx47YbKD0NuNjUTid07ZTwkMEREREQG8Jp7V1f1YC9XV/WxvKQDAKoEhIgnGWgu7XsVMj+PyEfASGAB9PfE9rwDqgSEiIiIiHN4Do74+k62byrh5MarAEJHEszcM3V3x7X8BBxIYPd3ejiQSV6rAEBEREZERe2C8/ZIINjPb24VERCSR7NwKgKmcEd/zHpzAkLhTBYaIiIiIDOuBkZXlfczLi2AiedDe6nd4IiLDHNiB5MS4ntdkB7GgBIZPlMAQEREREcDrgbF0aRcbN2Ywf34/zc1pMGMKtl1LSEQkwezYBgXFmJxQfM+rCgxfaQmJiIiIiABQU9NCMGipq8sgO9tSU9MC+VOhbZ/foYmIDGN3bYt//wtQAsNnSmCIiIiICFVV5VRWVlBbG8JaQ21tiMrKCn69ugLaWvwOT0RkPzswAA07MH4kMLK8BIZVAsMXSmCIiIiIyIhNPJcs6eIdl2VDeys2EvE5QhGRqMZdMDgA8d5CFVSB4TMlMERERERkWBNP3LLrOQAAIABJREFUYw408cwtnwKDg9DZ4XeIIiIAWL92IIEDCYxeJTD8oASGiIiIiABeE8/q6n6sherqaBPP/ALvi+qDISKJYuc2CARg2vT4nzsrG4xRBYZPtAuJiIiIiFBVVU5vr9l/u74+k/p6+OBTVdx9Jl4fjDhvVygiMhK7cxuUVWIyMuJ+bmOMl8RQAsMXqsAQERERkSP2wPjend7XrSowRCRR7NzmTwPPIdlBJTB8ogSGiIiIiAzrgZGVdaAHRtHMfO+AVu1EIiL+s/39sKfJn+UjQ5TA8I2WkIiIiIgI4PXAWLq0i40bM5g/P9oDI5gL6RlKYIhIYmhpBmuhuMy/GLKC2kbVJ6rAEBEREREAampaCAYtdXUZZGdbampavPXeBUXQEvY7PBERCDcCYPxMYKgCwzeqwBARERGRw5p41taGqK0NkZVl2fTJEqwSGCKSAGw0geFrBUZ2EPY0+3f+FKYKDBERERE5YhPPtWsbMYXFsFd/rItIAgg3QloaFBT6FoLJDkKvKjD8oASGiIiIiAxr4mnMgSaepaURKCiBfXuxg4N+hykiqS7cBIUlmECafzFoCYlvlMAQEREREcBr4lld3Y+1UF0dbeIJUFQMkQi07vU3QBFJeTbc6O/yEVACw0fqgSEiIiIih/XAqK/PpL4eqqqyefn+EizA3jAUlvgWo4gI4UbM6Wf7G0N2EPr7sIODmDQfK0FSkCowREREROSoPTAoLAbAqg+GiPjI9nRDeysUlfobSHbQ+6gqjLhTAkNEREREhvXAyMo6pAfGUNWFdiIRER8NNjV4n/i9hCRLCQy/aAmJiIiIiABeD4ylS7vYuDGD+fMP9MAwwRwI5mjbQBHx1WCjl8AwficwsnO8j0pgxJ0qMEREREQEgJqaFoJBS11dBtnZlpqalgNfLCzB7mnyLzgRSXmDTbu8T0r8TWCY/UtIunyNIxWpAkNEREREDmviWVsborY2RFaWZcuWBiirgF2v+hihiKS6waYGyMyEvKn+BjKUwOhVBUa8qQJDRERERI7exBMwZRXQvBs7OOhnmCKSwgYbG6CoDGPMsQ+OJTXx9I0SGCIiIiIyrImnMYc08QQoq4TBQdAyEhHxyWDTLv8beML+BIZVAiPutIRERERERACviWd1dT/19RnMnXugiSeAKa3AAjTugtJy32JMBY7jZAN/B7Lw/l6/13XdrzqOMxO4BygC1gNXuK7b51+kIvE12NiAmTHH7zBUgeEjVWCIiIiICFVV5Tz4YJD6+kzAUF+fyYMPBqmqiiYryioAsI07/QsydfQCF7muuxA4HVjsOM45wM3ACtd1ZwMtwEd9jFEkrmxnB7arI6EqMOhWE894UwJDRERERI7ZA4O8KRDMhaFdACRmXNe1rut2RG9mRP9Z4CLg3uj9dwCX+hCeiD/C0X48iZDASM+AtDQ18fSBlpCIiIiIyLAeGFlZh/fAMMZAWQW2UQmMeHAcJw1vmchs4PvAy8A+13UHoofsACp9Ck8k/vZEk6lF/icwjDGQFdQSEh8ogSEiIiIigNcDY+nSLjZuzGD+/OE9MCDaB+PlDT5Fl1pc1x0ETnccZyrwW2DeaB/rOM5yYHn0eSguLh7z+dPT08f1uMkgmccGyTu+zu4OOoCiufMJhPL9Dofm3FwyrWXKBM51sl47mLixKYEhIiIiIgDU1LRw3XX51NVlsGhRHytWtAw/oKwCnvw7tr8Pk5HpT5ApxnXdfY7jPAKcC0x1HCc9WoUxHRixIYnruiuBldGbNhwOj/m8xcXFjOdxk0Eyjw2Sd3yRbVswOSH29vRBj//ji2Rk0dPaQv8EznWyXjs49tgqKipG9TzqgSEiIiIiVFWVU1lZQW1tCGsNtbUhKisrDjTxBJhWCdaCGnnGlOM4JdHKCxzHCQJvATYAjwBLo4d9GLjfnwhF4s/uaSYtkXZAytYSEj8ogSEiIiIix27iCZjKkwCwO1/1JcYUUg484jjOc8CTwJ9d130A+BLwecdxNuNtpfpTH2MUia+2fQQKCv2O4gAlMHyhJSQiIiIiMqyJpzGHN/H0DqrwOu/v3OZfoCnAdd3ngEUj3L8FOCv+EYkkgI42AifOZNDvOIZkB6Flj99RpBxVYIiIiIgI4DXxrK7ux1qorh6hiWd6BpRVYnepAkNE4qy9jcCUAr+j2M9k56gCwweqwBARERERqqrK6e01+2/X12dSXw9VVdls2dKw/35TeRL2lZf8CFFEUpTt74PebkzeFL9DOSAnF7o6/Y4i5agCQ0REJkxdXTrz5k3jxRcP5McbGwO8971FNDUFRrw92mMaGhjX48ZzTCyf2+/zj3RfXV06JSUZw66bpJ7R9MAAoPIkCDdie7p8iFJEUlJ7GwCBKVN9DuQgwVzo7cYOJsyilpSgBIaIiEyYq6+eSnu74VOfOvAHxq23hli3LpMVK0Ij3h7tMTfemDaux43lmFu/E8S2t2HDjdx5yz72vrCde77VgN1Sz2+/tYX0zc/wwM0vYJ9Zi13/OA9+8znSNz/Dvd/cin31Ze769h52PLuHlbf0Y3u6sIOD44oxFmM72n1XXz2VtjaGXTdJPQf3wMjKOkIPDMBUnuh9smu7D1GKSErqiCYw8hLo91ROrvexW1UY8WSstX7HMF52165dcT9pMu/Nmwg0v7Gl+Y2tVJ7fyspywBzzOD9kBXqYHtzN9OAuKoO7KcjcR0FGK4WZ+yjIbGVqRisFma0UZLQyJaONgJnY34ut/SEae0rZ3VPC7t7ox55SGqMfd/eUEO4rxCbUewqWnTsbjn2YjNpk+fnwsY8VEApF2Lgxg/nz+2lvD1BT0zLsGNvUQOS/P4FZdhWBN7zVp0iHG+v8VlRUQKL+0Jp44/qbebJ8z45HMo8NknN89sWniaz4KgVf/wFtpdP9DgeAyON/xd5+K4Gv/xgzQdu7JuO1G3KssY3257JqRUVE5Lg0NgY49dQ+wuE0GhrS8H73WMrLB5k/f4A1azLp7g6QnR2huDhCOJxGT48hGIxw4YU9gOHRR7NGcUw23d2HP66nG2ZP3ckp014lv283Zem7OSlvJyeX7qSIBqaYvYfF3DkQZN/AFAaz8uhgChua5hLumUqHzaf4pBx6yOX5DTl09mRCehrBvDT27MuisycTk5nGwjMiREjjufUG+vvID3ZTOrWHvs4+0gZ7ycvu4eQ5nWTSS2tjO8XpzVTkNDFvyhaKMvaQZiKHxJPDi21z2NhVTaSyiu1Uc8/f5tHWlTUB8+YdM9J9WVkRAgHo7jbDrltxcYSmpsBh77xL8qupaeG66/Kpq8tg0aI+VqxoOfyg4jLIzAI18hSROLFDS0jyE6cCw+TkYgG6OvwOJaUogSEiIsfl1ltD1NVlkp8/9GLXq2DIy4tQWTm4vxy9t9eQkxOhtzdtf3l6SUkEa82ojunthcKcDqqyNvOO0AtMG3iZ5ae/wty8lwmlH1iL3x9JY1fPNAYyy9gUOJdHnz+Bhv5ytrZVkllexPr6Emx6Fn19cMUVnVhruOuhHDIz8e57jXffr7cduG/OnH427c7wbu+DuSXeMU825+y/b06on02vZhx4ntcd/txz5vTz8qYAFaG9FKY18YG3bScvsoe9L+zilKn1LJn2B0LGG8s156ezubOKuta5NGXNZnXHQurtfHp6AmOat4OXAxx6X1+fIT8/Ek1geNetq8tQV5fBihUhbrqpLZ7fSuKzQ5t41taGqK0NkZVlhzfxDASg4kSstlIVkXjpOCiB0TfgczBRQ0tI1MgzrpTAEBGRcTn0xU5rq7fdYnq6ZdasfvbtSyMcHmTZsk4uv7yLu+/O4aGHgsNuNzV5jxnpmCuWNrPu7k1Mbd7EdDbzn+/YQsHgTu9kndBpQzSVzqLv5Dfzu83V/HH9bKrPLeCdH8rh7l/m7X/u0vMG+fhBz/3+D3Vz+eVtRzz/0WKaiGM+tKybyy+Hu++ewd+bZnkxvnaQcy7v4pt3ZWObGziRTczNreeMGfWcuP0fhOwqriqBgZwCno2cy7rm89jAa1m2zI7p/CPdd889Ocyd28+WLRn095v91/FIL14lea1Z08gNN+SzenX2/qqdxYt7uP76wxNZpvJE7HP/wlqLMamyEkNEfNPRBiaAyc2DvhEqw/yQE+0tpR4YcaUeGGOUzOuSEoHmN7Y0v7GVSvPb2BjgYx8roKwsMmyJwtCLnfEsPbA93bD5RezG57Ebn4NXt4CNgAlAWTlZs+bRV1KOmT4Tps+AwuKUeOFkrYV9e7Ev1cGzT2DrnvL+WErPgHmnYRa+FnPaazGFJcd1nv7+Yj772YERX7xqKcnxmyw/H669dgp33ZWz//YVV3SOWIkTeXgV9p6fEPjWzzFTC+MZ4ojUA+Oo1APjEMk8NkjO8UXu+gF2/eOU3flQwozN7m0m8qWPYq74FIHz3zYhz5mM126IemCIiIhvbr01xNNPZzJnTv8xdyw4EtvXCy9v9BIW9c/B1k0wOAhp6VBVjXmHg5l3KsyoxmRlMTWJf6kfjTEGCoowZ18AZ1+AHRjwEj3PPol97gns3T/C3v0jmD4Tc/rZmDe8ZVzJjPJyDtuBIi3NcuWVBfzwhy1KYqSIcDhAdXU/9fUZzJ3bT3Nz2ojHmRNmeouOtr8CCZDAEJHkZjvaIG+K32EMp11IfKEEhoiIjNqhy0ZeeikTgEjEsmxZ5/4lCkdi+3rhuSeJrPs71K2HgX4IBGDGHMxbl3gJi1kLMFlZMR3HZGbS073Ki3mnYZ2PwO6dXiLjuSexf3Cxf3Qxi87FvPldMGv+mKpUwuHAsOUlf/1rNjt2pKkfRoo49P93fX0m9fVQVZV9+DKi6TMBsNu3YE49M55hikgqam+DUJ7fUQyXFfT+hlEPjLhSAkNERI6psTHAJz9ZwKpVzfzgB6ExLTOwkUHY+Dx23d+wTz0OPd0wpRBzwWLMyYtgzgJMds6Ij5WjM8ZA+XRM+XR423uw4Ubso3/E/uNP2PWPwYmzMG96J+a152MyMo75fEPbZY62maMklzH1wMjJ9XYjeXWLD5GKSMrpaINplX5HMYwxxqvC0C4kcaUEhoiIHNOtt4ZYty6Tu+7KOWyZwUjLRqy1sG2zl7R48h/Q2gLBHMyZr8OcfSHMPQUTOHq1hoydKS7DLP137Lsuw659FPvwKuztt2Hv/bmXMLrg4lH1KxjpheyFF/bQ2Jiu7VWTWFlZZFT/v/c7sQq7/ZX4Bikiqam9FTN7vt9RHC6YqwqMOFMCQ0REjmikd+IBAgHLqlXNw3a2AG+JiH3sYexfV8HunZCeDqe+hsDZF8KpZ2IytTQkHkxWNuaCxdjz3wYbniXy1we85SUP3os56wLMpR/CFBYf8fEjvZB9+eV0Nm3S9qrJLhwOsHRpFxs3ZjB//pF7YEC0D8bTa7E9XaqiEpGYsZEIdLZDKMF6YADkhLBKYMSVEhgiInJERyspLy2NcOON3gtZ29XpLV34y++hvRWq5mKWXYU543WY3JDPo0hdxhhYcDppC07HNjVg//oA9u+rsesfw1y8FPPWS4+YVBrqh/HLX+Zirdnf70TLSZJbTU0L112XT11dBosW9bFixZG3KzQnVHnVVju2wuwF8QtSRFJLdydEIpCXYD0wQEtIfKAEhoiIjGio78X06QNHLCm3rS3Yv/we+7cHobsLTjmDwOKlUH1ySmxxOpmY0nLMBz6OffO7ifz6duz9d2P/+WcC7/sInHHuYccP9cP4zGc6Rt0XQSa3Mfc+OWGokecrGCUwRCRW2qO/bxKyAiMXWvb4HUVKUQJDRERGNNT3Yteu4TtTNDWlYZt3Y//0W+w//wKDA5gzz8Nc/F7MibP8DluOwRSXkXbltdiNzxG55ydEfvQNmHsq/VdeA7mH/3E40nISba+anMbSxBOAgmJvVwD1wRCRWOpoBcCE8n0O5HAmJ4TVNqpxpQSGiIgMc+i7sK++msEdd2Rwzz25vPz8S9jf3UXky6shEMCcexHmbe/BlFX4GLGMh5l3GoGv3OotKbn/bvZ+/sOY8xdjLvngYX8kanvV1HBwssqYYzfxNMbACVXYbS/HOVIRSSkd0d8zeQlagdGpJSTxpASGiIjs19gY4OST+ygri/Doo1n734W9+G2dfO3i+4h8+Q7o6vR2s7h4KaagyO+Q5TiYtDTMG9+OPesNZK3+Dd0P/Rb7r38Q+PCnMaefvf84ba+aOsLhANXV/dTXZzB37tGbeAKYk2Zj/3w/tr8Pk5EZpyhFJJXY/UtIEq8Cg2AuDPTrZ2AcBfwOQEREEsett4Z4+ulMXn45bf+SgXlZL/Cfkf8gdP/3oOJEAl9ZQeCDn1DyIomY3Dzyl3+BwPW3QmEJke9/ncgvfozt7xt23Jo1jVx6aRfBoPeOfHZ2hKKiQR54oNmPsGWCVVWV8+CDQerrMwFDfX0mDz4YpKqq/IiPMTPnwOCAlpGISOx0JHACY6hRuXYiiRslMEREhKqqciorK6itDe3fcaIwo4Wvz/s/7n/dv5PbvwfzsS8Q+M8bMdNn+h2uxIiZPoPAtd/CvPnd2Ef+QOTG/8Q2bN//9ZH6YezZE+DOO7WFZjI4NEEVDEZYsqSLtWsbj/ygGXMAsFs3xSNEkRFF/vhrIrXfw254FhsZ9DscmWjtrZCZhclKwK3Yg7neRyUw4kZLSEREUtzhy0YMH5n1a66Z+wOCgW7MW5ZQ9M73Y7L1IjUVmIwMzPs/hp2/kMjttxH52ucwH1iOef1bMMYQDgcIBNBSkiQ0UoLqaD0wAK+R55QCeEUJDPGH7enCrvolDAxg//EnmFJI4D++hJk93+/QZKJ0tCVm/wuiTTxBW6nGkSowRERS3MHLRvIie7jzrE/zP3O/SUNGNWn/810CS/9dyYsUZE57LYGv/j+YNR9b+z3sj7+J7eqgpqaFJ58cxzv1MimEwwGWLu2iurqf972v69g9MIyBGXNUgSH+eeEZGBgg8OmvEvjENdDRhn32Cb+jkglk29sSc/kIeE08QRUYcZQQFRiO45wA1AJlgAVWuq57m79RiYgkt0MbMp6wbx33vP4GQuld/D70Of7QvoSa8n0+Rih+M1MLCXz2f7Grf4P93V3YrZsIXP0VyipP0taqSaqmpoXrrsunri6DRYv6WLGi5ZiPMTPmYJ99AtvViRn6Y14kTuyzT0BOCBacjklLg/vvxjapEiypdLRBXqImMLweGLarA3OMQ2ViJEoFxgDwBdd1FwDnAJ9yHGeBzzGJiCSlxsYA731vEatWNXPppV0U5HbxtZO/we2v+Rw92UX0fH4FS1a8kZoaJS8ETCBA4OKlBK75BgwMEPnGNdi69fu3Vl21qpllyzpZty6LdesyWbEi5HfIMk6H9sKprQ1RWVlx1CaeAGZmtffJts1xiFLiwUYi2MHE7yVhI4PY5/+FOeVML3kBUFIOTbv8DUwmVnvrYdt7JwxVYMRdQiQwXNdtcF33qejn7cAGoNLfqEREktOtt4ZYty6Tu+7KoTpYz31nLmPZSfeycsvl/KTwBxSdMt3vECUBmVnzCPzXt6F4GpH/93+svPxubryxjXe9q4Q77gixfXv6mF70SuIZVxNPgBmzATXyTBb2pToi//Ee+jc863cox7al3nt3/vSz9t9lyiqgqQFrrY+ByYTqaIdQYvbAOJDAUA+MeEmIBMbBHMeZASwC1vkciohIUhn+7ipk/P33LG+5krz0Dl59z9fZfvbH2R0O+h2mJDBTWEzgS9+AU8/E/uJHRO75CWse23XYi96LL+7i5JP7aWpKuD8z5CgObuJpzCibeOJtw0tpOfaVl+IUqcRUMBdshEh7m9+RHJN99klIS8OcfMaBO0vLoa8XWo+9/EkSn+3vg95uCOX5HcqITEYmZGRCtyow4iUhemAMcRwnBNwHfNZ13cN+ajqOsxxYDuC6LsXFxXGOENLT0305b6rQ/MaW5je2Enl+Gxpg4UJLeXmEv/2lj/+ZfSPvqXyQF9LfwIJb/otps6fw2iuGjk7MMSTy/CaDscyvvf47dNzxPbpW/YqKfXuoLPoavb2G7GxLb69h69Zs6usNP/xhCd/9buKXocfDZPn+bWtLY/58y4YNhvnzLa2tQYqLM4/5uNZ5p9JX9xRFRUVeY884myzzOynkesvAIu2tPgdybPbZJ6D6lGG9V0xJubcrRNMumFroW2wyQYYSaQm6CwngVWFoCUncJEwCw3GcDLzkxd2u6/5mpGNc110JrIzetOFwOF7h7VdcXIwf500Vmt/Y0vzGViLP7/XX5/PkkxmcM6+B2oXXcfrUF7nlpU+w79z3c+PUjoSN+2CJPL/JYMzz++7LMfkF9P1yJR8c/Djmgzez0j2JSMSwYYP3AnblyjRWrkzT9qpMju/fQxv7vvii4cUXIT8/cMzrF6mcgf37nwi/tAFTVBrrUA8z1vmtqKiIYTSTXK7Xa8B2JHYFhm3aBQ3bMee/bfgXyiqiX2/AVJ/iQ2QyoTq8RFrC9sAAyAlhtYQkbhKittNxHAP8FNjguu53/I5HRCRZHLxsZNGU5/lu+UeYHdrKJ575NvvOu4ymcIbfIcokFrjw7QSuvp4TsndxTdpVPPHg89pedRIbdw8MwMyeD4DdvCGmMUocZGZCekbCLyGxzz4JgFl41vAvFJZAWhpoJ5Lk0KEKDBkuIRIYwHnAFcBFjuM8E/33dr+DEhGZ7IZekHxo5u/41dmfoDsS5LvBH3LjH+Zx441t1NRojbAcH3PKGQQ+fwN0tlN4+zWclLN9xO1V1Q8j8R3cA2Po+o2mBwYAlTMgKwibX4x5nBJbxhgI5RFJ8AoMttRDcRmmZNqwu01aGhSVeRUaMunZoURaIldgBJXAiKeEWELiuu4/QVvniohMpMbGAFd9Mo9Plt7G+fPv47E9Z3Hl0zfy7g+kU1qa4H+YyqRiquYS+MLXiay4no+2f5qMD97CWz9cyt135/DXv2azY0caK1aEuOkmfd8lunA4wNKlXWzcmMH8+f00N6eN6nEmLQ2qqlWBMUEcxzkBqAXKAAusdF33NsdxCoFfATOArYDjuu7EZ6Jz87AJ3gPDNjXAtCNsWlhargqMZLG/AiNxExgmJ4Rt3Ol3GClDb4eIiCSp769I4+MD/835A/fxeHApRf/7FS65LH3UL0hExsKcWEXgizcydWqET/d/mmsu26vtVSehmpoWgkFLXV0G2dl2TFVaZvYC2LkNq3ciJ8IA8AXXdRcA5wCfchxnAXAt8LDrunOAh6O3J15uKKGXkFhrobnhsOqLId5Wqru1lWoyaNsHgQDkhPyO5MhycrULSRwlRAWGiIhMnKqqcnIirdz+ms+ysORF/qvuWu56dSlZD6iRosSWqTiRwBdvIvKdL/O7Cz7BioFbWPnnM+juDhAMRli8uIfrr0/cF0Wp7tAmnrW1IWprQ6Nuwmpmz/deMG6ph1POOObxcmSu6zYADdHP2x3H2QBUApcAF0YPuwN4FPjShAeQm4fd0zThTzthOtqgu8urtBhJSbm39Wb7PsgviG9sMrFa9sDUQkwggd93j/bAsNb6sgtTqlECQ0QkiTQ2BnjjaVu5ofjzTI008Ymnvsk/2s5nyZIuvXCUuDBlFQSu+Qbc8mWuav4c/8z+HnWR04b1w/jhD1tG11dB4mrNmkZuuCGf1auzx5d0qqoGE8C+vAGjBMaEcRxnBrAIWAeURZMbALvxlpiM9JjlwHIA13XHvMVsa1EJfds2U5KgW9P2hRtoAabMmkfWCDH2zp7LPmBKTxeZVXMO+3qyb7ubTONr6WzDFpdRGB1PIo6ts6SMjkiEolAOgWDusR9wFIk4vokyUWNTAkNEJIn86tsNfC3vWrIjfVz+xPd5rmshfX2MvhGfyAQwRaUEvngT+774FX7xus+w+7Kb+NmfT1U/jAR3cBNPY8bYxBMw2Tlwwgz1wZhAjuOEgPuAz7qu2+Y4zv6vua5rHccZcY2E67orgZXRm3asW/hG0jKw7W00Nzcn5DvKkc0bAWjLzsWMMDYbfRG5b9NGAqWH98mYDNsaH49kGt9g026oOHH/eBJxbJHo/8I921/FFJYc13Ml4vgmyrHGNtrtrRO4FkdEREarqqqc95+2nWXNn6XfprPksf/P3p2HR1WeDRz+vZN1soeEhCQgEElYAoq4VqlWcYHWjQqnWiu21Vq1ahe1i/pRqwLWve5FagWl2oOtVlqpe3FjUVQ0oAHZA9kmC4RM9vN+f5yZECCQbfY893XlmsnMyTnvTJJJ5jnP8hc+qp2IZcGsWQ3S90IEnErPIOePt+NMjyflmdm896JL+mGEAZfLQWFhK1pDYWHPm3h6qSPHwpYN6PZ2P61w4DAMIwY7eLHYNM1/em6uMAwjx3N/DuCfOo/EZGhtgZZmv+y+3yrLQCnI7DIBBQZl2X0TpJFn+KurRqVnBHsVh6USPFkX0v8nICSAIYQQYayiwsFFF2Xwv/teZNGJP2dXcw4XfvhXSttHMH26m9WrK2RcqggalZGF45d3kp6ueem0axiVXgqA02kxbZqboqJWGa8aQvLzc1i2zElJSSygKCmJZdkyZ+8CTaPGQnMT7Njst3UOBIZhKOAvwJemaT7Q6a5XgMs91y8H/uWXBSQl25cN9X7Zfb9VlsGgwaiYmC7vVtHRkJEFMko1rOlGNzQ1QogHMPCWjbj3BncdfqJbW9CfrQr2MjrIfw1CCBHGHnooiRE7l5Gz7B52RBcxY8V86hjc69RvIfxFDckj+qY/EK8aefqo6xiaXEVTk2LTpmg+/TSGBx8M4c7yA8yKFRVceKEbp9N+3XA6LaZPd7NyZUWP96FGjQNAb1zvlzUOIKcAlwFnGIbxmefj28DdwFmGYWwEzvR87nMq0fN7uTc0Axi6sgwOMYGkQ3auvZ0IX3XV9mVaiAcwvL8vEZqBoT9ZgfXYHHTp1mAvBZAeGEIIEZa80wJ+POJ57prYC05AAAAgAElEQVRwP+9UnsxPP7mHFuL473+qWLw4gcpKKRsRoUENHclD1n38KvEXLDzmWmaseIoNG9KA3k+6EP7TuQdGXFzve2AAqEGZMHgIesM6OOsCP642spmm+T5wqOYTU/y+gMQU+zJUMzCqylCTTj7sJmpwDnrTVzIZIpzV2gEMFeoBDE8GhnY3HPKXNqzV7wZAl+1ADR0R3LUgGRhCCBF2KiocFBW18PC0P3P7uPt5tfx0rl9/D9MusFizpoKiojYpGxEh57YFuThvvI1RaaW8cvZ1ZCTZqbZ9Ocsv/MflcjBjhpvCwlZmznT3qX+OKiyCjevQlmSAhS3vGeUQDGBo9147M+RQI1S9snLsUaueN18i/GhvBkaol5AkRHYJCQ2ex1W+M7jr8JAAhhBChJmHHkzkrIb5XKie4h87v82v1s+lvjFOSkZEyFNjjiLq6t8wTG/gvjG3kRDfSmOj4oMPYoO9NOGxYEEtTqemuDiG+Hjdt0BowXj7jW/ZDt8vUASGpweGbgjBN2RV5YCdYXE4Ktsz0aBC+mCErVpvCcmg4K6jO84Ib+LplgCGEEKIPsjPz2Fo3hBGrXmcnx25kGe3XcSv1t5Oa3u0TBoRYUMdfQLP618yJet9VvziLkaPbqGyMkp6YYSA/Pwc8vJyWbQoqV/TYlRhEYBdRiLCU4K3B0bojTvu6GvRXQbGkKH29hJIC1911ZCYjIqNC/ZKDktFRUG8ExojNIDhycTSFRLAEEII0QsrPtjFC+fezg9HLOHJzZdx1+Zfc+H0Jpk0IsLOrAWnMX/rLNI//w+nt74AyGjVUOCLJp6APdoyPRM2SgAjXKnYOIiNC82UeG8Ao7smnhlZ9mPYtd3/axJ+oWurQ798xCshcV+pRYTR3syS8p1orYO7GCSAIYQQYaGiTLPuN0/wDetV/vT1Fdy/5XqamhxSNiLC1ncXzWCN4wxuGfMI5+W8LqNVQ0DnJp5K9a2JJ4BSClVYhN5QHBL/7Iq+cSSnhuYUksoySB2Eios/7GbK4YCcYZKBEc5qq0N/AolXUio6BDOWfMIbyGxuhN3BP1kmU0iEECLE6fZ2ds55jNPi3uSpip/g+salLH3UJZNGRFjLzoFH0n5L+9c1PHj07/n+6kw2bRrPxo32aNV58yL0H8EQ53I5KCxspaQkhtGjW/temlZYBKuW2282vb0IwpxhGGf0cNN20zSX+3UxAeBITqEtFJt4VpVBVjfZFx4qdxj6y8/9vCLhN3XVqOFHBnsVPZOSBnvqgr0K/2ioh8Rk+7JiZ9B7kkgAQwghQljBkYO5Z8xszs99kz+W/IzHNv0I1sALLyTKyEkR9sqrnbxZ8Acyt1/Pgkk3ceGKp9F6hIxWDRLveGavkpJYSkogPz++198HVTgeDegNxfuaKYa/N4BtHHq8qddgIOybuqiklJCcQkJlOWr8MT3bNucIWPEO2r0XlRD235IBRbe12hNkQr2Bp4dKSUPv3BbsZfhHw17IHw1ffIwu34kaPSGoy5EAhhBChKiKXRZ/OfkWTol/h3u+vp7HNl2O02kxdWoTs2fL2WkR/uy+LYqqL2cT/cCNPH3cjZz3wULaYhLk5zwIVqyo4I47UnjttXgaGx39e73JzrPPSG5YB9882/eLDQ63aZr53W1kGEbwc6x9wJGcAtVVwV7GfnRzE+yugW4mkHip3CPQAGWlcOQYv65N+NjuWtDa7qcTDlLSoL4OrTVKdRfjDB9aa3A3oPKGo0s+D4lJJFJkKoQQIUi3tVIx535OiX+HJ6pu4LGNs4iL63tNuhChbPDYLJ5PuYNhzlIem3QrLU0WUVGaa65Jl34YAdS5B0Z/X2+UUqiCiOuDcWEPt7vIr6sIEEdyauhlYFT1cAKJV+4wALQ08gw/nhGqKlx6YKSkQVtb5I1SbW6C9jZ7tHJWbkhMIpH/CoQQIsSMPjKT/373TxS1vMfsdTcx76NZaK2wLGRcqohYH++exLKUG/hW5gcs/O6fWLUqjlWrYmW8aoC5XA5mzHBTWNjKzJnu/r3ejB4PNVXg6uUUkxBlmuZbPdzubX+vJRC8JSQhFYCqLAdA9TSAkZEFsbGwSxp5hp06O4BBeniUkJCSZl/uiYgErH28DTwTklDZeVBeGtz1ICUkQggRUip2tvPMyTdzQvwH/GHDzTyz7Xv7pXFL5oWIVHY5yek8N20blwx9nmPaitihp0o/jABbsKCW3/0uheLiGI45poUHH+z7P+OqcIKnD8Y6VHcjL8OMYRiXAJ+ZpvmlYRijgaeAduAa0zS/Cu7qfMORnArt7fbkgfiEYC8HAO1985TVs74qyuGAIcMkAyMM6Y4ARniUkKiUNLtcaU8d5AwL9nJ8xxPAUIlJ6CF58MkKdGsrKiYmaEuSDAwhhAgRurUV15x7OCH+Ax6uvJGnNxlSNiIGnLMWXMbX6ijuO+pOJqR8KeNVAyg/P4e8vFwWLUpCa8WiRUnk5eWSn9/Ds90Hyh0GSSlQ8oVvFxoa7gJqPNfvA1YDy4HHg7YiH3MkpdhXQmmUalkppGWgnD0PqKjcI0BGqYaf2mqIiYVwab7qycDQYT6JRDe60W1t+25o2JeBwZA80Na+Uq4gkf8EhBAiBIw5MoM3ZjzImNYV3FL8W+77+BIpGxEDUnZeFGbaHVS3pLHguBtJsmrYtCmaTz+NkXISP1uxooILL3TjdNrBUqfTYvp0NytX9q0ERCkFhePRG4p9ucxQMdg0zQrDMOKBycCtwB3AxOAuy3dUsieA4X0DEwJ02Q7IGdq7L8odBrUudKT1Joh0tdWQNih8GmJ2lJCEbwBDt7Vh3X49+l+L993Y0LmExPO7F+RGnhLAEEKIIKqocPC9i5JZdcUvmJL1PrNLfstz22d0vHFYvbqCuXP3eNLrhRgYttVk8K+cu0iL2c2jE29h00aHbzICxGF1buKplG+yv1TheKiuREdIH4xOqgzDGAVMAz4yTbMZiKf7Eathw9ERwAiNaUBaayjfiepler7KPcK+IlkYYUXXVYdN+QgAicngcIR1AIPij6Gmyg4UemhvI9/EZDsDA4LeyFMCGEIIEUSPPhjDlW23kbTlI15OvJGFmy+SshEx4C1YUMv192bTZlzLNzI+4TfjngT6nxEguudyOSgsbEVrKCxs7Xf2lxo9HiASszDuBNYAfwHu9dx2JrA2aCvyMW8JiQ6VDIxal92Po7cZGDkyiSQs1VaHzwQSPP1WklPDOoBhvf+mfcUzAQbYN1UlMdEu3UpNlwwMIYQYiPLzc8gflsGpX/6BM7I+4Ldf3MINSy5BKVi6tErKRoQA0qaezkdx3+Hq4c9wTu57NDUpGa/qR/n5OSxb5qSkJBZQlJTEsmyZs38ZL7lH2GfuSiIjgGEYRgKAaZrPADnAUNM03/DcvRK4OEhL8zmVnGpfCZUeGGV2A8/eZmCQ6ZlEIhkYYUNrDXU14TOBxCs5LWx7YOjdtfDFx6Ac+ybAgN3E0+GAOKf9eXaeZGAIIcRAtOLd7bwy7Rd8a/AKfv35bbzkupDp092sWVNBUVGblI0I4bGw6ZeURY/iyRP/j+sv3STjVf3I1z0wwHNWsqAokjIwthmG8bphGL8Ack3TdHvvME2z0jTN8iCuzac6mng2hEYAoyOtvZcZGMoRBUOGSgZGONlbD22tEEYZGIDdByNcAxgr3wHLQh13CtTv3tfIs6EeEpM7epGoIUOhrDSo45UlgCGEEAFWsaOFXbfNY7T+mF9/cRsvVV0gJSNCHMITC9zk/eEm3A2aKZvvpLxUSz8MP+ncA8OXpWxq9HhwVaBrqny00qDKBf4IDAOWGoaxwTCMPxmGcY5hGLFBXptPqZgY+6xriAQwKCu1s3mS03r9pTKJJMzUugBQ4dQDA3uUajgGMLTW6PffhFFjYcwE0Br2eE6iuRv2nwQzdISdleH5HgWDBDCEECKAdHMTe+bNYXz0GuaW3oZzyhQpGRGiGyorF33ZzzkmbR2/n/AggIxX9ROXy8GMGW4KC1uZOdPtk9clVVAEgN64vt/7CjbTNFtN03zLNM0bTdMcC0wFNgI/B3YahvGKYRhXG4aRHdyV+khiUsgEMHTZdsgZ2repFHnDocaF3hsaDUlFN3Z7JhSnhVkJiSeAEczshD7ZXALlpahTztzXd8TTB0M37IWExI5N1bCR9pUdWwK9yg7yF18IIQJkfEEqH1xyN8Nb1vKLtXcw//MLWLgwifPOGywlI0J0I/2Mk/ggfiazhppcMOwNmpqUjFf1gwULanE6NcXFMcTHa9+8Lg0bAfFO2Liu//sKMaZpbjZN81HTNL8NHAHMByYA5wV3ZT6SlIwOoR4Yve5/4aFGFNhXtn7tu/UIv9F13gBGGJaQtLVCo7v7bUOIXvkOxMbZ5SPeoJE3iOQpIekwdAQohd6xOeDr9IoO2pGFEGIAqdzexPMn38bomHXctP4OXt41FafTYurUJmbPljNCQvTE4sZrOCKmmDlj5vBx1Xg2bLDLRxYtSmLRoiTi4jSbN5cFeZXhKz8/h+bmfWe3ffW8KkcUHDkmIjIwvAzD6OokYLNpmv8G/h3o9fhNYrKdLh5kun4P7N0DQ3o5gcRr+Cj7TdfWDajxk3y7OOF73gBGau/LhYLKu949dftlLYQ6XVkOecNR8QloT9BI19bYM6Hde1HZeR3bqngnZOWitwcvgCEZGEII4We60c3eeXdQGL2OOeV/4J/bz5FRqUL0wZ8X7GX4Hb8kKamdZ6fcSqKzFZDxqr7ijyaeXqqgCHZtj6QU/jag9cAPwzCaDcPYYhjG/YZhhH1qkEpMDo0SEk//ij5nYDgT7EaeWzb6clXCX+pqICkFFR0T7JX0ikrpFMAIJ40N4PQEXJJSICoadnsmkTTshcT9gzFq2EgpIRFCiEh1TGECn8y6g9yWL/nZZ3NZ8OlUtFZYFtL3Qog+UIOHEHXp1YzSn3NF3kLi4jSNjYoPPoio/olB0bmJp1K+DbKqgnH2la+/7Pe+QsT1wNvA2cBY4BzgLeDXwDXAycBDQVudryQmhcQYVV3etwkknamRhbBlQ/j1JxiA9O6a8Ot/AXYJCUB9+AUwlDMB8EyOSk2H2hq0ZdnBjc4lJADDRtqNmYOUnSUBDCGE8JPKTXtYcvLVFKVu5Prie1hWPqXjjObq1RXS90KIPlInfYvV+kx+WTifN+a/x+jRrVRWRkkvDB9wuRwUFraiNRQWtvouyDqyEKKjI6mM5FfADE9Dzw2mab4JGMANpmn+F5gBnBvUFfpCYjI07LXfyARTWSnExsGgwX3fx8gCqN8NkTENJ7LVhXcAQ4ddBoZ7/5KX9Ax0XTU0ue2JJAn7/21Vw/LtK6VbA7fGTiSAIYQQfqDrqmm/9xaGOHZw6657WbbzVCkbEcJHlFKc9PAVlDVmo56+n52bWgAZrdpf+fk5LFvmpKQkFlCUlMSybJnTJ8+niomFEQXoyGnkmQIkHHBbApDquV4OOAO6In9ITgFt2WnkQaTLdsCQPPvscB+pkYX2lS0bfLQq4Te7a1Cp6cFeRe8lpYByhF8JibtTCQnYwaO6mn2/9wcEMPBMItFBKiORAIYQQvjY5HGw+dr/I6HZxWWrH+GFtZOlbEQIH1MJiSTd8EuGJZYxZ8I9gPTC6C9/9sAATx+M7ZvQzU0+2V+QLQLeMAzjJ4ZhTDUM40rgNWCh5/6zgZKgrc5HVHqmfaWuOrgLKStFDelb/4sOecPtLCDpgxHStNUOu+sgNcwmkOBpWJyUHFYBDN3aCq0t+49KTcuwf+c9JSIq8YAMjLRBdrZJkCaRSABDCCF8pKwMrp3ZyJtTryArsY4frX2U1bWTpGxECD/JOGEM/3NexvScV7lw2Os0NSmiojTXXJNOZaX8i9NbnXtg+CNjTBWMg/b2SBlleTPwKHAx8CDwfeAx7B4YAO8ApwVnaT7kHWNZ6wraEnRTo1320Y/+F4DdEHJYPnqrZGCEtPo9dtZPOJaQAKSkhVcJSWODfenslFCWNgiaGqHaU251YAYGwLCRQcvAkDGqQgjhI/P/sI3b4q+nZW8rf019iNWVE6RsRAg/W+L+IQUxq3ng+LvJ/dYYlv4vl9JSux/GvHkRM/EiYFwuBzNmuPnqqxjGjvVhDwyAEQUA6K0bUaPH+26/QWCapgU86fno6v6ISDPBk4Gha6tR3WzqN5W7AFD9DGCAXUai338D3d7W730JP/GMUFVhHMBgdxidqHJ7Ahide2B4R6nu2mZ/nnhwAEMNy0e/8S90W2vAp8XI6QkhhOin/Pwcpo7dzczt16DQnL/8Ke55fiJKwdKlVVI2IoQfzV9Qz/DZ19He0MTR6x5hx44otJZ+GH21YEEtTqemuDiG+Hjt04wxlZwKGVmwNfxT+A3DUJ7ykbcMw/jcc9uphmEYwV6bT6Wm2zX9QczAwOUpYcoc0v99jSyAlmbaSrf1f1/CPzwBDMKxBwaeUaphlYHhBkA59wUpOoJHO7fbl10EMBg2Etrb7Aa7ASYBDCGE6KePF7/BPyb/lEbLyYyVT1HaPoLp092sWVNBUVGblI0I4WcqZxht3/kB04a8w8zhywC7f8O0aW6KilqlnKSH8vNzyMvLZdGiJP8FgUaMQkdAAAO4A7gCeAo4wnNbKfCboK3ID1RUlP1GMog9MHRHACO73/tSI+xGnm2RMw0n4ujdnp+1cM7AqK8Ln3G9jZ5GnfuVkHgyMHZ6An1dlJB4J5HoIPTBkL/oQgjRD7XvrCThL7+nVmVz0coFlLUPk5IRIYIgefp5bIsu4v8K7mNochVNTYpNm6L59NMYGa/aQ/5u4gmgRhSAqwJdH/blPT8EzjVN8wXA+05lC5Dvi50bhvG0YRiVhmEUd7ptkGEYbxiGsdFzGZhT1OkZ6NogNvF0VYAz8aBGgn2SlQMJibRKACN01XlO+KSEZwYGKWnQ0gLNjcFeSc94MjD2LyHxBI8qd0F0DCo27uCvy86xRxsHoQ+GBDCEEKKPrPffIOlvd/NF3Rh+vP4Jzp+VKSUjQgSJckSxoPUWEmObuHPMXLSGDRtipZykFzo38VTKP/17lKcPBtvCPgsjCvDOFvUGMJI63dZfzwBTD7jtt8BbpmkWAG95Pve/9EwIYgBDuyohM8sn+1IOB4wopOXLz32yP+EHu2sgORUVHaatGlPS7MswKSPR3h4YncaoqninnZHR3g6JyV1+nXJE2Y08gzCWWAIYQgjRB/O+9QZ64SO8W3Uil6x+nHVbMvnzn6M477zBUjIiRJDMXZBMrHEZUwa/x5zzXvJrJkGkcrkcFBa2ojUUFvq4iSfA8FGgVCSUkbwKPGAYRhzYPTGAO4Glvti5aZrvAjUH3HwB+8a0LgQu9MWxuqPSM4LfA8MH5SNeatxE2ndsQddU+Wyfwnd0XQ2khmn5CJ4eGBA2AYyOKSSdMzBg3wSiA2/vRBUUwdav0c3Nflpc1ySAIYQQvaC1pn7hM/y64BE+0mdw3br7aGx34nRaXHxxu7xBEiLI1JRzYdQ4ZlgPk6KrOyYByXjV7uXn57BsmZOSklhAUVISy7JlTp9mrihnAmTnocN/lOqvgBxgN5CKnXkxHP/2wMg2TbPMc70c8N27+sNJz4SmRrQ31TyAtNZQXYHyZQCj6Bh73+s+9dk+hQ/trg3f/hcQdhkYuBtAKYiL3/927/fgMKVbqnC83chz81d+XODBwjQ3RwghAk+3t6Ofe5yE999g0bYZPNf6c+obYzveIKWkaOl7IUSQKUcUjh/eQPStN/DXqXcTfe1vWLw4gbffjpfxqt1YsaKCO+5I4bXX4mlsdOB0Wkyd2sTs2b59vtSIAvRXa326z0AzTXMPMN0wjGzsJp47TNMsD+DxtWEYh+wSaBjGVcBVnm3JzMzs9TGio6PJzMyk6YgR7AbSaSe6D/vpj/baalwtLSSNOJIEHx1bZ2TgGjSYmK/Xkzb9+z7ZZ6jxfu/CUdWeOmILxpJ6iPWH+mNrd4ALSGxv7dPPbKAf3x4smhKSGJy1f5nW7uxcmr5cS2x6BumHWI914mSqHFE4d2wm6ZtTuj2Wrx6bBDCEEKIHdFMjb1/yMN/K/ICHNv6EBzZeBSgALEsza1YDFRXO4C5SCAGAys4ldrrB+Jef46c/Oo9lO7/Vcd+iRUksWpREXJxm8+ayQ+9kAOrcA8MbmPVLQ+LcYbDyHXSTGxWf0P32IcIwjK7Sd6o8Hx33m6bpr0h2hWEYOaZplhmGkQNUHmpD0zTnA/M9n2qXq/clIJmZmbhcLnS03cCvdvPXKGfX9fD+ojfZZ3Yb4hNx9+ExHErsxBNoWvk/qioq7EkrEcb7vQs3ur0dq66G5viEQ64/1B+btiyIimbv9q19+pkN9OOzqqvR8c6Djml5emK0Rsccfj1H5NPw2Sqazp7e7bG6e2y5ubk9WrPkUQohRDd0XTUtc2/hmxkrWKxv5InSnwCqo65+9eoK5s7dg2m2B3upQggPdc50yBvO49+cx8UXVO3XD0PGqx6ay+Vgxgw3hYWtzJzp9ktDYpXl+Se1MuwCSG1Aaw8+/OUV4HLP9cuBf/nxWPt4Usl1EPpg+HKEamdxx5xop86Hfy+WyFJfB9qyR/eGKeVwQMZgqD5kfDGk6MaG/Rp4dkj39sA4/PQfVTgetmxAtwSuD4b85RZCiMPQpVux5t1Me9lOrljzAH/ddJH/z04KIfpNRcfgmHUdUfU1TI+av9/vrYxXPbQFC2pxOjXFxTHEx2v/NCTOtntq6Ipdvt+3f43EHpOaD1wPLMeeFDLWc/kOcJ0vDmQYxvPACmC0YRilhmFcAdwNnGUYxkbgTM/n/udt5heMSSTeAEaGbwMYsUcdbzeTXfeJT/cr+mm3/XqjwrkHBkBG1r7gW6hrbOiyUafyNlI9xBSSju0Kx0NbGwRwGomUkAghxCHo9Z+y+957aGhL4EcfL2DdnjEdCbvespHKyshLPRUiUqj80ajTv8OJb73MLZecyb0vnoDWig0bYgEpJzlQfn4Ozc2q43O/PT+DPRkYYRbAME1zm/e6YRi/Ao4zTdPbqW+DYRgfAx8DT/jgWJcc4q7uC819TMXEQHJqcCaRuCogJQ0VF+fT3TpSUmFEgd3I8/zI7IMRluo8g3dSM4K7jn5Smdnoz1YFexk943bbGSMH6mEGBgVjQTnQJcWo0RN8v74uSAaGEEJ0oe7VN2l54A5ihmTxePITbG4tBDiobETGpQoR2tT0H+AYlMFPE+9h5fulXHihW8arHsKKFRUBeX5UXJw92aIyvAIYB0gFDmzgkeC5PfKkZ6KDkIGhXRUweIhf9q2KJsGWjeiGer/sX/Se9gYwIiADg/rdAR8v2ieNDaiuRqVm58HgIajhRx72y1VCEgwbid5Q7KcFHkwCGEII0YnWGuul50h+6WE+cB3PvdajtKcMlrIRIcKUik/AcenVsHMbg9f+86AmlTJedZ/OTTyV8vPrXVYOOvx6YHS2EHjTMIyrDMOY5pn68Zrn9siTnhG0DAzl4/IRL1V0DGgLvT68J+JElLoae6SndxRpuPL2bKkJgz4Y7q57YKiERKLmzkeNGtvtLlTheNhcgm71ZwugfeSvtRBCeOiWZl4+/3H0qybPb7+QH338EE89l82zzyaiFCxdWsWsWQ1+aWonhPAfdfQJMOkb6P/8He2qYNasho7f51Wr4li1Klb6YXi4XA4KC1vRGgoLW/32eqeyc8OuhOQAvwYeBr4HPABcDDzquT3iqPTMgPfA0O3tUFPl8waeHUYW2rX/X3zsn/2L3ttdA8mpYT8ZRmV4RpK6QjuAoS0Lmtxd9sDoDTW6CFpbAtYHQ3pgCCEEoKursB6fy/lDNrE06ipu33QFbToKp9Ni6tQmZs/eQ1aWxdy5e4K9VCFEHzi+dyXWuk+ZO/E+oq67LXD9HsLIgc9JSUksJSWQnx/v++ckKxf27kE37EUlhl/wyDMq9UnPR+RLzwD3XnRzEyouPjDHrHWBZUFmll92r6KiUOOPQ3/xEdpqRznC+01zJNB1NeFfPgIdP7O6ugLVzaZB1dQIWoOzn+OsC4rsprhffoYqLPLN2g5DMjCEEAOe/upzrLt+iVVRxt319/BO3KU0NTmkZESICKIGDUaddzGsXY3+bFWX/R4G+njVQPXAAPaliIdR/wHDMM7u4XZn+XstAZeeaV8GMgvDM8VB+SsDA2DiibC3Hr7+yn/HED23uwZSIyCAkZIO0dEhn4FBo9u+7GqMai+oxGQoKEKv+dAHi+rewPwLLYQQePpdvPkvrAdnQ3Iqf0r4M0+8fzqrV8ful2IuJSNCRAY15XzIPQLrhafISnMf1A9joI9X7dwDw98B3I6pEs1NPt+3H73Yw+3+7tdVBIHyTiSoC1wAo2MMpR8DGGr8JIiKRq8Nk4kRka6uJvxHqALK4YBBWVAd6gGMvQBdN/HsJXXsyVC2A71re7/31R0pIRFCDEi6uRn97KPoVct5vfJb/OK/t7O3zX7Tsn17DAsXxvDCC4kDNpVciEikoqNxXHoN1r2/Q//HxOX6ObNmNfD884kyXtXD5XIwY4abr76KYexY//XAINZThhBeAYwkwzC6++9cAb6d+RkKPBkYurY6cCnxrgpwOGBQFyMefUQ5E2DMBPRnq9AzfoRSIZ3wH9F0ezvU74bU9GAvxTcys9ChHsBw+yYDA0BNOhn9wlPoNR+ico/o9/4ORzIwhBADjnZVYN3zG/Tqd2k48zKesO7km2dFyWhFIQYAVViE+sYZ6Ndf5qk7P2fu3D2sXBnA0okQt2BBLU6nprg4hvh47b9R0d4+Ci1hFcA4Hbism48fAFODtUC/SfNkYARyEomrAtIz/d7QUU08ESrLoGyHX48julFXY/dj8JYrhTmVkdVRBhWyGhvsS18EMNIGwaix6DUf9Htf3ZEMDCHEgKK/XIs1/x5ot3Bcdxvznp/CJ5/GU1DQKlwH72QAACAASURBVKNShRgg1Iwfoteuxlr8JI4b7zqodKKxUfHBB7HBXmbABbSxqTeA0RQ+AQzTNJcHew3BouLiIDE5oD0wtKvCr+UjXuqoE9CLn0SvXe33M8fiMGqqAFCDIiOAQWY21O8ObOPbXtLeAIYPSkgA1LGn2FkYZaWonKE+2WdXJANDCDEgaKsd699/x3rw95CcxplvLWLotAtYtCipI3Vca4VlIX0vhIhwKiUNNf0yKPkC/dF7gF064e19M3p0K5WVUQOuF0ZAm3h6/qHX4ZWBMbClZ6ADmoFR6d8Gnh5qUCYMH4X+TPpgBJP2BDD8WTIUUN5RqqFcRuL2cQBj0skAfs/CkACGECLi6epKrHtvRf9rMer4yVRfeT9J+UOYNq3xoH/UV6+uYO7cPf5LmxZChAR16tn2mxbzaXSTmwULannhhUTOPjuLkpJYQLFoURJ5ebnk5+cEe7kB0TkTRSk/Z6N1NPFs9v2+hX+kZ3acJfc33dJsT6QYPCQgx1MTT4AtG9C75W9/0NR4gmMRkoHREXwL5QBGxxSSfo5R9VDpGXDkGL9PI5EAhhAiolmr38X6w8+hdAvqil/i+MlNPPhEFp9+GsumTVFSNiLEAKUcUTguvRr21KKXvgB0nYEw0EarulwOCgtb0RoKC/3YxDPOaV+GVxPPAU1lZkNVOVpr/x/M+6YvABkYAGriSaB1QOr3xSHUVkFCIireN2+mg86TgaFDeZSquwFiY1HRMT7bpTruFCjdgq7Y5bN9Hkh6YAghIpJucqP/Nh+94m3IH43jyhs58sRj9qvv9k4csCzNrFkNVFZK2YgQA4kaWYiafBb6zVfQJ08hO294l6NVN260R6vOm7cn2Ev2qwN7YJSUxFJSAvn58b7vgdHWZl86BkZgKCJk50FTI9TXQYqfJ0VUlQMEpIQEQA0dAUNHoj98G844NyDHFPvTNa7IKR8BSEmD6BioDuFGno0NPmng2ZmadDL684/t1wo/kQCGECLi6M0lWAvut+tnz72YquMv4dqrM1m6tIrHH0/itdfiaWx04HRaTJ3axOzZeyTzQogBSn13FvqTFVh/exLHTXM7emEMxNGqK1ZUcMcdKV2+Rvqcp5eCCrOJA4ZhRAPnA98BjgbSgDpgLbAMeNk0zbbgrdB/VHYOGqB8l98DGLrK86YvQCUkAOqUKei/L0Dv3IbKGx6w4wqP6qqImUACoBwOOwsj1DMwfB3AGDSYqF/d6dN9HkjC3kKIiNHRqPOPvwHLwnHzXBwXfJ+HHkll1apYnnsu4aCzq1I2IsTAppJSUN+dBRvWoVctZ8GC2gE7WvXAaSx+fY2sDb96d8MwrgY2Az8FNgFzgKs9l5uAnwCbPdtFnqxcAHSl/1LDO7gqIDYOklP9fywPdeJpEBWF/vCtgB1TdFLrQmVEUAYGQEaWPU0nROnGBp/1vwgkycAQQkQEXbkL65mHYeN61Amnoi69miPHFxw0EhDA4dAsXVrF4sUJUjYihLDLSN5/A73kafRRx6ESkrp8Mx8VpbnmmnSeeKI2YgOfLpeDGTPcfPVVDGPH+q8HRsc0i/QMv+zfT0YBJ5imWd7FfS8Bcw3DyAFuDOyyAiQjC6KiIQABDO0qh8FDUEp1v7GPqORUOOp49Ip30NNnoaLlbVKg6OYmaKiPqAwMAJWZhd6+KdjLOLRGt88mkASSZGAIIcKabm3BeuV5rN9fD6VbUT/+JerKG1EJSYccCbhmTQVFRW0ybUQIAdipvo5Lr4H6PeiXnu24vfNo1VmzGli1Ko5Vq2IjerzqggW1OJ2a4uIY4uO1/14ja6shKsquEw8TpmnedIjgRedtykzTvClQawokFRUFg7PRFQEooaoqD1gDz84cp5wJ9bth3ScBP/aA1jGBJMIyMDKzYe8etB/7QfSLuwHl4xKSQJAAhhAibOn1n2LdfgN66fOoY07CccfjOL5xOkopKiocXHttOtHRUjIihOieGn4kasq56OX/RW/6CqCjnOS88wazcGESO3ZEo3XkjlfNz88hLy+XRYuS/P84a1yQOgjlCM8sOMMwag5xewgXvPtAVi5U7PTrIbTWdg+rIAQwKJoEyalYH7wZ+GMPZJ7xvCrSAhieSSSEahlJY4NkYAghRCDouhqs+fdiPfh7QOP45R9wXHUzKm1QxzYPPZTEqlWxrF4du98ZVL+NBBRChD11wfchLQPr2cfQbfv6MB4qmyvS+mEE8nHqWle4lY8c6KC5g4ZhxAAR/UdGZedCVRna8uOJgL17oLkxoA08vVR0NOobp8PnH6H31AX8+AOV9gQwwqknTk+oIUMB0GWlQV7JIfihiWcgSHGXECJsaKsd/c4y9L+eg9ZW1HmXoKZdhIqJ7djmwDGA27fHsHBhDC+8kBixkwOEEL6h4hNwfP8qrMfmot/8F2rqRUDXzS0jsR9G58eplP+beKrho3y/Xz8zDOM9QAPxhmG8e8DdQ4EPA7+qAMrKhZYWqKvx35vNAI9QPZCafDb69ZfRH7yJmjYjKGsYcGpcoBSkhXVQ82A5Q0E5YNc2YHKwV7Mf3doCba1h2cRTMjCEEGFBb9mINecm9AvzYeRoHLc/guP8S/YLXlRUOCgqamHatMaIP1MqhPAPNfEkmHgSeunz6Kp97Q4GSj8Ml8tBYWErWkNhoX+aeGp3A1RXBuUMuw8sAJ4G2oC/dPpYAFwDfDd4S/M/lW1PIvFnGUnH1IbM4Px8qJyhMHqCXU7mz0wTsU9NFaSmR1zjVBUTC9k56J3bgr2UgzU22JcJ4fc3LLJ+SoQQEUfXuND/MdHvvQYp6airfo067pQuO5M/9FASn34aS0FBq/S9EEL0meOSq7Bm/wzrb0/iuOH3KKU6mlkemOW1aFESixYlERenwz7L68DHVlISS0kJ5OfH+/Sx6eI10N6OmnCcz/YZKKZpLgQwDGOlaZpfBXs9AdcxSrUMNfZo/xzDGzgMUgYGgDptGnr+PbDuU5hwbNDWMVDomqrIa+DplTscSrcGexUHc7vtS8nAEEII39A1VViLn8S69Sr0B2+gzjgXx52P4zh+8kHBiwMbz23YEIvWCstC+l4IIXpNDcpETf8BFH+CXrV8v/u66hMxbZqboqJWKivD+9+qgPXA+GwVJKdCfqFv9+tnhmGc771+uOBF5+0iTnoGxMT6d5SqqwJS0lBxcf47RjfUMSdCShrW8mVBW8OAUuOKvAaeHirvCLtvTEtzsJeyP08GhgrDJp6SgSGECCm6ugq9bAn6fbsDuDplCmrajEPWwnrLRrKzLf73vzgaGx04nRZTpzYxe/YeybwQQvSJOv3b6I/eQz//Z3TheJSn3r+rfhibNkWzcWMMDz6YxLx5e4K88r7r6rH5OoNNt7aiv/gYddzkcJxAcrFhGHOBxcByoASoB5KBQuA04AfAZ8ArwVqkPymHA7Jy0BX+C2BoV0XQy4tUdAxq8lnoZf9AV1ehMiLzzXUo0FpDrQsmnhDspfiFyhtuP8ayUhh+ZLCXs4+3hCQMm3iG96kCIUTE0NWVWM8+hnXrT9Hvv4mafCaOOU/iuOxnh23k5S0b2bQpSspGhBA+oxxROH78C2hrw1r48H618N5+GFqzX9ZXJIxXdbkczJjhprCwlZkz3b7PYCv5Apoa7V4jYcY0ze8DlwB5wLNAFdAIVAILgSHA90zT/EHQFhkIWTngxwAGVeWojOCVj3ipU88BNPrd14K9lMi2dw+0tkR2CQmEXh8Mt7cHRvgFMCQDQwgRVLqqHL3sRfSHb4FSqG+ebU8W6eYP2YG12hs22M08LUsza1YDlZVhd2ZPCBFiVFYuauaP0YufQC9fhjr9OwAd/TB+/vO93HFHCq+9Fn9Q9le4WrCglt/9LoXi4hiOOaaFBx+s9en+9dpVEBsHY4/y6X4DxTTNL4DrAAzDSADSgDrTNN1BXVgAqew89Bcfo612n2fR6LY2eyLFSSEQwMjIgvHHoj98E33B9+3sE+F7nhGqKj2yRqh2yMqB6GjPJJLQoRvDtweGBDCEEAGntYbtm9DvvIpe+Y4duDj1HNTUGR1p2odSUeHg2mvTWbq0iscfT+ryjYNkXgghfEWdNhW9dhX6xb+ixx6NGjK0475IG6/q7wal2rLQn62G8ZNQscHrb+ALhmEcZZrm58CACVx0yMqBtjaorvJ9qUdNFWgr6CUkXuq4yegvPobtm2BEQbCXE5mq7QAGEVqmo6KiYMgw9M7twV7K/rZssEe8JiYHeyW9JgEMIUTA6N216FX/Q3/4NuzcBjGxqNOmoaZehErv2ezvhx5KYtWqWJ57LsHvtdpCCKGUwnH59Vi334D19EM4fvNH+x9SD285yaWXulm8OIG3346ntDQqLPthrFhR4d+Mkm2boK4adfSJvtlfcP3bMIxE4D3sfhjLgU9N09TBXZb/qexcNNhlJL4ONHhGqB6udDSQ1ITj0MqBXrsaJQEMv9C1LvtKpJaQYDfy1BvXBfSYet2n9rGLjjn4vpJi9Huvo848HxUXH9B1+YIEMIQQfqXbWmHtR1gfvgXFa8CyIH806gfXoo6fjOrh/OmuzgwCOByapUurWLw4QcpGhBB+odIyUJdeg55/D/rVJajzLu64L5LGq3bOKFHK94Fh/cbLEBuHOvp4n+wvmEzTPMIwjHzgVOzmndcBGYZhvG+a5rnBXZ2fZecBoCt3oZjk011rl3eEaohkYCSnwKgxdubQBZcGezmRqabKnmyTlBLslfhP3nBYtRztbgjY1A/r+fngKsdx3W2o8ftGAevmJqyFD8PgIagLLwvIWnxNirmEED6ntUZv24T1/Hysm3+I9eTdsH0T6pzpOO54nKjf3YvjtKk9Dl7Aocf7rVlTQVFRG3Pn7ul4IyGEEL7mOH4y6oTT0P9+AV1SfND9B75GxcdbZGS08+9/VwV6qf3icjkoLGxFaygsbPVZE0+9ZSP6o/dQZ12ACsOU5a6YprkZ+BBYAawE2oGsoC4qEFLSIN4J5aW+33dVBURFQ/og3++7j9TRJ0LpFnR1ZbCXEpmqqyA9E6VU99uGKeVp5MmuwJSR6OYme9Sx1lhP3I3etG/qs37pWagqx3H5DUEdVdwfkoEhhPAJrTXs3IZe9wl6xTt2iUh0DOqYk1AnnwHjJva52Ze378XQoW1SMiKECBp16dXo7V9j/fmPOG59YL/Ril31w2hqUjz7bELYlJIcmEVSUhJLSQnk58f3K4tEa431j2cgKQV1znd9sNLgMwzj78A3gF3A/7BHq15tmmZ9MNcVCEopGD4KvXmDz/etq8ogY3BIjdhVR59g98BZuxp1RmQn1wSDrnVBN/3Pwl7eEQDoXdtQo8b6/3g7t4HWqB9cg37tJayH77AbJ5dug4qdqNO/jRo93v/r8BMJYAgh+kzXVaPXr4UvP0N/uRZ2ezIgRhaiLr0adfypqMSeZ1kcirfvxa5d+9eaS8mIECKQVEIijp/dijX3JqzH5+D49R/3O4PlcjlwOOiylCQ+XrNpUzBW3XN+64Gx7hMo+QJ18VWoMOx4fwiTAAtY6/n4LFDBC8MwpgJ/AqKABaZp3h2I43amCsah/7ME3eRGxfvme6rb2uCrL1DjfVuW0l9qSB5k56HXfgQSwPAprTWUl6KOmxzspfjXoMEQ54QANfLUpVsAUGMnosZOxHpsDuzYAnnDUSefgZpyfkDW4S8SwBBC9JhuaoQNxej1n6HXfwZlO+w7klNRY4+2syzGHt3tCNSeOvBs4PbtMSxcGMMLLySGTU25ECKyqCFDcVx5I9ajd6EXPQpX/qoj9XnBgloqKhxdBgEeeij0/+XqKoukv5lu2mrH+sdCu976tHN8uNrgMk2zwDCMHOweGKcCvzUMwwm8a5rmlf46rmEYUcBjwFlAKfCRYRivmKa53l/H7IoqGIfWFmwqgS6aBPbJhmJoqEdNOtk3+/MhdfQJ6LeWohvdkRSEC77dNeBusHtERDDlcEDuMPTOAI1S3bHVLvPKzEYpRdTtjwTmuAESMj0wDMOYahhGiWEYXxuG8dtgr6crFRUOpkyJprLS0fH5RRdldHze1W2yjWwTStuUl9Pj/WitqSpxMffiL6l//gXa7/0d7b+4FOuRO7GWvwbpGagZP6T2Zw/zvW3/xnXBr3GcciaVrdk+WXNxcTTR0Zozzmg6qO/FypUVCCFEsKijjkddcCl69XL06y/vd19XQYCWFpgwIYb16/cFMXryOujr23qyjcvl4DvfaSQqSnPuuY397oGhVy6H0q2o6ZehomP6ta9QY5pmGVACfA1sBYYA0/x82BOAr03T3GyaZgvwAnCBn495sPzRoBzor30XN9GffAhx8RBiGRhgBzBob7OziYTveDISVIQHMMDzGHdutbNO/EyXboWhIyK2r0jU7bffHuw1eKPJ/wXOAeYBDy9ZsuTdmTNnHq7z1e319YEtM5wzJ5n//CcWt1tx5pnNzJmTzKuvOjs+927T+TbZpnfbJCQkcOutUSGznkjbpqFB8a1vNRy0zZTT6vnrnRXo4k8Y/PUbDF1nos2ncS5fwuS4N4naUoxKTOa95rP53YdXUzz+Oqb836moUWO5809H8OqrCT5f8/e+N4jy8ihqahw0NDiIi7PTso8/voULLmjywW+07yUkJOB2u4O9jIglz69/yfPbSwXj0Lu2w9v/QeWPRmXldNz1wgsJnHxyM/Pm7cbhgFdfdbJ3r2LVqlh++EP7Oe7J66Cvb+vJNuef38QDDyRRXm4HLv75z5o+P0W6tQX9xDzIysXxvSv9+s90b39+k5OTAf7Q1+MZhvHKkiVLHgO+CzQDbwC3mKZ5a1/32RNLliw5CciaOXPmK57PRwJjZ86c+eoB67tqyZIlf16yZMlVM2fOzI2LiyMhIaFXH9HR0cTHx3d5X2JKKs0fvU9UQz0Z587o9b4P/HDGxdE4/z5iJ55IxjkX9Ht//XlsXX7kDsW97J/ExcQw6Ixv+319AX98Qfpg7WpaPltN5lU3kjgoI6Ie24EfjuYmmt97g/TJZ5I8bLjfHp/T6cS98FGcx5xE+qlnBv1x9+axRdkjyrt9XVaBiAJ1xzCMbwC3m6Z5jufz3wGYpjnvMF+md+3aFYjlHZTGLkR40mTG1pDnLGOYs4xhCTsZk/w141I2cGTiNqId7QC42+L5qn4UX9YXsG7PaL7cU8BX9aNoaA/M2KfDrf/yyxuorIwK2WkjmZmZuFyuYC8jYsnz61/y/PaebmrEuvvXUFuN47d/ROUM2+/+vLwcIBL+f9Ds3Nm7sj2tNXrxE+jl/8Vx412oMUf5aW223v785ubmQj++OYZh/BBYbprmlr7uo4/HnQFM9ZapGIZxGXCiaZrXHebL+vQ/c3fPqfX3Bfb39+Hn+51do0uKse67BXXVr3Ec7/9+CH15vbOeuh/95Wc47ltolwSEsHB5PbeeeRj9+UdEPfBsj78mXB7bgXTDXqwbZ6HOPA/HjB8dcrv+Pj5dVY51y1Woy67FcerUPu/HH7p7bD19XQ6Vgsw8YEenz0uBEw/cyDCMq4CrAEzTJDMzMB1rS0pa+e1vo/jXvxw0Niri4zVZWZrKSrvDuNOpOftsO8X99ddlm/5so5SD114jZNYTTtskOtuYcVYl6bqcXV+UMziqnOFJZYxM2cVgRzm58eXERzXv97O9szGbkoYCVjaexpqKQtbWFFJp5XHm2Qqy9j/WEXlWQB5XXJwmKgrsE2kK0AwfrnnxxTaOOirWs/LQ7FYdHR0dsNelgUieX/+S57dv2v/vfmp+exU88H+k3fEI0cNGdty3enUrM2ZEs327wvt6lpenGT9e8+679mteV6+Dvr6tJ6+9Tqfm1FMtiosVO3fuW6/39be3PxvuV/9B/fL/kjD9ByRPPqPvT3APBfrn1zTNZwJ2sP3tBDpHyoZ6bgs4NWoc+s1XYNsmOHJMv/alP/kQYmJRE4710er8YPwkWL0cdmyG4aOCvZqIoHdtj/j+F14qMQnGHo1e8yH6oh/6LyOtdKt9vKEjD79dGAuVAEaPmKY5H5jv+VQHKvoWEwMxMak0NSUQH69pbob4+Daam2M89a2QmtqI1oqmpgTi4mSbvm4TF+ekqckRMusJ5jYJ8c0k6kaOHFRLiqrl5PhyEq068oc2MNhZS1pUHcPSqnEOryMjro60mN1EtXkarY2zL1zN6VTrbL6qO5K3XZPZ0ZBDwYnp1DhymP/iSJodSbS0QEFBKxtLY4iNhZYWSE1tCNpjb2mBlBQLu0WPnSEWF9dGbq6LUA+4h+tZgXAhz69/yfPbR1Gx8Ku7sO6/lepbr8Vx0xxUrj0yLy8P4uIGY/+7Zb+eJSa2kZXV2vGa19XroK9v68lrb1MTZGc3snlz3H7r7cvrr17/KdZfHoSjT6Bp6gyaA/Bz1ccMjHD0EVBgGMZI7MDFxcD3g7KSAnscpP56PaofAQxtWXYAY/wkVLzTV6vzOVV0DBrQxZ+gJIDRb9qyYNd21OSzgr2UgFHHnoxe+Ahs3wzDj/TLMfSOLaBURAeGQqIHxpIlS1KBC2bOnPmc5/PvAPUzZ858/zBfFtAeGN561iefdNDc3Mi6dbFcdJG7o761qioKt1vtV/Mq2/R+m6amKE480R0y6+n3NkpTX9VMjLuGbx+/jTnXfcGYhK9Ida3n6tPeZ/aFb3FWxluM2/06x7qXcu3Y57n5qL/ys+Hz+fGgP3N1/rP8YOiLzBz6bya0/I/RrSv5RsYnFGXtICOpgTq3E5WRRcqEfFbvPYkPWs7if1zEqkGXknbFLJ7a8SPuWTGT+FNO4dybx7Kh5Ti+qBxKVVMGx52kg//8HGKbzz6LZdSoNu66aw9ffx3N7t1R/PSnDQH7fe+rhATpIeBP8vz6lzy/faeSU1ATjkevfAf9wVuo8cehUlIBePjhZIYObePhhzXr1rWze3cUqanWfq95Xb0O+vq2nrz2VlVFsXVrNEOH9v31V5fvxHro9zA4B8cNs1Exsd1/kQ/09ue3vz0wgmXmzJnWkiVLNgKLgeuB50zT/Ec3X9an/5m7e05VnBO9ajm0NOM44dRe77/D5hL0m6+gzv0eauiIvu+nF/ryeqfi4tGffwTVlTgmn+mnlflGWLyeV1eiX3sJNfnMXgWEwuKxHcqgweg3XoaEJHt6Xxf6+/ist5aCpXGcfWGf9+Ev3T22nr4uh0oPjGhgAzAFO5r8EfB90zTXHebLAtYDozM5Q+Vfofr8aq2huRHq98DePVC/G92wFxrqoWEvuO3ruuO65z73XrAOM34uKhoSEiExGRKT7Bc0zyUJSZCUAskpqORU8H4kpaCi+tYVPlSf30ghz69/yfPrX/L89p8uL8W67zaw2u2+D53OgA2E51c37MWadzM01OO49X5UZnbAjh3oHhhhxi89MMDTw+DTlTgefK7PfSGsF/+KfnOpvY8AjSjt6++j9dJz6P++aK81IckPK/ONcHi90Ws/wnr0Thy/+SNq1Ngef104PLbDaX9wNrgqcNz1ZJdlJP19fO23XAVH5BN1degN9YyoHhimabYZhnEd8BoQBTzdTfBCiH7TTW6oq4HdtXZAYu+e/QMUnT/fuxva2g69s4REO+DgCUSoQYM7AhIdtyUk2bd1vj02LmJHHAkhxECjhgzFcdMcrPtvxbr/toOCGJFMt7Vh/fmP9j/mN94V0OCFCKKCIvjgTSgrhbwj+rQL/fnHUFgUsOBFf6jxk9CvmvDlWjj2lGAvJ6zpXdvsK7l9+7kJV+rYk9HPPg47t4KP+1ToJjdUlaNOnuLT/YaakAhgAJim+SrwarcbCtEN3dwMu2ugrgbtufR+7Pd5c2PXO3AmQnKKnf2QMRg1PB+SOmU/eO9LSraDEM4ElKNvGRFCCCEiixqSh+OmuVj33YJ13604rrr5kKnCkUK3NKOfeRi+XIu6/HpUwbhgL0kEiCoYZ/eFKPkc1YcAhq4qh7IdqFPP8f3i/CF/NDgT7T4YEsDon13bIT0TlRDsKXeBpSaehH7uSfSaD33faLPUDgqpYZHbwBNCKIAhRE9oraF+N1RXQXUFuroSXJX2ZXUl1FWDu4ta3ZhYSBsEqYPsX+rxk+zP0wahUgd1BCdISu73KDAhhBADm8rOxXHzXKxH52A9OBt17sXoy68N9rL8QtdUYT0+D7ZvQn33chwDqCGfAJWVA1k56OJP4Ixze/31+vOP7f0cdZyvl+YXKioKxh2NLv4ErbVk0faD3rmtz1k74UylpMGYCej330R/e6ZP+wTpUs9U5wieQAISwBAhRmuNrt8NVeUdwQk7UFFlByiqK+wxGZ0lJEFmFmTl2nPmvYEKzyVpgyAhUf7ICCGECBiVlYvj1vvRi59AL32euq0b0JffgEpND/bSfEZvXI/1xDxobcHxs1tRR58Q7CWJIFATjkO/+xq6pRkVG9err9VffATZeais8JkKo4omodd8aGcQDJASMV/TVjuUlaLGTgz2UoLC8e2ZWPffhn73ddSU3gf+DmnjevuE7KDIHokuAQwRFNq9FyrK0BU7oXKXfb1yF1VV5eiGAzplJyZDRhbkDEWNnwQZ2aiMwXbQYlDWgEs9E0IIER5UXDzqx7/EGn0ULX97Eu74OY4rb4yIkhLr3dfQf/szZGThuHkuKmdYsJckgkSNPxb91lIoKYYJx/b463RTI5R8gTr9O35cne+pokn7xqlKAKNvKsuhrXVAZmAA9gnX0RPQy5agv3lWrwN/XdHNTejPVqFO+lbEn7SVAIbwG93SDOU70RW7PEGKnejKMqjYZTfG9FIKBg2GrBziv3kmTSmD7JTEzGy7B0V86Dd1EkIIIQ7FccoU0iYeR/Xdv+soKVHnGmHZP0m3taL/vgD9v2UwfhKOn9wU0tMYRACMHg+xsegvPkb1IoDBV2uhrQ01ITzKR7zUoEzIGYZe/xmcMz3YywlPngaeaoA18OzMcf4lWPfegn73xPOO8QAAIABJREFUv6gzL+j3/vTa1dDSjOrPSOMwIQEM0W+6uRnKd6B37YBd29Fl9iWuCug8pjdtkJ0meMxJkJ1rpwtm5ULWkI76r5TMTFrCeDSSEEII0ZXo4UfaJSV/exK99Hl08RocF12OGj0h2EvrMb1lI9bfn4JNX6HO+S7qu5eFZRBG+JaKiYUxR6OL1/SqL4T+/GOId0IYNn1V4ybaZTOtLT7tYTBQ6J3b7ROYAzhzSxWOh7FHo199Ef3Nc1Bx8f3an179LqRlhOXvU29JAEP0mG5qhLJSdNl22LUDvWs7lO2we1N4AxVR0XZw4ogj4aTTIWcYakgeZOX0+xdTCCGECGcq3mmXlIybiP7HIqz7boVxx+CY/gPUiIJgL++QdNkOrJefg09W2M2ur7wRx4mnBXtZIoSoCceiP/8IKnbCkKHdbq+1tgMYRceEZfN0NW6iXTazcT2MG5h9HPpDr/sEco8Y8O8NHOdfgvXH36Lfex115vkdt+sv12I997j9SVQ0avwkHMYVh9yPbqiH4k9QU84dEEFlCWCIg2irHSrLYOc2dOlWdOlWKN1qZ1R4RUfb2RQjC+HkKXYKWO4wGJyDipYfKyGEEOJQHCedjj72FPQ7r6KXLcGacyNM+gaO/2/vzqPkLOtEj3+f6g4JgewdknSnk5AEEAiLyCqoIKgwbDpXHsFxZhQdzuyLM8c7DHNn7pk7zvVe79HrXK96mNGrnmGGeVTcRoZFRB0loKyCIBgIWZosdPaQEJLu5/7xViBLJ+nuVPVbVf39nNOnqt7t+b3vW6k89atneef7Gmosidy7hvztW8mL74WxYwlXXkd429WEI+3aqb2FRW8oxoV4/CHCIBIYLH8ONq0nnHJW3WOri+MXQVs7+clHCSYwhiSvXlm04nr3B8oOpXRh4Ukw+1jyI4thzwTGj+6GLZuLAXKXP0v+0d3ka64/YOum/PBi6Ns1KrqPgAmMUS9v2Qw9ryUp8srnYdXy12b6CBWY2UWYdxycvztRMadIVLS1foZPkqR6CGOOILz9neQ3vZ189zfJd3+D/keqA7BdeS1h+szSYsubN5C/8xXyD+6AEAiXXEm47BrChImlxaTGFjpmFONCPP4gvO3Q/fnzQz+GSqVppk/dVxh3JCx4HfmpR8sOpenk++4p7v25F5YdSkMIp55JvuNr5Je2Eo46mty3qxgg9vRzqFz/x/Tf82/kW2+GzRvhALNY5Qd+ADO6YM6CEY6+HCYwRom8a2cxoObuREVP8cjG9a9tNGESzJ5HePNlxePsecXMHzUYGVeSJO0vHDmecNV15IsuJ9/xVfL3vkO+/16YfwLhtHMIp59DmDWIX7QPU968sRjD4Gc/hccfgl07CedfQrjiPYSp0+tevppfOOUN5Hv+jfzi6oMm4HLORQLjhFMIEyaNYIS1FU46nfyNfyJv2dTU5zGScn9f0aJr0RtaakrpwxFOOZN8+1eK1jxnXcDOp5+AbVsJpxWtk8LMLjLA6p4BExh54zp45onis7rFZx/ZzQRGC8qbNxRJihXP79GqYgX07So2aG8vxqY48bTXEhWz5xEm+kEiSVIZwoSJhGuuJ198FfnH3yU/+gD5ti+Rb/tS0RLy9HMJp58Dxx5PqFQOu7ycc1FH+NlPi6TF0meK8awmTS1agbztncUYVtIghTdeQv6Pu+n/2w9T+dCHiy9m/f2waiVMmkw4utqCZ+XzsHYVocln8Hg1gfHkowTHhBmcJx+FjeupXHtD2ZE0jvnHw9ET4PGfwlkXsOPB+6CtDU6sdk2qfg7nNSsJJyzab/f8k/+AnEdN9xEwgdHU8s6dsHolecXS17qBrFgKWza9ttHkqTD7WMKiM6rJimOLQTYdp0KSpIYTpnYQrrwWrryWvP5F8mM/IT9yP/nub5Dv+BpMnFzMXDK1AyZPI0yeWow8P2UaTJqy14CIedfOotnx5o2waWPxA8fmjdC7hvzzR2BDddavY48vxrc49SyYM3/U/Iqn2gpdc6j85Sfo/9zH6P/7v4ETT4MVz8HWLdB9LJW//ASh0kZ+sNp95PXnlR3y4Zm7AMYfDU89CiYwBiXf973iy/ppTTr2SR2EShvh5DPITzxM7u/nlYfug4UnEcYfVWwwpQOOOAJW9Qy4f37gBzB34eDGnmkRfottAvmVHUX3j+r0pPmFFUWLirWrIPcXG7WPga65RV/C3YmKrnn2V5UkqUmFqdMJF10OF11O3raV/PhD8OgD5KXPwCOLYdcu8r47TZhUfKnasgm2bR34wEdNgBMWEa5+L8Gm3KqhcMwsKn/+P8np8+SnHyecejYcPYF81zfIP7wT3nJZS3QfgeKLJyeeSn7ysSFNHzta5Ze2kh+5n/DmdzTlzDN1dcqZ8MAPyA/dx67lzxGuuf7VVaFSgWM6yWv2T2DkVSth+bOE9xx4hpJWZAKjgeQdO4oWFauW752oeHHNa4mK6puYrjmEM88vpiDqPhaO6XRQTUmSWlQYf3TRTL36S2/Oufhle9M62LC+6Ae9cT1sXAcvbS0SGZMmFy02Jk6BiZOL/tMTJxPGHFHy2aiVhSPGEt73u6++zjmTlz1L/sYtxa/Ea3oIgxjosxmEk04nP3TfoKePHc3yj++ujq1zcdmhNJyw6AxyqJC/+oXi9T6D24YZXeTlz+63X37g+xAqhLNGT/cRMIExovIrO2Ddi7BuLXndWli3BnrXkte/CL1rYdMeA2q2tRVJie75RWVl1hxCZ3e1+4dZS0mSRrMQAkyYWPzNPhZ/+1WjCiFQue4G+v/mj+j/7MeKL1yvP7fssGoiLDipmD526S9HVRP+ocovbyffcRucdDphlMyUMRThqAmw4ARY8hRts2aTZ+wz/tCs2fDwYvLOnYQxxffAnHPRfeTEU0ddKzoTGEOUcy5aSuzYDjtehpe3F89ffhl2bCdXH3l5e9F0c30vuXcNrFtb9DvdU1t70Yd12jHFGBUdxxBmzYHO7mKaUsepkCRJUpMLXXMJF11Ovufb8LpTCRMnlx1SbczqgiPGwrIlcN5FZUfTsPK9t8OWTVSuem/ZoTSscMqZ5CVPMfYNb2THvt2RZnQVrfFfXAWdc4plz/4CetcQrrxu5IMtmd+Qh6Dvxt9i7foXob9/cDu0t8PU6UWC4rSzYdoxMG06YdqM4vnkKUX/OUmSJKmFhauuI//ySSoX/krZodRMqLTBnPnkZUvKDqVh5e3byHfeBqecSVjwurLDaVjhjDeS77iNcW96Gzv2XbfnVKrVBEZ+4AdwxBGEM1qjNdNQmMAYgnDeWxk/9gi29QPjxsHYcYRxR8LYI2HsOBi3x+O4I6F9jAP6SJIkadQL44+m7b98suwwai7MXUj+j7vI/X3+MDmAfM+34aUtVK4afS0FhiLM7KLt7/+FMR0d0Nu798oZu6dS7SEAedcu8oM/Ipx2DmHc+JEPtmQmMIagctV1HN3Rwcv7vqkkSZIkjT5zFsArO4ppLrvmlB1Nw8i9a8gP/Zh819fh9HMI844rO6SmFY4cD5OmwqqVxYKf/QS2biace2GpcZXFBIYkSZIkDUOYu7AYyHPZEoIJDPLaVfR/+dPw9OPFgnnHUXn3B8oNqhXM7Hp1KtX+H94JUzpg0RklB1UOExiSJEmSNBy7B/Jc/iy88a1lR1OanDN58ffI/3wzVCqEX/0NwpkXEKbPLDu0lhBmdJEf/FExOcSTjxKuuHbUdlkygSFJkiRJw/DqQJ7P/7LsUEZc7u+HXzxGfvoJ8lOPwdJn4PiTqVz/YcK06WWH11pmdsG2reR//xoQCBdcUnZEpTGBIUmSJEnDNFoH8sy3fJb8wzuhUoG5Cwnxg4SLrxhV12CkhJmzi65KP7oLFp1BmDp6E0QmMCRJkiRpuOYuhHu+PaoG8swP3Uf+4Z2Ei68kvPN9xcyMqp+ZxUwk9PdTefM7yo2lZJWyA5AkSZKkZhXmLgAgLxsd3Ujy+t5ioM65Cwnvfr/Ji5EwbTq0j4HJU+GUM8uOplQmMCRJkiRpuGZ2wdhxsOzZsiOpu9zfR/8XPgl9u6j81p8R2seUHdKoECpthAsvK1q7tI3uLjp2IZEkSZKkYQqVNuieT162pOxQ6i4/8EN4+nHCb/4BYUZn2eGMKpX3fKjsEBqCLTAkSZIk6TCEuQtgxXPk/r6yQ6mb3N9Pvv0r0DWX8MaLyw5Ho5QJDEmSJEk6HF1z4ZVXoHdN2ZHUzyOLYfVKwuWRUPFrpMphFxJJkiSpQcQYrwH+K3AicHZK6cE91t0IfBDoA/4wpXRnKUFqP6FrLhngheVwTOt1rcg503/7V2BGF+ENbyw7HI1ips4kSZKkxvEE8KvAD/dcGGM8CbgWOBm4FPhMjHF0j+bXSDq7Acg9y0sOpE6eeAiWP0e47D8VY35IJTGBIUmSJDWIlNJTKaWnB1h1NXBrSmlHSmkpsAQ4e2Sj04GEceNh2jFFC4wW1H/7V2DqdMI5F5YdikY5ExiSJElS4+sCVuzxemV1mRpF5xxyCyYw8poXYMlThIuvJLQ7AoHK5TtQkiRJGkExxu8CMwdYdVNK6Zs1OP4NwA0AKSU6OjqGfIz29vZh7dcM6nVuWxaewLZvP8a0KZMJbeV9zar1+b3047vZCky75HLaSn5PtPL7Elr7/Gp1biYwJEmSpBGUUrpkGLv1AN17vJ5dXTbQ8W8Gbq6+zL29vUMurKOjg+Hs1wzqdW79k6fDrp30PvkEYdbsmh9/sGp9fn2Lvw9dc9lQGQMlvyda+X0JrX1+hzq3zs7BDX5rAkOSJElqfN8C/jnG+AmgEzgO+Em5IWlPoWtOdSaSZVBiAqOW8ratsORJwtvfWXYoEuAYGJIkSVLDiDG+K8a4EjgP+E6M8U6AlNLPgQQ8CdwB/F5Kqa+8SLWfmd0QQkvNRJJ//gj09RFOdbxYNQZbYEiSJEkNIqX0deDrB1j3UeCjIxuRBiuMHQsdM+o2E0le+gz5xdVUzn5zXY4/oMd+AkdPhPnHj1yZ0kGYwJAkSZKkWuiaW/OZSPKWTeTbvkz+0d0A9O/cSeX8i2taxoDl9vWRH3+IcNpZhEpb3cuTBsMuJJIkSZJUA6FzDqx9gbxzZ02Ol5c/R/9f/g558fcI73gXvO5U8j99hrz0lzU5/kE9+wvYtpVw6ln1L0saJBMYkiRJklQLnXOgrw/WDDhBzJDknOlPn4e2Nip/9Skq7/4AlRs+ApOm0P+ZvyNv3lCDgA9S/s9+Am1tcPIZdS1HGgoTGJIkSZJUA6FrDkBtupE88TA8/TjhivcULTuAMGEild/9C9i2hf5bPnf4ZRxEfuJhOO5kwpHj61qONBQmMCRJkiSpFmbMhkrlsAfyzP199H/tizB9JuHN79hrXZgzn3Dh5fDYT8kvbT2scg5Y/ktb4YXlhBMW1eX40nCZwJAkSZKkGghjxsAxnYc9lWq+/wfQs4zwrl8ntI/Zv5yzLoC+XeRHFh9WOQf03C8gZ8KCE+tzfGmYTGBIkiRJUo2ErrnQ8/yw98+7dpG/eQvMXUh4w/kDbzR3IUyfSf7pj4ZdzkFjWPJU0ZJk/gl1Ob40XCYwJEmSJKlWuo+FF1eTt28b3v4vroL1LxLeegWhMvDXtRAC4cwL4BePkbdsOoxgB5aXPAnd8wljx9X82NLhMIEhSZIkSTUSZh9bPBluK4zeNcVxZnQevJyz3gT9/eSH7hteOQeQd+2Epb8kHHdSTY8r1YIJDEmSJEmqle55AOQVzw9r99y7tngy7ZiDbzh7HszsIj9Y424ky5+Dna8QFjr+hRqPCQxJkiRJqpUpHTD+aFi5dHj7r1sD7WNg4uSDbhZCKFphPPMEeeP64ZU1gLzkyeKJA3iqAZnAkCRJkqQaCSFA97HkFcNMYPSuhY5jDjj+xV5lnfUmyJn8cO26keQlTxXTt06eWrNjSrViAkOSJEmSaijMngc9y8j9fUPeN/euOXT3kd3lzOqGaceQn35iyOUMWHbOsOQpu4+oYZnAkCRJkqRa6j4WXtkBa1cPfd91awnTZgx687DwRHj2qSL5cLjWroItm8AEhhqUCQxJkiRJqqFXZyIZ4jgY+eXtsHUzdAyuBQZQJBs2bXh19pLDsXv8i7DQGUjUmExgSJIkSVItdXZDpTL0mUjWvVg8DrILCfBqd4+85KmhlTWQpc/AkUfBzNmHfyypDkxgSJIkSVINhTFHwMzZ5KHORFJtRRE6Bt+FhM45cOR4qEECI6/ugc7uQQ0gKpXBd6YkSZIk1ViYfezQu5Csq3YDGUIXklBpg/knkJ+tQQuM1T2EGV2HfxypTkxgSJIkSVKtdc+D9b3kl7YMfp91a2HMETBh8pCKCgtPhBeWk7dtHVqMe8jbt8Gm9TDTBIYalwkMSZIkSaqx1wbyfH7Q++TetTDtGEIIQytrwYmQMzz79JD228vqnuJYjn+hBmYCQ5IkSZJqrbtIYOQVQ+hG0rsGhjL+xW7zTygGDT2McTDympXFE1tgqIGZwJAkSZKkGguTpsCESfDC8sHvtG4tYShTqO4ua+w46J5/eONgrO6BSgWmzxz+MaQ6M4EhSZIkSfUwq5s8yARG3r4NXtoypClU9xQWnghLnybv2jWs/VndAx0zCe1jhre/NAJMYEiSJElSHYTObli1kpzzoTdet7Z4nDaMLiQAC06EV15h19JnhrV7Xr3S7iNqeCYwJEmSJKkeZnbDtq2weeOht+0tplANwxkDAwjzFgKwc+kvh7xv7u+HtasIJjDU4ExgSJIkSVIdhM7u4skgupHk3S0whjEGBlB0PRk7jl3Lnxv6vutfhJ2vwAwTGGpsJjAkSZIkqR5mFQmMvGrFobftXQtHjIWjJw6rqFCpQOcc+oaTwFhdzEDiFKpqdCYwJEmSJKkeJk2BI4+CQSQwcu8amHYMIYRhFxc65wyrBUZe3VM8sQuJGpwJDEmSJEmqgxACdHaTV6089Mbr1sAwx794Vddc+jdtIA9mzI09remB8UcV075KDcwEhiRJkiTVSZjVfcgxMHLOsHY1YfrMwyura27xpGfZkPbLq3tgRtdhtf6QRoIJDEmSJEmql1ndsGUTecvmA2+zoRd2bH91zIxhqyYw8iAGDd3L6pWOf6Gm0F52AJIkSZIKMcaPA1cCrwDPAh9IKW2srrsR+CDQB/xhSunO0gLVoIVZ3WQoxsGYcPLAG72w4tVtD8vEyYQJk4bUAiO/vA02rnf8CzUFW2BIkiRJjeNuYFFK6VTgGeBGgBjjScC1wMnApcBnYoxtpUWpwatOpZpXH3ggz1fXzTq8VhAhBNrnzB9aC4w1LxT7msBQE7AFhiRJktQgUkp37fHyfuDd1edXA7emlHYAS2OMS4CzgcUjHKKGakoHjB33aiuLAa1aCUdNqMkgmu1zF7Dze98h5zyoMS1yNYHBDBMYanwmMCRJkqTGdD3wr9XnXRQJjd1WVpftJ8Z4A3ADQEqJjo6OIRfc3t4+rP2aQRnntq57HpXe1Uw5QLnre1fDnPlMnT79sMvaMW8h21/eztS8i7bpsw65/Us7d7AVmLbweCpHTTjs8uupld+X0NrnV6tzM4EhSZIkjaAY43eBgaabuCml9M3qNjcBu4Bbhnr8lNLNwM3Vl7m3t3fIMXZ0dDCc/ZpBGefW3zGLXb/42QHL7Vv+HOH159Ukromz5wGw/olHCaeOOXRsq1ZC+xjWbXuZsH3HYZdfT638voTWPr9DnVtnZ+egjmMCQ5IkSRpBKaVLDrY+xvh+4Arg4pRSri7uAfYc4XF2dZmaQWc33H8vedtLhPFH7bUqb9kEW7cc/gwkVe1z5hfH7VlOOPWsQ++waQNMmuIUqmoKJjAkSZKkBhFjvBT4CPCWlNK2PVZ9C/jnGOMngE7gOOAnJYSoYdhrJpIFr9t75ardM5DUZhrTylFHw9QO6Hl+UNvnagJDagbOQiJJkiQ1jk8DE4C7Y4yPxhg/B5BS+jmQgCeBO4DfSyn1lRemhmTecRAq5J89uN+qvGpl8aRGLTAA6JxL7hnkTCQmMNREbIEhSZIkNYiU0sKDrPso8NERDEc1EiZPhZNfT77vHvJV1xHa9pgBd9WKYpaSKbUbvDF0zSH/4jFyX9/eZQ1k0wbC8YtqVrZUT7bAkCRJkqQ6q7zpbbBxHfz84b2W51UrYOZsQqWGX8265sGuXbD2hYNulnfuhJe2wKTJtStbqiMTGJIkSZJUb6eeBRMm0f+ju/devmplzca/2C10zSme9Cw7+IabNxaPk6bWtHypXkrvQhJj/DhwJfAK8CzwgZTSxnKjkiRJkqTaCe1jCOddRL7n2+TNGwgTp5C3b4MNvTCztgkMZnUXY270LCOcecGBt9u0vojNMTDUJBqhBcbdwKKU0qnAM8CNJccjSZIkSTUXLngb9PWRF3+/WLC6GMAzdM6pbTljjoAZs8iHbIGxoXg0gaEmUXoLjJTSXXu8vB94d1mxSJIkSVK9hFndsOB15B/eST7zgmL8C4AadyEBoGsurFh60E3yRhMYai6lJzD2cT3wrwdaGWO8AbgBIKVER0ftRuodrPb29lLKHS28vvXl9a0vr299eX3ry+tbX17f+vL6qplU3v4u+j/73+m/8UMwYRK0tcP0WTUvJ3TOJT+8mLxjB2Hs2IE32rQBQoAJDuKp5jAiCYwY43eBmQOsuiml9M3qNjcBu4BbDnSclNLNwM3Vl7m3t7fWoR5SR0cHZZQ7Wnh968vrW19e3/ry+taX17e+vL71NdTr29nZWcdopIMLZ5xH5e9uJi/+Hvm+78HxJx96qtPhlDN7LjlnWLUc5h038EabN8DRE+tSvlQPI5LASCldcrD1Mcb3A1cAF6eU8kjEJEmSJEllCNNnEq56L/nK6wgh1KeQzrkA5J7lhAMkMPKmDc5AoqZSeheSGOOlwEeAt6SUtpUdjyRJkiSNhLolLwCOmQljjoCe5w+8zcb1MNnxL9Q8GmEWkk8DE4C7Y4yPxhg/V3ZAkiRJktTMQqUNZnWTe5YfeKPNGwkTTWCoeZTeAiOltLDsGCRJkiSp1YSuueQnHx1wXe7vL8bAcAYSNZFGaIEhSZIkSaq1rrmwaT156+b91720Bfr6TGCoqZjAkCRJkqQWFLqKgTwZqBvJpg3FNiYw1ERMYEiSJElSK6omMPILy/ZfV01gOAuJmokJDEmSJElqRZOnwvijYeX+CYy8aX3xZNLkEQ5KGj4TGJIkSZLUgkIIMHsueeXS/Vdu2lg82gJDTcQEhiRJkiS1qHDcybD0l+QN6/ZesWk9jDuSMHZcOYFJw2ACQ5IkSZJaVDj3Isj95J/8YO8VmzbARAfwVHMxgSFJkiRJLSrM7IL5J5AX30vO+dXlefMGmGwCQ83FBIYkSZIktbBw3kXQswxW7DEWxsYNBMe/UJMxgSFJkiRJLSyc9SZoaycvvve1hZs3wERnIFFzMYEhSZIkSS0sHDUBTjuL/MD3yX195C2b4OXtzkCiptNedgCSJEmSpPqqnHcR/Q8vpv/TfwvPPAFAmLew3KCkITKBIUmSJEmtbtEbYNIUePpxwtlvIlx0OWGuCQw1FxMYkiRJktTiQvsYKn/5SRgzpuhSIjUhExiSJEmSNAqEyY55oebmIJ6SJEmSJKnhmcCQJEmSJEkNzwSGJEmSJElqeCYwJEmSJElSwzOBIUmSJEmSGp6zkEiSJEkNIsb434CrgX5gLfD+lNILMcYAfAr4FWBbdfnD5UUqSSPPFhiSJElS4/h4SunUlNLpwL8Bf1VdfhlwXPXvBuCzJcUnSaUxgSFJkiQ1iJTS5j1eHgXk6vOrgS+nlHJK6X5gcoxx1ogHKEklsguJJEmS1EBijB8FfgPYBFxUXdwFrNhjs5XVZasG2P8GilYapJTo6OgYcgzt7e3D2q8ZtPK5QWufXyufG7T2+dXq3ExgSJIkSSMoxvhdYOYAq25KKX0zpXQTcFOM8Ubg94G/HsrxU0o3AzdXX+be3t4hx9jR0cFw9msGrXxu0Nrn18rnBq19foc6t87OzkEdxwSGJEmSNIJSSpcMctNbgNspEhg9QPce62ZXl0nSqOEYGJIkSVKDiDEet8fLq4FfVJ9/C/iNGGOIMZ4LbEop7dd9RJJaWcg5H3qrxtS0gUuSJKl0oewABhJj/BpwAsU0qsuA304p9VSnUf00cCnFNKofSCk9OIhDWmeW1CwO/bmcc/ZvCH/XXHPNg2XH0Mp/Xl+vbzP/eX29vs385/X1+jbzn9fXa+q5jY7za+Vza/Xzq9W52YVEkiRJkiQ1PBMYkiRJkiSp4ZnAGLqbD72JDoPXt768vvXl9a0vr299eX3ry+tbX17f2mvla9rK5watfX6tfG7Q2udXk3Nr5kE8JUmSJEnSKGELDEmSJEmS1PBMYEiSJEmSpIbXXnYAzSLGeCnwKaAN+MeU0sdKDqllxBi7gS8DMyjmKr85pfSpcqNqPTHGNuBBoCeldEXZ8bSaGONk4B+BRRTv4+tTSovLjap1xBj/BPgQxbV9HPhASunlcqNqXjHGLwBXAGtTSouqy6YC/wrMA54HYkppQ1kxNrMDXN+PA1cCrwDPUryHN5YXZfMa6Pruse5Pgf8FTE8p9ZYRX7NrpTrvgeqYrfZ5t28dL8Z4LHArMA14CPj1lNIrZcY4HAPVrYCnaZF7N1DdBphFk967odQtYoyB4nPmV4BtwPtTSg8PphxbYAxC9UPh/wKXAScB18UYTyo3qpayC/jTlNJJwLnA73l96+KPgKfKDqKFfQq4I6X0OuA0vNY1E2PsAv4QOLP6H2IbcG25UTW9LwKX7rPsz4F7UkrHAfdUX2t4vsj+1/duYFFK6VTgGeDGkQ6qhXyR/a/v7i+rbweWj3RAraIF67wHqmO22ufdvnW8/wF8MqW0ENgAfLCUqA7fQHWrlrh3B6nbNPO9+yKDr1tcBhxX/bsB+OxgCzGBMThnA0tSSs8WpjwQAAAFXElEQVRVM2C3AleXHFPLSCmt2p1xSyltofhw6io3qtYSY5wNXE6RxVaNxRgnAW8GPg+QUnrFX1Zrrh04MsbYDowHXig5nqaWUvohsH6fxVcDX6o+/xLwzhENqoUMdH1TSnellHZVX94PzB7xwFrEAd6/AJ8EPkLxa6aGp6XqvAepY7bM592+dbzqL9tvBb5a3aQpz+8gdauWuXfsX7dZRRPfuyHWLa4GvpxSyiml+4HJMcZZgynHBMbgdAEr9ni9Er9g10WMcR7weuCBkkNpNf+bolLXX3YgLepY4EXg/8UYH4kx/mOM8aiyg2oVKaUeiibhyyn+c9+UUrqr3Kha0oyU0qrq89UUTa5VH9cD/152EK0kxng1RfP5x8qOpcm1bJ13nzpmK33e7VvHmwZs3CNh2qz38EB1q5a4dwPVbSi6jLTCvdvTge7XsD9rTGCoYcQYjwa+BvxxSmlz2fG0ihjj7r5oD5UdSwtrB84APptSej3wEk3apLERxRinUGTqjwU6gaNijO8rN6rWllLK+Ct2XcQYb6Jo1n5L2bG0ihjjeOAvgL8qOxY1poPVMZv5867F63iHrFs1+b3br27DAF3jWkmt7pcJjMHpAbr3eD27ukw1EmMcQ/Efyy0ppdvKjqfFnA9cFWN8nqIp6FtjjP9UbkgtZyWwMqW0u+XQVyn+01VtXAIsTSm9mFLaCdwGvLHkmFrRmt3NN6uPa0uOp+XEGN9PMcDZr1UrcqqNBRRfAh6r/l83G3g4xjiz1KiaU8vVeQ9Qx2yVz7v96ngU40ZMrnZLgOa9hweqW7XKvRuobnM+rXHv9nSg+zXszxpnIRmcnwLHVUf07aEYYOW95YbUOqp99T4PPJVS+kTZ8bSalNKNVAeLizFeCPxZSslfr2sopbQ6xrgixnhCSulp4GLgybLjaiHLgXOrv7Jup7i+D5YbUkv6FvCbwMeqj98sN5zWUp3Z4SPAW1JK28qOp5WklB4Hjtn9uvpl7kxnIRmWlqrzHqSO2RKfdweo4/1ajPErwLspkhpNeX4HqVs9SQvcOw5ct7mXJr93+zjQv7VvAb8fY7wVOIeie/CqgQ+xNxMYg5BS2hVj/H3gTooRYr+QUvp5yWG1kvOBXwcejzE+Wl32Fyml20uMSRqqPwBuiTEeATxHMRWWaiCl9ECM8avAwxRN7x8Bbi43quYWY/wX4EKgI8a4EvhrispFijF+EFgGxPIibG4HuL43AmOBu2OMAPenlH67tCCb2EDXN6X0+XKjag0tWOcdsI5J63/e/Wfg1hjj31L8n9ms/z4GqltVaIF7d5C6zXdo0ns3xLrF7RRTqC6hmEZ10PXmkLMtGCVJkiRJUmNzDAxJkiRJktTwTGBIkiRJkqSGZwJDkiRJkiQ1PBMYkiRJkiSp4ZnAkCRJkiRJDc8EhiRJkiRJangmMCRJkiRJUsMzgSFJkiRJkhpee9kBSJJqI8a4APgpcElK6eEYYyfwGHBNSun7pQYnSZIkHaaQcy47BklSjcQYfwv4E+BM4OvA4ymlPys3KkmSJOnw2YVEklpISukfgCXAA8As4KZyI5IkSZJqwwSGJLWefwAWAf8npbSj7GAkSZKkWrALiSS1kBjj0RTjXtwLXAacklJaX25UkiRJ0uGzBYYktZZPAQ+mlD4EfAf4XMnxSJIkSTVhAkOSWkSM8WrgUuB3qos+DJwRY/y18qKSJEmSasMuJJIkSZIkqeHZAkOSJEmSJDU8ExiSJEmSJKnhmcCQJEmSJEkNzwSGJEmSJElqeCYwJEmSJElSwzOBIUmSJEmSGp4JDEmSJEmS1PBMYEiSJEmSpIb3/wEx81yeLukXpgAAAABJRU5ErkJggg==\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()" ] } ], "metadata": { "kernelspec": { "display_name": "Python 3", "language": "python", "name": "python3" }, "language_info": { "codemirror_mode": { "name": "ipython", "version": 3 }, "file_extension": ".py", "mimetype": "text/x-python", "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython3", "version": "3.6.9" } }, "nbformat": 4, "nbformat_minor": 4 }