{ "cells": [ { "cell_type": "code", "execution_count": 1, "metadata": {}, "outputs": [], "source": [ "import numpy as np\n", "from scipy.integrate import odeint\n", "from scipy.interpolate import interp1d\n", "import cvxpy as cp\n", "\n", "import matplotlib.pyplot as plt\n", "plt.style.use(\"ggplot\")\n", "\n", "import time" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "### kinematics model equations\n", "\n", "The variables of the model are:\n", "\n", "* $x$ coordinate of the robot\n", "* $y$ coordinate of the robot\n", "* $v$ velocity of the robot\n", "* $\\theta$ heading of the robot\n", "\n", "The inputs of the model are:\n", "\n", "* $a$ acceleration of the robot\n", "* $\\delta$ steering of the robot\n", "\n", "These are the differential equations f(x,u) of the model:\n", "\n", "$\\dot{x} = f(x,u)$\n", "\n", "* $\\dot{x} = v\\cos{\\theta}$ \n", "* $\\dot{y} = v\\sin{\\theta}$\n", "* $\\dot{v} = a$\n", "* $\\dot{\\theta} = \\frac{v\\tan{\\delta}}{L}$\n", "\n", "Discretize with forward Euler Integration for time step dt:\n", "\n", "${x_{t+1}} = x_{t} + f(x,u)dt$\n", "\n", "* ${x_{t+1}} = x_{t} + v_t\\cos{\\theta}dt$\n", "* ${y_{t+1}} = y_{t} + v_t\\sin{\\theta}dt$\n", "* ${v_{t+1}} = v_{t} + a_tdt$\n", "* ${\\theta_{t+1}} = \\theta_{t} + \\frac{v\\tan{\\delta}}{L} dt$\n", "\n", "----------------------\n", "\n", "The Model is **non-linear** and **time variant**, but the Numerical Optimizer requires a Linear sets of equations. To approximate the equivalent **LTI** State space model, the **Taylor's series expansion** is used around $\\bar{x}$ and $\\bar{u}$ (at each time step):\n", "\n", "$ f(x,u) \\approx f(\\bar{x},\\bar{u}) + \\frac{\\partial f(x,u)}{\\partial x}|_{x=\\bar{x},u=\\bar{u}}(x-\\bar{x}) + \\frac{\\partial f(x,u)}{\\partial u}|_{x=\\bar{x},u=\\bar{u}}(u-\\bar{u})$\n", "\n", "This can be rewritten usibg the State Space model form Ax+Bu :\n", "\n", "$ f(\\bar{x},\\bar{u}) + A|_{x=\\bar{x},u=\\bar{u}}(x-\\bar{x}) + B|_{x=\\bar{x},u=\\bar{u}}(u-\\bar{u})$\n", "\n", "Where:\n", "\n", "$\n", "A =\n", "\\quad\n", "\\begin{bmatrix}\n", "\\frac{\\partial f(x,u)}{\\partial x} & \\frac{\\partial f(x,u)}{\\partial y} & \\frac{\\partial f(x,u)}{\\partial v} & \\frac{\\partial f(x,u)}{\\partial \\theta} \\\\\n", "\\end{bmatrix}\n", "\\quad\n", "=\n", "\\displaystyle \\left[\\begin{matrix}0 & 0 & \\cos{\\left(\\theta \\right)} & - v \\sin{\\left(\\theta \\right)}\\\\0 & 0 & \\sin{\\left(\\theta \\right)} & v \\cos{\\left(\\theta \\right)}\\\\0 & 0 & 0 & 0\\\\0 & 0 & \\frac{\\tan{\\left(\\delta \\right)}}{L} & 0\\end{matrix}\\right]\n", "$\n", "\n", "and\n", "\n", "$\n", "B = \n", "\\quad\n", "\\begin{bmatrix}\n", "\\frac{\\partial f(x,u)}{\\partial a} & \\frac{\\partial f(x,u)}{\\partial \\delta} \\\\\n", "\\end{bmatrix}\n", "\\quad\n", "= \n", "\\displaystyle \\left[\\begin{matrix}0 & 0\\\\0 & 0\\\\1 & 0\\\\0 & \\frac{v \\left(\\tan^{2}{\\left(\\delta \\right)} + 1\\right)}{L}\\end{matrix}\\right]\n", "$\n", "\n", "are the *Jacobians*.\n", "\n", "\n", "\n", "So the discretized model is given by:\n", "\n", "$ x_{t+1} = x_t + (f(\\bar{x},\\bar{u}) + A|_{x=\\bar{x}}(x_t-\\bar{x}) + B|_{u=\\bar{u}}(u_t-\\bar{u}) )dt $\n", "\n", "$ x_{t+1} = (I+dtA)x_t + dtBu_t +dt(f(\\bar{x},\\bar{u}) - A\\bar{x} - B\\bar{u}))$\n", "\n", "The LTI-equivalent kinematics model is:\n", "\n", "$ x_{t+1} = A'x_t + B' u_t + C' $\n", "\n", "with:\n", "\n", "$ A' = I+dtA|_{x=\\bar{x},u=\\bar{u}} $\n", "\n", "$ B' = dtB|_{x=\\bar{x},u=\\bar{u}} $\n", "\n", "$ C' = dt(f(\\bar{x},\\bar{u}) - A|_{x=\\bar{x},u=\\bar{u}}\\bar{x} - B|_{x=\\bar{x},u=\\bar{u}}\\bar{u}) $" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "-----------------\n", "[About Taylor Series Expansion](https://courses.engr.illinois.edu/ece486/fa2017/documents/lecture_notes/state_space_p2.pdf):\n", "\n", "In order to linearize general nonlinear systems, we will use the Taylor Series expansion of functions.\n", "\n", "Typically it is possible to assume that the system is operating about some nominal\n", "state solution $\\bar{x}$ (possibly requires a nominal input $\\bar{u}$) called **equilibrium point**.\n", "\n", "Recall that the Taylor Series expansion of f(x) around the\n", "point $\\bar{x}$ is given by:\n", "\n", "$f(x)=f(\\bar{x}) + \\frac{df(x)}{dx}|_{x=\\bar{x}}(x-\\bar{x})$ + higher order terms...\n", "\n", "For x sufficiently close to $\\bar{x}$, these higher order terms will be very close to zero, and so we can drop them.\n", "\n", "The extension to functions of multiple states and inputs is very similar to the above procedure.Suppose the evolution of state x\n", "is given by:\n", "\n", "$\\dot{x} = f(x1, x2, . . . , xn, u1, u2, . . . , um) = Ax+Bu$\n", "\n", "Where:\n", "\n", "$ A =\n", "\\quad\n", "\\begin{bmatrix}\n", "\\frac{\\partial f(x,u)}{\\partial x1} & ... & \\frac{\\partial f(x,u)}{\\partial xn} \\\\\n", "\\end{bmatrix}\n", "\\quad\n", "$ and $ B = \\quad\n", "\\begin{bmatrix}\n", "\\frac{\\partial f(x,u)}{\\partial u1} & ... & \\frac{\\partial f(x,u)}{\\partial um} \\\\\n", "\\end{bmatrix}\n", "\\quad $\n", "\n", "Then:\n", "\n", "$f(x,u)=f(\\bar{x},\\bar{u}) + \\frac{df(x,u)}{dx}|_{x=\\bar{x}}(x-\\bar{x}) + \\frac{df(x,u)}{du}|_{u=\\bar{u}}(u-\\bar{u}) = f(\\bar{x},\\bar{u}) + A_{x=\\bar{x}}(x-\\bar{x}) + B_{u=\\bar{u}}(u-\\bar{u})$\n", "\n", "-----------------" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "### Kinematics Model" ] }, { "cell_type": "code", "execution_count": 2, "metadata": {}, "outputs": [], "source": [ "\"\"\"\n", "Control problem statement.\n", "\"\"\"\n", "\n", "N = 4 #number of state variables\n", "M = 2 #number of control variables\n", "T = 20 #Prediction Horizon\n", "DT = 0.2 #discretization step" ] }, { "cell_type": "code", "execution_count": 3, "metadata": {}, "outputs": [], "source": [ "def get_linear_model(x_bar,u_bar):\n", " \"\"\"\n", " Computes the LTI approximated state space model x' = Ax + Bu + C\n", " \"\"\"\n", " \n", " L=0.3 #vehicle wheelbase\n", " \n", " x = x_bar[0]\n", " y = x_bar[1]\n", " v = x_bar[2]\n", " theta = x_bar[3]\n", " \n", " a = u_bar[0]\n", " delta = u_bar[1]\n", " \n", " A = np.zeros((N,N))\n", " A[0,2]=np.cos(theta)\n", " A[0,3]=-v*np.sin(theta)\n", " A[1,2]=np.sin(theta)\n", " A[1,3]=v*np.cos(theta)\n", " A[3,2]=v*np.tan(delta)/L\n", " A_lin=np.eye(N)+DT*A\n", " \n", " B = np.zeros((N,M))\n", " B[2,0]=1\n", " B[3,1]=v/(L*np.cos(delta)**2)\n", " B_lin=DT*B\n", " \n", " f_xu=np.array([v*np.cos(theta), v*np.sin(theta), a,v*np.tan(delta)/L]).reshape(N,1)\n", " C_lin = DT*(f_xu - np.dot(A,x_bar.reshape(N,1)) - np.dot(B,u_bar.reshape(M,1)))\n", " \n", " return np.round(A_lin,4), np.round(B_lin,4), np.round(C_lin,4)" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Motion Prediction: using scipy intergration" ] }, { "cell_type": "code", "execution_count": 4, "metadata": {}, "outputs": [], "source": [ "# Define process model\n", "# This uses the continuous model \n", "def kinematics_model(x,t,u):\n", " \"\"\"\n", " Returns the set of ODE of the vehicle model.\n", " \"\"\"\n", " \n", " L=0.3 #vehicle wheelbase\n", " dxdt = x[2]*np.cos(x[3])\n", " dydt = x[2]*np.sin(x[3])\n", " dvdt = u[0]\n", " dthetadt = x[2]*np.tan(u[1])/L\n", "\n", " dqdt = [dxdt,\n", " dydt,\n", " dvdt,\n", " dthetadt]\n", "\n", " return dqdt\n", "\n", "def predict(x0,u):\n", " \"\"\"\n", " \"\"\"\n", " \n", " x_ = np.zeros((N,T+1))\n", " \n", " x_[:,0] = x0\n", " \n", " # solve ODE\n", " for t in range(1,T+1):\n", "\n", " tspan = [0,DT]\n", " x_next = odeint(kinematics_model,\n", " x0,\n", " tspan,\n", " args=(u[:,t-1],))\n", "\n", " x0 = x_next[1]\n", " x_[:,t]=x_next[1]\n", " \n", " return x_" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Validate the model, here the status w.r.t a straight line with constant heading 0" ] }, { "cell_type": "code", "execution_count": 5, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ "CPU times: user 3.29 ms, sys: 0 ns, total: 3.29 ms\n", "Wall time: 2.74 ms\n" ] } ], "source": [ "%%time\n", "\n", "u_bar = np.zeros((M,T))\n", "u_bar[0,:] = 0.2 #m/ss\n", "u_bar[1,:] = np.radians(-np.pi/4) #rad\n", "\n", "x0 = np.zeros(N)\n", "x0[0] = 0\n", "x0[1] = 1\n", "x0[2] = 0\n", "x0[3] = np.radians(0)\n", "\n", "x_bar=predict(x0,u_bar)" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Check the model prediction" ] }, { "cell_type": "code", "execution_count": 6, "metadata": {}, "outputs": [ { "data": { "image/png": "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\n", "text/plain": [ "
" ] }, "metadata": {}, "output_type": "display_data" } ], "source": [ "#plot trajectory\n", "plt.subplot(2, 2, 1)\n", "plt.plot(x_bar[0,:],x_bar[1,:])\n", "plt.plot(np.linspace(0,10,T+1),np.zeros(T+1),\"b-\")\n", "plt.axis('equal')\n", "plt.ylabel('y')\n", "plt.xlabel('x')\n", "\n", "plt.subplot(2, 2, 2)\n", "plt.plot(np.degrees(x_bar[2,:]))\n", "plt.ylabel('theta(t) [deg]')\n", "#plt.xlabel('time')\n", "\n", "\n", "plt.tight_layout()\n", "plt.show()" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Motion Prediction: using the state space model" ] }, { "cell_type": "code", "execution_count": 7, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ "CPU times: user 2.63 ms, sys: 0 ns, total: 2.63 ms\n", "Wall time: 1.94 ms\n" ] } ], "source": [ "%%time\n", "\n", "u_bar = np.zeros((M,T))\n", "u_bar[0,:] = 0.2 #m/s\n", "u_bar[1,:] = np.radians(-np.pi/4) #rad\n", "\n", "x0 = np.zeros(N)\n", "x0[0] = 0\n", "x0[1] = 1\n", "x0[2] = 0\n", "x0[3] = np.radians(0)\n", "\n", "x_bar=np.zeros((N,T+1))\n", "x_bar[:,0]=x0\n", "\n", "for t in range (1,T+1):\n", " xt=x_bar[:,t-1].reshape(N,1)\n", " ut=u_bar[:,t-1].reshape(M,1)\n", " \n", " A,B,C=get_linear_model(xt,ut)\n", " \n", " xt_plus_one = np.dot(A,xt)+np.dot(B,ut)+C\n", " \n", " x_bar[:,t]= np.squeeze(xt_plus_one)" ] }, { "cell_type": "code", "execution_count": 8, "metadata": {}, "outputs": [ { "data": { "image/png": "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\n", "text/plain": [ "
" ] }, "metadata": {}, "output_type": "display_data" } ], "source": [ "#plot trajectory\n", "plt.subplot(2, 2, 1)\n", "plt.plot(x_bar[0,:],x_bar[1,:])\n", "plt.plot(np.linspace(0,10,T+1),np.zeros(T+1),\"b-\")\n", "plt.axis('equal')\n", "plt.ylabel('y')\n", "plt.xlabel('x')\n", "\n", "plt.subplot(2, 2, 2)\n", "plt.plot(np.degrees(x_bar[2,:]))\n", "plt.ylabel('theta(t)')\n", "#plt.xlabel('time')\n", "\n", "\n", "plt.tight_layout()\n", "plt.show()" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "The results are the same as expected, so the linearized model is equivalent as expected." ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "## PRELIMINARIES" ] }, { "cell_type": "code", "execution_count": 9, "metadata": {}, "outputs": [], "source": [ "def compute_path_from_wp(start_xp, start_yp, step = 0.1):\n", " \"\"\"\n", " Computes a reference path given a set of waypoints\n", " \"\"\"\n", " \n", " final_xp=[]\n", " final_yp=[]\n", " delta = step #[m]\n", "\n", " for idx in range(len(start_xp)-1):\n", " section_len = np.sum(np.sqrt(np.power(np.diff(start_xp[idx:idx+2]),2)+np.power(np.diff(start_yp[idx:idx+2]),2)))\n", "\n", " interp_range = np.linspace(0,1,np.floor(section_len/delta).astype(int))\n", " \n", " fx=interp1d(np.linspace(0,1,2),start_xp[idx:idx+2],kind=1)\n", " fy=interp1d(np.linspace(0,1,2),start_yp[idx:idx+2],kind=1)\n", " \n", " final_xp=np.append(final_xp,fx(interp_range))\n", " final_yp=np.append(final_yp,fy(interp_range))\n", " \n", " dx = np.append(0, np.diff(final_xp))\n", " dy = np.append(0, np.diff(final_yp))\n", " theta = np.arctan2(dy, dx)\n", "\n", " return np.vstack((final_xp,final_yp,theta))\n", "\n", "\n", "def get_nn_idx(state,path):\n", " \"\"\"\n", " Computes the index of the waypoint closest to vehicle\n", " \"\"\"\n", "\n", " dx = state[0]-path[0,:]\n", " dy = state[1]-path[1,:]\n", " dist = np.hypot(dx,dy)\n", " nn_idx = np.argmin(dist)\n", "\n", " try:\n", " v = [path[0,nn_idx+1] - path[0,nn_idx],\n", " path[1,nn_idx+1] - path[1,nn_idx]] \n", " v /= np.linalg.norm(v)\n", "\n", " d = [path[0,nn_idx] - state[0],\n", " path[1,nn_idx] - state[1]]\n", "\n", " if np.dot(d,v) > 0:\n", " target_idx = nn_idx\n", " else:\n", " target_idx = nn_idx+1\n", "\n", " except IndexError as e:\n", " target_idx = nn_idx\n", "\n", " return target_idx\n", "\n", "def get_ref_trajectory(state, path, target_v):\n", " \"\"\"\n", " \"\"\"\n", " xref = np.zeros((N, T + 1))\n", " dref = np.zeros((1, T + 1))\n", " \n", " #sp = np.ones((1,T +1))*target_v #speed profile\n", " \n", " ncourse = path.shape[1]\n", "\n", " ind = get_nn_idx(state, path)\n", "\n", " xref[0, 0] = path[0,ind] #X\n", " xref[1, 0] = path[1,ind] #Y\n", " xref[2, 0] = target_v #sp[ind] #V\n", " xref[3, 0] = path[2,ind] #Theta\n", " dref[0, 0] = 0.0 # steer operational point should be 0\n", " \n", " dl = 0.05 # Waypoints spacing [m]\n", " travel = 0.0\n", "\n", " for i in range(T + 1):\n", " travel += abs(target_v) * DT #current V or target V?\n", " dind = int(round(travel / dl))\n", "\n", " if (ind + dind) < ncourse:\n", " xref[0, i] = path[0,ind + dind]\n", " xref[1, i] = path[1,ind + dind]\n", " xref[2, i] = target_v #sp[ind + dind]\n", " xref[3, i] = path[2,ind + dind]\n", " dref[0, i] = 0.0\n", " else:\n", " xref[0, i] = path[0,ncourse - 1]\n", " xref[1, i] = path[1,ncourse - 1]\n", " xref[2, i] = 0.0 #stop? #sp[ncourse - 1]\n", " xref[3, i] = path[2,ncourse - 1]\n", " dref[0, i] = 0.0\n", "\n", " return xref, dref" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "### MPC Problem formulation\n", "\n", "**Model Predictive Control** refers to the control approach of **numerically** solving a optimization problem at each time step. \n", "\n", "The controller generates a control signal over a fixed lenght T (Horizon) at each time step." ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "\n", "\n", "" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "#### Linear MPC Formulation\n", "\n", "Linear MPC makes use of the **LTI** (Linear time invariant) discrete state space model, wich represents a motion model used for Prediction.\n", "\n", "$x_{t+1} = Ax_t + Bu_t$\n", "\n", "The LTI formulation means that **future states** are linearly related to the current state and actuator signal. Hence, the MPC seeks to find a **control policy** U over a finite lenght horizon.\n", "\n", "$U={u_{t|t}, u_{t+1|t}, ...,u_{t+T|t}}$\n", "\n", "The objective function used minimize (drive the state to 0) is:\n", "\n", "$\n", "\\begin{equation}\n", "\\begin{aligned}\n", "\\min_{} \\quad & \\sum^{t+T-1}_{j=t} x^T_{j|t}Qx_{j|t} + u^T_{j|t}Ru_{j|t}\\\\\n", "\\textrm{s.t.} \\quad & x(0) = x0\\\\\n", " & x_{j+1|t} = Ax_{j|t}+Bu_{j|t}) \\quad \\textrm{for} \\quad t= 0.0] #min_speed (not really needed)\n", "constr += [cp.abs(u[0,:]) <= MAX_ACC] #max acc\n", "constr += [cp.abs(u[1,:]) <= MAX_STEER] #max steer\n", "# for t in range(T):\n", "# if t < (T - 1):\n", "# constr += [cp.abs(u[0,t] - u[0,t-1])/DT <= MAX_ACC] #max acc\n", "# constr += [cp.abs(u[1,t] - u[1,t-1])/DT <= MAX_STEER] #max steer\n", "\n", "prob = cp.Problem(cp.Minimize(cost), constr)\n", "solution = prob.solve(solver=cp.OSQP, verbose=True)" ] }, { "cell_type": "code", "execution_count": 11, "metadata": {}, "outputs": [ { "data": { "image/png": "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\n", "text/plain": [ "
" ] }, "metadata": {}, "output_type": "display_data" } ], "source": [ "x_mpc=np.array(x.value[0, :]).flatten()\n", "y_mpc=np.array(x.value[1, :]).flatten()\n", "v_mpc=np.array(x.value[2, :]).flatten()\n", "theta_mpc=np.array(x.value[3, :]).flatten()\n", "a_mpc=np.array(u.value[0, :]).flatten()\n", "delta_mpc=np.array(u.value[1, :]).flatten()\n", "\n", "#simulate robot state trajectory for optimized U\n", "x_traj=predict(x0, np.vstack((a_mpc,delta_mpc)))\n", "\n", "#plt.figure(figsize=(15,10))\n", "#plot trajectory\n", "plt.subplot(2, 2, 1)\n", "plt.plot(track[0,:],track[1,:],\"b\")\n", "plt.plot(x_ref[0,:],x_ref[1,:],\"g+\")\n", "plt.plot(x_traj[0,:],x_traj[1,:])\n", "plt.axis(\"equal\")\n", "plt.ylabel('y')\n", "plt.xlabel('x')\n", "\n", "#plot v(t)\n", "plt.subplot(2, 2, 3)\n", "plt.plot(a_mpc)\n", "plt.ylabel('a_in(t)')\n", "#plt.xlabel('time')\n", "\n", "\n", "plt.subplot(2, 2, 2)\n", "plt.plot(theta_mpc)\n", "plt.ylabel('theta(t)')\n", "\n", "plt.subplot(2, 2, 4)\n", "plt.plot(delta_mpc)\n", "plt.ylabel('d_in(t)')\n", "\n", "plt.tight_layout()\n", "plt.show()" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "## full track demo" ] }, { "cell_type": "code", "execution_count": 12, "metadata": {}, "outputs": [ { "name": "stderr", "output_type": "stream", "text": [ "/home/marcello/.conda/envs/jupyter/lib/python3.8/site-packages/cvxpy/problems/problem.py:1054: UserWarning: Solution may be inaccurate. Try another solver, adjusting the solver settings, or solve with verbose=True for more information.\n", " warnings.warn(\n" ] }, { "name": "stdout", "output_type": "stream", "text": [ "CVXPY Optimization Time: Avrg: 0.1610s Max: 0.2291s Min: 0.1434s\n" ] } ], "source": [ "track = compute_path_from_wp([0,3,4,6,10,12,14,6,1,0],\n", " [0,0,2,4,3,3,-2,-6,-2,-2],0.05)\n", "\n", "# track = compute_path_from_wp([0,10,10,0],\n", "# [0,0,1,1],0.05)\n", "\n", "sim_duration = 200 #time steps\n", "opt_time=[]\n", "\n", "x_sim = np.zeros((N,sim_duration))\n", "u_sim = np.zeros((M,sim_duration-1))\n", "\n", "MAX_SPEED = 1.5 #m/s\n", "MAX_ACC = 1.0 #m/ss\n", "MAX_D_ACC = 1.0 #m/sss\n", "MAX_STEER = np.radians(30) #rad\n", "MAX_D_STEER = np.radians(30) #rad/s\n", "\n", "REF_VEL = 1.0 #m/s\n", "\n", "# Starting Condition\n", "x0 = np.zeros(N)\n", "x0[0] = 0 #x\n", "x0[1] = -0.25 #y\n", "x0[2] = 0.0 #v\n", "x0[3] = np.radians(-0) #yaw\n", " \n", "#starting guess\n", "u_bar = np.zeros((M,T))\n", "u_bar[0,:] = MAX_ACC/2 #a\n", "u_bar[1,:] = 0.0 #delta\n", "\n", "for sim_time in range(sim_duration-1):\n", " \n", " iter_start = time.time()\n", " \n", " # dynamics starting state\n", " x_bar = np.zeros((N,T+1))\n", " x_bar[:,0] = x_sim[:,sim_time]\n", " \n", " #prediction for linearization of costrains\n", " for t in range (1,T+1):\n", " xt = x_bar[:,t-1].reshape(N,1)\n", " ut = u_bar[:,t-1].reshape(M,1)\n", " A,B,C = get_linear_model(xt,ut)\n", " xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n", " x_bar[:,t] = xt_plus_one\n", " \n", " #CVXPY Linear MPC problem statement\n", " x = cp.Variable((N, T+1))\n", " u = cp.Variable((M, T))\n", " cost = 0\n", " constr = []\n", "\n", " # Cost Matrices\n", " Q = np.diag([20,20,10,0]) #state error cost\n", " Qf = np.diag([30,30,30,0]) #state final error cost\n", " R = np.diag([10,10]) #input cost\n", " R_ = np.diag([10,10]) #input rate of change cost\n", "\n", " #Get Reference_traj\n", " x_ref, d_ref = get_ref_trajectory(x_bar[:,0] ,track, REF_VEL)\n", " \n", " #Prediction Horizon\n", " for t in range(T):\n", "\n", " # Tracking Error\n", " cost += cp.quad_form(x[:,t] - x_ref[:,t], Q)\n", "\n", " # Actuation effort\n", " cost += cp.quad_form(u[:,t], R)\n", "\n", " # Actuation rate of change\n", " if t < (T - 1):\n", " cost += cp.quad_form(u[:,t+1] - u[:,t], R_)\n", " constr+= [cp.abs(u[0, t + 1] - u[0, t])/DT <= MAX_D_ACC] #max acc rate of change\n", " constr += [cp.abs(u[1, t + 1] - u[1, t])/DT <= MAX_D_STEER] #max steer rate of change\n", "\n", " # Kinrmatics Constrains (Linearized model)\n", " A,B,C = get_linear_model(x_bar[:,t], u_bar[:,t])\n", " constr += [x[:,t+1] == A@x[:,t] + B@u[:,t] + C.flatten()]\n", " \n", " #Final Point tracking\n", " cost += cp.quad_form(x[:, T] - x_ref[:, T], Qf)\n", "\n", " # sums problem objectives and concatenates constraints.\n", " constr += [x[:,0] == x_bar[:,0]] #starting condition\n", " constr += [x[2,:] <= MAX_SPEED] #max speed\n", " constr += [x[2,:] >= 0.0] #min_speed (not really needed)\n", " constr += [cp.abs(u[0,:]) <= MAX_ACC] #max acc\n", " constr += [cp.abs(u[1,:]) <= MAX_STEER] #max steer\n", " \n", " # Solve\n", " prob = cp.Problem(cp.Minimize(cost), constr)\n", " solution = prob.solve(solver=cp.OSQP, verbose=False)\n", " \n", " #retrieved optimized U and assign to u_bar to linearize in next step\n", " u_bar = np.vstack((np.array(u.value[0,:]).flatten(),\n", " (np.array(u.value[1,:]).flatten())))\n", " \n", " u_sim[:,sim_time] = u_bar[:,0]\n", " \n", " # Measure elpased time to get results from cvxpy\n", " opt_time.append(time.time()-iter_start)\n", " \n", " # move simulation to t+1\n", " tspan = [0,DT]\n", " x_sim[:,sim_time+1] = odeint(kinematics_model,\n", " x_sim[:,sim_time],\n", " tspan,\n", " args=(u_bar[:,0],))[1]\n", " \n", "print(\"CVXPY Optimization Time: Avrg: {:.4f}s Max: {:.4f}s Min: {:.4f}s\".format(np.mean(opt_time),\n", " np.max(opt_time),\n", " np.min(opt_time))) " ] }, { "cell_type": "code", "execution_count": 13, "metadata": {}, "outputs": [ { "data": { "image/png": "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\n", "text/plain": [ "
" ] }, "metadata": {}, "output_type": "display_data" } ], "source": [ "#plot trajectory\n", "grid = plt.GridSpec(4, 5)\n", "\n", "plt.figure(figsize=(15,10))\n", "\n", "plt.subplot(grid[0:4, 0:4])\n", "plt.plot(track[0,:],track[1,:],\"b+\")\n", "plt.plot(x_sim[0,:],x_sim[1,:])\n", "plt.axis(\"equal\")\n", "plt.ylabel('y')\n", "plt.xlabel('x')\n", "\n", "plt.subplot(grid[0, 4])\n", "plt.plot(u_sim[0,:])\n", "plt.ylabel('a(t) [m/ss]')\n", "\n", "plt.subplot(grid[1, 4])\n", "plt.plot(x_sim[2,:])\n", "plt.ylabel('v(t) [m/s]')\n", "\n", "plt.subplot(grid[2, 4])\n", "plt.plot(np.degrees(u_sim[1,:]))\n", "plt.ylabel('delta(t) [rad]')\n", "\n", "plt.subplot(grid[3, 4])\n", "plt.plot(x_sim[3,:])\n", "plt.ylabel('theta(t) [rad]')\n", "\n", "plt.tight_layout()\n", "plt.show()" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "# Iterative Linearization" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "explanation here ..." ] }, { "cell_type": "code", "execution_count": 14, "metadata": {}, "outputs": [ { "name": "stderr", "output_type": "stream", "text": [ ":41: RuntimeWarning: invalid value encountered in true_divide\n", " v /= np.linalg.norm(v)\n" ] }, { "name": "stdout", "output_type": "stream", "text": [ "CVXPY Optimization Time: Avrg: 0.5635s Max: 0.8227s Min: 0.2898s\n" ] } ], "source": [ "track = compute_path_from_wp([0,3,4,6,10,12,14,6,1,0],\n", " [0,0,2,4,3,3,-2,-6,-2,-2],0.05)\n", "\n", "# track = compute_path_from_wp([0,10,10,0],\n", "# [0,0,1,1],0.05)\n", "\n", "sim_duration = 200 #time steps\n", "opt_time=[]\n", "\n", "x_sim = np.zeros((N,sim_duration))\n", "u_sim = np.zeros((M,sim_duration-1))\n", "\n", "MAX_SPEED = 1.5 #m/s\n", "MAX_ACC = 1.0 #m/ss\n", "MAX_D_ACC = 1.0 #m/sss\n", "MAX_STEER = np.radians(30) #rad\n", "MAX_D_STEER = np.radians(30) #rad/s\n", "\n", "REF_VEL = 1.0 #m/s\n", "\n", "# Starting Condition\n", "x0 = np.zeros(N)\n", "x0[0] = 0 #x\n", "x0[1] = -0.25 #y\n", "x0[2] = 0.0 #v\n", "x0[3] = np.radians(-0) #yaw\n", " \n", "#starting guess\n", "u_bar = np.zeros((M,T))\n", "u_bar[0,:] = MAX_ACC/2 #a\n", "u_bar[1,:] = 0.0 #delta\n", "\n", "for sim_time in range(sim_duration-1):\n", " \n", " iter_start = time.time()\n", " for _ in range(5):\n", " u_prev = u_bar\n", " \n", " # dynamics starting state\n", " x_bar = np.zeros((N,T+1))\n", " x_bar[:,0] = x_sim[:,sim_time]\n", "\n", " #prediction for linearization of costrains\n", " for t in range (1,T+1):\n", " xt = x_bar[:,t-1].reshape(N,1)\n", " ut = u_bar[:,t-1].reshape(M,1)\n", " A,B,C = get_linear_model(xt,ut)\n", " xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n", " x_bar[:,t] = xt_plus_one\n", "\n", " #CVXPY Linear MPC problem statement\n", " x = cp.Variable((N, T+1))\n", " u = cp.Variable((M, T))\n", " cost = 0\n", " constr = []\n", "\n", " # Cost Matrices\n", " Q = np.diag([20,20,10,0]) #state error cost\n", " Qf = np.diag([30,30,30,0]) #state final error cost\n", " R = np.diag([10,10]) #input cost\n", " R_ = np.diag([10,10]) #input rate of change cost\n", "\n", " #Get Reference_traj\n", " x_ref, d_ref = get_ref_trajectory(x_bar[:,0] ,track, REF_VEL)\n", "\n", " #Prediction Horizon\n", " for t in range(T):\n", "\n", " # Tracking Error\n", " cost += cp.quad_form(x[:,t] - x_ref[:,t], Q)\n", "\n", " # Actuation effort\n", " cost += cp.quad_form(u[:,t], R)\n", "\n", " # Actuation rate of change\n", " if t < (T - 1):\n", " cost += cp.quad_form(u[:,t+1] - u[:,t], R_)\n", " constr+= [cp.abs(u[0, t + 1] - u[0, t])/DT <= MAX_D_ACC] #max acc rate of change\n", " constr += [cp.abs(u[1, t + 1] - u[1, t])/DT <= MAX_D_STEER] #max steer rate of change\n", "\n", " # Kinrmatics Constrains (Linearized model)\n", " A,B,C = get_linear_model(x_bar[:,t], u_bar[:,t])\n", " constr += [x[:,t+1] == A@x[:,t] + B@u[:,t] + C.flatten()]\n", "\n", " #Final Point tracking\n", " cost += cp.quad_form(x[:, T] - x_ref[:, T], Qf)\n", "\n", " # sums problem objectives and concatenates constraints.\n", " constr += [x[:,0] == x_bar[:,0]] #starting condition\n", " constr += [x[2,:] <= MAX_SPEED] #max speed\n", " constr += [x[2,:] >= 0.0] #min_speed (not really needed)\n", " constr += [cp.abs(u[0,:]) <= MAX_ACC] #max acc\n", " constr += [cp.abs(u[1,:]) <= MAX_STEER] #max steer\n", "\n", " # Solve\n", " prob = cp.Problem(cp.Minimize(cost), constr)\n", " solution = prob.solve(solver=cp.OSQP, verbose=False)\n", "\n", " #retrieved optimized U and assign to u_bar to linearize in next step\n", " u_bar = np.vstack((np.array(u.value[0,:]).flatten(),\n", " (np.array(u.value[1,:]).flatten())))\n", " \n", " #check how this solution differs from previous\n", " delta_u = np.sum(np.sum(np.abs(u_bar - u_prev),axis=0),axis=0)\n", " if delta_u < 0.1:\n", " break\n", " \n", " \n", " # select u from best iteration\n", " u_sim[:,sim_time] = u_bar[:,0]\n", " \n", " \n", " # Measure elpased time to get results from cvxpy\n", " opt_time.append(time.time()-iter_start)\n", " \n", " # move simulation to t+1\n", " tspan = [0,DT]\n", " x_sim[:,sim_time+1] = odeint(kinematics_model,\n", " x_sim[:,sim_time],\n", " tspan,\n", " args=(u_bar[:,0],))[1]\n", " \n", " #reset u_bar? -> this simulates that we don use previous solution!\n", " u_bar[0,:] = MAX_ACC/2 #a\n", " u_bar[1,:] = 0.0 #delta\n", " \n", " \n", "print(\"CVXPY Optimization Time: Avrg: {:.4f}s Max: {:.4f}s Min: {:.4f}s\".format(np.mean(opt_time),\n", " np.max(opt_time),\n", " np.min(opt_time))) " ] }, { "cell_type": "code", "execution_count": 15, "metadata": {}, "outputs": [ { "data": { "image/png": "iVBORw0KGgoAAAANSUhEUgAABDAAAALICAYAAACJhQBYAAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjMuMSwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy/d3fzzAAAACXBIWXMAAAsTAAALEwEAmpwYAAEAAElEQVR4nOzdd3RU5dbH8e+ZTCoppAAhCUU6iAgBBBFEIGJH7Fjw2q4XGyqR9wqiqICimICoWK6I9VquBbtiLIBiAQGRIkVpScCQhJLeznn/GCYkJIH0mUl+n7VYM3PqzpyEmdmzn/0YlmVZiIiIiIiIiIi4MZurAxAREREREREROR4lMERERERERETE7SmBISIiIiIiIiJuTwkMEREREREREXF7SmCIiIiIiIiIiNtTAkNERERERERE3J7d1QHURWpqqsvOHRERQXp6usvOL8ena+QZdJ3cn66R+9M1cn+6Rp5B18n9ufIaRUVFueS8rlTV5y13+ltxp1hA8RxPZfHU5G9LFRgiIiIiIiIi4vaUwBARERERERERt+fRQ0hERERERESaugULFrB69WpCQkJISEiosN6yLBYtWsSaNWvw9fXl1ltvpVOnTgCsXbuWRYsWYZomo0aNYuzYsY0cvUj9UQWGiIiIiIiIGzvjjDOYOnVqlevXrFnD3r17mT9/PjfffDMvvvgiAKZpsnDhQqZOncrcuXP54YcfSE5ObqywReqdKjBERERERETcWK9evUhLS6ty/apVqzj99NMxDINu3bqRk5PD/v372bdvH5GRkbRp0waAIUOGsHLlSmJiYmoVh3VwP+Z/niDT2xuzZ19so8fW6jgitaUEhoiIiIiIiAfLzMwkIiKi9HF4eDiZmZlkZmYSHh5ebvnWrVurPE5SUhJJSUkAzJ49u9wxAUpscNDLi5LkHdgy04m46qZ6/klqzm63V4jTlRTPsdU1HiUwREREREREPJhlWRWWGYZR5fKqxMXFERcXV/q40uk3734Y3/cWkfd9kltMz+kJ04S6kifEU5NpVJXAEBERERER8WDh4eHlPhRmZGQQGhpKcXExGRkZFZbXlS0oBHJysEwTw6a2itJ49NsmIiIiIiLiwQYMGMCyZcuwLIstW7YQEBBAaGgonTt3Zs+ePaSlpVFcXMyKFSsYMGBAnc9nBIWAZUJeTj1EL1J9qsAQERERERFxY/PmzWPjxo1kZWUxYcIELr/8coqLiwEYPXo0/fr1Y/Xq1UycOBEfHx9uvfVWALy8vLjhhhuYNWsWpmkyYsQI2rVrV+d4bEHBjjvZWdAiqM7HE6kuJTBERERERETc2F133XXM9YZhcNNNlTfUjI2NJTY2tl7jsQW1dNzJPgRtqt+/QKSuNIREREREREREqs0WFOK4k5Pl2kCk2VECQ0RERERERKrNODyExMo+5OJIpLlRAkNERERERESqzRZ8uAIjWxUY0riUwBAREREREZFqMwICwWaDnGxXhyLNjBIYIiIiIiIiUm2GYYC3DxQXujoUaWaUwBAREREREZGa8faGIiUwpHEpgSEiIiIiIiI1Y/eG4mJXRyHNjBIYIiIiIiIiUjPePqrAkEanBIaIiIiIiIjUjN0biopcHYU0M0pgiIiIiIiISM14e2MVK4EhjUsJDBEREREREakZVWCICyiBISIiIiIiIjWjaVTFBeyuDkBERERERESObe3atSxatAjTNBk1ahRjx44tt/6jjz5i+fLlAJimSXJyMgsXLiQwMJDbbrsNPz8/bDYbXl5ezJ49u+4B2e2Qm1P344jUgBIYIiIiIiIibsw0TRYuXMi0adMIDw9nypQpDBgwgJiYmNJtxowZw5gxYwBYtWoVn376KYGBgaXrp0+fTnBwcP0FpSEk4gIaQiIiIiIiIuLGtm3bRmRkJG3atMFutzNkyBBWrlxZ5fY//PADp512WoPGZHj7gJp4SiNTBYaIiIiIiIgby8zMJDw8vPRxeHg4W7durXTbgoIC1q5dy4033lhu+axZswA488wziYuLq3TfpKQkkpKSAJg9ezYRERGVbme32/ENDKTQLKlym8Zit9tdHkNZiufY6hqPEhgiIiIiIiJuzLKsCssMw6h0219//ZXu3buXGz4yY8YMwsLCOHjwIDNnziQqKopevXpV2DcuLq5cciM9Pb3Sc0RERFBQYmIVFFS5TWOJiIhweQxlKZ5jqyyeqKioau+vISQiIiIiIiJuLDw8nIyMjNLHGRkZhIaGVrrtDz/8wNChQ8stCwsLAyAkJISBAweybdu2ugdl94YizUIijUsJDBERERERETfWuXNn9uzZQ1paGsXFxaxYsYIBAwZU2C43N5eNGzeWW5efn09eXl7p/XXr1tG+ffu6B6UeGOICGkIiIiIiIiLixry8vLjhhhuYNWsWpmkyYsQI2rVrx5IlSwAYPXo0AL/88gsnn3wyfn5+pfsePHiQJ554AoCSkhKGDh1K37596x6UZiERF1ACQ0RERERExM3FxsYSGxtbbpkzceF0xhlncMYZZ5Rb1qZNG+bMmVP/AXl7g2VilZRgeHnV//FFKqEhJCIiIiIiIlIz3t6OW/XBkEakBIaIiIiIiIjUjN3HcathJNKIlMAQERERERGRmvE+3I1AjTylESmBISIiIiIiIjVTWoGhISTSeJTAEBERERERkZpx9sBQBYY0IiUwREREREREpEaM0iaeSmBI41ECQ0RERERERGrGrllIpPEpgSEiIiIiIiI14+3ruFUCQxqREhgiIiIiIiJSMz6HExiFSmBI41ECQ0RERERERGrGxzkLSYFr45Bmxe7qAERERERERDzNN998U63tvLy8GD58eANH4wKHKzCswgIMF4cizYcSGCIiIiIiIjX0wgsv0LNnz+Nut23btiadwNAQEmlMSmCIiIiIiIjUkI+PD9OnTz/udtdff30jROMC3oeHkBRqCIk0HiUwREREREREauixxx6r1naPPvpovZxv7dq1LFq0CNM0GTVqFGPHji23fsOGDTz++OO0bt0agEGDBnHppZdWa99aKa3AUAJDGo8SGCIiIiIiIjXUtm3bam0XGRlZ53OZpsnChQuZNm0a4eHhTJkyhQEDBhATE1Nuu549e3LvvffWat+aMux28PLSNKrSqDQLiYiIiIiISB188skn7NixA4AtW7Zwyy23cPvtt7Nly5Z6Of62bduIjIykTZs22O12hgwZwsqVKxt83+Py9lEFhjQqVWCIiIiIiIjUwaeffsrIkSMBePPNNzn//PPx9/fn5Zdf5pFHHqnz8TMzMwkPDy99HB4eztatWytst2XLFiZPnkxoaCjjx4+nXbt21d4XICkpiaSkJABmz55NREREpdvZ7XYiIiLY5+ePr80guIrtGoMzFneheI6trvEogSEiIiIiIlIHubm5BAQEkJeXx44dO7j//vux2Wy8+uqr9XJ8y7IqLDOM8pOXnnDCCSxYsAA/Pz9Wr17NnDlzmD9/frX2dYqLiyMuLq70cXp6eqXbRUREkJ6ejmn3Jv/QIQqr2K4xOGNxF4rn2CqLJyoqqtr7awiJiIiIiIhIHYSHh7N582Z++OEHevbsic1mIzc3F5utfj5uhYeHk5GRUfo4IyOD0NDQctsEBATg5+cHQGxsLCUlJRw6dKha+9aatw+WhpBII1ICQ0REREREpA6uueYaEhMT+eCDD0pn/li9ejVdunSpl+N37tyZPXv2kJaWRnFxMStWrGDAgAHltjlw4EBptcW2bdswTZOgoKBq7VtrPr5q4imNSkNIRERERERE6iA2Npbnn3++3LLBgwczePDgejm+l5cXN9xwA7NmzcI0TUaMGEG7du1YsmQJAKNHj+ann35iyZIleHl54ePjw1133YVhGFXuWy98fdXEUxqVEhgiIiIiIiJ1kJycTGBgIC1btiQ/P5+PPvoIm83GBRdcgN1ePx+5YmNjiY2NLbds9OjRpffPPvtszj777GrvWy+8fSA3p/6PK1IFDSERERERERGpgyeffJLc3FwAXn31VTZt2sSWLVt44YUXXBxZA/NRBYY0LlVgiIiIiIiI1MG+ffuIiorCsixWrlxJQkICPj4+3H777a4OrUEZPr5q4imNSgkMERERERGROvD29iYvL4/k5GTCw8MJDg6mpKSEoqIiV4fWsHx8oVBNPKXxKIEhIiIiIiJSB6eddhoPP/wweXl5pX0otm/fTuvWrV0cWQPTEBJpZEpgiIiIiIiI1MF1113Hb7/9hpeXF7179wbAMAz+8Y9/uDiyBubnD/l5WKaJYVN7RWl4SmCIiIiIiIjUwv3330+/fv2IjY3l5JNPLreuc+fOLoqqEbUIAsuE/FwICHR1NNIMKIEhIiIiIiJSC+PHj2f16tU8++yzHDp0iJNPPpnY2Fj69OmDn5+fq8NreC0OJy1yspXAkEahBIaIiIiIiEgtdOvWjW7dujFu3DgOHDjA6tWrWb58Oc8//zwdO3akX79+9OvXj+joaFeH2iCMFkFYADlZ0CrS1eFIM6AEhoiIiIiISB21bNmSkSNHMnLkSEpKSti0aRNr1qwhISGB4cOHc+GFF7o6xPrnrMDIzXZtHNJsKIEhIiIiIiJSj5zNPHv37s348eMpLi52dUgN4/CwESsnG8PFoUjz4FYJDNM0uffeewkLC+Pee+91dTgiIgLExdl56y1XRyEiIuK+0tPT+d///seOHTvIz88vt+7JJ5/Ebnerj131p0WQ4zYny7VxNBIr+xCk7MLo3tvVoTRbbvWX9NlnnxEdHU1eXp6rQxERkcOWL3dMi5aQEER8fPN4gyIiIlITiYmJREVFcfnll+Pj4+PqcBpPQJkmns2A+cwjsG0jtgXvYXh7uzqcZsltEhgZGRmsXr2aiy++mE8++cTV4YiINHtHJywSE488LrtOiQ0REWnuUlJSmDlzJjabrcHOsXbtWhYtWoRpmowaNYqxY8eWW798+XI+/PBDAPz8/Ljpppvo2LEjALfddht+fn7YbDa8vLyYPXt2vcRkeHuDr1+zqcBgb7LjNucQtAx3bSzNlNskMF5++WWuueaaY1ZfJCUlkZSUBMDs2bOJiIhorPAqsNvtLj2/HJ+ukWfQdXJPcXF2li+3kZjoKA2Njo4CYNy4SJKSiklM9OHRR30BSu/PmOHF/feXuCzm5kx/R+5P18gz6Dq5P3e9Rv3792fjxo307t0wQwtM02ThwoVMmzaN8PBwpkyZwoABA4iJiSndpnXr1jz44IMEBgayZs0aXnjhBR555JHS9dOnTyc4OLj+gwsI9JgKDGt/BgS0wPCt5RS3/gGQfcjxTwkMl3CLBMavv/5KSEgInTp1YsOGDVVuFxcXR1xcXOnj9PT0xgivUhERES49vxyfrpFn0HVyPwkJQbz1VjrR0VFMmpRVmsQAx3ASX19HaeyR6xZFeno6M2dGccstf5ceIz4+S9UZjUR/R+5P18gz6Dq5P1deo6ioqCrX3XDDDUybNo02bdoQEhJSbt2tt95a53Nv27aNyMhI2rRpA8CQIUNYuXJluQRG9+7dS+937dqVjIyMOp+3WgKDHL0hPID5f9dDhy54TUus3QH8Axy32Xpv4ypukcDYvHkzq1atYs2aNRQWFpKXl8f8+fOZOHGiq0MTEWlWEhKCSEwMKk1aOG+PTmTAkaqMsvedCQvncJOqhp2IiIg0JQsWLMBmsxEdHd0gPTAyMzMJDz/yjX94eDhbt26tcvtvvvmGfv36lVs2a9YsAM4888xyXwqXVd2K97KVMPvDW2FmZxFexbZmXg6Gjy+GV8N89KxJVc7fADu31bqKJzMohCIgyAC/ajw37qCpxeMWCYyrrrqKq666CoANGzbw8ccfK3khItLIyiYfUlJSiY6OIiUllXHjIsstB0rXORMeTmWTH0erLJmhpIaIiDQF69ev5/nnn8ff379Bjm9ZVoVlhlH5xKXr16/n22+/5eGHHy5dNmPGDMLCwjh48CAzZ84kKiqKXr16Vdi3uhXvZSthTL8WWLt3VLltyT/HYAwchu3myVX/gHVQm6qc2lbxlNgdjTsP7UkmuxrPjTvwhHiOVd10tIbrMiMiIh7DmYhwVlKUrahISnLMXT9pUsVEgzP54ExslFX2WGWrNYAKFR7Oc4mIiHiiDh06kJXVcAn58PDwckNCMjIyCA0NrbDdzp07ef7555k8eTJBQUdeV8PCwgAICQlh4MCBbNu2rf6CC24Jhw5UmmRxLrNWLq+/89WSZZp1PobhdzhB5SFDZpoit0tgnHjiidx7772uDkNEpNkoWwXhTESkpKQyaVJWueqIsvfLJjPK3k9JSS13jKNVlsxwciYzyiYylNQQERFPcOKJJzJr1iw++OADvvnmm3L/6kPnzp3Zs2cPaWlpFBcXs2LFCgYMGFBum/T0dJ544gluv/32ct9o5+fnl06UkJ+fz7p162jfvn29xAVAcAgUFUJ+JZMxFBfX33nqqqQeGo07q14aqQeGtXEN5hfvNcq5PIVbDCERERHXOLrnxdG9LKpSWWKjsgoNoNywk7KOrvZwKjvURD00RETEE2zevJmwsDDWrVtXYd3IkSPrfHwvLy9uuOEGZs2ahWmajBgxgnbt2rFkyRIARo8ezbvvvkt2djYvvvhi6T6zZ8/m4MGDPPHEEwCUlJQwdOhQ+vbtW+eYSgW1dNweOnCkyaVTcVGdD29lpGGEt67zcSg5EotVUoLh5VWLYxxOgjRSBYY5d7rjztmXNMr5PIESGCIizVRVPS9qmyiorELj6KTG0T00qkpqVBaDM5lRdp2SGiIi4g6mT5/e4OeIjY0lNja23LLRo0eX3p8wYQITJkyosF+bNm2YM2dOg8VlBLfEAkcCo81RVZZ1TGBYG9dizn0A24R/Y/Q/rU7HKlcNkn0IQioOwTluPId/HiurcYeQWHm5GEcnh5optxtCIiIiDe9YPS/qIyHgPEZVw07Kcg5XKevo2MomOo5uGuqM20nDTkRERBpR8OFpYw8dqLiuqLD0bmU9Mo7HSnN88WFtWFObyMorO4Qk60DdjnGgkaaodWrs87kxJTBERJqZ6va8qG/HqtCoLJ5jNQY9OklRWVKjsu1ERETqy+23316t7Zr87Iohjgah1sHMiuvKVmDk5dT82C0cr+NWTj28PylbgXHwQO2OUXL4GPsbKaHg69+45/MAGkIiItKM1LbnxbFYhQWweztWZrrjzUleDuTmQl425OVi5eVCruM+uTmQl8tdJcWU3NOCu/wDKHkkAAJakHRFCOarPkzt3gbzUwv8A7g4Kpr5Lxbx2icdmPVCV7KLAwGq/TNo2ImIiDSUzMxM3n777eNud/DgwUaIxoWCQsDLDpmVTNVZVCZpcOgABATW7hz10XOibA+MzH1UPgnt8Y5xuAIjLwcrPxfDr4GHdQQGQUEe1oGM2sXbBCmBISLSTNRHzwuruBhSdmLt2Ao7t2Ft3wqpO+HoqckMGwS0cDTz8g9wvGGJaOMYvxkQCDabo1t5bg5WXg7k5tCtRRrWulxu6pKDtdhRcjqvL5hPw9XA1aOBwGBW725P/7PC+OnPDrzz7QnszIlhV140cxNbVUhqOFXWGFSJDBERqYuhQ4eWm9q0KkOGDGmEaFzHsNkgLAIy91VcWbYC4+ABiIyp2cELDw9BqY9ZP8pWYFQWa3WUlDnG/kxo29AJjGDISFMFRhlKYIiINAO1qbywTBP2JpP3+0rM31c7kha7tx95MxIQCB27YvQZiHFCF2gVdThZ0QJ8/TCM2n1X4MXhJll5uY5qjpwcyNzH0vcyOb3nTnJ27Mf6azOD9n/PoD5lEid2b4how1e/ncAfWV3YdKgbG7O60i66XaU/a1UznCixISIi1XHrrbe6OgT3EdYKa38lFRjFdax6cPbQqI8hJGV7YGSk1f4Y3j6OuPbvg7Y1TMjUlO1wx4cDlQzPaaaUwBARaUaqU3lhpezC+ulbrJ++gwMZHALw9YMOnTFGngcdumB07AqtImudpDgew+7tKEkNOtwY7ISunNHfcffXtCDOiM/CKi5m4ZxcbrzwT+69MY9H4zdj7dtL+60pnBm1ovSNSl6JL5uzOrNpSTemvteVU0K70rNDV6B8VYoqNERERGrHCI3A2vJ7xRVlmniS8XfND+zcvz6GkJSpwLAyalmBUVwMEW1gz26szPSGH9bhnPUkfW9Dn8ljKIEhItKEOSsvnKqqvLAO7sf6ZRnWT9/Crr8cGf8TYzEuvIqw2EHs92uBYavFfOkNwBm3Ybdz05RgoB+tLw3CdqmjRPfz3CB6TsyEPbu469KDzI1fQ85bqVzZ62vIXlx6nN25bdm0tCtzPurBGa1OxMoOxwgMLl1fWYWGkhoiIiKVCGsFBzKxSkowvMq8Xyg7hCS9FlUPzgRGSUnde044e2AEhdShAuNwAuPvFEivRUKmppxJl78rNjZvrpTAEBFp4pxVF877zg/hVkEB1tqfHJUWG9c4+lh06IJxxU0Yp5yOEdwSAHtEBEZ6JWWhbqRsUsFx3xvad6b9FUHYrojlyklRJL+fAgcyGT/iIK8+uprVT++lV9BW4lovx2ZYmHfDjpwYnjy5N9OG9KZfyxOZNyeKuyYXlCYzqhp2IiIi0qyFt3K8j9if7viA7+RMYNi9sWqTNChbwfF3KnToUvsYncmANlHw12as4mIMew0/DpeUYPj6YUVEYu1Nrn0s1eV8/jLSahdvE6RnQESkiTq67wVAdHRbEv/1PebLn2D9usLRSDMsAuOsizFOHYHRtp0LI65/zgTDpElZjuEuoeH0G98R2zmduOMmx1AaKz+XSwce4H+P/0jxkr8YbFvNRdFfAFD4h53Vl3Xj4V4nYv4YQ6cWp2FZ3hiGoQoNERGRw4w20VjgSDKUSWBYzllIIqNrV/VQJoFh7U3BqIcEhhHTEWvbJkhLhaj2NTtGSTF4eTl6X+xJxjJNRxPThlJc7KiKNU3MhGnYJj/SsOfzAEpgiIg0QZXNODJnwgqu8F4Af/6Btc8fo/8QjMEjoFvvJv9iWLFCw5HUADD8Avgpswu2c6Lofo5jmE3y+t+5adQ++rbcQN+W67k05lOsl3L5bvhc0q8LYdX+k5nQ6WSsbdHQoasqNEREmrHi4mK2bt3Kzp07ycnJoUWLFnTo0IGuXbtiby7fmLeNBsDam4xxYr8jyw9XEBht22H9+gNWURGGt3f1j1tYCD6+UFiA9WICVnR7jJgTahejs4lnu06OWLduhMiYmr0HKikBL7sjYfPbL5iz/w+vqU/ULp7qKC6C6A6OJurbNsK+vY4KkmasmfxFiYg0DwkJjmqLspUXZ3TP58X+kxi9axmEhGFccyvG4BEYvr6uDNXlyiYXnMkM530jNJwv/j6Jhat7AJfQLroNu375hXsu/pv+ob8xIPQ3RrdZhvkY5Jf48N7gnpjvdSGu9WlY2a0xAoMrbQaqpIaISNNx6NAhFi9ezNKlSwkMDCQ6Oho/Pz/y8/P5/PPPyc7OZvjw4YwdO5bg4ODjH9CTBbUE/xawN6X8cmcFRYfOsHI5/J0MNUlAFBc5jltYAID147cYl9U2gXE4mRLTEQuwXl8ANhvGsNE1OEYx2O3Quq3j8fYtWPl5GH7+tYvpeIqLMLr0gvadsH74GmvJB3DxtRgtgo6/bxOlBIaISBPirLhITAwief3vvHHlYq5s/zEFhj/GmGsw4sZg+Pq5Oky3c6wKDQATL4zoDryVfCoJP58CQJ8T/Ogfuo6BoWsZEPobBZ99yEsD3sO8G7ZmncDs3n0xV3TgnWdHEh/vOI4qNEREmo7p06czYsQI5syZQ1hYWIX1mZmZfP/990yfPp25c+e6IMLGYxgGREZX7AvhrMDo0MWRNEjZVa6Cwtq4FgKDMNp3rvzARYXg44Pt7ocw5053NBzv3R+j58k1jtFy9sDwb3Fk2bqVUNMEhpcXxqkjYOc2rOVLMP/vemz3z8NoFVnjmI6rqAh8fDAuu96RwFj2JRQWYtx4d4VNraJCsHmVb6LaBCmBISLSBDgrLwB6dgji392fJjf+TS6JLmF1y4sZcP9YjKAm/u1PPausQqNsUiOjMIxFq7sB3YiOvovk7du5OHY/A8N+Y0DoWs5rm4S1KIsVI+ax/5Y2hAzsxeUxQ7H2tYOINqrQEBHxcHPmzDnmEJGwsDDGjBnDueeeWy/nW7t2LYsWLcI0TUaNGsXYsWPLrbcsi0WLFrFmzRp8fX259dZb6dSpU7X2rQ9GdAesNT9hWdaRadadTShjOjp6R6TsAIY74s3Yhzn3AfDxxeuZ/1V6TKuwEOzeGL36YQwchrVyOWbi/dhe+LDKqdytXX9h/vc5bBOnYwQcSVaUNvH08sI2aQbm0zNg7c+YLyZguym+ej+kcwiJjy+cfwXW8iWQl4v5ylPYLhqP0blH9Y5TDZZlHa748Mbw9jmy/KdvMb1s2K67s9z25q2XQuwQvG65t95icEdNe9CziEgz4GzW+fQ8X2464XWWnzGW2zq/zPbQYbze5VUGPn6tkhd15EwqVDXsBMDw8eWX/bFMXXYWv58+kz5ffc2Zy9/i/g2TWb67N/u+W8sTfWZgTr2Z5PE3M+/k+zGXL+H95/Y73qRA6bCfsgmpsvdFRMR9lE1evPTSS5Vu8/LLL9dLHwzTNFm4cCFTp05l7ty5/PDDDyQnl692WLNmDXv37mX+/PncfPPNvPjii9Xet16c0BVysrC+fB/LPNxvouhwAsPXH9q2w/p9NWbSh1imifXl+451hQWY331e+lpYTlEhOD+8h4SWLjZvvhBr57ZKwzAXvw5//uGYYa2sksMJDLsdo+fJGAOGAWD9vBTrt1+wTPP4P6OziSdAaMSR5Zt/x5z9f5gvzaVo2yasA5lYGWmO25xsrP0ZWPszjn/8cucqAcsCu6NniO3O6aXPgfXD15TcdTXmL8uw9iZjOad0Xb0C88M3Kn8umwhVYIiIeDDnN/YrX93AG+c87OjwfWI/znk+niWbgunt6gCbsGNVaDgben7zRwDR0VfwyIphWJbFiB4FDA77lcFhqxka8QvWq5+z7IynOXRrBEGxvbiq3VCsvTEkJg4sPb6GnYiIuL+lS5dyww03VFi+bNkyrrvuujoff9u2bURGRtKmjWOGjyFDhrBy5UpiYmJKt1m1ahWnn346hmHQrVs3cnJy2L9/P/v27TvuvvXB6NjNMUzkvVcw2kRDv8FHqh7sdowuPbG++xzr7YUY7btgrVxWuq/1xrMYnbrB0UNJDg8hATDOvRyyDzmmfwfMmZMwLhoP195SPo4WQY440vZQrkajTAIDwBh8BtaKrx3HenomxvlXwLCzMMIiqNLhCgxwDJuxJbyCOeXmcj06Mn/89thPVLfeGG2iMOLGQMvw8lUiZTmrVw43PTV698cYNQbr/Vccy3OysP7zBEenKqxP3sY4ZbhjppQ6soqLHMmgokLHNLl1yYt42TB6969zTEpgiIh4qISEIJ6a64ffZy/xximvsXXHCTywcQGDevTkrJsA9EG3sVSrQsMw2Jrdie82+5GQcDa3JQbSucVOBof9yqDw1Zya/SuzT1qGeT+sGhnOxkl96DGmO11ajMKyfMpN3Xr0sJNHH228n1VERI745ptvACgpKSm975SWlkZQUP1U0WVmZhIeHl76ODw8nK1bt1bYJiIiotw2mZmZ1drXKSkpiaSkJABmz55d7nhl2e32Cuusli1xTpTql7KDoDPPJ8vbi1xvH1q1akV+7GAOfve5Y/8v36MwO4vAayaQ/fpzALT4O5mA2EHlfyYsjIAWhEZEQEQE1qSHSLt8+JFzfvAahV17ENwiCK+o9nhFtOaAWUwB4LN3Ny3LxJjr60sWEN66DbbAYBg2ipJefUi/6ULHsT55G+uL9wib9Sze3U6s8DNblkVaSQkBQUEEOo8bEUH+xPs5+MS0Sp+nSm1Zj7VlvWP4CeA7aDiBV/8Lr8iockNFzEMH2QcEhrQk4PD5rCuuI69NJFnPPnbMU/j++DUtLroar1aRlV6r6rAK8tn/8N0UbfytxvtWxvAPoNV/k2odj5MSGCIiHighIYhJV29i1M/zOSnkD17deSnXfXwFg56O0Df0bqKyZqBHV2gs2+JDdPQlPP7TqSQ8Ecj7zx/g1PBfGRS2mlOtX7He+JZvhj/H3/8I45fMflzboT9WSjvmJg4qV6Hx6KOFqs4QEXGB5cuXA46pVJ33nUJCQrjtttvq5TyVDQk4ugdEVdtUZ1+nuLg44uLiSh+np6dXul1ERESl62xzX8d8eia561ZRkJ6OeegQ2O2kp6djRXcs3a5w3SowDHJPOQPD7oP1+gKy1/1KTlgb6NS9NL6S3Bzw8St3Ltu0uY7+FQcyAdj/+H2OFeGtMcZchfWL4zoUrF9D2qfvYfQ/DcNuxzx0EICMg4cw8gudzwR06w1b1jseFheT+e9/Yrt/boXGotbhiojcgkLyy/7s3ftge+Z/mI/dC7v+rPT5OpaCn5dS8PNSOKEbxpkXYht4eGjL4Z8vO7+A3LLniz0NY/xtWB+8CtlHXvdtCa/Aru2YTz5I3ufvkff5e9hmPUerXn2qvI7HYr40D2vTOoyrb8FodwLYbFDF7021GDbS09Mr/d2Jiqr+1LBKYIiIeJiEJwJJ+d/XZK9/ghh/X25c9QRfpZ1B5tNZ+gDrhiqb4QQqVmjE35NN4tz2/LDVTnT0RSQnp8C+vUy6IJlTD1dpnNf2a8wHYU1cCH/c3YduF/SkW+AoLCumyqEmSmyIiDSc6dOnA/DWW28xbty4BjtPeHg4GRlHeihkZGQQGhpaYZuyHwyd2xQXFx933/piBAZj9OyL9ek7WIf2O4ZBHO7hYASHYnvuA6wP38D6/F3wC8DwD8A4LY6SdauwfvrOMTwkNALjnEuwjTjP0UPj8BCK0nN06IwtfhbW1x9jfffZkRUZaViL5jnu2+2QdRDrxQTIycIYeX65Jp5leU1+BPON58ody/pjXcWZUUpKjhz76J/bxxev++diJe8g8FAmWT98Ay0CobgYK2MfRkgo2AyslF2wo/LqF7ZvwXphDtZJ/TH8AioMISnLdvpZWANOg7+2YC79HNuIczGCQ6F3KEb/07B+/cHxc+z8C3r1qfx8x2Bt34r14zcY516G7Yxzarx/Q1ICQ0TEgzz9ONwVPA36rIAefRj+zGxW/1VMQoKSF57mWBUacPjbsdZteSe5P3N/HkhCQhDvPJvl6KERvprBxb9ivbmcpNNfYP154TzVtz9f3t+b0Xd0IzGxf4UeGkpkiIjUr+Li4tIGncdKXhQVFeFdyYfQmujcuTN79uwhLS2NsLAwVqxYwcSJE8ttM2DAAL744gtOO+00tm7dSkBAAKGhoQQHBx933/pkDByK9clbWCu/L5fAABxTfA4b7UhgREYfWX7yQKzVKxwP9qdj/fd5rGFnQWEBhrdvxXNERsOVN0NgMNYnb1UMokcfWL8aAGv9aiiXwKgkAXHFjRijzsd84HawTKyV31OybRNGx64Ybdth9Bt8pIfGMaYpNWI64h8xgJxesVVuY+3PcPSTSN+L+c2n4Py5nevfeQnzQCa2i8c7Ftgr/90xAgKhdyxevcufy7h5MkbhHZgTr4Q9u6uM41jMz95xTG97ziW12r8hKYEhIuIh3prxF2M2P0qRbzqPb57IC59dg4VNyQsPV1mFRtXDTqJ48heIjr6AlJRU/vNoNhsXb2JI+CqGhK8icu8SzPvgxxFtMF86EXqcRFu/M4HKm4EqqSEiUnv33HMPI0aMYNiwYYSFhVVYv3//fpYtW8Z3333H3Llz63QuLy8vbrjhBmbNmoVpmowYMYJ27dqxZImjj8Lo0aPp168fq1evZuLEifj4+HDrrbcec9+GYkS1hw5dsL7+GNp1qlCxYLSKxDbxASgzpMQ4+ZSK/SHXrXQkQKpI/hg2G8aFVxF0cn8ObtmI9b9FjhW9Y7FdeTPWn5uxfv4ONq7Fykw/PIOIvdLhM4bdGyJjsD3/AdbbLzpi37HVMS0sYHv2vSMVGJUkQGrCCD3cjyS8FV7dT8I6uN9RPbJkMdZvP5f2xrAi2hyJrSbHt9nALwAi2sDems82Y2Xsg99WYpx9saMSxM0YlgfPsZKamuqyc1c17kvch66RZ9B1Oj6ruJgfp33AoMzX2Z4dQ+dH7iLmtOGkpKQ2ygdQXSP34bze0dFRpKQ4XgOjo6MoKCjE19ebTi12liYzTg1bRbjvAQC257Tjx4wBtBzcm/PjuxDT80RSUlLLHUfJjIalvyPPoOvk/lx5jY4ep3/o0CEWL17M0qVLCQwMpG3btvj7+5OXl8eePXvIzc1l+PDhjBkzhuBgz5zOvKrPW8e7Dtb61ZhPPuh40LYdXg8/c9xzWVs3QmAw5GZjLnrSMfNF5j6MURdgG/fPKvdzxmJ++g7Wim+wzXgGw+aokrDS/8acNgEjdgj4B2D9vBSvp985dhw7/8SceXe5ZbZbp8IJXTEnX48x/lZsp5993Hhqw3z35SPTyzrPffv9GCcPrPGxSuY/DL+vIvSh+RyK6lj9GD77H9YHr2F79D8Yh5Mo9Uk9MEREmjArN5udU+YwKHcNb+++gOkbJ5N7miMbrg+czU/VFRq+gMHyLT7AEKKjLyV5dzKvPprOn59t5NTwVZzfdgnBqR9gxsNXwzph/rcnZ7U5AysnCqNFkCo0RERqKDg4mGuvvZarrrqKrVu3smvXLnJycggMDKR9+/Z06dKldIhJc2P0jsW44kas75MwTos7/g6A0bVX6X3bdRMxn5npqHbo1L1a+9vOuxzOu7z8MSPaYJxzKdYnb1c/+PadHDF37ILROgpz/kNY27fAysNNWr3qNhzoWIyzL8batwfbyAswn5jqWFjL3yFjwGlYv68i99P/wT8nV3s/a+X30LlHgyQv6kPz/IsSEfEAVuY+0u6fQbuSZO7+7UHm/xLL5OiARqu8EPdVcdiJb8VpW202/nFfa6IX9OXhH86gfUxrTgzezGnhKzk1/FfaffU1/+n/KcV3Gmw41I37egzE+r0TdO1FYmJU6UwpagYqInJsdrudnj170rNnT1eH4lZscRdC3IW12tfo0hPb44ugpLjOwxiMMVdBSYmj70Z1tjcMjOvK9AgJb4O1cS3s3OZ4fIweGHVlBAbjdcuU8gtrOITEyTZkFCVrfqJkb0q197Ey9kHydozLbqjVORuDEhgiIm7ISt7OwVkz8MnLY9zqp1iRMZD3Dve60gdJqUxVM5w475dYdj7fGAqMJjr6OpJ37uSivvs5NXwVQ8JXcl2HtzHnF1FsevHBqb0wP+jBaeEjsApbYfj4VtoMVL+LIiJHHDhwgG3btpGVlVVu6tKRI0e6MCrPZXj7gLdP3Y9jGHDBldVOYFTQJgp+X3XkcR17YFRby3A4kFHrCgwAo3VbijeuxWaajt4Yx2H98ZtjvxP71fqcDU0JDBERN2Nt+o28ebMJCvZj9Lcv8vUfLYiORpUXUm3HawwKjqZgK/f3ZfH61sC5dGoXRv/Q3xkSvpIh4aso+uR93hz0P/ImeLP6wEnc2WUg1paOPDX3jAoznICSGSLSvP3yyy889dRTtG3blt27d9OuXTt2795Njx49lMBwA0YdZoExWrct32A0N7vO8VRLdHtHAqMgr/bHaBUJhQVwcD84m4cey8bfILglRLWv/TkbmBIYIiJuxPzpO4oXzmdHVnuuTZrPnvxIolV5IfWgsgqNskmNAtOP/62LBqKJjr6V5D+3cc3gvxkSvorTwldyd9cXMOdY/H6mH3/d1ZuOZ/Xi5JCRWCUhGF5eqtAQkWbt7bff5tZbb+XUU0/l+uuv5/HHH+fbb79l9+7aTWMp9c+4+hbYX4vmmn7+jtt2J8Du7Q06hKQs23UTsT78L3Q9sdbHKE2+pO05bgLDsiysTWsxevWtdKYWd3H8OhIREWlwlmVhfv4u1sJEUgN6c8mPC1n1pwk4Ki8mTdJUqVJ/nL9LVQ07ATD8Avhu32nc9vVlfD3oWU5OSuKmX5/g7eQLyd+bifX+q3x82nUcuPEavhgzhxs7voG1eztzE1uUHiMxMQhwJDKcyt4XEWkq0tPTOfXUU8stGz58OMuWLXNRRHI02xnnYLtofI33M0aeh3H+FdimPIHt7ocwhjRORY3RMhzbP+5wDKWprVZtAbD27Tn+tik7Iesg9Dy59udrBEpgiIi4mGWWYP33Oaz3X2Vx6lmMeH8Bh4qDiI52TCmlb7GlMRyrQiM+PouDRSEsWt2N6Rsn0+utedgSXuG2NY/w8Z7RdAncwfReczEfvpM1cWfyx6QnML/9jM4tdmBZVmkiAyh3X8kMEWkqgoODOXDgAACtWrViy5Yt/P3335im6drApM6M4FBsF16N4e2N0atf6RStHiGslaNiJO34CQxr8+8AGD2UwBARkSpYhQWYz87G+u5zVoWN4+KPb6HQdGTaVXkhrlKtCo3gUD7eM5prv7yeD/u/yqBvPuHu3x7k67RhBKRtxvrvc3w7/FL2XHsjT548jS/uX4a1b2+5Y6hCQ0SailGjRvHHH38AcN555/HQQw8xefJkRo8e7eLIpDkzvLzwah1VrQQGu/6CoBCM8FYNH1gdqAeGiIiLWIUFmE/PhD/W8W2bifxj0bXw+pH10dFRFT40irhKZc1Ay1ZoJCZGMf+XWKKjzyc5OYWFs7P448NNDAlfyWkRK2m99wvMqfDDGW3579kD+DmzP+38LSyrfDPQynppiIi4u7Fjx5beHz58OCeeeCL5+fnExMS4LigRwKttDCVHfYFQGSt5O7Tr1AgR1Y0qMEREXMAqLMB8Zhb8sY4vI/+PuJlxgKPqAhwfDFNSUvUBTtxOZTOcQPnEhmEY3DQlmDd3X8TFn97OgK+/wPbQ0xhX3szvh3owus0yEk9+kB9GXEjy+JuZd/L9fHn/d1h7kuFwr/eqhpqoQkNEPEFERISSF+IWvCKjYd+eclP7Hs0qLobUXRjtOjZeYLWkBIaISCOzigoxFzwCm35jSZv/458LLyvtd+G8FfE0x6rQAAMjqj22keczYfUcwhe9wmsdFzJtw//x6/4+DI34hbi9iZgP3Mqvo87io/Of5LoOb/HKrL+xTLPSHhpKZIiIiByfPbo95OXCgcyqN/o7BYqLIeaExguslpTAEBFpRFZREeaCR2HDGpa0uYdzZpwGHKm8UN8L8XSVVWgcndQwbDauu68Vr+68nLGf3uGo0JjxLF9F3sOyfYPpE7KRh098gmt2/JP9N4xn0YC7MD95G2vTb7TwygEqr9BQUkNERKQ8e+cejjvbt1S5jbV7OwBGO/dPYKgHhohII7GKijCffRTW/0pSZDw3vXQFvORYpxlHpCk7/rATAyMymrNnRBMdPY6UlFRO6WwwKGw1g8JXM6DlOqwPv8cC1o+28fsVnXm0d28+v78bZ9/WgcTEgYf7cBz5+9HfkoiICHif0BW87Fjbt2DEnlr5Rru3g90ObaIbN7haUAJDRKQRWMVFmM8/Br+vYsrvU3j8P6fCS46Ki+joKFJSUvWBS5qdYw07Sclvy1Mr+wH9iI6OInnrFt6bs5sd324jtuXvnN/2K0L2foB5P6yLC6bkya5M7DIQa2Nb6NCFxMSoCskM/Y2JiCfKzs5m7ty57Nu3j1atWnH33XcTGBhYbpv09HSeeeYZDhw4gGEYxMXFce655wLwzjvv8PXXXxMcHAzAlVdeSWxsbKP/HOIaho8vxHTE2rG1ym2s5O0Q1QHD7v7pAfePUETEwzmSF4/Db7/wTZu7eOOzS3jjcIJblRcixx92AmAEBHLp9J5EvzCKlJRUYqIj6RK4g9iW64htuZ7YH9cxqevzmHMdTcpWjIik5On2GO07sf6NAVjXtSQxsa0qNETE4yxevJiTTjqJsWPHsnjxYhYvXsw111xTbhsvLy/Gjx9Pp06dyMvL495776VPnz6ljUTPO+88xowZ44rwxQ0YbaKx/vqj6g1Sd2H07Nto8dSFEhgiIg3IKi7GfH4OrP2ZaRv+j1c/u7zc+rLTUIrIEVXNcOK8b2Hju81+wClER48lJSWVHh2C6dtyPScGb6ZX8BbyfthM57UrebH/W5j3wu9nBlHyREeMdp3Y+XY/rCvCmPdWT+6+Jw9QUkNE3NPKlSt58MEHAccUrQ8++GCFBEZoaCihoaEA+Pv7Ex0dTWZmpmZCEYfwCPg1HcsswbB5lVtlFeQ7Gny28YxG8kpgiIg0EMsswVqYCGt/whj3T1699vJyQ0aio6P0YUmkGqpToQGQVRzIW7+1B9oTHf0PAPy98ugRtI0Tgzc7Ehs5W+i58Qvmnvwh5kMwwbRTcn8ktInC77PumKeEYLSJ4rkPujPh/+wYhtEoP6OISFUOHjxYmpwIDQ3l0KFDx9w+LS2N7du306VLl9JlX375JcuWLaNTp05ce+21FYagOCUlJZGUlATA7NmziYiIqHQ7u91e5brG5k6xgHvGE9j+BLJKSgjzsuEVXj62op1/kgkEd+6GXyPEXdfnRwkMEZEGYFkW1hvPY636nlmbJvL8tdcC5YeMVPYBTESqp7IKjaP/ppyz+0RHn8QnG8KJjr4UAC+jmE4tdtEreAs9g7ZyZvBfdLXt5LoOa7FeLcQCbgbMOwPYa7WjbZ9IiIzm01WdOf/aIAgNh+BQjxgrLCKeYcaMGRw4cKDC8nHjxtXoOPn5+SQkJHDdddcREBAAwOjRo7n0Usf/f2+//Tavvvoqt956a6X7x8XFERcXV/o4PT290u0iIiKqXNfY3CkWcM94cnwdvwuZ2zZjWOUT89bmjQBk+QeS3QhxV/b8REVVv/pDr7wiIg3A+vANrGVfYJx9Cc9/dq2adYo0IOffU1XDTspy/g0mJnZia3YnPuRsZm92rLNRQpT/33RqsZNOLXYy4/ZNbHknncgWm2DlMs61LMzZhw9kGBDckr/zI2jTIxSjZRi0DIfQcIyQMEeSo2UY+AdUKNcVETna/fffX+W6kJAQ9u/fT2hoKPv37y9txnm04uJiEhISGDZsGIMGDSpd3rJly9L7o0aN4rHHHqu3uMVDhLUCwMpIw3BOq3qYtW+P406ryMaOqlaUwBARqWdm0kdYn77Dm7sv5N8T7wXUrFOksR2rQsM55WrZxCI4/k6T8xz/lqWfysuTD+8/LItJD6czqk8JX7+zgf+7uYTHpv4FBzLZ8F42bVqlYv35B2Q7yrqto4Px82dfYDCmrx/4t3AkNQJalN7Hed/XD8PbG+ze4GUH533nP287eB2+tXuDzQaGDTDAZjiSKobt8K2h4S8iTcSAAQNYunQpY8eOZenSpQwcOLDCNpZl8dxzzxEdHc35559fbp0z+QHwyy+/0K5du0aJW9zI4QQGmfsqrkvbA4HBGAGVDytyN0pgiIjUI/Onb7HefhFiT2Xq51NISdmjygsRF6tdhUZQ6bLExCOPY85xjCmP3JpFfHwW102JIuVDRwKkU7tw/ly9gbeey+eKs5PhYAY/JhVzar/9+JjF5O/PhNwcOLgfa28y5OU4Hptm6bkqJD/qyrA5khscTnDYjGMmPUofe3uDjy/4+pXeGmXuO259wccPAlpghEVAWGsIb4Xh7VPfP4VIszZ27Fjmzp3LN998Q0REBJMmTQIgMzOT559/nilTprB582aWLVtG+/btmTzZkX11Tpf6+uuvs2PHDgzDoFWrVtx8882u/HHEBQxnsrySBIaVtgdat3VBVLVjWJZV76+VjSU1NdVl53a3sU1Ska6RZ2hK18lat5Lip2bxY3p/rls1jwLTt3TdpElZHpu8aErXqKnSNaq9sonFsvfLNtutLKlRlcqqOlJSUhk3LpK33tpb8ZxPBDLpjnTIzeGl57y4YfwBXn/Zh2vGHYDiYt5725tLLjyIVVTM5x97cc6ZWXz9pRejhmeDZbLsOx9OH5YPWHy/zJuhp+Wz4gdvhpyaDxb89KM3gwflg2Xyy88+nDIwHyyLX1fa6R9bwOrV3sT2LQDL4re1dk7uUwiWycbfLHp2zmLnlmI6tM2Fwnwy9xYRFuC4X5JbgBfFlT8JQSHsLWpL5IlhGGGt+Pa3doy8NJjXPuvI+LsCMVoEVvq8V3Ut6mt9dbYte53EPbny/7uajNNvKqr6vOVOrzvuFAu4bzwlD02E8NZ43T6t3PqSf9+I0e1EbDdOatR4yqrJ35YSGLXkbr+YUpGukWdoKtfJ2rKBwiemY2/fnp4vLGTLroNNpvKiqVyjpkzXqP45/24rS0YcvawyzqRlVfsc635Dr6+vYyXv3EXPzmFsWrUFMtOZeE0RT07fApn7+O79Qww/abfj277CwvJPTqtI3lkzkCvu64jR9URiYvuXq1Zzh59b3JcSGI1LCYyac9d4Sp6aAZn78Jo+v3SdVVSEedulGOePwzbmykaNpyw18RQRaUTW7u3kJcxkd1ZbLl34LDklLYiObgGo54WIp6psutbaDjtpqj1wDLudrOJAjFaR0CqS91OjeOr8fgCMnxJFyuJULMuiT6cA1n27jn9eUswLszZi/fkHcSnLsF75GAtYNTKckue6c32HIVi7oiGmo0t/LhGRpsgIb4W1bWP5hel/g2VpCEljUQWGHIuukWfw9Otkpe0h64F7aRHsxeD3Xmbln2aTqbxw8vRr1BzoGjWu6g47ueSScH76yfdYh2q2DEy6BO7glNA1DAxbyylha4jxdwzdOFTUgl/3n8wv+/vxUepodudFuyTGwYMLeO+9DJecW6qmCozGpQqMmnPXeMwv3sN67xVs899y9MTAMfzZfGoGtnsfrzA7SUPHU1ZN/rZs9R2QiEhzYR06QOaDD1GQZzJi8XOk5kc22W9aReSIsn/bx2oM6vzw6xySkJKSWq37Db3eHc5lYeO7zX48/tOp3PXbDDq8/gKDv/kE48ZJhIwaRrT/Xv7d/Rl+GDmWVwZMJPnT9/Eyihvl53Y+VvJCRJoU50wkGWmli6zMw4mE8FYuCKh2lMAQEakFqyCf1PseoaWRzvWr5rFsi6PrfkpKqkc37BSR2qvJsBOpKDU/EtvgM7CNv5W45e9ge2whxvlX0DN4K+Yzj7DijDGYH72Jtb/hEwsJCcdv2Coi4kmMyBgArD3JRxbuz3BMyR3c0jVB1YISGCIiNWSVlPDnvxNolbeFG1bMZs2Bk1R5ISKlKqvQGDbsyFSpVSU4nPcber2nnMsIa4VtzFW8ffKb2G6dSkFEB6xP3sK890a+vfxOrPW/YplmvcSSkBBUriFrYqLjsRIZItJktG3nSFYk7ziybH86hIRh2LxcFlZNqQdGLbnb2CapSNfIM3jadbIsC+vVp7G+/4p7f5/KnJ8GN7meF0fztGvUHOkauT9do/ph7duLtfxLrO+TIOsgRLTBGDYaY9hZGEHBdT5+REQEvr5HKurE/agHRuNSD4yac+d4Sh64DVq3LZ1KtSTxfijIx2vKHJfE46QeGCIiDWTFlPexvv+KeVtv4r+7L1blhYhIIzJaRWK7+B/YHn8J4+bJEN4a64PXMO+/BXP5EizTPP5BqpCQEFSavABHU1ZVYYhIU2JEd4CUnUcW7E+H0HDXBVQLSmCIiFSTuexLBme8gnHaKBK3/gtQzwsREVcw7N7YBg7D655Z2KbPh6h2WK8+jTlnKlbqrlodMz4+i4KCwnLDS1JSUvX/u4g0Ha3bwv50LLMEy7JgfwZGaISro6oRJTBERKrB+m0lJa89yzdpQzhh2izAACg3ZlpERBqfEdMR2z2PYPzjDtizG/PhuzA/eA2rsKBWxyubsFD1hYg0KaHhUFIChw5CXg4U5KsCQ0SkqbH+2kzBM49j69CJW9fMZmeyY/qpSZOy9O2ciIgbMGw2bEPPxDZjAcYpp2N99j/MB+/AWr+6RseZMcNLzTxFpMkqrbbYn+H4B6AKDBGRpsP6O5Xsx2eSmh1Bv4ULyC0JUNWFiIibMoJCsN1wF7Z7ZoGXF+aTD2K+MAfrQGa19r///hJSUlLLNfDUMEERaTJKExjpjn+A4WEVGHZXByAi4q6srINkPvQwLf0txn/9FOu25xMdTZOecUREpCkwup+E7YH5WF+8h/XZ/7DW/4px6XWO2UoM45j7JiQEkZh4pOIiMdHxWIkMcZXs7Gzmzp3Lvn37aNWqFXfffTeBgYEVtrvtttvw8/PDZrPh5eXF7Nmza7S/NAOHExjW/gzw8Sm3zFOoAkNEpBLz5viQMvVR/PIzuHDJk+zIba8ZR0REPIjh7Y3tgnHYHnwKOnbFem0B1n+fwyopOeZ+8fFZpQ2anTRcUFxp8eLFnHTSScyfP5+TTjqJxYsXV7nt9OnTmTNnTmnyoqb7SxMXGAR2b9i/D/amgGFASKiro6oRJTBERI5imSV0XvYYbQs2MXHtDD7Z4Cit04wjIiKex2gThe2uhzDOugjru88xFzyCVZB/zH2OrsLQlKriSitXrmT48OEADB8+nJUrVzbq/tJ0GIYBYRFYX36AteQDsCwMu7erw6oRDSERESkjISGI0/9+hnMjv+WhDZP44u+RREcfWafkhYiI5zFsNoxLr8eMaIP13xcw50zFdsf9GFV88xgf70hWl01klO2LIdKYDh48SGio43c1NDSUQ4cOVbntrFmzADjzzDOJi4ur8f5JSUkkJSUBMHv2bCIiKh9eYLfbq1zX2NwpFnD/ePa360hh2h7HA2+fRo+1rs+PEhgiIoclJASx/71PiT3xXV7aPo6FO64CKC0jVvJCRMSz2c44Fyu0FeYLj2M+OhnbndMx2rarcvv4+KzSBIaS2NKQZsyYwYEDByosHzduXI2OERYWxsGDB5k5cyZRUVH06tWrRnHExcWVJj4A0tPTK90uIiKiynWNzZ1iAfePxwxt7bgTEIjt/x5t9Fgre36ioqrfIF8JDBERHG9MJ438iuJNCdB3MA9/djcpKalER0fpDauISBNinDwQ2+RHMJ+agTn7/7Ddeh9G994VtlMzT2lM999/f5XrQkJC2L9/P6Ghoezfv5/g4OBKtwsLCyvdfuDAgWzbto1evXpVe39pJiIPlxaf0BUjuoNrY6kF9cAQkWYvISGIbxbuJOepBNYeOJFus5/AxMuR1JikN6kiIk2N0bErtilzICQMc+4DmD8vrbCNs5ln2aEjauYprjBgwACWLnX8ji5dupSBAwdW2CY/P5+8vLzS++vWraN9+/bV3l+aDyPocALL28e1gdSSEhgi0qwlJAQxafwWXhpwN/6Rodz4ayJ/7s4s/YZNb1RFRJomI6INtn8/Bp17YL2YgPnZ/ypsk5AQVDoDFaiZp7jG2LFjWbduHRMnTmTdunWMHTsWgMzMTB599FHA0efigQceYPLkyUydOpXY2Fj69u17zP2lmToxFmKHYLvsBldHUiuGZVmWq4OordRU1zVTcrexTVKRrpFncOV1SkgI4qWnSvjg1BsI8znI2B9fYntOB5UHH0V/S+5P18j96Rq5L6uoCOuV+Vg/LyXon/HknjK8wjZq5uk+XPm3VJNx+k1FVZ+33On/NHeKBRTP8dS1B4YqMESkWUpICGLSxAxe7H8PnVvu4aZfE/h+i7eSFyIizYzh7Y1xw11w8ilkLZyHtXFNhW3Kvi6o+kJExHWUwBCRZichIYi5iS34cOzznBK2llt/eZiV+/uqw7yISDNl2Lyw3TQJe7uOmM89jrU3uXTd0cNIEhODNIxERMRFlMAQkWbFmaS4t/vTXBD1FbM2TeT5X09U5YWISDNn+AXQcurjYLdjPjUTK+fIFNpq5iki4h6UwBCRZsM5hvnfp67gls6v8srOy3h++3hVXoiICABerdtiu3UKZKZhPvcYVnExoGaeIiLuQgkMEWkWnEmKUa2X88hJj5P09zCu//wqJk3KVvJCRERKGV16YYy/Hf5Yh/X2f4AjVRhlp9ZWFYaISOOzuzoAEZGG5qy8SFq4m3cGTWHdge7ctvYRbplXrDefIiJSgW3ISMzUXVhfvo8Z1R7biPMARyLDORuJqvekOTjW7BDuNCuLO8UCiud46hKPKjBEpFmI8U/lk3MmklEYSt//3Mstdyp5ISIiVTMuHg8nn4L11n+wNq5RM0+RMu69915Xh1DKnWIBxXM8dY1HCQwRabKcbzYXzrd4ZcCdHMwo4R8r55P4YnslL0RE5JicM5PQth3mc48z6fq/1MxTRMTFlMAQkSYteedOnu8/mfYByYROmcKYf0XozaaIiFSL4ReA7bb7oKQI883/qJmniIiLKYEhIk2So+9FIG9fsIgh4b8y+fcHiBk52tVhiYiIhzFaRWJccCWs/YlJI79SM08RIC4uztUhlHKnWEDxHE9d41ECQ0SaHGdjtds6v8xlMZ+QuOVmOo0bqjeZIiJSK0bchRDdAfPNF7Dyc8u9lqj6Qpojd/pQ7E6xgOI5HiUwRETKcM448s/+G/l392f4IOVs5m37p6vDEhERD2bY7djG3wYHMlj1wLtq5iki4iKaRlVEmgxn5cXXC3fy3KAHWPV3Hy758CZ2zs9W5YWIiNSJ0bkHxvCziV36PskrhmB06FKayCjb2FOkKVu7di2LFi3CNE1GjRrF2LFjGz2G2267DT8/P2w2G15eXsyePZvs7Gzmzp3Lvn37aNWqFXfffTeBgYENcv4FCxawevVqQkJCSEhIADjm+T/44AO++eYbbDYb119/PX379m3QWN555x2+/vprgoODAbjyyiuJjY1t8FgA0tPTeeaZZzhw4ACGYRAXF8e5555br8+PKjBExOMlJASVVl4M7Gxj4YB4dh2M4J+rnyBxfriSFyIiUi+Mi8ZDcAh75jxL+5jWpcvVzFOaA9M0WbhwIVOnTmXu3Ln88MMPJCcnuySW6dOnM2fOHGbPng3A4sWLOemkk5g/fz4nnXQSixcvbrBzn3HGGUydOrXcsqrOn5yczIoVK0hMTOS+++5j4cKFmKbZoLEAnHfeecyZM4c5c+aUJi8aOhYALy8vxo8fz9y5c5k1axZffvklycnJ9fr8KIEhIh4vMdFRedHCK4efxt+Gny2fjnOm8o/bvZW8EBGRemMEBGJc8U/aFGxlx8svqpmnNCvbtm0jMjKSNm3aYLfbGTJkCCtXrnR1WACsXLmS4cOHAzB8+PAGjatXr14VqjuqOv/KlSsZMmQI3t7etG7dmsjISLZt29agsVSloWMBCA0NpVOnTgD4+/sTHR1NZmZmvT4/SmCIiMdyVl4AtItuw9P97qN4dzK3rHmMxDdP1BtJERGpd8aA06B3f6zFbzDp+r9Kl6v6Qpq6zMxMwsPDSx+Hh4eTmZnpklhmzZrFv//9b5KSkgA4ePAgoaGhgOND9KFDhxo1nqrOf/RzFhYW1ijP2Zdffsk999zDggULyM7OdkksaWlpbN++nS5dutTr86MEhoh4JOeQkcRExxvG+3vOY1Tr71nadiIDr1XyQkREGoZhGNiu+hdFhSaf/eO10uVq5ilNnWVZFZYZhtHoccyYMYPHHnuMqVOn8uWXX7Jx48ZGj6G6KnvOGtro0aN56qmnePzxxwkNDeXVV19t9Fjy8/NJSEjguuuuIyAgoMrtahOTEhgi4nGczTrBUbI7vv3/uPGEN3lx+5WMnjlCyQsREWlQRqtIfC4ax9mR35H81WelyzWMRJqy8PBwMjIySh9nZGSUfqvemMLCwgAICQlh4MCBbNu2jZCQEPbv3w/A/v37SxtYNpaqzn/0c5aZmVkaf0Np2bIlNpsNm83GqFGj+PPPPxs1luLiYhISEhg2bBiDBg0C6vf5UQJDRDyKs/LC2fn9sj4pPNTrCf5qMZics290cXQiItJcGHFjOGRvzaoH3gEc3yKqmac0ZZ07d2bPnj2kpaVRXFzMihUrGDBgQKPGkJ+fT15eXun9devW0b59ewYMGMDSpUsBWLp0KQMHDmzUuKo6/4ABA1ixYgVFRUWkpaWxZ88eunTp0qCxOBMFAL/88gvt2rVrtFgsy+K5554jOjqa888/v3R5fT4/huWKupZ6kprquimrIiIiSE9Pd9n55fh0jTxDTa6Ts/IiOjqKlJRUTu1i8v3548koCqPVE49h+Fddoia1p78l96dr5P50jTxDTa+TuXwJ1qtP82HMI9zxwmhAU6o2NFf+LUVFRbnkvO5k9erVvPLKK5imyYgRI7j44osb9fx///03TzzxBAAlJSUMHTqUiy++mKysLObOnUt6ejoRERFMmjSpwaZRnTdvHhs3biQrK4uQkBAuv/xyBg4cWOX533//fb799ltsNhvXXXcd/fr1a9BYNmzYwI4dOzAMg1atWnHzzTeXVso0ZCwAf/zxBw888ADt27cvHV505ZVX0rVr13p7fpTAqCW9EXF/ukaeobrXyVl54dTCK4cPhtxAx5A0AmbMwWitNxUNRX9L7k/XyP3pGnmGml4nq7gY84FbwdefDi+8jYWNSZOyNIykASmBIdK8aQiJiLi9o3teGJhs+ve/6Ra0nYA7Jyt5ISIiLmHY7XxhvwGSt3Nu5DeAmnmKiDQkJTBExK0d3fMiOjqKu7v+B9b+hNcVN2D06uvaAEVEpFk798GB0LYdz577NDZKADXzFBFpKEpgiIjbOrryAiD5o3e5q+t/ME4bhTHqAleGJyIigmHz4hPjRtibzEXRnwNq5iki0lCUwBARt1RZ5UXPoC0UPD8POvfAuPpWl8w9LiIicrQx0/tC+048OOB57EYxoCoMEZGGoASGiLidSisv/tjE/0bcjXdIC2y3TMHw9nZliCIiIqUMmw3bhVcTUrSHy2M+AlD1hYhIA1ACQ0TcSmWVF95GEbvum0OwsR/bbVMxQkJdHKWIiEh5iUtGsGp/HyZ2WYivrUDNPEVEGoASGCLiNiqrvEhJSeXdq+YQk7cO4x93YHTs6soQRUREKhV/TzanzLiMKP+/uardB4CGkYiI1DclMETELVRWeQHw8fSV9Nv/PkbcGGyDhrsyRBERkWNK/Gwov2T25Z+dXsduFKuZp4hIPVMCQ0TcStnKixm3beDcjCccTTsvuc61gYmIiBxHfHwWg+8/jxj/vZzXNglQFYaISH2yuzoAEWneZszwYubMqNLHzsqL+XPs3JY/DXx8sP3r3xh2/XclIiIeoM9AiIzhXye8yoepZ5UbHinSEBYsWMDq1asJCQkhISGhwvrly5fz4YcfAuDn58dNN91Ex44dGzlKkfrhFhUY6enpPPTQQ9x9991MmjSJzz77zNUhiUgjWbrUKK26AMc3VZPuPsTtLWfD3hRs/7wHIzTchRGKiIhUX+LcECYvuY7eIVsYFvGzmnlKgzvjjDOYOnVqletbt27Ngw8+yBNPPMEll1zCCy+80IjRidQvt/hK08vLi/Hjx9OpUyfy8vK499576dOnDzExMa4OTUQaUEJCEMuX20qrLsBRgfHy9a9ibV6GMfYajJ4nuzBCERGRmomPz8Ka2A9zSij/OuE1lqcPLpeoF6lvvXr1Ii0trcr13bt3L73ftWtXMjIyGiMskQbhFgmM0NBQQkMd0yL6+/sTHR1NZmamEhgiTZizpDYxMYiUlFSio6OYNCmLSRetwnx8AfQZiHHOpa4OU0REpMYS54eR//PV3NvjaU4M/oPo6B4ATJqUpeEk4lLffPMN/fr1q3J9UlISSUmO/i2zZ8+msLCw0u3sdjvFxcUNEmNNuVMs4F7xuFMsUHU8Pj4+1T6GYVmWVZ9B1VVaWhrTp08nISGBgICAcuuq+wfVGNztl0Eq0jVyX3FxdpYvrziC7ZzTM/lPx/FgsxGesAhbYLALopOj6W/J/ekauT9dI89Qn9fJzMki5dqL+HT36dz520wKClz3vrUpceXfUk0+ZDW2tLQ0HnvssUp7YDitX7+ehQsX8vDDDxMUVL0hTamplVcPRUREkJ6eXqtY65s7xQLuFY87xQJVxxMVFVXJ1pVziwoMp/z8fBISErjuuusqJC8A4uLiiIuLK33syovhbr8MUpGukft66y3HUBFn5UVKSiqJTwRwp9e/MbdkYLv3cTLzCyFf188d6G/J/ekauT9dI89Q39fJd9SZXPDlJzy++TamTAlU9UU9cOXfUk0+ZLmbnTt38vzzzzNlypRqJy9E3JFbNPEEKC4uJiEhgWHDhjFo0CBXhyMiDSAhwdHIzNnzwnmbkBDEXT1ego1rMK68GaNDF1eGKSIiUmcJCUGcMuWfWMBNJ/xXzTzFZdLT03niiSe4/fbbPToJIwJuUoFhWRbPPfcc0dHRnH/++a4OR0QaSHy8Y+yvM3GRkpLKuHGRTBq7EvPxtzAGDccYdpaLoxQREak7x2semAtPZ5y5mHnbbmLjjhxXhyVN0Lx589i4cSNZWVlMmDCByy+/vHSYzejRo3n33XfJzs7mxRdfBBwTKMyePduVIYvUmlskMDZv3syyZcto3749kydPBuDKK68kNjbWxZGJSH07+punJR8dZN+dCRAagXHVBAzDcFFkIiIi9SshIYjP/nMzS4Z9yzXt3yc6+npAzTylft11113HXD9hwgQmTJjQOME0EmtvMmQdglaREBFRt2PlZENBHvj6Y7QIrN0xSkogLRX+TqUgNBTLNCA0DIJDMWyNM+jB2rcXa8Ma+GszRtwYjPadGuW8jc0tEhg9evTgnXfecXUYItKAEhKCSEwsn7yIjo4i6Zr76XZgH7bJj2IEtHBRdCIiIvXPUYXRgu139uOa9u/y3F/j2ZVc9XSXInJs1p5kzKdnQNqe0mWHzr4IK24sRkhozY5VVIS15AOsxa87Fvj6Y5w8EOOKGzGCq38sc+VyrC8/gJ3bADhQdqXdDqEREN4ao3UUtI3GiDkBup9U6y/trLQ9WEu/wNq2EYoKwc8fI6IN1uofoSDfsc2P30DvWErumg40rS8H3SKBISJNn/ObJmcSIyUlFfPnpVgvfo5xwZUYXXq6MjwREZEG0/G6czAXPMLoNktJSDhF1RfSLFkF+Vi/LIPsQxAUgnHqSMjJwvrwv1jJ2yE0HNv42zBaVN4nxtq2EfPZ2VCQj3HmhRDWCmvz7+R98QGs/hnbndMxWretfjyL5mGtXA4du2L0PBlr559YvyzD2rIB2/hbMfoMPP4xfl2B9Z8nwL+FI6aYjgQFB5OVmgwHMrH27XUkW3b+ifXHOsc+4Eg6nDoC47QzMTp0rnbM5pLFWJ++Dbk50CIIAoMhIw0reSe0bYft4muhbTusZV9iffEe2f99Aa78V7WP7wmUwBCRBldZ9cWgLvDtqOcI7HESJedd7qLIREREGlZCQhDzEi9k+RmLuK7D21yROIrExCANI5FmxbIszLkPwJ9/HFn26w+QnQU7tkLLcPhrM5Zhw/jX/1Xc3yzBfPUZ8PbBNmkGRnQHx4q4MQSlbOfAjHjM6bdhi5+J0aXX8ePZsgFr5XKM0RdhXHpdaTWEtWUD5mtPY76YgO3BpzDCWh3jGOsxn5sNHbo4Kol9fQHwj4gg56iZcizLclRL7PwTa8t6rPWrsb79DGvpFxinn4Ux5iqMoJBjx7zpN6z/vQSde2C79nZo2w7DMBzHtqxyQ1WMMVdiZh8if9mX2M66+Jg/h6dxm1lIRKTpio/PIiXlyDzi8XcfYMU/78XXxyTkrukYXl4ujE5ERKThxMdnsTvlb9pfexanhq+mR9BWUlJSlbyQ5mXTb/DnHxgX/wPbjAUY510O61fDnt3YbpuK15xFGBdejbXqe8w3nquwu/XzMse2l11/JHlxmO/JA7E9/DSERmC+mIhVVHTMUKziIsyX5kJEG4wLxpUbymF0OxHbxOlQWIj1xXvHPI752f8guGW55EVVDMPA8PHF6NoL23mX4/Xv2dhmPgd9B2F99zlm4v1Y27dUHfO+vZjPPAKR0djufhgjqn1p3IZhVNpnwxg9FkwL66uPjhmbp1ECQ0Qa1NFTpwIUfvQubNuIcfUEvNpoOi8REWnaEhKC6P2v8eSV+HJdh3dKXxc1pao0F9aP30JgkKO5ZGQMtrHXYHt4AbZH/4PRdzAAxrmXYoy6AOu7z7BWfX9kX8vC+vhNaN8Z+p1a6fGN1lHYrrnFMZxi0TyslF1YmemVbsumdZCRhu2KGzH8/Cseq1UkxuAzsJZ/5RjaUtnPs2UDbFjj+HmOk7yoitEmCq9bpmC7fRrsz8Cc+wBW6q7Kz5f0ERQXYbvrYQxfv+odP6INvoOGYa1a7qjSaCKUwBCRBnV09cXjt/zM5J4vYJwyHNvgES6MTEREpHHEx2excUcO28LiuCj6M0K8D6oKQ5oV689N0PVEDG/v0mVG25hywyYMmxfGpdfDCd0clRTO4SbJO2DfXowR5x5zRg+jVz+MMVdhrVyO+eDtmPfehPnTtxVj+fV78G8BJ/av+lgXXwstgjBffqrSD//mF+9BSBjGyAuq8dMfm3HyKdimJYKXF+asSVi7yydNrNxsrB+SME4ZhhFes6EgPn0GwIFMSP+7znG6CyUwRKRBlf12KdCezbjcGY4pU69uWtN5iYiIHM/Jd43G36uAK2I+UvWFNEnW5vWYH72J+cFrWHm5jmWHDjgSEJ17HHd/w27HdteDENwS87/PYZkm1vrVjnW9Y4+7v+2CcRiXXgcndIO2MVivPIW5fEn5GLdsgJ4nl0umVIgjuCXGRdfAzm1Yq34ov39hAfyxDmPAabWuvqhwvog22B6YD77+mK8+XS5pYn2f5GhcOmpMjY/r0/NkxzG2bKiXON2BEhgi0mCczTudw0fu6/EkJWlpvNNimqZMFRGRZiUhIYiYQafxY0Ys13b4H/MSAzSMRJoUa/WPmE9Mxfr4TazP/of5zCws04TtWwEwTuhereMYAYEYY6+BXX/B779ibd3gaFjZMrxa+9vOuhivqU9g+79HoVtvrDeeLR0KYuXmOJIp7TsdP47BI6B9Z8f+WYeOrNiyAYoKMU48fkKlJozQcIyLxjuamm5YXbrcWvMjdOhSo9lKnLzanQD+AbBza32G6lJKYIhIg3GWxqakpHJa+C9c3f4D7GdfyJX3d3RtYCIiIo3MOaTytPtG0z4glVGtl2sYiTQp5uLXIao9tjmLMK69HTb/jvXTt1hph4cSR7Wr9rGMU06HsAjML9+D1F0Y7U6ocTxGiyBs/7wH/AIwP3rTsfDw8Ayj/fGTAYaXF7Yb7oLcbKyvjzTCtHYcTgZ07VnjmI57zlNHQHhrzP8+7xg6UlAA27di9OhTu+PZbI5pVVN313OkrqMEhojUu6Mbd3Zt35LHTprJfu8YjDFXuTg6ERER10hICKLDhWNJyWvD9R3VzFOaDit1F+zZjXHGORgtwzGGnumoXvj0f5CW6qgCaFH933PDbsc480LYuhEy0qBt9ZMf5Y4TGIxxxjmw9mesv1OPNOWsZkLEiO4AJw/CWr7EUU0CkLoLwltj+AXUKqZjns/uje2meNi3F+vLxfDXH1BSjNH9pNofs207R8xNhBIYIlLvjm7cufmxx2kXsIfwu2/H8KmfsYIiIiKeJj4+i13JaexofwFDI34hedUvqsKQJsH6/VcAjH6HZxQxDGznXQ5pqVjffe6YsrTMdKXVYQwdDQGBjvtR7WsdmzHyPPDywkr6EPbtBV9/CAmt/v79BsGhA45mohxO1tQhnuOer0tPjP6nYX3zMdYfvzsWntC19geMag9ZB8sPg/FgSmCISINwfpt0SugarG8+wTbqfIyuvVwclYiIiOsNu/d0Ck07q+Z+4+pQROrHrr8gLKJ8n4q+gyC6g+N+RJsaH9Lw88c441zHg5iOtQ7NCA7FGDwCa8XXWLv+hPBWNUqmGL36AWBtXINVUgJ/p2DUYDhMbRgXjIP8PKzP3nFMPxsYXPtjOatX9jSNYSRKYIhIvXIOH0lMDMLXls/jfWawKzeap3bf4urQREREXMr5GhnTsxdf7B1Bp7+X0KldmIaQiMezdv8FMeWHZRg2G8Y5lzoeFBfX6rjG+Vdgu+cRjNZt6xSfMep8KCx0DEkJq9lUpEbLMIjugLVhDWTuc/wskTF1iue454zuAL0PT/PaJrpuB2vjeO6sfXvrGJV7UAJDROpV2eEj8d2ep1OLXXScNoE7J9fuhUtERKSpcL5GpqSk8sauS2jpc4ht77ynISTi0azCAkdVQiV9JYyBQzFGnIftwtr1QDO8vTG6965riBgxJ0BHxzAMI7xmCQwA48R+sG0j/J3ieBwaUeeYjnvOPgMcd2x1/Mge1tpxjLQ9dQ/KDSiBISL1pmzzzr4h6/nnCW/wxq6LSPxsqKtDExERcQvO18ofM/vzZ3Z7fnniGzXylDpZsGABN910E/Hx8ZWutyyLl156iTvuuIN77rmHv/76q34DSEsF0zwyXKQMw+aF7ap/YXToUr/nrAWjy+GhzP4tar7vibFQXIz5/VeOBdWc0rUujJ59Hbd1rMAw7HZH1ck+JTBERMpxfrPkYyvkiT4Pk+sdzvgPLtc3SyIiIoc5XysnTcrmjd0XMzDsN5J/+VGvlVJrZ5xxBlOnTq1y/Zo1a9i7dy/z58/n5ptv5sUXX6zfADLSATDCW9fvceuZ0fPwVKQtw2q+c/eTIDQCfl1R+2PUkBEZje2eWRhX3Fj3g7VuqyEkIiJHc357dEfnhXQL+ouQW2/FCKh5lltERKSpi4/P4t3k88kv8WH1PDXzlNrr1asXgYGBVa5ftWoVp59+OoZh0K1bN3Jycti/f3+9nd/KTHPccfcERp+B2CY/Qmlj0Jrs6+WFMWTkkQWN9P7W6H5SvUzXarSKhPSmkcCwuzoAEWkaEhKCSEwM4pMX0vh86Mu8m3wek86+gEmTsvStkoiISBnO10yAz/aOYpT5FV3aT+KWO4v1min1LjMzk4iIIz0bwsPDyczMJDS04lSiSUlJJCUlATB79uxy+5Vlt9tL12XlZZNr9ybihM4Yde3XUAtlYzmuiDNqfZ7C00ay/9N3AGjVquo+GjWKp4E5Y8mJ6UD20i8IDwrC8PV1eTx1OkY9xSIizVx8fBaJiYEk3fQw+9cHcvk7V3JFUKqrwxIREXE78fFHkvsX9b6Yi6M/Z8t/38E29EwXRyZNkWVZFZZVNY1oXFwccXFxpY/T09Mr3S4iIqJ0nZm8C0LDycjMrIdoa65sLA3JCj1SYXKs8zVWPNXhjMX08QMg/c/NGK2jXB7P0aKiqh+ThpCISJ2Ubdx5SfSnsGUDj/5xB4kv1HHKJxERkSbM+fr5y/6+bMnqxOon1cxTGkZ4eHi5D40ZGRmVVl/UlpW5z+2Hj9QHw27HuOwGjBsnuTqUGjOcTUf3uybJVJ+UwBCROnE2IwuxH+K+Hk9C5x5EXTZCJbAiIiLHUK6Z566L6ddyA8k/Ltfrp9S7AQMGsGzZMizLYsuWLQQEBNRrAoP9GUc+IDdxttFjsQ0+w9Vh1Fyo4/pYBzJcHEjdaQiJiNRZQkIQ/9f9aUJ9DmK7+kHi2+W4OiQRERGPEB+fRa/55zKlx1Nseeob+s3p7OqQxMPMmzePjRs3kpWVxYQJE7j88sspLi4GYPTo0fTr14/Vq1czceJEfHx8uPXWW+s3gOyDEBxSv8eU+uVMMCmBISLNmbMJ2ckh6/lwyPu8tGMcDw8+TY07RUREqqFsM8+P9ozmXOtrurW/h3/daep1VKrtrrvuOuZ6wzC46aabGuTcVkE+FBZCoBIY7szwDwBff9jv+QkMDSERkVqLj88iefduHuk9m7SCCG7++EJSUlL1pktERKQanMNIUlJSeWPXxQTac3nqHx/qdVQ8R9ZBx21QsGvjkONrGQYH1ANDRJopZ/Ox+4au4KSQP3h44yRiunRR8zEREZEacL6erjnQm42HutJm86dER7fV66l4hqxDABhBqsBwe0HBWNmHXB1FnSmBISK1Eh+fRfKG9UzutoBl+wbR7cpBqr4QERGpobLNPF/fdQknhWwm+ftlej0Vz5B9uAIjUBUYbi8wGJTAEJHmKiEhCOt/i/C1FTJtw7+Jvyfb1SGJiIh4JGcvjMWpZ5NT7M8btyzTlKriEazSISSqwHB3RlCIEhgi0jwlJATxw8tbsH5ZyrN/XceO3PZ6oyUiIlJLziqMmydafJR6Fhe2/ZLkrVtVhSHu7/AQEiUwPEBgEGQfwrIsV0dSJ0pgiEiNGVYJD/ZKgLBWPPPnP0obkOmNloiISO3Fx2fxxu6LCbDnk/TIj64OR+T4sg+B3Q5+/q6ORI4nMBhKSiAv19WR1IkSGCJSbc5GY6nvfsuJwVu4NWkSBaafKi9ERETqyPkau+5gL9Yd7EnbrZ+pmae4v9xsCAjEMAxXRyLH45zq1sOHkSiBISLVFh+fRfLWrUzutoCfM/vx3KpeTJqUpcoLERGROjp6StWewdtIXvatXmPFveXnqfrCQxjOqW6dfUs8lBIYIlItzm+Gnr3gU8J8DvDQxnhiYqJdHZaIiEiT4Xyt/TD1LLKKWvDO7UvVY0rcmqUEhudwzhST7dlJUSUwRKRa4uOzSP51JTd0fJO3k8cw+qZo9b0QERGpR84qjAl3lvBB6jmc3zaJ5C1b9For7ksJDM9xOIFhaQiJiDQX22a/Sn6JH3M236o3UyIiIg0kPj6L/+66CD+vAr5WM09xZ/m54KsEhkdwDiHJ1hASEWniEhKCuPLknXTK+ZH5224kvTBcJa0iIiINwDmMZGNWd3470Iu2f6qZp7ix/DwMVWB4Bl9/x4wxWZ5dgWF3dQAi4v4m3bkf8+DjbN/WjkU7x5GSkurqkERERJqk+PgjzbHvGXwRj500i+Rl32J07uHiyEQqoSEkHsMwDMdMJBpCIiJNWUJCEPefvgL27GbmprsoNH1UfSEiItKAnFUYH6WOJqfYn//e9r1ee8U9KYHhWQKDPb4HhiowROSYJv0rBXPXcyzbOYiv0k7XtKkiIiINzFmFkZAQxEdLzuLCqC+46oOrMPwDXB2auKG1a9eyaNEiTNNk1KhRjB07ttz63Nxc5s+fT0ZGBiUlJVxwwQWMGDGizue1zBIoLAA//V56jKBgVWCISNO2+qF3IT+XhzdNAgwlL0RERBpJfHwW/909lgB7Pl/N+tnV4YgbMk2ThQsXMnXqVObOncsPP/xAcnJyuW2++OILYmJimDNnDg8++CCvvvoqxcXFdT95fr7jVhUYHsMIDPb4HhhKYIhIlV5+JJ2T9n/Eor8uZUt2ZwCVsIqIiDQC5zCS3w6eyIZD3Wi95XO9BksF27ZtIzIykjZt2mC32xkyZAgrV64st41hGOTn52NZFvn5+QQGBmKz1cPHwPw8x60SGJ4j0PMrMDSEREQqZVkW4/2e5EBRIDd+MIbp3VHzThERkUZStpnnlCFjmXni4ySvWIbRoYuLI5P68PTTT1drO7vdzoQJE6pcn5mZSXh4eOnj8PBwtm7dWm6bs88+m8cff5x//etf5OXlcffdd1eZwEhKSiIpKQmA2bNnExERUWVcof5+ZADBrVrjV8V2jcFut1cZpyu4UzxHx5LdJpKc3GzCW7bEsDd+KqA+nhslMESkgoSEIH5//VcWDviNxK338HL3HqXLNYRERESkcSQkBJGYGESw/Rzu6/Ek7938PVPXqx9VU7BixQouuuii4273ySefHDOBYVlWhWWGYZR7/Ntvv9GhQwceeOAB/v77b2bMmEGPHj0ICKjYuyIuLo64uLjSx+np6ZWeNyIigv17UgDIKiomu4rtGkNERESVcbqCO8VzdCym4QVA+q4dGMEtXR6PU1RUVLWPoQSGiFQwaWImZsYTbPmrE6/vupSUlFQlL0RERBpZ2WaenySdyYVtv+TaD6/AUMm+xwsPD+eyyy477nY//PDDcY+TkZFR+jgjI4PQ0NBy23z77beMHTsWwzCIjIykdevWpKam0qVLHat5NITE8wQEOm5zc8AFCYz6oB4YIlKB9fVHsG8vD22aRLHlyHMqeSEiIuIa8fFZvLl7LEHeOXwxa5Wrw5F68NRTT1Vru3nz5h1zfefOndmzZw9paWkUFxezYsUKBgwYUG6biIgIfv/9dwAOHDhAamoqrVu3rlXc5RQVOm59fOt+LGkURkALx528HNcGUgdKYIhIOc8+VsSht97lq7+HsTx9MKDGnSIiIq7ibOa5av/JbM06gfBNX+h1uYn7+++/2bdvX7W29fLy4oYbbmDWrFncfffdnHrqqbRr144lS5awZMkSAC655BK2bNlCfHw8M2bM4OqrryY4OLjugToTGN5KYHgMZwIj13MTGBpCIiLl/KvNs1jbC5ix6W5AjTtFRERcqWwzzwdOG8v0XnNJ/nkFRkxH1wYm9WbevHmcc845dO/enW+//ZYXX3wRm83G9ddfz8iRI4+7f2xsLLGxseWWjR49uvR+WFgY06ZNq/e4raIixx1v73o/tjQQf8cQEis3B+M4m7orVWCISKnXZqVS8v3XPLf1SnbktgdUfSEiIuJqziqM91LOo6DEm4XX/6DX5yZk/fr1dO7smK7+k08+4f777+eRRx5h8eLFrg3seIoKHLfePq6NQ6qvdAhJtmvjqAMlMEQEcHSxvso+H1twME9tuxGASZOySElJVf8LERERF4qPd7we33CHF5//PZKLoz8jeft2vT43EcXFxdjtdjIzM8nOzqZHjx60a9eOgwcPujq0Y1MFhudpAkNIlMAQEQCsn5fCto0YF40nq9hRXqY3RiIiIu4jPj6LN3ddRIh3Fp/NXO3qcKSedOzYkQ8++IB33323dChIZmYm/v5uPrtHaQ8MVWB4DB9f8PJSAkNEPJuVl0v2yy+z9kAv2o+7tnS5ylNFRETcg3MYyY+Z/dme047QDWrm2VRMmDCBXbt2UVhYyLhx4wDYsmULQ4cOdXFkx6EKDI9jGIZjKtVczx1CoiaeIoL1yVsElOxn2oa5JKfsJTo6Ss07RURE3EjZZp4zho1lao+nSF71C0bbGBdHJrX19ddf069fPyIjI7nzzjvLrRs8eDCDBw92UWTVVFQIXnYMm5erI5Ga8G+hCgwR8VyLHsmg8IuPeWvXhaw7eCLR0VEA+kZHRETEzTirMN5NPp8i04tnr1mhKgwP9ueffzJt2jQmT57Mm2++yR9//IFlWa4Oq/qKilR94YkCWmDleW4CQxUYIs2YZVlc6zsXAv2Zvfl2wDFtakJCkPpfiIiIuBlnFUZCQhBffTucy2I+5pYvLsLQh0iPdPPNNwOwa9cuVq9ezZtvvklqaiq9e/emX79+9O3bl+DgYBdHeQxFBep/4YkCVIEhIh7q4wd/hT/WMfWX29lf1BKgtAJDRERE3FN8fBZv7L6YMJ+DfDJzravDkTpq3749Y8eO5aGHHuLJJ59k4MCBrFu3jsmTJ3Pfffexdu1aV4dYOVVgeCTDw4eQqAJDpJmy8vM4L28BtO/Efz+7CHBMm6rKCxEREfeVkBBEYmIQBpHsyo0ieN2XREdfqNfwJiIgIIAhQ4YwZMgQALZt2+biiI6hqBDsqsDwOAEtQENIRMTTWJ+9A/vTeTtoOiaO5kt64yMiIuLeyjbznH36GCZ3f47kNb9itG7r4sikLjZt2sT27dvJz88vt/ziiy92UUTHZ6kCwzNpCImIeBprbwrFn3/I/5LPZ/Jzp5YuVyMwERER9+ds5vlO8hhKLBtPjftRr+Ee7KWXXiIxMZFNmzaRkpJS+i811c1nhCsuBB9fV0chNRUQCEWFWEWFro6kVlSBIdLMWJaF+dYLePn7cMXblxHf07Fc06aKiIh4hrLNPL9eOpTLYj7mjiVjMOx6a++Jli9fTkJCAmFhYa4OpWZUgeGZAlo4bnNzIMTzhgCpAkOkmbF+WQYb1vDgr7cQ0/PE0uX65kZERMSzxMdn8ebui2jtm8GHM9e7OhyppYiICLw9MRFQWKAeGJ7Iv0wCwwMpgSHSjFiHDmC99QKc0I2Hlw8tXT5pUhYpKanqgSEiIuIhnMNIvtt3KnvyWhO45gt9GeGhJkyYwPPPP8+PP/7Ixo0by/1za6rA8EhGQKDjTm62awOpJdWZiTQj1psvQH4erzKF621epcuVuBAREfEsZZt5JpwxholdFpK8bi1GeGsXRyY19ddff7FmzRo2bdqEj0/5ioZnn332uPuvXbuWRYsWYZomo0aNYuzYsRW22bBhAy+//DIlJSUEBQXx0EMP1T3w4kIMb1VgeBznEBIPnYlECQyRZsJavQJr1ff8EHEj0545iWnPHFkXHR2l6ddEREQ8jHNK1Wi/C5nYZSGJl/xM4tZ/6TXdw7z55pv8+9//pk+fPjXe1zRNFi5cyLRp0wgPD2fKlCkMGDCAmJiY0m1ycnJ48cUXue+++4iIiODgwYP1E7gqMDzT4QSGlZuD4eJQakNDSESaASv7EOYbz0H7zgybcR5wpGlnSkqqho+IiIh4oPh4xxDQK24NZOm+U7ki5kOSd+3Wa7qH8fX1pVevXrXad9u2bURGRtKmTRvsdjtDhgxh5cqV5bb5/vvvGTRoEBEREQCEhITUOWYAigrBW7OQeBwP74GhCgyRZsB6eyElh7I499MFbHquPeCougDHtzd6oyMiIuK54uOzuPGNsbzQ///4YOYmLp7e29UhSQ1cccUVvPzyy1x66aUEBweXW2ezHfv75szMTMLDw0sfh4eHs3Xr1nLb7Nmzh+LiYh588EHy8vI499xzGT58eKXHS0pKIikpCYDZs2eXJj2OZrfbMYqL8Q8OJqiKbRqL3W6vMk5XcKd4KovFCg4iDWhhWLRo5Djr47lRAkOkibPWrcT66Vvs548j6T+BREc7lqekpCp5ISIi4uGcw0jsRmvSCsLx//ULoqNHaxiJB3H2ufjqq68qrHv77bePua9lWRWWGUb5gQElJSVs376d+++/n8LCQqZNm0bXrl2JioqqsG9cXBxxcXGlj9PT0ys9b0REBFZhPnnFJRRUsU1jiYiIqDJOV3CneKqMxe5Nzr408ho5zqriqex3sSpKYIg0YVZuDuZrCyC6A8Z5l1XoTK43NiIiIp6tbDPP+SMv4F8nvEby+t8xQsOPs6e4i6effrrW+4aHh5ORkVH6OCMjg9DQ0ArbBAUF4efnh5+fHz179mTnzp01+tB4NMs0obhYPTA8VUALj23iqR4YIk2Y9e4iOLifN+33EtOhA4mJRxIYmmpNRESkaXBOqfrW7rHYbSU8duHPep33IK1atary3/F07tyZPXv2kJaWRnFxMStWrGDAgAHlthkwYAB//PEHJSUlFBQUsG3bNqKdJbm1VVTkuNUsJJ4poIV6YIiIe7E2rsFavgTj7Eu45pJorpmWWtr3wtnAU0RERDyfswojISGEH74fyBXtPuLf352NcZz+CeI6b731FuPGjTvudu+88w6XX355leu9vLy44YYbmDVrFqZpMmLECNq1a8eSJUsAGD16NDExMfTt25d77rkHm83GyJEjad++fZ3it4oKHHdUgeGZ/FtgKYEhIu7C2p+B+WIiRMYw/69/Mie6fLMcTZsqIiLS9MTHZzHhzYt4pt9U3p25hcse6OHqkKQKn332GSNHjqy0h0VZn3/++TETGACxsbHExsaWWzZ69Ohyj8eMGcOYMWNqF2wlrMJCxx3NQuKZVIEhIu7CKi7CfP4xKCzAds8s7ooq5K7JR6ovlLgQERFpepzNPH1sEWQWhuD3yxdER4/U676bKigo4I477jjudt7uWuFQ5ExguGl8ckxGQCBWepqrw6gVJTBEmhjr3Zfhzz8wbp6MEdW+wkwjehMjIiLS9JRt5vnsqPO5vuNbJG/agBEcepw9xRWON7uIu7MKnUNI1APDIwW0gNxsV0dRKxoYJ9KEmD8vxfr6Y4y4MdgGDiv9NsZZfQFq3ikiItJUOZt5vrn7IrxtJcw8b5Ve96VBOIeQGKrA8EyHh5AcbwiTO1IFhkgTYaXsxHr1aejSC+OS68qtS0lxDCFR804REZGm60gzz3B+XtGPK9stZtqyOAzDcHVo0sRYziEkdlVgeCT/QCgphsJC8PWsPiaqwBBpAqy8XMxnZ4OfP7Z//R+JT4YSHR1VOm2qswJD38CIiIg0ffHxWby5aywntNjNOzP+dHU40hRpCIlnC2jhuM3zvGEkSmCIeDjLsjAXzYN9e7D96/8wWoYRH59VrtoiJSVVTbxERESaAecwkk/3juJgURD2n7/UMBKpd6UVGD5KYHgkZwLDA2ciUQJDxMNZX74Pa37CuOQ6jG69S9+4HN33QkRERJo+55cYf+3O5P2UczmnzTckb/5DX2K4ufz8fDIyMsjPz3d1KNVyZBpV9cDwRIa/5yYw1ANDxINZm37Dev816D8E48wLgSPjXzVtqoiISPPkbOLdPegiru/4NtPP+pWFO67WewI3s2vXLpKSkli9ejX79u0rXd66dWv69u3LmWeeSfv27V0YYdVKZyFRDwzPVDqERAkMEWkk1pb1mM88ApHR2K6bWK5BV9kyUb1RERERaV6ONPNsw+ofe3NV+w946Psz1MzTjcybN4/k5GSGDBnCHXfcQXR0NP7+/uTl5ZGSksLGjRuZP38+MTEx3HXXXa4OtyLnEBL1wPBMAYEAWLk5eNr/CkpgiHgga9NvmE/PhLBW2CY9jOEXABz5xqWs6OgofeMiIiLSDMXHZ3HnKZeSePKDvDPjL654oLOrQ5LDhg4dyoABAyosDwwMpHv37nTv3p2LLrqIX3/91QXRHZ+GkHi40h4YauIpIg3MWr8a86kZ0CoS2+RZGC3DS9dV1rwzJSVVyQsREZFmxtkT6+M9cRwoDMbvl0/VzNONlE1ebN26tdJttm3bRv/+/RsrpBqxijQLiUfz4B4YSmCIeBDrt5WYz8x0DBuJn4URHFq6rqrmnXqjIiIi0vyUbeb5dvIYzmrzLckbfteXGm5o5syZlS6fNWtWI0dSfUcqMJTA8ESGt7djBhklMESkoVirf8R89lGI7ogtfiZGUHC59UdXX0yalKXqCxERkWbM+eXG67suwdtWwpwLf9KXG27ENE1M08SyLCzLKn1smiZ79uzBy8vL1SFWragQDBu4c4xybP6BauIpIg3DXLkc68UEOKEbtonTMZzj1spISAgql6xQ4kJERKR5O9LMsyXfLT+Vq9u/z+Svz8Kw6yOAO7jyyitL748bN67cOpvNxkUXXdTYIVWbVVgA3t5qDOvJAlpgeWAPDP3vJeLmzB+/xVr0JHTpgW3iA6UNO8tyNu8s28BTzTtFREQEHImM616/lIUD4vlw5u+MfbCfq0MS4Omnn8ayLB588EEeeuih0uWGYRAcHIyPT/WGZ6xdu5ZFixZhmiajRo1i7NixlW63bds27rvvPu6++24GDx5cp9itwkINH/F0AS00hERE6o9lWZhff4y1aB50743tzgcrTV7AkWoL5xASNe8UERERODKM5Ou0oSTnRdLyNzXzdBetWrWidevWLFiwgFatWpX+i4iIqHbywjRNFi5cyNSpU5k7dy4//PADycnJlW73xhtv0Ldv33qJ3Soq1Awkns5fCQwRqSfWgUzM+Q9jvfUfOGkAtjvux/D1q7Dd0Y07nbd6UyIiIiJwpEfW7pS/eWPXxQyL+IXkX3/Rlxwu9sorr3DgwIFjbnPgwAFeeeWVY26zbds2IiMjadOmDXa7nSFDhrBy5coK233++ecMGjSI4ODgSo5SC4UFqsDwcEZAoEdOo6ohJCJuxvp1Bebrz0BBAca4mzFGnIthqzzX6Bzb6kxcpKSkVuiFISIiIs2bc6hphM+F3N31BV69ZjkPb4rXUFMXioqKYsqUKcTExNCzZ0+ioqLw9/cnLy+PPXv2sHHjRlJTU7n44ouPeZzMzEzCw8NLH4eHh1eYljUzM5NffvmF6dOn8+yzzx7zeElJSSQlJQEwe/ZsIiIiKt3uYHExXn7+Va5vTHa73S3icHKneI4Vy6GwcPI35TVqrPXx3CiBIeImrNwcrDdfwPrpW+jQBduNkzDaxhx3v6OrLfRGRERERMo60swziM+/GcllMR9z86cXVVrdKY3jzDPPZMSIEaxatYo1a9awcuVKcnNzadGiBe3bt+fMM8+kf//+x52JxLKsCsuObqz58ssvc/XVV2Or4guxsuLi4oiLiyt9nJ6eXul2XgX5lNi8qlzfmCIiItwiDid3iudYsZg2L6ycLPbt29dozViriicqKqrax1ACQ8QNWJt/x3xpHhzIwDh/HMZ5lx+3Q7jz25Sy1LhTREREqhIfn8VFiy7jwqglLJn5M2fNGO7qkJo1u93O4MGD69RQMzw8nIyMjNLHGRkZhIaGltvmzz//5MknnwTg0KFDrFmzBpvNximnnFLr83J4FhLxYAEtwDShIB/8/F0dTbUpgSHiQlZRIdbi17G++hBatcX278cwOnWv1r6VDR8RERERqcyRLz7asvFQV6IPfUh09DgmTcrWFx8u9vLLLzN06FC6dOlS4307d+7Mnj17SEtLIywsjBUrVjBx4sRy2zzzzDPl7vfv379uyQucTTzVA8Oj+bdw3ObmKIEhIsdnbd+C+cpTkLIT44xzMC69vtqlnKq+EBERkZpwfvEBcPegcTzRZwbJ3yzB6H6SiyMTy7KYM2cOvr6+DB06lKFDh1a7pN7Ly4sbbriBWbNmYZomI0aMoF27dixZsgSA0aNHN0zMhYXQQk3jPZkR0AILIC8HcI+eHdWhBIZII7IsC7asx/zsXdi4BkJCsU2cjnFS/xod5+jqCyUuRERE5HicX4D42s5iao/5/HxPEv9afZbeR7jY9ddfzz/+8Q/Wr1/P999/z3333Ufr1q0ZNmwY559//nH3j42NJTY2ttyyqhIXt912W73EbBUVQjWnehU3FVCmAsODKIEh0ggsy4J1KzE/fxf+/AOCW2Jc/A+MM87B8A+o8fGOnmlEbzpERETkeMo28/zvJxdzS+dXSP5tDUZEG1eH1uzZbDb69OlDnz59yMzMZMGCBbz22mvVSmC4RGEBhoaQeLaAQMeth02levxWtCJSa1ZJCebPSzEfmoj59Ew4kIlx1QRsj/4H2zmX1Dp5kZgYVFp9AY7hI0fPRiIiIiJSmfj4LF7ddSmWZfDLnCRXhyNAfn4+y5Yt49FHH+XOO+/Ey8ur3qolGoJ6YDQBhyswLFVgiIhVVIi14husL9+HfXuhbTuMG+/GGDDsuLOLHE98fBaJiUGkpKQSHR2l5p0iIiJSbWX7aH2+dySnl3xGl/a3c8udxarodJHExETWrFlDp06dOO2007jtttsIDg52dVjHZBUWgF2zkHg0f2cFhhIYIs2SZZqw60+sdSuxli2Bg5lwQjdsl98AfU7BqMbc28dydONOZwXG0cNJRERERKpStpnnhb2v4IKor1hw7fuMjh/h4siar06dOnHttdcSEeE5jRStwkINIfF0zkrwPM8aQqIEhkgdWPm5sHEt1rpVWOt/hYP7wTCgRx9sN94NPfpgGEa9nKuyaVOVvBAREZGaKjul6u8He9Au60Oio6/SlKouMnbsWFeHUCOWZUFRIXirAsOTGXY7+Pp5XAWG2/TAWLt2LXfeeSd33HEHixcvdnU4xzVjhlfpfWfvgbI9CCq7f7z19XksrW+4a2H9nYr51Ydsv/NBzLuuwXx2NtbqHzG69eaLtlOwJbyK16QZJH42FMMw6jXWSy4Jpyy9yRAREZGaio/PIiUllUmTsnlpxzi6Bf1F8lef632FVE9JMViWemA0Bf4tPK6Jp2FZluXqIEzT5M4772TatGmEh4czZcoU7rzzTmJiYo65X2qq68b+l+094Lxf2bKarK/PY2l9FAUFhaSnp9fpWiRv305cn2K+em01/LWZPz9cS6cWuwDYktWJ7peezKUPnc17a1ph2O0N9rNMmpRVbviIU1OY9iwiIoL09HRXhyHHoGvk/nSN3J+ukWdoTtfJWYXhYyvkxxHns/bAidz461y3f2/hymsUFRV1/I2amMo+b1l5uZgTx2FcdgO20WMbP6ijuNvfrTvFc7xYSh6+E0Ij8LrjfpfGU5O/LbcYQrJt2zYiIyNp08YxhdOQIUNYuXLlcRMYrmJ+8DofDtlAySNFYBi8f6ovJbMLeW+wLyWPFYEB7wzyo2ROIRgGb57iS0lCIf89xY+SxAIwDF4b6EfJPMf9lwf4UTK/EICX+vtT8nQBL/b3o+SZArB58XTfFpj/KQQvG4+fFIT5WgEzTgzGfCsfbDamdA/BfD8XvLy4s0tLzE9zmNApFHNJDnh5Mb59GObSLLDZuDiqFebKHM5s3QZrQzbYvekbkom1+yDYvYnxB+vgfkLsgc2oOY+FlXUQ9iRzVbufMN/egLU3me/P2It5eypLhllYLwB2b3bmDKTzP8/B6N2fuL6xpLyVys93RmHYGzaZVtnwEREREZHaKjul6hsfX8zELgtJXr0Ko03z+5AuNVTk+NyiCowmILglHDrg6ihqxC0qMH766SfWrl3LhAkTAFi2bBlbt27lxhtvLLddUlISSUmOqZ5mz55NYWFho8Y5Y4YXM2d6cVvnRQwKW42B5fhnWBiAgQWljw8vK73v+IfBUfuV347SdY7tvIwSvIwS7IdvvQwTu1HsWGYru64Yb1tJg/zchaadghJfCk1vCkxfCkyfI/dLfCg0fcg3fSgo8SXf9D18W+ax6Ut+ic/h2yOP800/Ckp8ymzjOLZzm4ISH0y8jh/gUXxshQTbswj2ziLYnk2wdxYh3lmly4LsOYeXHSLaby+dA3cS6nOwdP+8El/+zO7Anzkd2ZZ9An9md2RbTke257SnwPStz6e2ToYNM0lKKnZ1GHVmt9spLvb8n6Mp0zVyf7pG7k/XyDM01+sUE3SIFSMuYFubMYz8T7yrwzkmV14jH5/m94G90gqMjDTMe2/C+Mcd2Iae6YKoynOnigdwr3iOF4u5cC7W1g14zX7RpfF4XAVGZTmUyhofxsXFERcXV/q4sX8xbrnF8Q/OIjr6erccQhITHcnunbvpckIbtm1JBrOEk3u34rc1KVBictrgMH74LoVz4kL4/ONUKCpk/JVBvPbS31hFhUya2ILEx/bx4H3+PDgtHYqK+M88X27/134oLuSt1+yMu+QQn35k49wzs6C4iJU/FHJabCYUF7FzawkdovM4kFZMy8B8qGuSyctOboGdgADH70heHvj7W+TlGfj7W2BBfr6Bn59jfUG+ha9X0XGO6UVGbhDh7fyhZRivJ41i/ORQjMh2DLqwPz9vLeFkm41zKzzXGW4xXKZsaaeb/N9YJ+70n7xUTtfI/ekauT9dI8/Q3K7TkWaeEbyfei5j+YTIwFu4/g4vtx1GoiEkbkAVGE3H4QoMy7LqbeKBhuYWCYzw8HAyMjJKH2dkZBAaGurCiDyXhQ3D7k2+6YdxeGqcjMIwjJb5AOzMjcKI9uL3Q1EYXUIA+HZfFEZsKgbwv+Qo5p2RysIdUTx8juND82O3RDHxCsf9yf8XxVVfpDLhwShSPnYsuyQhipT3HPeHHf6w3efwrWVZdGrfir8274CiIk7t35Iflydz9sgQvvg4BYoKufbKIF5duAerqJD/uyuAx2ftY9aDvtz3fxlQVMBrz/gzYYKjO+4rzwVyyy3ZvLIgkFtudTScWbQgiFsP31+4IIjb4kuYOjOapxb6k11icuG4Dnz4VR4EtKBrny5s3ZlJv5jo0qTA1HlR/CPOcT8lvy2Gzb2HZ7jrGwoRERHxLGWnVD2j+9Vc2e5D1j39Erbzx7k4MnFrRf/P3n3HN1V/fxx/3XQXSidQOthLBESGCIqgVH5uEffeCKgIKTgQXIgi0pQhKAriVpw4vw5EEUEFGSoiMgU6oHRBoaW0zf39ERLa0kILbZO27+fj4aMZN/cec2mTnJzPOY4vCw1NIan9GgU7ElL5eeAf6O5oKsQjEhht2rQhNTWVtLQ0wsLCWL58OSNHjnR3WMc0fvyR5RpWa06Jn+VdPt79VbkvT7nfMAzuG5WPEdgQgKuHB2E0i2XQXUEYbRsB0O3mIIwerTGAZlcHYRmYQ+DaICyXOvaRty0Iy9WOywd3BGG5KoeD2x0/AfKLXT60PQjLxTk03hBEwDl+HEhPp/8dQRhRjvuHP1CIYRi19lyceWY+IiIiIlXlSBUGfJ92Fqe9/z/6DL+Xe0cd0pcmUjZXBYbnLK2WExQU4vi5L7vWJDA8ogcGwOrVq3n99dex2+2ce+65DBky5LiPcecUkvpWYlgb6RzVDjpPnk/nyPPpHHk+naPaoT6fp4SEIH557V8WnDkM4+Z7sZzzf+4OqUxaQlKzyuyB8e867FPHYYl/GqNjVzdEVZKn/d56UjzHi8Vctwr79CexPPQcRttT3BZPreuBAdC9e3e6d+/u7jBEREREROqd+Pgcom09+GtvR6IXfE7E2edjWCzuDks8kXpg1B2NQhw/a9EkEo9JYIiIiIiISM0rvoxkztabeCF4PLf22MZpN3XTMpJaYO3atcyfPx+73c7AgQMZPHhwifuXLl3Kp59+CoC/vz933XUXLVu2PPEDuhIY6oFR64WEAWDuzaR2tPAEpVVFREREROqx+PgckpNTSE5O4atdcSTlRTL/hnlKXtQCdrudefPmMW7cOBITE1m2bBlJSUkltmnSpAlPPPEEU6dO5corr+Tll18+qWOaqsCoOxoGg5c3ZHnGkpeKUAJDRERERKSeS0gIIjo6ikLTm3nbroeN67iwUxYJCUHuDk2OYfPmzURGRtK0aVO8vb3p27cvK1euLLFNhw4daNjQ0VC/Xbt2JaY/npDDU0jwVgVGbWdYLI4qjKyT/DdRg7SERERERESknnOOVE1ICGLO9MGMavcKX46ai2XoWHeHJseQmZlJeHi463p4eDibNm0qd/vFixdz+umnl3v/okWLWLRoEQCTJ08mIiLiqG1y/XzJAcIim+EVGn7U/TXN29u7zDjdxZPiqUgsmY0jYf8+wmog5qp4bpTAEBERERERwJHIsNmieGfHEO7xeQtj8E0YTZq5OywpR1kDJQ2j7G4G69at44cffuCpp54qd39xcXHExcW5rpc1McKenQlAZk4ORpH7B1p60tQP8Kx4KhKLvWEjzB1bayTmqphCoiUkIiIiIiLiWkYCMO+/Gygo8uKNm7/RMhIPFh4eXmJJSEZGBqGhoUdtt337dubMmcPYsWMJCjrJ8+lcQqIeGHVDaDhkZ5SZDPNESmCIiIiIiEiJZp5p+RG8n3QZN7X+DOud/7k7NClHmzZtSE1NJS0tjcLCQpYvX07Pnj1LbJOens7UqVO57777KvVNd7kOHW7iqR4YdUNYBBzKhwO1o2mvlpCIiIiIiAhQeqTqzVwfu5B5V35P3kV3aiqJB/Ly8uKOO+5g0qRJ2O12zj33XGJjY/n2228BGDRoEB9++CH79+9n7ty5rsdMnjz5xA9acAh8fMtdqiK1ixHRFBMgfTc0bOTucI5LCQwREREREQFKNvO02WL4LHUQ95zyIZZ7LgA8/8NNfdS9e3e6d+9e4rZBgwa5Lg8bNoxhw4ZV3QELCzC0fKTuiIgEwNyzG6NlOzcHc3xaQiIiIiIiIiU4qy1mb7kN8g9iLv7CvQGJ5yg4hOHn5+4opKo0diQwSN/l3jgqSAkMERERERFxKd7Mc+P+Nny9awBZH33FjClebo5MPMLhJSRSNxh+/tAoBPYogSEiIiIiIrVM8WaeALO23EaI7z7uO+1DN0cmHqFAS0jqnMaRmGmp7o6iQpTAEBERERGREopXYfyxtzNL089g91ufMe15LR2o78yCQxi+SmDUJUZkNKTudHcYFaIEhoiIiIiIlOCswrBaHb0wXth8B038MxjZa6F7AxP3KzikCoy6Jqo57MvG3L/P3ZEclxIYIiIiIiJSJmczz18ye5Dq3wnz648wCwvdHJW4VcEh8FUlTl1iRDV3XEjZ4d5AKkAJDBEREREROUrxZSRg8OjPd0FGGv976je3xiVuVlCAoQRG3XI4gWEmK4EhIiIiIiK1UOlmnovS+kFsK/6v6E1Me5GboxO30RKSuic0Aho2gu2b3B3JcSmBISIiIiIiZSpdhTF04XBIS+HLJ353a1ziRgUFauJZxxiGAa07YG7d6O5QjksJDBERERERKVPpZp7f7B4A0S24kDcw7Xb3BifuUXAIVIFR5xitO0DqTszc/e4O5ZiUwBARERERkWNyNvM0sfCVeYtj5OLq5W6OStxCY1TrJKNtJ8eFjevcG8hxKIEhIiIiIiLlKrmMBEbMvYTN+1uw+7UPVYVRHxUUqAdGXdSmI/gHYP612t2RHJMSGCIiIiIiUq7SzTzteNHugSE0zt8Kf6xwc3RS4woPaQpJHWR4e8Mpp2H+ucKjm/QqgSEiIiIiIsdUugqj5VXX8t+BGFLnfYBpmm6MTGqSWVQERUWgBEadZOndH7Iz4e817g6lXEpgiIiIiIjIMZVu5llketPq3iE0zd8Ef2kiiTutXbuWBx54gPvvv5+FCxcedb9pmrz66qvcf//9jBkzhq1bt574wQoLALSEpK467QxoFIL96489NjGpBIaIiIiIiFSIs5knwPRfLoXwJti/WOCxH3bqOrvdzrx58xg3bhyJiYksW7aMpKSkEtusWbOGXbt2MWPGDIYOHcrcuXNP/ICHDgGoiWcdZXj7YFxyHWxch/njV+4Op0ze7g5AREREREQ8X0JCEDZbkOv61MRQUmLvYnKXZ2D9Wjj1dPcFV09t3ryZyMhImjZtCkDfvn1ZuXIlMTExrm1+//13zjnnHAzDoH379hw4cICsrCxCQ0Mrf8ACRwJDY1TrLuOc/8NctwrznTkUrVyKERxWxkZG5Xfs6wtjJp50fEpgiIiIiIjIccXH57gqMJz9MKYs7YF9fAT2L97D0qkbxol8sJETlpmZSXh4uOt6eHg4mzZtOmqbiIiIEttkZmaWmcBYtGgRixYtAmDy5MklHgdQRBFZ0S3wCQ076j538fb29phYwLPiOdFYzPHPk/vZexz89UfM1J3F7ylj44rt0/D3r5LnRgkMERERERGpkNJVGDEtW3BLizt4+tQp8O9f0LGrG6Orf8paulM6iVSRbZzi4uKIi4tzXU9PTy+1hRc8MROfiIgy7nOPCA+KBTwrnpOKpf9Fjv+qiAkUFhaWGU9UVNTRDyiHemCIiIiIiEiFlG7mCfDMkjMgOAz7FwvcGFn9FB4eTkZGhut6RkbGUZUV4eHhJT40lrWNSG2hBIaIiIiIiFRK8WaethnhGBdcAf/+hblpvRujqn/atGlDamoqaWlpFBYWsnz5cnr27Flim549e/LTTz9hmiYbN24kMDBQCQyptZTAEBERERGRCktICHL1wACw2YJod/vtHPAKVRVGDfPy8uKOO+5g0qRJjB49mj59+hAbG8u3337Lt99+C8Dpp59OkyZNGDlyJHPmzOGuu+5yc9QiJ049MEREREREpMLKaua5ZWcm9m8ux/zwNcwtGzDadHRniPVK9+7d6d69e4nbBg0a5LpsGIaSFlJnqAJDREREREQqpXQVRnR0FB3uvoM8r0bYv3zfjZGJSF2mCgwREREREakUZxVG8akkm3ZkY//yMsyFb2Fu34zRoq2bo5STdazpEJWZHFHdPCkW8Kx4PCkWOPl4VIEhIiIiIiInpHgzz4SEIIzzLoHABuqFUcc9/PDD7g7BxZNiAc+Kx5NigaqJRwkMERERERGptLKaeca0bcsvgVfD2t8wk7a5MToRqYuUwBARERERkUqLj88hOTmF5OQU123JySmcNX4Q+AVgfrPQfcGJSJ2kBIaIiIiIiJyQspp5xrRvz5rAizBX/oSZme7G6KS6xMXFuTsEF0+KBTwrHk+KBaomHiUwRERERETkhDirMKzWI70wkpNT6PHgBWA3MRd/4cbopLp40gdjT4oFPCseT4oFlMAQEREREREPcFQzz4imGD3Pwvzpa8y8XDdGJiJ1icaoioiIiIjICSs+ShUczTxttiAmD7+RG/KWYv78Hcb5l7sxQqkqa9euZf78+djtdgYOHMjgwYNrPIZ7770Xf39/LBYLXl5eTJ48mf3795OYmMiePXto3Lgxo0ePpmHDhlV+7NmzZ7N69WqCg4NJSEgAOOaxP/nkExYvXozFYuH222+nW7du1R7P+++/z/fff0+jRo0AuP766+nevXu1x5Oens6sWbPIzs7GMAzi4uK46KKLqvz5UQWGiIiIiIicsPKaed48Pgran4q56DPMoiI3RihVwW63M2/ePMaNG0diYiLLli0jKSnJLbE8/vjjPP/880yePBmAhQsX0qVLF2bMmEGXLl1YuHBhtRx3wIABjBs3rsRt5R07KSmJ5cuXY7PZePTRR5k3bx52u73a4wG4+OKLef7553n++eddyYvqjsfLy4ubb76ZxMREJk2axDfffENSUlKVPz9KYIiIiIiIyEkpq5lndHQUnx64ATL3YK5a5sbopCps3ryZyMhImjZtire3N3379mXlypXuDguAlStX0r9/fwD69+9fbXF16tTpqMqO8o69cuVK+vbti4+PD02aNCEyMpLNmzdXezzlqe54QkNDad26NQABAQFER0eTmZlZ5c+PEhgiIiIiInJSymvmecVjp0JkNOY3n2CaphsjlJOVmZlJeHi463p4eDiZmZluiWXSpEk89NBDLFq0CIC9e/cSGhoKOD5I79u3r8ZiKe/YpZ+vsLCwGnu+vvnmG8aMGcPs2bPZv39/jceTlpbGtm3baNu2bZU/P0pgiIiIiIhIlTiqmafFgnH+YNixBTauc19gctLKSkAZhlHjcUycOJHnnnuOcePG8c0337B+/foaj6Ei3JWwGzRoEDNnzmTKlCmEhobyxhtv1Gg8Bw8eJCEhgdtuu43AwMBytzvReCqcwHj99df577//TuggIiIiIiJSt5VeRmKzOa7P+O0yCArG/s0nboxOTlZ4eDgZGRmu6xkZGa5v1mtSWFgYAMHBwfTq1YvNmzcTHBxMVlYWAFlZWa4GljWhvGOXfr4yMzNdsVenkJAQLBYLFouFgQMHsmXLlhqLp7CwkISEBPr160fv3r2Bqn9+KpzAKCoqYtKkScTHx7Nw4cISBxMRERERkfqtvGaeo8bmYwy4EP76HTMjzX0Byklp06YNqamppKWlUVhYyPLly+nZs2eNxnDw4EHy8vJcl//880+aN29Oz549WbJkCQBLliyhV69eNRZTecfu2bMny5cvp6CggLS0NFJTU2nbtm21x+NMFgCsWLGC2NjYGonHNE1eeukloqOjueSSS1y3V/XzY5iVqN2w2+2sWbOGpUuXsnr1atq1a8c555xD79698ff3r+z/40lLSUk5/kbVJCIigvT0dLcdX45P56h20HnyfDpHnk/nyPPpHNUOOk8nr/RIVacn7tvIHVtvwLjiZiwXXX3C+3fnOYqKijr+RnXc6tWref3117Hb7Zx77rkMGTKkRo+/e/dupk6dCji+YD/77LMZMmQIOTk5JCYmkp6eTkREBFartVrGqE6bNo3169eTk5NDcHAw11xzDb169Sr32B9//DE//PADFouF2267jdNPP73a4/n777/577//MAyDxo0bM3ToUFelTHXGs2HDBh577DGaN2/uWlp0/fXX065duyp9fiqVwChu586dzJgxgx07duDr68tZZ53FNddcUyNlMU5KYMix6BzVDjpPnk/nyPPpHHk+naPaQeep6hRPZDgrMoqeewgO7Mfy5Asn3DtBCQyR+q1STTxzc3NZvHgxTz75JI8//jht27blySefJDExEX9/f5555pnqilNERERERGqJ0s08AYzeAyB1J+zc5qaoRKS2q3ACIyEhgWHDhvHbb79x/vnnM2fOHO655x46duxIREQEt9xyC2lpWtMmIiIiIlKfldfM88UV/wdeXpi/LXFjdCJSm3lXdMN27dpx5513EhISUub9FouFV155pariEhERERGRWig+PsdVgeFMZDiWkVgoeqEH5oolmFfegmHxcmOUIlIbVbgC47LLLis3eeHk5+d3svGIiIiIiEgtV7oKIzo6iujoKL7ccwFkZ8K/69wYnYjUVpXqgSEiIiIiInI8zpGqVuuRXhjJySlc+mgX8A/A/O1H9wUnIrWWEhgiIiIiIlItSjfzNHz9MLr3xVy1HPNQvhsjE5HaSAkMERERERGpcuU18/xw54VwMA/+XOnG6ESkNlICQ0REREREqpxzGYmjgadDcnIKV49vA8Fh2H/90X3BiUitpASGiIiIiIhUi7KaecbExvKX0Rc2/o1pt7sxOhGpbZTAEBERERGRalFeM8+ul7WEvAOwZ5f7ghORWkcJDBERERERqVZHNfNs2Q4A879N7gpJRGohJTBERERERKTalNXMs2Wf3hQavvDfZjdGJiK1jRIYIiIiIiJSbcpq5jlydB7erVphblcFhohUnLe7AxARERERkbotISEImy3Idd1mCyK4UzdubPUp/vYiDIuXG6OT8qSkpJR5e0REBOnp6TUcTdk8KRZQPMdTVjxRUVHlbH00VWCIiIiIiEi1KquZ5x1PNsPXPAi7kt0YmYjUJkpgiIiIiIhItStdhXHe7X0B+N9LO90VkojUMkpgiIiIiIhItStdhbFlfwvw8+eCjuvcHJmI1BZKYIiIiIiISI1xjlS140WSpT3mdk0iqcvsiz7DTNrm7jCkjlACQ0REREREakTpkapf/d2Fg5v+wzY10I1RSXUw8/Mxf/8Zc8Fc7C9Mcnc4UkcogSEiIiIiIjWi9EjV3fmN8ffKZ/S9njMlQaqG+dX72OdMcVwJaODeYKTOUAJDRERERERqTPEqDLtpAHBKx0gSEoKO9TCpbfbvc100opq7MRCpS5TAEBERERGRGlOymacjgfHP+hRXbwypI/IPHrlsuC8MqVuUwBARERERkRoXH5+D3XR8HJk1S0sM6hozKwPadITIaMyCAneHI3WEEhgiIiIiIlKjnMtIzMPXX5rdgOjoKC0jqUuy0jHCGoOvPxQccnc0Ukd4uzsAERERERGpX+LjcxwVGD/kYL4DhmG6GntK7WeaJmRlwOl9IHMPFKoCQ6qGKjBERERERKTGJSQE8ci4UAAs2ImOjlIVRl2xP8eRtAgNA18/VWBIlVEFhoiIiIiI1Lj4+BzsPfZivg0Ww7GYRFUYdYRzAklQCHj7QO4Bt4YjdYcqMERERERExD0sjvEUxuFuGKq+qCNy9wNgBDYEH184lO/mgKSuUAJDRERERETc4rvvAgAwDDsANluQlpHUBc6Ki8AGGD4+6oEhVUZLSERERERExC3OPz8P8034feUuYro0BbSM5GTMnj2b1atXExwcTEJCAgD79+8nMTGRPXv20LhxY0aPHk3Dhg2rNQ7zcAUGzgoM9cCQKqIKDBERERERcY+UnRQY/rToeqrrJjXzPHEDBgxg3LhxJW5buHAhXbp0YcaMGXTp0oWFCxdWfyDFKjDw8YECVWBI1VACQ0RERERE3MLcsgGf9u3YkZSG1Zrjuj05OYX4+JxjPFLK0qlTp6OqK1auXEn//v0B6N+/PytXrqz+QFwVGA3AR1NIpOpoCYmIiIiIiNQ481A+7NyKMegKwDGVxGZzVF0kJAQpgVFF9u7dS2ioY1xtaGgo+/btK3fbRYsWsWjRIgAmT55MREREmdt5e3uXex9Ajmkn19eXxs2i2B8czIHCAsLDwzEM4yT+T8p2vFhqmuI5tpONRwkMERERERGpef9thqIijDYdSUgIciUvwNHM02YLwmrNUSKjBsXFxREXF+e6np6eXuZ2ERER5d4HYM9Mh4CGpKenYy8oBLud9N27MLx9qjzm48VS0xTPsZUVT1RUVIUfrwSGiIiIiIjUOHPLBseF1h2Jjz+SqIiOdnyYUTPPqhEcHExWVhahoaFkZWXRqFGjaj+mmbvfsXwEHD0wwNEHoxoSGFK/qAeGiIiIiIjUOHPrBmgShRHk+ECdkBDkSl6AmnlWlZ49e7JkyRIAlixZQq9evar/oLkHiiUwfB0/1QdDqoASGCIiIiIiUqNM04QtGzDadHTdFh+fQ3Jyipp5noRp06Yxfvx4UlJSGDZsGIsXL2bw4MH8+eefjBw5kj///JPBgwdXfyC5BxwjVOFI1YUmkUgV0BISERERERGpWXt2Qc5eKJbAcFIzzxM3atSoMm9/7LHHajaQ3P0YTaMdl339HD9VgSFVQBUYIiIiIiJSo8ytjv4XRpsOJW4vvYzEZgvSMpLaKPcANHAsITGcPTAKlcCQk6cKDBERERERqVlbNoB/AEQ1L3GzmnnWfqZpOhIYAYeXkDh7YBxSAkNOniowRERERESkxpj5+ZirlkOHLhgWr6PuVzPPWu5gHpj2I008XT0wlMCQk6cEhoiIiIiI1Bhz2XeQsxfLoMFl3q9mnrVc7gHHT2cCwz/Q8fNgnnvikTpFCQwREREREakRZmEh5jefOJp3tjv1mNsWT1io+qIWyd0PgOGcQhIQAICpBIZUASUwRERERESkRpgrfoLMPVguvBrDMMrdrrxmnhMnHr3kRDxMeRUYebnuiUcwd2zB3LLB3WFUCTXxFBERERGRamfa7ZhffwQxLaFrz2NuW14zz4iICNLTqztSOSl5jgoMXBUYziUkSmC4i33iaAAsiW9hNGzk5mhOjiowRERERESk+q39DVJ3Ylxw5TGrL5zKaubp5+er5SQezjxQqgLD1w8MC+RpCYm7mUu/c3cIJ00JDBERERERqVamaWL/6gNoHInR8+wKPaasZp75+YfUzNPTlarAMAzDMTI3XwkMdzCLT39J+s9tcVQVtycw3nzzTUaNGsWYMWN4/vnnOeDM2Hm44uvvimeBnZfLuq0qtq3OY1x5ZTgiIiIiIlXunz9g+2aMC4ZgeFWuj0XxhEVcXO1aAb979+4K/ZeWlubuUKuO8/Pc4eadrsvqgeEWRXt2uy6bu3a6MZKqYZimabozgD/++IPOnTvj5eXFW2+9BcBNN91UocempKRUZ2jHFB0dRXJySrmXj3f/iW5bU8eoCxxrJLVI0tPpPHk+nSPPp3Pk+XSOagedp+pTlDAeUpOwPPsKho9PhR+XkBCEzXb0khGrNafGKzGioqKOv1Ep1157bYW28/X15c0336z0/qtbeZ+3jvW7Yn9nDuZvP+I1/V3XbUWP3QvNYvAa/kiVx+hpv7eeFk9Q0haynxwNzdvAriQsMxdgWNxXx1DW81OZ3y23pzBPO+001+X27dvz66+/ujGa4zN3bME+cTSrB4Zif6s3RLfkjNAemLkNjowKquUSEoJUmiciIiIiVcL8YwVs+BPjqtsrlbyAI808i/fCqE1fuPn5+fHGG28cd7vbb7+9BqKpIfv3QcPgkrcFBKoCw02K0lIBMDr3wNyxBbLSIbyJm6M6cW5PYBS3ePFi+vbtW+79ixYtYtGiRQBMnjyZiIiImgoNcCwbmflcA/46H1IORuK7aCmNfL7mwz5gfwBS8pryWs82vHBeW66Iaktcx7ZsOdAS4KgGRKUvH+/+qnhcZbZdubIBixYVHvsJ8XDe3t41/m9EKk/nyfPpHHk+nSPPp3NUO+g8Vb3C5B1kvpqId+sOhF11C4afX4UfO3GiFxMmFB21bMT5frVfP7vHv1+97bbbKrTdrbfeWr2B1CBzXzY0KpXA8A+EvNrRKqCuKUpNBm8fjM7dMb96H3ZsVQLjeCZOnEh2dvZRt1933XX06tULgI8//hgvLy/69etX7n7i4uKIi4tzXa/p0pzhwx3/wWdcEh1FUlIyZKZzy8AcXn92NdHJ28n+LoXzmq2AosN/TL282Jjdgg7nRUN0C+4Yfzrzvw2C8CbExMZ45BKS6Ogo3ntvF488UrsrMTytfEvKpvPk+XSOPJ/OkefTOaoddJ6qlnkwF/szY8HihX3oWDJyciDn+O8tndXATz8dxdNPH90vo/jykZo8XSeyhOS8886r0HYDBgyo9L491v590LhZydsCAhzf/EuNK0rZAU2aQcu24OWNuWUDxulnujusE1YjCYwJEyYc8/4ff/yRVatW8dhjj1VopJKnMAwDwhuzeM9pWC5sDcAFj0eRtH0H551awPdvroTk7Wyfv4v2W/+FlUuZ1/Mt7OMAvwA+PrMd9ndiuC6mO+b2MIhq4bb/F2czz7KqNYBancgQERERkZplmib2+dNhVzKW0U9iHOcb3+JLmG22I5fL+qKtNr0vXbduXYW269y5czVHUoP2ZWO06VjiJsM/AFNLSNyiMGUnNI3C8PGF5q0xt/3r7pBOituXkKxdu5ZPP/2UJ598Er9KlJS52/jxRa7LxUc7Wa05GN7eXDI0FMsZ5wDw99YgLojPwczL5d2EdK47Zz0kbafZrzswl//AlK5fYX8a8PJi1RUtsL/aEpq3JmHYqZi5kRiBDY46RlnHPdbl490fH5/D8uW+fPRRxlEvELXthUJERERE3Mv834ew+heMq+/AOOW0crdzJi6cSYvjfanWr5+9+oKuBi+++GKJ65mZmRiGQVBQEDk5OZimSXh4OC+88IKbIqxapt0O+3OO7oHhrx4Y7mDai7DvSsY4tTsARou2mL/+gGmatapwoDi3TyG5//77KSwspGFDRwPMdu3aMXTo0Ao91p1TSKqqxNC02yF9F+zYirljK+bOrbBzG+zNOrJR40iIbY3Rog1G6w7Qsi2Gf+BJH7ssx+r0DLWrEkNloLWDzpPn0znyfDpHnk/nqHbQeaoa5rpV2Gc8hdGrH8Zd8WV+UHImLop/cVYW53IR5/buPEcnsoSkuI8//pj9+/dz7bXX4ufnR35+PgsWLCAoKIgrrriiiqKsWpWdQmLm7MNuvQnjuruxDLzUdbv98/cwP3sHy4sfYXhXrpHr8Xja760nxWOmpWJ/9B6MW+7D0m8Q9m8/wfxgPpZp72A0cM8Ailo/hWTmzJnuDsGtDIsFmkRBkyiMnme7bjf3Zh1OamyBndswd27FXL0c0/EgiIp1JDNad8Bo1QGaxVTJOJziCYriiYzil2tTEkNEREREao6Zlor9lakQ3RLjlvvL/Za3+HvLspIXpZeL1IX3n19++SVz5szB29vxEczPz48bbriBe+65x2MTGJW2f6/jZ8NGJW8POnx9fw6EhNVsTPXZji0AGM0d7Q6M8CaOz5MZaeCmBMbJcnsCQ8pmBIdClx4YXXq4bjMP5MC2jZhb/8XcthFz1TJY+q3jH2FAILTthNGhC0bHrhDbEsNydNOjiii+/rB4A1Dni4jGrIqIiIhIaebBPOyznwHDgmXEI0dNHHG+h3QuEyld9eustnAmNIove64L/P392bx5Mx07HukPsWXLllq1jP64chwJDCOo5BISIyjY8Zll/95qTWCYq5ZDQABGp9Or7Ri1ibltE/j4QvThXothh3vRZKbB4aRGbaMERi1iNAiCzj0wOjuSGqbdDmkpmFv/hS3/Ym78C/Ov3x1/HAIbQPsuGB0PJzSimld6nZPVevx1iEpkiIiIiIhZcAj7PBuk7MQy6nGMxpGu+4r3uShvqXLxxp21celyRVx77bU888wz9OjRg/DwcDIyMli9ejV33nmnu0OrOvsPn7PSFRjOnhg5+6rt0GbOXuwvTQaolqUqtZH530Z8WrXD7nwuwhs7bs/YQ+3sgKEERq1mWCwQGYMRGQN9BwJgZmdgbvgL/v0Lc8OfmGt/dSQ0goIdiYxuvTE698AIbHDc/Rd/0Si9RlHNPUVEREQEwNyXhX3WM7D1X4zrhrq+/S7doBMqNlWkrr6/POecc2jdujW//vorWVlZREdHc+WVVxITE+Pu0KqMeeDwuWtQKlF1eAmJmbO32j44m0u+PnJl7W9QbHl+vZWahPeZ/TnkvB4UDL6+jiUktZQSGHWMERKOceYAOHMAAGb6bsx//4INf2H+vRpWLsX08oYOXTBO741xWm+M0PBj7vNYHaGdt9fVFxoRERERKZ+ZtA37zKdh/14swx7G9uP/ET/wyHJkp/KqeetqtUV5YmJiuOqqq9wdRvXJ3e/4Wbq/QlANVGCsWgZtOsL2LZj/bSrRX7A+MgsLIGcvlsNVF4CjIj+8KeaeXW6M7OQogVHHGRFNMSKawllxmPYi2Pov5trfMNf8hvn2S5hvvwQt22F0643R7UxHc9AylppUpLln6e1EREREpO4y/1iB/ZUECAjgnagZ3NwjCttlFetzUV+/BPv9999Zv349+/aV/CB/3333uSmiKnYgB7y8wc+/5O0NGoJhwP7qSWCYaSmQ9B/GtXdiHszDTNlZLcepVfZlA2Ap/WV1s1hI3l7z8VSRkx9bIbWGYfHCaNsJy1W3Y3n6RSxPzcK44mYwDMyFb2F/4j7sE0Zg//J9zKyMox4fH59zVPmf86ezPFBERERE6jbTNLF/+wn2WZMgMhrLuAQent3TdX90dFSZiQugTk0VqawPPviAl19+Gbvdzq+//krDhg35448/CAwMdHdoVefAfmjQ8KgvRA2LlyOJ4ZxSUsXMNb86jtPtTIyo5rArqVqOU6vszQLAK7RxiZuNqFhIS8UsKHBHVCdNFRj1lGEY0CwWo1ksXHS1o3fG2hWYK5diLnwL89N3oHN3LGfHQddeJZrgHKu5Z33NpouIiIjUB2ZhAeZbL2IuW8SmoHPoMPZ+bC9EABUbh1qf/fDDD4wfP57mzZvz448/ctttt3H22Wfz0UcfuTu0qnNg/9H9L5yCQjD3VVMCY/Uv0LwNRkRTzMgY+P1nzEP5GL51aMJLZWVnAmAJK1WBERkDph12J0NMy5qP6yQpgSHA4d4ZAy6EARdipqVgLvsec/n32F+c7GgA2udcjLPPx2gWe9QLUHlLSvRCJSIiIlJ3mPv3Od4bblyHcdE1xN03BnPB0QXd5Y1Dre/vDQ8cOEDz5s0B8Pb2prCwkLZt27J+/Xo3R1Z1zNz9R/e/cAoOhb2ZVX/M/HzYtgnjQkdvESMqFtM0YVdyrR0VWhXMw8+1JTQc7EduN6KbYwJm8naMWpjA0BISOYrRJArLFTdjmTwPy/0ToO0pmN9/jv2xeyl6diz2pd9iHsw77pISZzWGiIiIiNRu5s5tZD74IGzdwANrn8JyxU2YWEhOTinzfSAocVFaZGQkO3c6ejPExsby7bff8tNPP9GwYTkf+GujAznlVmAYIeGuqoCqVJj0H5h2jNiWjhuaxQJgpp5YHwxzVxL25d8fmahSW2VngmHBEhxa8vZmzSEgEDauc09cJ0kVGFIuw8sLuvbCq2svzH3ZmL/+gPnzIsw3XsD88DWMgZdiDLzkmEtK4EgyQy9eIiIiIrVL4lR/Hmg3D/N/H3IoN4QF7RL5JKUPn0Q77i9vqggocVHatddeS06O4zm58cYbmT59OgcPHuSuu+5yc2RV6MB+jOgWZd8XGgbZmZh2O4al6r5HL9y+xXEhuqXjZ5MosFjgBBIYZkGBY6pOWgqcexHGDcOqLM4atysZQsMwvEp+5De8vKDdqZgb/nJTYCdHCQypEKNRCMagKzDPHwxb/sH+9ceYn7+L+e1CRg+4EGPQ5UBzV7lg6fWOxed/i4iIiIhnS0gIwjpkNYN+n4357xb+aXQ+1379ENnfh5TYrr5PFakou92Or68v7du3B6Bt27bMnDnTzVFVg2NUYBAcDkWFjkkkjUKq7JCFO7aAtw80aQaA4eMDjZudUAWGuehTR/ICMHdsrbIYa5pZVIT5z1rHlMkyGKd0xfxzJeaeXRiNI2s4upOjJSRSKYZhYLTthNd947E8PgOja0/Mbxdif/huRjebysuTc4GSlRjFM/NaViIiIiLiuRISgjALDuH75WvYnx1LiM8+bv89kf9771myC0Jc22mqSOVYLBamTJmCt3fd/f7YzNkHB/MgNKLM+43QMMeF7KOnHZ7wMU2TQ2tXQIs2jsoCp2YxkFq5SSRmZjrmFwug25kYAy6ClB2OXhrVyL7iJ4oeugP7S89V7Y63/Qu5BzC69Cjzbmdiw1y1rGqPWwPq7m+QVDsjpiXG0LGYl9+I+b8PMX/6mjv5ht7Xn0/XsZcT071nie1LLysREREREc+y5NWt3LL1CUa02cm7Oy5n0j+j2Fd45AsoTRU5caeccgobN250VWHUtLVr1zJ//nzsdjsDBw5k8ODBVXuAlB0AjjGmZQk5PA0jOxOat6maY27fTOH2LRg3jShxsxHWGPPfyvV4MD+cD6aJ5Zo7MP9eA3m5kJkO4Y2P/+ATYF+5FPOVqY5jZ6ZXaTWE+dcqxzKaTt3KvN+IaAqt2mMu+RpzwEUY/gFVctyaoAoMOWlG0ygst43EMulljHP+j86532OfMIKZ3caRtGqlGnyKiIiIeLCEhCDM/HxWPvgGH/W5i9y9Bdy44gUe+msC+wqDsFpzXO/jQM05T1Tjxo159tlnmTVrFu+99x4LFixw/Vfd7HY78+bNY9y4cSQmJrJs2TKSkipXoXA8Zsp2x4XjJDDMqqzAWLYIfH0xevUreUdwKOQdcEwoqch+/vkDc+VSjAuuxGgceaSPR/J/FY/lYB5mxp4KHdPcsgHz9ZnQpiOWZ14Gw4L586IKH+u4+//rd2h7CkZg+Q1iLVfdBhlp2Kc/gbk3q8qOXd1UgSFVxghvjHHDPZiXXIP57adc+N3/sD+xmFXBQwjyHlFmg0/Qi5+IiIiIOzibrC9/7V8Gr3qa7g2SeH3H1UzecB8HihpgteaU6GOmxMXJOXToEL169QIgM7Pqp3Ecy+bNm4mMjKRp06YA9O3bl5UrVxITE1N1B0nZ4ZhuERpe9v2NQsAwIKtq/t/N1CTM337Cv8+5FAQ2KHlnyOHlKnszXb0xyt3P3izs8xKhSTOMC4Y4box2JGHM5B0YXXsd+/E5+7C/9Cxs/BuANIDABhAcBiFhGI1CHNcDGkBgQ8hKx1zyNYSEYRn2MEZIGHTpgblsEeal12FUYJmRmZaKuehTR58Obx+MM87BODsOw+KFuX0z7NyGcdXtx9yH0b4zxt1jMF+bgX3c3dD2VMcyH/9AKL4c56QYRy56+2C54qaT3qMSGFLljEahGFfdhv+gyzE/eYseyz5g5YXf0uDGm2hx3c3sTN7tKj1UCaKIiIhIzSk+Ge79F3MY3XAK75/5MzSOxHLrM0w4b9DhZSINjnqPpvdsJ2fEiBHH36iaZGZmEh5+JLEQHh7Opk2bjtpu0aJFLFrkqASYPHkyEREl+1kUZaaTu/BtslOTCOzaE7+z4/AKDcc0TTI2rcer7SmENi5/ycWekDB8Dx4guNR+zYICzMICLAGBFfr/ObThL7KfewjDx4dGV92KUWp/+c1bkQ0EU4RvRNk9OQDMwkKyEh/DnneAsCem4RN1eLwOEeyJaIpveupRsZZ4vGmS/dKzHNq2iQbX3oElrDHG/n0UZOzBnpmOPXMPRds2YuYewMw9APYisHjhf/ZAgu4cheVwM9ODcZew1/Y4IQey8WnT8dj/7+vWkD1pLKa9CJ92nbDvy6bozVl4LfkfXrGtKFi/FqNhIyKuuAFLYAO8vb2POo8uF15BYedu5H6zkIK/12LfnYyZdwDs9mPGUBGl+4dYAgKJuHvUseOpACUwpNoYjUIxbr0fc8BFBL73CuYbL/D5Wd9xRecxwJHmnupaLSIiIlK9nIkLmy0I64jd/PbEZyw+50NyfzN4aevdvPj1rRx83d+1vaotqsahQ4fw9fWtsu1OVFnNKA3DOOq2uLg44uLiXNfT09NL7idnL/ZvPsESEk7+78vIeX0WxlW3YcS2wp68Hft5lxz1mOLsjUI5uCuZgmLbmKaJfeo42JWM5alZGOVNMXFu/+9f2BMfh7AILNaJGDEtj47TcFQQZG/fhqVJ+VUm9k/fwVy/FuPO0extGALF9mOPjOHg1k0lYj0qlo3rsK/6BeOaOzkYdzkAERERHCj2GOPwf6ZpOpqcevtQ4OND5qFC1/HMAMdSj+xtmzGCj5EwycvFnjABQkKxjH4Ke1hjTNPEWL6Ywl8WU7hpPUTGYLn4GjJz8yA3j4iIiGOeEwKCYPDNMPhmV6zVJT09vcx4oqKiynnE0dQDQ6qd0aINlgefxRg6lhbhWXzY525e6PYIUf67AMeIVZstSH0xRERERKqY8/2VzRaEaS/i+thP2H3PCHplvsOXqXH0X/IxiZvuYcSoApKTU5S4qGJ33313hba75557qjWO8PBwMjKO9J7IyMggNDS00vsxgoKxJL5N4zkfYXlqNpxyGuaCudinPgpBwRg9zjr2DkLCHE08izF/W+JYfrEvG3PRZ8d8uFlwCPtcGzRuiuVRm6MZZXnHAccSkvL2dWA/5nefYvQ4C8uZ5x79/xrdHHbtxDxGNYK5+hfw8cXoN+iYccPhaY4BgY4xr0fFe7g/yHGW15g/fQPZmVhuH4UR1ti1X8tZA/EaMwmvSXPwsk7E6NDluPHUVqrAkBphGAZGr36EdD0D85uPGLTwEy5rsYTE9bcS/80gYlq3cjX31AumiIiISNWw2RwJjLPCV7Du+kSe67KJ3zO7csfvNv7Y2/nwchGNQ60uhw4d4oUXXjjudkVFRdUaR5s2bUhNTSUtLY2wsDCWL1/OyJEjT2hfhq+f42ezGCwjH4O/12Du3Orow9Cg/KaRAEZIGOaWf1zXzYJDmB++Bi3bQe5+zNSdx3y8+csPkJ3hqLw41rECG4K3z1HJkhL7WvkT5OdhXHRV2RsEhUBhIRw66OgLUdY+1v4Gnbqd/BSPRsGOqSHHaHBqmibmz99Cm44YrTuc3PFqMSUwpEYZfn4Yl93A2+sHc3baHEa3e4Wdd37GeY0fITr67BLb6gVUREREpPKcXwglJATRqsF2Oi2ZzqjeP7EztxkjVj9L++t789VH+4k+vNzfWXUhVW/IkCEV2q7KR5qW4uXlxR133MGkSZOw2+2ce+65xMbGnvR+DcOAzt0xOnev2ANCwmF/DmbBIQwfX9j6L+zNxHLTMOw//A/S0475cHP59xDdAjp2PX5cgQ0co1DL29e61RDeBGJbl72BMylxMK/MBIa5fx9kpGGce/ExY6kIw+LlaPqZdYwJLWmpsCsZ44ZhJ3282kwJDHGLoQ8HAqN5d+JgrilM4LWAURh9zqPzk+OJj9+v5p4iIiIilVS8z8X8mUXc3/ZlFvV7n3y7H8/9ey+Bl17GFz+GkzzGMRJVy0Wq39VXX+3uEFy6d+9O9+4VTDRUl4gmjp97dkFUc8zNh6sx2p2K8ddqxwSNcpg5+2DrvxiXXFtm/46j+Ac4kg9l7auwEDb8hdG7f/n7ciYw8vIgpIz7kx1jY42YlsePpSJCwo45Ytbc5JhyYnToXDXHq6XUA0Pc6voJrZjZ8BWmb7qTgmVLWHTONdx6uuMPV0KC+mKIiIiIHEvx90o2WxBm7gGs7ebwx6WXclfr9/gw6VIaTXuRWVtuZ9TY/BLVFkpcSE0zYtsAYG7f4vi5eT00i3U07oxoCgdyMMupmjDXrwHTPO5YUxc/f8z8g2XftzsF8vOg3Snlx+qsuigvCZL0n+NCVSUwQsOPueSFjX9DwyBodvKVM7WZEhjidqPG5mNeehMLWs8m41Aor/a0Mu20Cbw6s0jNPUVERETKULw5J8D0530Y1vp1MoYPY1S7V/hqWx8GLlnAQ+vGYwSHqtpCPEOzaPD1g+2bHc0xt/yL0a6T4z5nQ8703WU/Nvk/8PKGmFYVO9YxKjBI3QGAEdX82I8HOFjOMpTk7Y7GpcGVb4ZaFiMk/Ng9MJK2Qct2Fas+qcOUwBCPEB+fwy2PNuPSZW9gXHodlzb7lj+vvIpBTX90reEUERERqe9KJy58LYcY13cp1/x5E+M6zmRt9qlc/PObbDx3Aj/+66/EhXgUw+IFzdtgbv0XUnZA3gFo46iCMI6TwDBTdkLTKAzvCnZB8A8sv3oiZScYBjQtf8QqAcV6YJS1j4y0I0mXqhASDnm5mGUczzRN2LMLo0nFx43WVeqBIR7l/tEHSdx0D18vu5SpXZ9kbo8xfHTx/zH/77GA44VaL8AiIiJSXzkTF15GIaN6/84P57xCbGAqv2Wezog1k/lkXVNujY7i63hHnwu9bxJPY5xyGuYX72GuWua43vbwMo7DyQAzfTdl1hik7sQor+FmWcfx88fML6cCY1cSRDTF8PMrfweHKzDMg3llx5OVAc2OkQCprNDDo1+zMyCy1H5z9joSKY0jq+54tZQSGOJRjrzIRtH1gclMGfgtY06Zy1nhK2l67lBiLr1KL8QiIiJSrxSfKmJgZ+M7v/Jdv5do23A7f+49hd9jRnHlyx1ZERMNpGiqiAfKzs7mzz//5L///iM3N5fAwEBatmxJ165dCQkJcXd4Ncro1Q/z83cxv1gAYY2PfChvGAR+AZBx9CQSs+AQ7NkNvftX/EDHauK5OxmaRh/n8c4eGOUsIclKx+jUreLxHIcREo4JjsRI6QTGnl2ObRo3q7Lj1VZaQiIeKT4+B9v0UGZsvovzf3yLXQebYH9xMpNOfZZpz/tqSYmIiIjUecWXi8RER/LvO7/x9dk3MLv7I9hNLz6PfopLlr3BVY+fgmEYWi7igZKSkkhISMBqtfLTTz9RVFRESEgIRUVF/PTTT1itVhISEkhKSnJ3qDXGaBYDLds5Lvc829XTwTAMiGiCWdYSkvQ0MO3QpBIf4P0DoLwmnnuzMULCjv94KDMJYublOm4PDa94PMcT4tiXWUYjT3NPquNCZf7/6yhVYIjHOvLi25TLE1/jwfazGNbmTf75/Q/uXfMsEKEXaBEREalzio9DtY7O5rJmX/PCRXMgdSeb97fAuHM0g668jp3v7WZL0H7X4/S+yPPMnj2byy67jJEjR+Lj43PU/YWFhaxcuZIXX3yRSZMmuSFC97DcMRr7GzMxBlxY8o6IpmX3wMjcA4AR1qTiB/Hzh4MHMU2zRONL026HnGxoFHLsx/v4gpcXlDUVxdlsM6QKExjOZEhZjTzTD1elRFTi/7+OUgJDPJrzhdhmC+LexVdzw2m9eHPgBL4IvJkGve8mYeoVxI/Zf5y9iIiIiHg2Z9ICHO97DLOIIVFfsvHGV3nh9O1s3Nia6Zsn8WVqHDvf3c0oq+NDlZIWnu2ZZ5455v3e3t706dOHPn361FBEnsFoFoPXQ88dfXtEU8wNfx11u3k4gUF444ofxD/AUbVxKN+RzHA6kAN2+3ETGIZhOJa0lLUMJSvdsU1oRMXjOQ7Dzx8CGjiWkJS2LwsCG2L4+FbZ8WorLSGRWsFqdaz7XJLel14L32NNdhfM12fSYvEUZkzx0pISERERqZVKTxVJnBrA1TGfcfnq25jW7XEK7D4MWz2Zr3q+wku/d1HiohabMmVKmbdPnTq1hiPxYA2DID8Ps7Cw5O2Ze8CwQPBxln0U53d4CUjpRp77sh0/G1Vg/GlA2ZNMzL2H91FFI1RdghrB/n1lH6+qj1VLKYEhtUJ8fA7x8TlYrTms3lrAjStewLj8Ri6L+pZ7997Fd3Prz7pBERERqd2Kf/HiTFz4GAXE917B4DW3kdD1KXIKG3DXqql802sOX+2KI37MAUCJi9rs77//rtTt9VJ5jTMz9kBIWMVHqEL5PSwOJzCM4y0hObwPs6wmnrmO30cCG1Y8nopoEIR5oIzq8n1Zx1/yUk9oCYnUKs4O3Ha8iL1nNGeEDmBGt/F80vd2vn/0HtaGXqklJSIiIuLRbLYjU0V8LYd4qM9ylgx4jZiAXfyR3YnH14/h9dWt+TYmmvljUhzfPEuttWDBAsDR78J52Wn37t00blyJZRF1XUADx8+8XGjYyHWzmbkHwiq3XMPwD3BM9ThYspGnuTfLcaGCCYwyl5DkHf68ERBYqZiOq0FD2F9GknJvFkarDlV7rFpKCQypdYp/82Cznc4FP7/N1K5PMcgyi4K//uQF+xjue7DMac0iIiIiblO8z0Xr2HCui13I0v6v0ywgjVVZXVjZbjRXvtyR72OiMYwUTRWpIzIyHD0N7Ha767JTREQE11xzjTvC8khGgDPpUCppsDcLoppXbmfOvhflVGAQHHL8ffj6OXpolJZ7APz8K1cRUgFGYBDm7pQSt5mm6fj/r0i89YASGFIrFW9y9fd/uURHJ7DzjZc55+3XOD9rKOaOh5n4YlOGD3dzoCIiIlLvFe9zMXuaD3e2fIdhrd+gqX86KzK7ET3uPq44/0KSP3SMSlTiom4ZMWIEAO3btycuLs7N0Xg4VwXGgZK35+7HaFDJ5RoB5SxH2b/PMV3Eeaxj8fWDnKN7UpCXW/XVFwANGkDpJST5eY4kinpgAOqBIbWcs7knGMTecg9X//oKqTtNcp94mH/m/w9ADT5FRESkxpXuc2G9bw9DW73Jxqsv5vFONpqe1gxL/NNc9esrGJ26YbVqHGpdtHfvXtflYyUvsrOzayCaWsDZAyOvVNVE7gEIrEDCobjDCQozt1Qy5GAu+AeWGK1aHsPPv8wKDDP3QMUSIJXVIAjyDjhGvTo5G4YGhVT98WohJTCkVive3DM5OYW1ezsTPXsq/p3ak3jaE9jffomZif7H35GIiIhIFSg9VWTGFC9GtH6NPXcPZfwp01m6rQNX/fIy04wZGB27uhIXSlrUTU8++SRz585l48aN2It/KMWxpGTjxo3MnTuXiRMnuilCDxPgaLxZvHGmeSgfCgsq3zDTWbFRupojL+9Ig8/j8fOHQwePvj3vBBIqFdGgIZimo8LDKdfxN8JoqC9lQUtIpI4o/qIfc0onvIxXeKjDLIbxJgvOTOKlyRM44BOhNwciIiJSLZz9LZwNOoO89zP5nK+4q9W7hHbcyw9pfZmx+U7639Gas88+8t5F703qtilTprBo0SLmzJlDWloaTZo0ISAggLy8PNLS0oiMjOT888/ntttuc3eonqGsJSSHP8BXOoHhXOJRakmGebASCQxfP8gvpwdGdUwFCTycpDiQc3QCpjoqPmohJTCkTrFac1xdvZ+xPcAf2acyteuTNF8/jBGrnwXa6Y2CiIiIVDlnxUWITzYJAz5j+bnvEeyzn+/Tzmbaprv4an0Yt0ZH8Vl8ynH2JHWJt7c3F1xwARdccAHp6ens2LGD3NxcGjRoQIsWLQgLC3N3iJ6lrCUkBw5/gK9kDwzD28eRgChdgXGwEv0rymvimXcAo2lUpeKpCKNBQ0cT0+JJF+dzEVDBpEsdpyUkUqeU/jbj5VWduHz5azRp7s97vYcz+rS3SZhaxfOaRUREpF5yLhdJSAgiwjcD/y9f5ZdzL2VUu7ksy+jF2y1fZtCnD/LH3s7AkeacUj9FRETQvXt3zj77bE4//XQlL8ri6wsWS8nGm84lFJWtwABH1UbpHhh5uUcSJcfj5w9FhZiFhSVvP5GeHBXhTNIcOPK3wlQFRgmqwJA6a/z4IhISgti4P4pT33wbW9fH+b8Fc2mRnMR0cySFlgBVY4iIiEilFV8u8vasPIa1fpll536Mr6WAz1PPZ99Z1zL+q64kf+6ottBUEXH677//+Oeff8jJyXGMxzzs2muvdWNUnsMwDMcH9apYQgIQ2AAzt9RUj4N5GE2aVezxvn6On4cOgrfj+KazR0V1JBScjUfzcnG1GHUmcyqadKnjlMCQOmvChCLS04+8YYiJfp4dL8/g8k/expK7gb5vziA+3s1BioiISK3gTFrA4akit27mmc6vcVPrz8Bu5/0dF3Pd/IsY2aMXyV+mkOl3JFmhxIUALFq0iNdff52uXbuydu1aunXrxp9//knPnj3dHZpn8Q8osYTENUWkwQkkDAIbHF2BUZkeGH7OBEb+kQTKoUNQVFg9CQzfYsdzynUmMLSEBLSEROoBZ08MEwuxQ0dxy8oZ7N2Wwed9b+G9iVs1ZlVERETKVXqqyLxn9zK165PkPzSMq6M/562tl9H3+4WM+fNxjMhoVVtIuT799FPGjRvH2LFj8fX1ZezYsVitVry8vNwdmmcJbHBk2QScZAVGwyOPdzqYW4kmnoenGRZv5Jl/OLniXw2TDv3KSGAczAU/fwz9OwGUwJB6wjlq1WrN4af0Ply2/DWyCoIZ/F88uz74TkkMERERKaF04qJ9wy18dPEsbt5yK5c1+5Y3tl9DvyULSR90P79t1jIROb59+/ZxyimnAI6lEna7ndNPP51Vq1a5OTIPExQMOXuPXHc2tDyBnhNGqQoM014E+QcrvBzDcFZE5BcbpVpwyPHTx7fS8RyXM2FSfHRrZXp21ANaQiL1RvGyz583+tCxxev8bY1nsuUZjGZrSZw6mtFj8o6zFxEREakPnImLUxtt4PNL57HonB84UBjAK1tv5OVtN/HHtnyejG5K/OGpIkpcyPGEhYW5Rqk2a9aM33//naCgILy99ZGsOCMoGDMt9cgN+Xng64dhOYEKhIBSS0gOOid6VKKJJ5SsiDhUnQmMw/ssXvGRV4mpKfWAfluk3rFaHUtKcgob0nLKbB7u8ALDeJMe6WnMso/noFew3oSIiIjUQxMnejF8uKP6olvwOjovmceos5eyr6AB0zfdid9Fl3LvfAvPRIcDKZoqIpVy+eWXk5ycTJMmTbjqqquw2WwUFhZy2223uTs0zxIUUrICI//gkURCZTVoCHkHMO12DIvlSG+NCi8hKdbE06nAkVxwVWdUIcPiBd4+JRImZmXGvtYDSmBIvVM8OREfn0N09AMMnxRBj1dmcVbWPcR9PJ34eP2REBERqS+cDTqfftqLb2ft4oF2TzPqrBVkHQrm+X+H0fCSi0n4rhnJD2qqiJy4AQMGuC6ffvrpzJ8/n8LCQvyro5dCbdYoGPIPYuYfxPDzd3yYP9FkQUADME1H5UVggyMVGBUeo+pcQlJDFRjgSNaUXkKiBIaLemBIveVs7gkQe9WNXP3ry+xOKmJh3zv45Ik/1RdDRESkjjvS56Ih5vo1fHDm3XzYZyj9Wv3LpH9GEj7nZWZuuYv7HjRLVFsocSEn4sEHHyxx3dvbG39/fx5++GE3ReShgoIdPw9XYZgnk8BocLjxp7Mp6OGRpEYlm3iaxZeQOHtgVEMFhmu/h0otIVEPDBclMKReK97c84+9nblk2Rts3t+SS5ImcOjT90mYegLdjkVERMRjFf+CwmZryMdPrmNhn9uxJz5O84BkHvt7DO0++JI5227B8A9QtYVUmV27dh11m2ma7N692w3ReC4jKMRxwbmMJP/EExiGc9SpsxGoK/lQweqJspp4HqrkPirL1+/IMQAO5lU84VIPaAmJ1HvFm3uu3lpI69iX2fz4ozxovIjRaB3Tnx/HA2ML3ByliIiInAznMhGbLQjr6L189uRavjrrHTonbWSHXxQP/zWOD5Mv4b5R+WyNz3QlOpS4kJP1wgsvAFBYWOi67LRnzx5iY2PdEZbnanS4AmPf4QTGofwT74HhnFzirMAoOPyevqLLP8pq4nm4BwY+1VSB4eeHWSJhkn9kKYsogSHi5GzumW/3J/bxqQxr/QYPmy/Qf99o5kx+kv0+TfQmRkREpJay2YKwjsrm8qiv2XDDq1wStJUtXs2x/vEEC1MuYOToPA7ZfImPTweUuJCq07Rp0zIvG4ZBhw4d6NOnjzvC8lyHl5CYOdkY4Kh+cC4rqazAw9XUzkkkruRDRRMYR1dgmDVSgVEqYVJdyZJaSAkMkcOObu55K+NnhdDSZqPLnnu44usE4uMbuzFCERERqQxn1UXi1ACujvmMLTfPZ2a3nfyb05p710ziy9Q4dibv5sNob+LjcwgM1DpzqXpXX301AO3ataNbt27uDaY2KL2E5GQqEA5XYJi5+zEA01WB4VOxx3t5g8VSKqFQzU08ff1dvTpM03QsJ6lovPWAEhgipRRv7hlz4eW0bdCVeT2tvNd7GP+bMJr1IRfqWxkREREP5kxcvDDNj7QPv2F469eJ7ZrKX3s7MHTVFDrd0IOX3jtAdLQXcGSqyIQJRaSnuzNyqWvWrVvnuuzt7V3ienGdO3c+6WP98ssvfPDBByQnJ/PMM8/Qpk0b132ffPIJixcvxmKxcPvtt3t0IsXw8wO/gBJLSE54ZKlzCYmrAqNyyQfDMA5PBSljCUl1VmDszXRcLqzkkpd6QAkMkTIUT1DYbK24bNnrzDr9EQZ5TWHHLzuxmXdiHZPrxghFRESkNGfiYvY0H0af9hk/D/iUSP890LoDty54iDfXtOLrmGjmjdE4VKkZL7744nG3MQzjqN4YJyI2NpYxY8bw8ssvl7g9KSmJ5cuXY7PZyMrKYuLEiUyfPh2LxYPnOTQKhpxsx+WTmULiHwiGUSyBcQIJAV//spt4VtOyDsPX78jUk+qeeFILKYEhUo7izT3Xb99P85jp/JfwDHctehe8/uGFKU9x34PH2YmIiIhUK2fSAmDOdAs9Mr5g2bkfYi7IZNuB7oz+40mWfdULMDCMFI1DlRo1a9asGjtWTExMmbevXLmSvn374uPjQ5MmTYiMjGTz5s20b9++xmKrtKBgzJyTb+JpWCwQEAi5zikkleyBAY5Ki/xSS0gMA7yr6aO0X7EpJIeqeblKLaQEhshxOJt7FpnexFof45qY03jG/iwX5N3Lq89MJMuvhd4AiYiI1LASU0WGp/LzxO9Yfu7HhO7Zy5J9ZzJz852syDodqzWH9+NTNVVEPEJhYSGbNm0iKyuLvn37cvCg45t9f/8TnLJRAZmZmbRr1851PSwsjMzMzDK3XbRoEYsWLQJg8uTJRERElLmdt7d3ufdVhezwxhTt2U1YeDhph/IJDA6l4QnGsqdhI3zthQRHRLDfx4cDQERkM4wK9pXIaNAQL8Mk5PAxcry8yPX1o3HjsnvjnexzkxMcQl5BPhERERQW5pMBBIWFE3CC+6zuc1VZJxuPEhgix3F0c8/Lsb3dgIZPTeHWXSO49adnIL61GyMUERGpH4pXW9hsQViHJjOm/UKyRyygr88Bvsvqx4zNd/LH3s5YrTmssB15HVfiQtxtx44dPPfcc/j4+JCRkUHfvn1Zv349S5YsYfTo0RXax8SJE8nOzj7q9uuuu45evXqV+RjTNCscY1xcHHFxca7r6eU0hYmIiCj3vqpg9w/EzMogPTUFTJPcoiIOnmAsdv8ADmZmUJCejn1vNhgG6dnZjv4WFVBk8aIwZ5/rGPa92eDjU23Pjb3Ijpl/kPT0dMzduwHIyc/nwAnus7rPVWWVFU9UVFSFH68EhkgFlWju2T+OKP/OvNIjnvk9R/PjuKH0n3QRNlsjvUESERGpJjabI4Hx4nMFPNpxGvtHfsh9bfL5367zmLn5DtbndCA5OYXoaCUsxPO88sorXHvttZxzzjncfvvtAHTq1Ik5c+ZUeB8TJkyo9HHDw8PJyMhwXc/MzCQsLKzS+6lRQYd7YDh7T/ieRIVKQIOSPTB8fCucvAAcy1eK98Co7rGmfv5QVIRZWACFjiUkhpaQuHhw5xYRzxMfn4PV6vgv5WAkV/4yjy9T4+i3Zw4fXvwSs6ZpxJGIiEhVc36BEOm/m7nnv80t/97AXa3e4evd53L+0gVsOnc8320Icm2v5pziiZKSkujXr1+J2/z9/Tnk7HNQTXr27Mny5cspKCggLS2N1NRU2rZtW63HPGlBwWC3w85tjusnM/EjsAHkORMY+ZXvJ+HrV3IKyaFD1duTokFDx8/9OUd6YFTXxJNaSBUYIpVUvHR1y85MoqOf4bIRTRmy8C1aN9iOmTUW26st9aZJRETkJDkTF+/NPkDYN2+wtP+nWAw7HyVfzKwtt7N8kxejoqOIj9dUEfF8jRs3ZuvWrSXGm27evJnIyMgq2f+KFSt49dVX2bdvH5MnT6Zly5Y8+uijxMbG0qdPH6xWKxaLhTvvvNOzJ5AARkQTTMCe+JjjhhNs4glgBDbEPOBs4lkAFex94Xq8rx9msSaeZsGhak0oGI1CMAH2ZRdrOqopJE5KYIicoCNdzA1ih47i/CbdmN7tMVJHjuX7VVOBFoDeRImIiFRG8T4X77+Ywy+Pz2LEgO/x9YG3tl3GLW9fyI0RTXkwOgrQVBGpPa699lomT57M+eefT2FhIZ988gnfffcd99xzT5Xs/4wzzuCMM84o874hQ4YwZMiQKjlOjYgt2V/OOJmJHyUqME6gesLPHw6VGqNanRUYjUIcP3P2FhujqgoMJ89OvYl4MOebJKs1h+TkFF5b054rfnmVpjFefHDmUEaf9Rk2W9Bx9iIiIiJwpNrCZgvC3LOLP8a8xJL+V3Dwh8W8t3MwZ363kHHrxmF73VH6rmoLqW169OjBI488wr59++jUqRN79uxhzJgxnHbaae4OzfOElZrw4XsSFQiBDSD/IGZhIebhHhiV4udfcglJQf7JxXM8QSEAmNkZmKt/cdzmrQSGkyowRE6S841TQkIQ/+ZEcdq7b/Ni94foOy+RcR3SsU29FdPw0hssERGRMpQYh3rzvzzf5RUOPfwVbU0v3tp5JS9uvZVdB5seTljkaKqI1GqtW7emdWtNrzue4k02LeOmQst2x9j6OAIP95TYugHWr4Gm0ZV7vK8vFFtCQmEhNKi+sbfOCgzzvVfgYN6RGARQAkOkyhx5I+XFTYmzeLxTAsPavMn3S7cycu0kIEhvtkREREqx2YIIObQTW9c5HHrkay6P8ub17dfw0tZb2J3fWFNFpFZbsGBBhba79tprqzmS2sfy4GTIycZo1f7kdhTYAAD78+Mc1yvZAwNffygqxCwsdCxlKSwAr2r8GO0f4KgScSYvoHqXrNQyWkIiUoXi4x3fDBWa3tzx7c088tcjDGz2K5/2vRXrjRtc5bEiIiL1mfP18NVnsph22gRu3nIbFzdbxKv/XcfZP35KzoVDWb21wLV98T4XIrVJRkaG67/U1FQWLlzIunXr2LVrF+vWrWPhwoWkpqa6O0yPZLTrhNG978nvJ6BhyRsqm3xwNhB1LiMpKqrWBIZhGI4pLMWpAsNFFRgi1cBqzSEhIYi3d17Jpv2tmNP9QbIefpCVa54lgVMBfZMkIiL1j3O5yOcv76HV4rnc3Ow7Djb145VtN/Ly1pu45T5f0mxBmioidcaIESNcl6dNm8YDDzzAmWee6brtt99+45dffnFHaPVHgwYlr+flVu7xzn4Xhw46qjmclRjVqVEIZO45cl1TSFxUgSFSDZyVGFZrDp+si+TS5W8Q3CqcN3qNZPRpb2GzNTz+TkREROqA4tWHX76yG/tLz/Fdv2u5vNVPeF04hL4/fs69319N+qFw12unkxIXUpesWbPmqCkhvXr1Ys2aNW6KqJ4oXYGxf2/lHu/nTGA4KzAKq3cJCWA0jSp5Q3UnTGoRJTBEqlF8vKMSIykvio7z3uDb3f0xF8zj+S5PMe15Py0pERGROqvEVJGd29gw+nm+63cd+35dy6wtt3HaF18QO/IRMg+FAqq2kLovMjKSr7/+usRt33zzDZGRkW6KqJ4oXYGxf1+lHm44KzDyiyUwqjuh0LJtyRiKNTWt75TKEalmxd+IDbM9x6h2rzC63Sv8/tt27lk1BQg6ajsREZHaqsRUkavW8nJ3G/anfqRpQQOm/XcX8/67nr0FwVitOcTHp7gSHXodlLpu2LBhTJ06lc8++4ywsDAyMzPx8vIiPj7e3aHVbY1CS14/dKhyj/c93AMj/6DjZzX3wAAwWrbDrNYj1F5KYIjUAOebMpstiDE/XsrdPdrw0pmP8/lZtxJz1UPE9D1Hb9xERKROsNmCaJL3L/N6PI/96aX0CQ/CtnEo8/+7jr2FjQ5PFQnWOFSpd1q1asX06dPZtGkTWVlZhISE0L59e7y1PKBaGRaLo4+FcwlIRNPK7aB0E8/CQvDyqroAyxKrUbvl0W+LSA1yNvf8alccF3wfy9ye8eQ++QiXNnuMhARHl2W9kRMRkdrGWXXx1tNJzO/5HAO3LyM7tBHP/zuM17Zfx90jTdbH5xAd3QjQVBGpv7y9vTnllFPcHUb9E9MStv6Lcd3dGD3OqtxjizfxhBpZQmL4+WN58WMwDLDbq/VYtY0SGCI1qGRyIopLX3iDOd0fZNbpjzLzi9uZunF4GduJiIh4Jmfi4sdXt9Ft6Stc3/gXskKCee7fEby+/RqGjjTJsTXUVBERcSvL0LGYX3+E0f/Cyk8QOdzE08zPx4AaaeIJHImzuqs9ahklMETc4MiSkijOXDCBty5+i/vbzqdTo02cP/xeEhIi9eZOREQ8ljNxsXT+FkYZM1nY9w9o2Ahj0K30vecONu7Yy6zoI4kLJ722iYg7GOFNMG4cfmIP9j2yhMQ0zRrpgSHl0zMv4kZWaw626WHY1o3j733teaLTVDbeuZOFqxKAcEBv9kRExDM4kxYAy17byJU7XuKjPmvYszaMOVsf4M0dV5H3fsDhrfeq2kJE6gbnGNX8g47qC1BVhBtpjKqIG8XH5xyeeb+fyb+cxfW/vUjbZtl81vdWrHGLsdk0ZlVERNzryDjUhpgb/mT7yAl8cOY9+GXu4Mn1oznrh894edvNDH+gkOTkFCUuRKRuKT6FpPBwAsPbx33x1HNKYIh4gPh4R3PPFVndOfPTt9meG0vhzKe5v81cEqY2dL15FBERqQnFX3dstoaY69fy4Zl3Y08Yj09WMo//PYazfvyUef/dyIhRBQCaKiIidZO3N1gsjvGrRUWO21SB4TZaQiLiIY684WvAkGlzea7LJMZ2eImvftyI9c8ngCC9KRQRkRphswVhte7jo6c28HGf8dgT/yQ2oAnj/36QBTsvJ9/ud3gcapRem0SkTjMM4/AY1oNQ5EjYVvcUEimfKjBEPIhzSUm+3Z+rvhzGxH9GcVHUjyzsezvWmzeqEkNERKpVQkIQpmlybuOf+f3qR7ki6SGa+e9m3LqH6bdkIRFXXsjWnRmu7bVcRETqBT//w0tInBUYSmC4i555EQ9kteZgszXilW03sSGnLbO6jSNz7FhWrn2GBE4F9GZRRESqTkJCEJgmf769hjW/zuX1XuvZmduMh/8ax4fJl7BtZzpvRfsSH58OKHEhIvWMrx8cyi/WxFMfo91Fz7yIByr+hjA+vjl92r7Bzzc9wBs+I/Huciuxt4/Qm0YRETkpzqkipmmy7u1VzL1iNvTcChFNGbt4PAnLTud5bx/eifYFjiQtQIkLEalnfP0w8/MxnAkMLSFxGy0hEfFgzuaeO/Ji6Pjqm3yzawDmB/OZdtpjTHve8YZSy0pERKQySkwVWfMru+6PZ26PMfz3zyGsfzxO6zc/ZUHSYGzTwwBVW4iI4OfvqMA4PIXEUAWG2+iZF/Fwxd8wDrM9x337XmVM+5f4e+U2erWZSspBNfcUEZHjc1ZcJNoaYD33W/539kfYZ29k/4HmPLv5CRamXECR6X1UwkKvMSJS77maeB7ugaEKDLfRMy9SCzjfPNpsQTzy04Xccnp75vd7lF8vv5Grvn0eiHS9MRURESlLoq0BbXKW8tXZb2F/cSMBXs0ZtfZJPk39P4pMb00VEREpj58/HMiBwsNTSDRG1W20hESkFnF+K/Z9Wj/O/foNNqeG8G7v4TzS92dstoYkJARpSYmIiLgkJARh2u0sfGIN/zv7Ri5NfowAr4M8sPYpBv70Pi2vO4cdSWmu7Yv3uRAREQfD1w/SUrFPftBxg5aQuI0SGCK1iPNbMas1h582+tJ+3mSW7OnL06dOYUqXiVhHZmKzKYEhIlLfORMX699eybrrx3Jp8uP4WfJdiYtW1/WjyPQu8boCWi4iIlKmho0cY1SdlMBwGz3zIrWQa0nJi5EkrkrA2m4OD7Sbx8rrt9HUb4qrCkNvREVE6g/XVBG7nX/eWYE9ZzYv99gOTaMxLrEy8Mpr2Zm8m0+ivY96fdDrhYjIMYSGl7yuHhhuo2depBZzvuE0uYl73mmPresTfHHWzQx99XnWZHcpsY2IiNRNJZpzDviG3fPfZ073rWz5tznTN0/ks5RB2OcfWa+tagsRkUoKKZXAUAWG22gJiUgtFx+fQ3x8Dv/bNZCgic9xsMiPT8+5m2tjFrrGsIqISN3j/PueaGuAuWoZ3/S7HvtLk9mbUcT9a59m4E8fsDDlQkZZc0lOTlHiQkTkBBkhYSVvUAWG2+iZF6kjrNYcbAu6MG/5G8zqNo7nuz7NvPOvZsY/8a5t9KZVRKTuSLQ1oO2+JXzT703sL23B22jB/Wuf5vOU87HjddRUEb0GiIicoNCIktc1hcRtlMAQqSOOvDENYsCoh3lx0Efc0/otOgZtoe/do4g5pZPevIqI1HIJCUFYR+/l8yfX8E2/t+iYsoVNRkvuW/M0X6SezyhrLjvjdxMdHQVoqoiISJUo3QNDS0jcRktIROqY+PgcbNNCmLRhFCPXTqRbyN/sHDGWLo3+0ZhVEZFayjlV5N93fuOfG6xcnPIkXkYR9615mvN/WkDb68/CjpemioiIVAPDz7/kDUpguI2eeZE66Mgb1rMZMncer/SI56M+d/Hge+NZmHJhqW1ERMRTOSsuNr7zK/Z9L/Ji9x3QLBbjkjGcf8XV7EzezWfRXpoqIiK8+eabrFq1Cm9vb5o2bcqIESNo0KABAJ988gmLFy/GYrFw++23061bN/cGWwtZnpqF/bF7HVfUA8NtVIEhUkc5m3uu29eR2NnPszb7VGZ0m8CjHadhHZWtSgwREQ/l/Pts2u1sfOdX0u4fxezuj7DpXy/uXTOJlvM+JPaK67DjWIOtagsRAejatSsJCQlMnTqVZs2a8cknnwCQlJTE8uXLsdlsPProo8ybNw+73e7maGsfo1nskStKYLiNEhgidZzVmoPtlVhuWDGb1/67mntav8WPV05m3ky7lpSIiHgQ59/jabZA7CuXsuf+B5jd/RGyMgzuXTOJ85e+x+ep/6epIiJSptNOOw2vw80l27dvT2ZmJgArV66kb9+++Pj40KRJEyIjI9m8ebM7Q639tITEbfTMi9Rxxd/Y3hl/M9beHXi++2S+CLyFVtc+REzvvnrzKyLiAabZAhl9zld82+8jzJe3kpnTisc2P8OXqQOx4+VISNuCNFVERI5r8eLF9O3bF4DMzEzatWvnui8sLMyV3Cht0aJFLFq0CIDJkycTERFR5nbe3t7l3lfTajKW3Yd/RjSNxCinCsOTnhuoe/EogSFST8TH55CQEMSCpMFs2t+aOd0fJGfCQ1wY+QQJCWe4thERkZrj6HGRzRdPrua7fm9hvrwNaM29a44kLkqPQxWR+mvixIlkZ2cfdft1111Hr169APj444/x8vKiX79+AJimWeH9x8XFERcX57qenp5e5nYRERHl3lfTajIWY+hYzK8/Jj0rC8Mw3B5PRdSGeKKioir8eCUwROqRI29+W3HJrDd5qfuDzOn+EDO+uIOEjcNKbSMiItXFmbjY9O5y/l05l4uCtrGR1oxY/Sxf7hrIaOuBMseh6m+0SP02YcKEY97/448/smrVKh577DHXB+zw8HAyMjJc22RmZhIWFlatcdZVll79oFc/d4dRr3lMD4zPPvuMa665hn379rk7FJE6zdncc3d+Y3q9+wTv7byMkW1fZV6PeKzDd6knhohINXKMQy1i87vLsD9+P7NOf5R27Qsxhj7I+UvfY86qUzGxaByqiFTa2rVr+fTTT3nooYfw8/Nz3d6zZ0+WL19OQUEBaWlppKam0rZtWzdGKnLiPKICIz09nb/++suj1uaI1HVWaw62GWHY/prAun0defyUBDbeuYOFqxKAcEBvmEVEqkJCQhDPPosrcZG+9WVeOH0H/25qzbRNk/lq13mY8458p+RMWoD+DotIxc2bN4/CwkImTpwIQLt27Rg6dCixsbH06dMHq9WKxWLhzjvvxGLxmO+xRSrFIxIYr7/+OjfeeCPPP/+8u0MRqTeKvymOjz+bIV3a8MH5D/JZ31sJibMSc9HleuMsInISEhIcDTen2QJ57KL/kf7Cq47ERUZrHnUmLrBgtea4+hSBkhYicmJmzpxZ7n1DhgxhyJAhNRiNSPVwewLj999/JywsjJYtWx5324p2xa0JntbNVY6mc1Qxzz4LEycG8ltmFGd++jav9Iin4cynua9NOi/OvhUMgwkTiqrt+DpPnk/nyPPpHHmOiRO9XH8zp9m8eOzCJXx3zmvss/1HWk4bxm2azP8OJy7Gjy/i6afh2Wf9AD+efRbA71i7l2qm3yXPp3MkUr/VSALjWN1yP/nkE8aPH1+h/VS0K25N8LRurnI0naOKGz4ccnODgAZcOW0ez3V5mgc7vMhXX/2L9c8nyM0tqrZvBHWePJ/OkefTOfIcTz8dxbB7Uvjyid9ZdM5b7EvcTpHZhmGrjyQunFNFhg/fTW5uEOnpqrjwFPpd8nzuPEeVmZQgItXDMCszV6eK7dixg6eeesrVZCYjI4PQ0FCeffZZQkJCjvv4lJSUao6wfHqB83w6RycmOjqKpKRknuz3AxM6zWDDvlZ0mvEgtjfbV0sSQ+fJ8+kceT6dI/dzThW5r/c6RradS9uG2/lnX1umbb6br3edy6PjTYYPd0wVSU5OcS0vEc+i3yXPpwSGSP3m1u4tzZs3Z+7cucyaNYtZs2YRHh7Oc889V6HkhYhUD6s1B5utEa9su4kbf5tBpN8eMseOZeUbf7vWZ2tSiYiIQ0JCELapgWx972c23jiKGd0mUGD34Z7Vz3HBz+8wd9UpmFhcy0o0VURE6oKHH37Y3SG4eFIsoHiO52TjcXsPDBHxLCWbezanb7s3WHrjA7zhMxLvLrdimoOx2fTNoYjUX87qCbOoiG3vLWX6/82BbskQ05Khn05h7u/tmWuxEB3t+J7IkbRwVJvqb6eIiMiJ86j5ObNmzaJRo0buDkNEwNURf3tuDB1ffZNvdvfH/GA+H178En6Wg4AqMUSkfnH+zZueGID91x9IHzmS6d0eY/2mQIaumkKLl9/n693nYUsMBlRtISIiUtVUgSEi5XK+6Y6PzyE6egr3tXmVMe1fol3DbfRqM5WUgxr5JyJ1n7PiYnpiAKP7fsb353yEOW8Hu/a146FNz/Pt7v6ucahQ8m+niEhdVHywgrt5UiygeI7nZONxaxPPk6UmnnIsOkdVy9l4zvxjBXsTEwkK8+aqb5/nk3WRJ9WMTufJ8+kceT6do+rVPKYJL97xKe03v03rBjv4e197pm2625W4cE4VSU4u/32JzlHtoPPk+dTEU6R+86glJCLiuZzfLNoWDeSy5a+zJTWYd3sP55G+P2OzNSQhIUhLSkSkzkhICMIsKuKrx5az+JyruSD1WfKK/Llr1VQu+vktTr2xJ0nJu1zbO/9GioiISPVRAkNEKqR4SfTl94TTbt5z/JTeh6dPncJzXZ7GOjITm00JDBGp3ZyJi+0LlrDl5pH8X+pkDhQGuBIXnW/sgYnF9TdRfS5ERERqjnpgiEilORp8RpL4u4349i8xsu2rrLx+K039priqMPRmXkRqi+JTRXYsWII9cw6Jp6VCbCssl43joouvIDk5lehoy1F/2/S3TkTqk7Vr1zJ//nzsdjsDBw5k8ODBNR7Dvffei7+/PxaLBS8vLyZPnsz+/ftJTExkz549NG7cmNGjR9OwYcNqOf7s2bNZvXo1wcHBJCQkABzz+J988gmLFy/GYrFw++23061bt2qN5f333+f77793Dce4/vrr6d69e7XHApCens6sWbPIzs7GMAzi4uK46KKLqvT5UQJDRE6I8027nZsZ9k57Ero+yRdn3czQV59nTXaXEtuIiHiiEs05+ywk660PsJ2WwrpN7UncFM93X/WHOYZre1VbiEh9ZrfbmTdvHuPHjyc8PJxHHnmEnj17EhMTU+OxPP744yWmVy5cuJAuXbowePBgFi5cyMKFC7npppuq5dgDBgzgggsuYNasWcc9flJSEsuXL8dms5GVlcXEiROZPn06FkvVLIQoKxaAiy++mMsuu6zEbdUdC4CXlxc333wzrVu3Ji8vj4cffpiuXbvy448/VtnzoyUkInLC4uNziI/P4atdcQRNfI58ux+fnnM318R86hrDKiLiaUqMQ132PT+ccxXm/OnsTA/izt8TuGjZ23yXNgCrdT/JySlKXIiIAJs3byYyMpKmTZvi7e1N3759WblypbvDAmDlypX0798fgP79+1drXJ06dTqquqO8469cuZK+ffvi4+NDkyZNiIyMZPPmzdUaS3mqOxaA0NBQWrduDUBAQADR0dFkZmZW6fOjCgwROWlWaw62BV14ddnrzDp9HFO7TmTe+Vcz45941zZ64y8inmJ6YgCdsr/mh3PexnwtiZzCDtz5ewLfpZ0DGK6pIhqHKiJyRGZmJuHh4a7r4eHhbNq0yS2xTJo0CYDzzz+fuLg49u7dS2hoKOD4EL1v374ajae842dmZtKuXTvXdmFhYWRmZlZ7PN988w0//fQTrVu35pZbbqFhw4Y1HktaWhrbtm2jbdu2Vfr8KIEhIiftyJv7IPqPeoQXB33EPa3fomPQFvrePYqYUzrpA4CIuFVCQhDWB7L4+slf+fGct2mxK5m/iiUurNb9vBafSnS0Y0yipoqIiJRkmuZRtxmGUcaW1WvixImEhYWxd+9enn76aY8eb1vWc1bdBg0axFVXXQXAggULeOONNxgxYkSNxnLw4EESEhK47bbbCAwMLHe7E4lJS0hEpMrEx+dgmxbCpA2jeGDtU3QL+ZudI8bSudEGjVkVEbdISAjCLCxk5/s/sO2W+xm0awr7CoO443cbFy97iy43dQcMTRURETmO8PBwMjIyXNczMjJc36rXpLCwMACCg4Pp1asXmzdvJjg4mKysLACysrJK9MeoCeUdv/RzlpmZ6Yq/uoSEhGCxWLBYLAwcOJAtW7bUaCyFhYUkJCTQr18/evfuDVTt86MEhohUqfj4HKzWHFpd148rf5kLwMd97mTLe8uw2ZTEEJGa4UxcJL2/GPuE4SR0fYoWp/hjuW88Fy97k9fXtMWZuChebaHEhYhI2dq0aUNqaippaWkUFhayfPlyevbsWaMxHDx4kLy8PNflP//8k+bNm9OzZ0+WLFkCwJIlS+jVq1eNxlXe8Xv27Mny5cspKCggLS2N1NRU2rZtW62xOBMFACtWrCA2NrbGYjFNk5deeono6GguueQS1+1V+fwYpjvqWqpISkqK244dERFBenq6244vx6dz5H7R0VEk/bOeX25PpHfYGl7aejMjvh2CbVqI60OCzpPn0znyfDpHDq5xqIWFWM9aw4QecwkuSOXPvaeQuGko36edDTjKnZOTU1zb1wSdo9pB58nzufMcefJShZqyevVqXn/9dex2O+eeey5Dhgyp0ePv3r2bqVOnAlBUVMTZZ5/NkCFDyMnJITExkfT0dCIiIrBardU2RnXatGmsX7+enJwcgoODueaaa+jVq1e5x//444/54YcfsFgs3HbbbZx++unVGsvff//Nf//9h2EYNG7cmKFDh7oqZaozFoANGzbw2GOP0bx5c9fyouuvv5527dpV2fOjBMYJ0guc59M5cj9ntcXMRH8mnGLjtpYf8NOe3ty79hnuvN9RAPbss346Tx5Ov0uer76fI2ciokVME7a9+xbZ735UZuLCas1xTUiq6UqL+n6OagudJ8+nBIZI/aYmniJSbYp/QLgz/mbie3dgyumT+aLvLbS69iFievfl2WcPuTFCEakLZiQGMPqMj/ix/8eYb6TwX3YnEjc9xOI9Z+FMXNhsQZoqIiIiUsupB4aIVDvnN57vJQ1m8NKX8ffKJ2fCQ1wY+T0TJ3qpL4aIVJqzx8XXE37ix/5DMN94gaxDIdy2chqXLn+dxXvOJjk5FeCoPhciIiJSOymBISI1wvkBYsAdrbhk2Zv8m9OGOd0fIm/ByyTaGiiJISIV4kxcpLz/Pf/deh/n75pK5qEQbj2cuOh282muxAVoqoiIiEhdogSGiNSY+HjH+vPd+Y3p+e4TLNh5KQ+0m8e8HvFYh+9SEkNEyuVIXBSQ8v732McPY0rXp2neqQGWkY9x2fLXeWttazQOVUREpG5TDwwRqXFWaw62GeHY/nqMv/adwuOnJLDxzh0sXJUAhAP60CEixaeKFJD6wSKyN89lStfdrNlyKombHuXHr/rCbMO1vcahioiI1G2qwBCRGuesxLBa9/PKxsHcsGI2bSOz+KzvrVjPX4zNpkoMkfqs+AQj+0/fkH3/CJ7rMokt6RHcsnI6ly9/jR/3nIXVup/k5BRVW4iIiNQTSmCIiNvEx+cwcaIXv2X2oM9nb7M9N4bCGU9zX5t5JExtqCUlIvVMycTF1ywZcAXmm7PYvKcxN6+YUSJxAWiqiIiISD2jJSQi4lYTJhSRm5sLNOTKafOY0nUiD3Z4kS9/3Ej8n48DQfpwIlJPzEz0p3P25ywZ8A7mm7tIO9iZR/4ax5L0PoBBcnIK0dFR+psgIiJST6kCQ0Tczrmk5KDdnyFfjODpfx7g4qgf+KTPHVhv2QSgagyROsrZnPPb8T+wZMAVxO2ykXYwgptWzGTwL/PpcUsXTRURERERQAkMEfEgVmsONlsjXt52Mzf+NoNm/mlkjhnDdaftcPXFUCJDpG5wJi52f/AtO267l4G7E9l9sLErcdHzls5oqoiIiIgUpyUkIuIxin8wiY9vTt92b7D0hpG87TeSietHYprnYrNpSYlIbeWaKlJQQNqH32BPm8uzXdKhdQcslw3nikEXkZycSnS0cdTvuX7vRURERBUYIuJxnB9UtufGcMr8N/kqtT8TTpnGhxe/hJ/lIAkJQarEEKlFnL+vL0zzw/7j/8geOZxnOk/m9y1R3LjiBZq/8BYxgy4GHCNRVW0hIiIiZVEFhoh4LKvV0RsjYep4/v6sA2M7vES7htu4e/ZUUg5GurbThxwRz+SsuHhhmh+jeyzgp/6fYL69m41ZXUnc9BhL03sDxpHf9cOJDv1Oi4h4hpSUlDJvj4iIID09vYajKZsnxQKeFY8nxQLlxxMVFVXhfagCQ0Q8lmtE4pgDzNxyF5b7xtMycCe/Xn4jZ4SuJj4+x9UbQ0Q8zwvT/Phu/GJ+6n8F5tsvkZLXlBtXvMCQX+axNP1MV3NOjUMVERGRilACQ0RqBas1B9uigVy2/HW2pAbzbu/hPNxnGWBqSYmIB0lICMIsKHAlLs7bPY2UvKbc8Nsshvw6j163nFrmVBERERGR49ESEhGpFY58MxvOt0WzaL9sMpM6P0fn4A1MmPYQh+y+pbYTkZqUkBCE9YFM0j78hp1r5nNewG5+z+vKmD8f4+eMM7Ba9/OzTVNFRETcYfbs2axevZrg4GASEhLcHY7ICVMFhojUKvHxOdz3oMmdv9swLrqG62M/ZfO9d9DEL73EGnoRqX7O3zezsJDUDxZhf3QYz3SeTHTnUCyjn2TIr/NY8GcsznGoxastlLgQEak5AwYMYNy4cW6NwSwqwv7jV9i/WICZe8CtsUjtpQoMEamVRllzSdw6nA2ru2MrfIIvz7qJS059njXZR5oA6QOSSPVwNueckRjA6DM+IvvdD3muyy5Wb+mMbdNj/PTVmTDTcG2vagsREffq1KkTaWlpbo3BfHcO5pKvHZdXLsXy4GSMBg3dGpPUPqrAEJFaKT7eMbWg4w29aTjxOfLtfnx6zt1cE/OpmnuKVBNnxcX0xADsy77nh3OuxHzjBf7bE8atK6cx+Jf5/JTeB6t1P8nJKUpciIgIAGZqEuaSrzEGXopl9FOwOwX7a9MxTdPdoUktowoMEanVHMtGuvLqsteZffo4pnadyNzzr8HbsGoko0gVm54YwCl7v2HxOW9jvraTfYUduf33RL5POxswSE5OITo6SlNFRERqqUWLFrFo0SIAJk+eTERERJnbeXt7l3tfWfYtfJM8H18ibroHS0gYB7LT2T9/Bg1W/UzgBVecVMyVjaW6eVI8nhQLVE08SmCISK3n+JAUxCrzGdb/bz5DW7/NKUGbGf7CZDIOhRXbRkQqKyEhCOvobL58YiWL+r1Fm9QdrCtsz52/T+W7tP5Yrft5Iz6V6GjH8i1NFRERqb3i4uKIi4tzXU9PTy9zu4iIiHLvK0vRquXQsSuZhXZIT8c88zxYsZScV6dzoFlzjOgWJxxzZWOpbp4UjyfFAuXHExUVVcbWZdMSEhGpE+Ljc7COyeXpDaMx7hxNt5C/WXPNDXQNXq/mniInICEhCNNexOZ3l/HvjaO5MPUZ8u1+3L3qeS5e9hZdbuqBszknqM+FiIiUzczKgF3JGB27uG4zLBYsd4yCgEDstgnYf/pajT2lQlSBISJ1itWaQ+Kyy/jul+7M6TGWD8+8iwfOGMeHyZe4ttEHLJHyOSou9rLxnV+x753NC6fvhOgWWC59iAsvu5Kk5F1ER1uO+j3S75WIiOeaNm0a69evJycnh2HDhnHNNddw3nnn1cixzc3/AGC071zidqNRKJb4p7HPTcB8czbmWy9B6/ZY7orHiGhaI7FJ7aMEhojUKUc+RMXQfOjzLL1lOrbTnqBL8HrufOA6Ylo01wctkVKcU0VMu50N7/xG2rY5zO6+jY0bWzNt07N8+dVAzFeOFG2q2kJEpHYZNWqU+w6eugMMA6KaH3WXEdUcy4RpsPVfzHWrMRd/jn3GU1gem4bh7VPzsYrH0xISEamT4uNzsL0cw00rX+CVbTdwe8v3+eXaiUT4ZpCQEKQlJSIcmSpiszXEXP0Lu0daean7w2RlmNy7ZhKDlr7LF7vOZ7T1gKaKiIjIidmVDBFNMXz9yrzbMAyMNh2xXH4DljutkLoTc8k3NRyk1BZKYIhInRUfn8MDo/M4cOHdjFw7ka7B6/nyrJv5ft52bDYlMaR+Kv7v3mZriPnHCr4660bsLz7LvoxCRq6dyPk/LeDz1P9jlDUXQFNFRETkhJmpOyEypkLbGl17QYu2mCuWVHNUUlspgSEidVp8fA7x8TksTLmQBk9MptD04vP+d3FNzKdq7in1ks0WhGmavP/URhb2uR37C0/T0DuXUWufJG7p+yxMuZCdybuBw81xNVVEREROkGkvcjTwbFaxBAaA0e0M2LYRc19WNUYmtZUSGCJSL1itOdg+6MYly97k513dmdp1IvMHvcHMRH8tKZF6wflvvFfoWpZd+SRX7hxDU/89PPjneM776UNaXncOO5LSXNtruYiIiJy0jD1QWFDhCgwAo0svME3Mf/6sxsCktlITTxGpF458CAvinFGPMPv8jxnW5k1OCdpE77usxHQ6VR/UpE5yJi4WzdvJaT+9xEd9lpN2MJwJf4/l3Z1XsG1nOu9Fe2scqoiIVL3UnQCVqsAgpiX4BcDmf6B3/+qJS2otVWCISL0SH5+DbVoIz/z7APeumUTn4A2k3DeG00P+cn3QUzWG1HbF/w1/+cpuRgU8whdn3cK5rf9i0j8jiZz7Es8s78chuy9AiWUiSlyIiEhVMVOTHBeaxVb4MYaXF7Ru7xq/KlKcEhgiUu841/W3u74vg5fP55Ddlw/OvJvUDxYRHR2FzaYEhtROR6aKBGHuSubv+Gl8c/b17FvxF1M3DqPTx58zZ9st2F6IAFRtISIi1WxXEgQFYzSo3Hsro01HSP4PMz+/mgKT2koJDBGpl5zNPf/JaU/Ll6fwS0ZPnusyiZ2TH8XXcghQJYbUHhMnegGHExeZ6UzuPIlDj95H88zlzN5yG2f9+BkzNt/F0JEmVmuOpoqIiEiNMFN3QmWWjxxmxLYC04SU7dUQldRm6oEhIvWa1ZqD0SCIW1dOZ2yHF7mX11jQO4XuraewO/9IAkMf9MSTPf20F/YcO+M6Tid3zPtcFVPEG9uv5oUtt5N+KJzk5BSio4P171hERGqMaZqQshOj9zmVf3BMK8c+kv7DaNW+iiOT2kwVGCJSrzk/0I2y5jJy8RAs9zxIx6DNrBxyAz1D1zp6ZmhJiXggZ4XQjOe9ub/NXG5YfyNDW73F56nnM2DJx+y78B7+2Hak9FbjUEVEpEZlZ0LeAYhqXvnHRjR1NPLcua3q45JaTQkMERGOJDJsSy7k8uXz+S+lAe/1HsZDfZYDpkatisdw/jucmejPuL5Lueavmxjb4SV+yejJoKXvkhwXT1JelKaKiIiIe6XsAMA4gQSGYbFATAvM5P+qOCip7bSERESkGMeHvKb8r2g2HZZN5pnOk+kavJ4J0x4i3+5XbBuRmpOQEOT6dzfNFsjovp/xQ/8FNA9Mgfadufy1BL74O5y7o6OIj08p8Vj9exUREXcwDycwTqgCAzCiW2KuXIppmhiGUYWRSW2mCgwRkVLi43O470G44/dEjIuu4brYz9g09BZiAlKIj89RJYbUmBJTRUyTj55cx9f9bsB8NZG9BUHctGImzafNZ012F0DVFiIi4kFSdzomkAQFn9jjY1s6lqBkpldpWFK7KYEhIlKOUdZcErcO587fE9i7ZTdfnXUTN3bbhs0WpCUlUq2KJy4AujT6h6VDJjI4aRx+lkOMWP0slyx7k563dCY5OZXx44sAJS5ERMRzmCk7oFnsCT/eiGnpuJD0X5XEI3WDlpCIiJTD+WEwge6E3jyVdfcn8MYZo0jceBfW0RcTExujD4xSLZyJi5iAFD68aDZfnv01GfkhTPh7LG/vuJLtSWlER1tc//4mTCgiXV9QiYiIh3BMINmB0XvAie8kuqVjX0nbME7rVSVxSe2nCgwRkeOIj8/B9mYHBi+fz4c7L2J0u1f4/oophPhkqxJDqozz31FCQhDB3vvw/+pVfjjnSi6M/IGZm29nQec3eWZ5PwpNx3cPmioiIiIeKysD8nJPuP8FgBEQ6JhGogoMKUYVGCIiFeD4pjuIJDOeRz7syhOdpvLlWTczbO4U/tp3SrFtRCrH2aDTZgvihWl+3Nz8A5YOmEcjnxw+TL6Eff1v5vlvWpP8g6M5p/pciIiIx9u2EQCjeeuT209MK8wkjVKVI1SBISJSQfHxOcSP2c/bO68kYMJkLIadLwfcwXUxC9XcUyqtRINOu51Lm33D5puu4PFOiazdeyrej09jzJ+Pc8/D/iWqLZS4EBERT2duXg++vtCizUntx4hpCbtTMfPzqyYwqfVUgSEiUklWaw62j7sz/+e3mdntUaZ0fZq3L7iMWX8/CDg+lOpDppSl+DhUZ5+L3mGrWH3tdGadvp6/t7bnmQ0TWJp+JsmxKaq2EBGRKrN27Vrmz5+P3W5n4MCBDB48uNqOZW78G1p1wPD2Oan9GLEtMU07pOyAVu2qKDqpzVSBISJSSfHxOcTH53D7/V4M+Phhpm26i+tiP+PTvrdjvfEf1wdTEafSU0USEoJo22Abpy55jA/OvIcmfhlY/3iCRb1m894fzZW4EBGRKmW325k3bx7jxo0jMTGRZcuWkZSUVC3HMtN3w44tGJ26nfzODk8i0TIScVICQ0TkBMXH52BLDMG2aRi3rJxOpH8a+x4Zw+VRX6u5p5RQPKnVrZUvEd/O5Nt+13Fm2Gqe+/dePjrtdT5MvgTrmFxAiQsREalamzdvJjIykqZNm+Lt7U3fvn1ZuXJlpfdjFhVhZuzBvm8vZkGBY9pI6W1+WwKA0avfScdNRCT4+Z9QI0/TXnTyxxePoyUkIiIn4cgHza5cMPsdXuj2KDO7jefdbwfz2PoxQJA+jNZTzuUizkRWu+YhjGr7Mve0fhNfyyHe3HEVd358CbM6nkLy2BSKLPp3IiIi1SMzM5Pw8HDX9fDwcDZt2lT5HWVnYH/4LvY4r/v4QrNYjDYdME7tDqHhmN99CqeejtE48qTjNiwWiG5RqQoMs7AQ8905mEu/g1O7Ybn30ZNeyiKeQwkMEZGTdKSnQRRnvv84M+I+47628+kWso5Tb7CSkHCKkhj1SPGpIjZbEF5GIdfHfkJ8u5do4p/BxqD+dHzoeh7v3pO7gtTnQkSkvlqwYEGF4D46DQAALEZJREFUtvPy8uKqq646qWOVVSlhGMZRty1atIhFixYBMHnyZCIiIkrcbw8MIP/ecRiH8inK3Y89Zy+F27dwaPlizB++cmzk60fY3VZ8Sj32ROWc2o3crz8hPKghhp//Ufd7e3uXiDNn3jRyf/oGn45dKVi3moYb/iBgwAVVEktFlI7HnTwpFqiaeJTAEBGpIlZrDrZpIdg23suvmd2ZftoEcsbFs23dIyTgKKPUh9S6q3jiwnGeTZL+9xn2D1+D1J3QpiOD33yez/92vHArcSEiUr8tXLiQfv2Ov8zi119/PekERnh4OBkZGa7rGRkZhIaGHrVdXFwccXFxruvp6elH76zbmURERJS4z1JQAJvXY2alY3Q8jb0NgqGsx54As/UpULCA9OU/YnTpedT9xWMxt2/B/uWHGAMuouj6ofD4fez74n0OdD76cdWl9HPjTp4UC5QfT1RUVIX3oQSGiEgVKf5BND6+Bd1bv8PK4WOZ7v0YRngc7SY8QXy8GwOUKlfWVBGAuI77eeeMe7HPXMHWA82ZvGEKc1/uwACfRoASFyIiAj4+PowYMeK4251Ir4rS2rRpQ2pqKmlpaYSFhbF8+XJGjhx50vt1Mnx84JTTOLqmowp06Ax+/pgrl5aZwHAy7Xbsb78IQY0wrrgJw2LB6HkW5pcfYB7Yj9GgYXVEJzVMTTxFRKqYs+/B7vwmtJo+j+mb7qTo5+/5/KxbmP9Mhpp71gFlTRUBeHvWQZ7v8iT/O/tGOjX6lx+a3E/bN6bR6cZeGIahpIWIiLi8+uqrFdrulVdeOeljeXl5cccddzBp0iRGjx5Nnz59iI2NPen91gTDxxfjrDjMFUsdE07KYS79FrZtxLj6doxAR7LCOLU7mHb4Z20NRSvVTRUYIiLVoPgH1QTbcFZknc700yZw9eZhTNrwAAnmBcSP2e/GCOVEHL1MBKKjowjwymNU25cZ1voNvIwiVodfw23vDeOf7aq2EBGRsnl7V+yjWEW3O57u3bvTvXv3KtlXTTMGXYG57HvscxOwPPAERkBgifvN5O2YH7wKHbti9B5w5I5W7cHXD3PzPxg9z67ZoKVaKIEhIlJNii8teO+P5pze+l1+f2AcT3tNAZ9FvPjcOIY/5OvmKKUyii8TiY6OwkIRV8Z8ydj2LxLpvwejx1mcNXUsv2y2cFcTNwYqIiIeb+bMmWU20iztvvvuq4FoPJsR3hjLbfdjn5uAfcIIjJ5nQcu2GA0akZuXg33Bq+AfgOXO0SWeU8PLC2JbYe7Y4sbopSppCYmISDWzWh1LStLyI2g+ZQ7j/36Qg3/8zVXr72ThE2sBtKzEgznPTellI2eFr+DLs28moetTRHYK44rl87AMe4irhgcDqroQEZFji4yMpGnTpjRt2pTAwEBWrlyJ3W4nLCwMu93OypUrCQwMPP6O6gmj59lYxj7rSEj89A3mvETsM54k5xUbhIRjsU7ECAk/+nHN28CObZh2uxuilqqmCgwRkWpWsrlnDtHR1/DMRy3Z+MBMLk1+DPtrA3l5xgQ1+PQwpcehOrVruJVHOswkrulSduY2wxg6FqPn2fT3dTToVOJCREQq4uqrr3ZdnjRpEg8//DCnnHKK67YNGzbw0UcfuSM0j2W06YjXA49jFhyC9DTI3U9obAuyfPzLr2Zp0QZ++BLSUiAypmYDliqnCgwRkRribO4JENPzDK5Y/iozNt9B4c8/8PXZN2BuWq9KDDcr/vwXT1okJ6eQtO4vnusyke/7X8cZYasxrryVhd1ew9Krnxp0iojISdm4cSPt2rUrcVvbtm3ZuHGjmyLybIaPL0azGIw2HfGOij3mUhwjuoXjQsrOGopOqpMSGCIiNSg+PgerNYfk5BQKTB+mbhzB1b++DBgUPDcO7y/eIHGqv7vDrHfKmyoSHR1FkPd+pp37CQfihzEk6iuMgZfyTqe3sVxwJaPG5rstZhERqTtatWrFu+++y6FDhwA4dOgQ7733Hi1btnRvYHXB4aoLM1UJjLpAS0hERGpY8W/qk5NTgCa0b/4OG56ayH3GfMj7idcmjeO2Rxu7L8h6orypIgA+RgE3t/iQkW3nEua7F+OM/sxLv4e7r23Ive4MWkRE6pwRI0YwY8YMbr31Vho2bMj+/ftp06YNI0eOdHdotZ7hHwChEbAryd2hSBVQAkNExE2sVscH5oSEIA4UNSD20cn8X9MfmJw/iet8hvLrQ9fyW8TNPDC2wM2R1l2lp4oAGNi5pNl3PNh+Ni0aJPNz+hmcM+06jBZtudtdgYqISJ3WpEkTnn76adLT08nKyiI0NJSIiAh3h1V3NIvBTFUCoy7QEhIRETdxfuNffFnJN7vPpfGsF/g4+SJ6Zb7DZWvvwvxrlZsjrVvKmyoC0Cfsd1YMuYlZpz/K/qIGWB54gt/PmozRoq1bYhURkfolIiKCtm3buiaR2DU5o0oYzWJhV5ImkdQBqsAQEfEAJRp8duwIPM5HyRfzTOdnsc94ko1BA+j42G0YIWHuDbQWK2+qCECv0LUkDpxN89zVEBiBccNovlt2CV07HyC+8343RSwiIvVFZmYm8+bN459//uHAgQMl7luwYIGboqpDImMg/yBkZUC4lujWZqrAEBHxEM5KDOfSkl8ze3LBz+8ydeMwmmcvJ++he7H/+JW+PaiEY00VSU5OoVfoWnbE38lHfe6iufdWljQZgeXpl7D0OZf4MQfK2qWIiEiVe/nll/H29uaxxx7D39+f5557jp49e3L33Vq8WBWMZrGOC+qDUespgSEi4kHi43NcS0uSk1M4ZPfloSUX8X8/v4tf+zaYb7+E/bmHMJO2uTlSz3asqSIAl3dO48crnuajPndB8nZH4uKZVzhv0gUYPr7uCVpEROqtjRs3Mnz4cFq2bIlhGLRs2ZLhw4fzxRdfuDu0uqFZNKBJJHWBlpCIiHggqzXnqA/dzW3zuCLqfzzrlYD/k6PxGnQ5xsXXYAQ2cGeoHuVYU0UAeoauZXS7l+kXsQKCglkSMJxzHzuP8/z83BWyiIgIFosFLy8vABo0aMC+ffsICAggMzPTzZHVEUEhENgQ1Miz1lMCQ0TEAxUftRofn0N0dBTJyalER1/EzB/b8PaQD7j+208wf/4WY9AVGAMvwfAPdGPEnqGsqSIAPUL+YHS7lzmn8W/syQ/DuPp2jP4Xcp6fvzvCFBERKaFt27asWbOGM844g9NOO43ExER8fX1p06aNu0OrEwzDcEwi2aUKjNpOCQwREQ9WvLmn8wN5TPsOwHjs51xEnz3zab3wLcxFn2FcMARjwMUY9ayawFl1UXrZiJdRyPlNfuKxs98mJu8P0vNDMa6+nQV/XM0DgwrdGbKIiEgJ999/P6ZpAnDbbbfx+eefk5eXx8UXX+zmyOoOo1ks5h8r3B2GnCQlMEREPFzxaoziFQaPzO4OdGfK8N+4ruFczA9fw/x2IcaFV2H0r/u9HMqbKhLqk831sQsZ0fl9GhWmQWATjEtu573DiQslL0RExJPY7Xbmz5/PPffcA4Cvry9XXnmlm6Oqg5rFwM/fYe7fh9GwkbujkROkJp4iIrVA6eaexX/eOD6WaUU2LA9OhmaxmAvmYh93j2NiSWGB22KuLqUrLcDxXCT9spTnuzzJHxdeyMMdX6BR20g+j56I5Zk5WAZdwQNjlbgQERHPY7FY+PPPPx3LHKTaaBJJ3aAKDBGRWqSs5p5Hej30BqM31vhl2D99G/PtlzD/9xHGJddi9O6P4Vt7l5Y4qy2gZOKiRUwTLm32Lb9euYBeYX9waTN/jLMG8vqOa7g9PoLBbopXRESkMi6++GLef/99rrnmGry99RGtWkTGAGCmJmG07eTmYORE6bdDRKQWKbu5ZwrR0VGu6/HxXbF06AL/396dR0dV3/8ff93JhECArBOWhE22WrSy1EC/CKIQrUWr1tMqSBfF74+yiQr06Om3trWIBH8i/oQAtVCLaOtSoS51DYiouBCQrywqQkGRACEJgYSQhGQ+vz/GxJBMICHJfG4yz8c5nJm59+beF/M5DLnv+Sw7Pg4UMp5YLPPMCjmDh8kZeqn03UFyWsgvRzVXFQkUb4xe/HOu7uj7tCb0WK0ubY+oIDJZzk9u08qPr9f0nxvdajs4AAAN8Nprr6mgoED//ve/FRNz+vCGpUuXWkrVyiQmSZFtJJZSbdFaxm+wAIDTBJvcs/KxcvusWUPkuWCw9Pk2mY82yGx+T+aD9VKHjnKGXBIoZvQbIMfjrtGENXtbzJpVqAinXDd876Cu6PSM3h61Qee1D/zysa99qm5Z/z96YksvOR6Ppl9hbEYHAOCc3H777c127vfff1/PPfecDhw4oAceeCBsVzZxPBFS5xQZllJt0ShgAEALVdfkntWfz5pVKJ1/kZzzL5IZ/2tpx5ZAMeODt2Q2vCbF++SkjggUM3r0ccX428qixaIHPbq6S6aeG/u2Ph7znuLaHFdpRaTey0tV70nXKPW2a7R5T4UGLegox1N49hMDAOBSAwY035CG7t27a/bs2Xrsscea7RothdO1m8x/PrcdA41AAQMAWrDqPRUqh5JUH1JSvTeDExkpDRomZ9AwmdISma0fymx6R2btyzJv/EvqlCznwiFSt15yup0nJfcI6ZKsDz8Urbt+sVu/7Pmu1l2/Qf+dmKU2Q8qVXxarN3MuVdthQ3XdPd/RLX366MBl2bp5arSkwtMKOQAAtBRr167VmDFjznrcunXrNHr06HO+Trdu3c75Z1ud5O5S1rsyJ4vltIu2nQbngAIGALQCZ57cM6D6jb4T1VbOsFHSsFEyJwplNm8MFDPefVMqK5WRJMeRkrqqoE9/+ZOS5XTrJXXrJSV2OudhJ8YY6dhRKSdb5nC2dPiAdr+Xo7iyrzX5ZLb8vzul+y+QvijqpRV7b1ZmzqVa80miZnXvrgOvZlf9XWv+fQAAaGmeeOIJjR49OvB/4xmsWrWqUQUMfMvp893A+717p/S9i23HwTmggAEArUD9JvcMfsPvtO8o59IfSpf+UMbvl3IPSV/vk/n6S5kD+1S+b7fMB29/+wtWVLvANxjt2ksREVKEV843j4qIkLxeyeP59rXHI+XnflOwyJZKT357cW+kyo92V+KlXbXkn5dp2n0ddeltl+vdXZE6X9K8lGQ5nuyqokXNvysAAC1VSUmJxo0bd9bjIiMjz3rMnDlzVFBQUGv7uHHjlJqaWu9MmZmZyszMlCSlp6fL5/MFPc7r9da5L9QaksUMHaEcb6TafvmFOl5+lfU8zc1NWaSmyUMBAwBakfpN7ll3AcDxeKROyYHhJEOGS5J8Pp+OfL1fyv5K5sCXgeJG9lfSyRNSRYVUUS7zzaMqKiR/RdX2wGOFFJcgdU7Wx4UXacgNSbr5rov0j7VRWvi387RgYZz0TuD66d/8HrdgQWBoCL0tAACt1eLFi+t1XH3mp7r33nsbG0eSlJaWprS0tKrXubm5QY/z+Xx17gu1BmfpN0DFG99SydgbAxN71sGUl0se54zHNEmeZuSmLFLdeZKTk4McHRwFDABoZeo7uWf1+THOxmnbTur9HTm9v3NOmRYs6KhZdxbqupRkHXgwW+/kJqvbwNrH1SxYULgAALRWSUlJtiOEJc+lP5T/zw/KbH5fTuqIWvvNqVMyz/9NZv2rUrtoeSbfI+c7F1pIimDctXYeAKBJzJr17eSWBw5kn/ZYfeLPUHn44Y61eoZUVz0bRQsAAJrORx99pMmTJ2vXrl1KT0/X3LlzbUeya/B/Sd16yTy1VGbX9tN2mc8+kf+B2TJrX5IzdKTkOPI/85ezzlOC0KEHBgC0YvWZ3LMhPTEaovK8ldevWTCZObOwan6OytcAAKBpDR06VEOHDrUdwzWciAh5ptwj/8I/yP9/fyvFJgSGuhYWSPm5UkKSPNP+R86gYfJveF1mVYb01R6pZ1/b0SEKGADQqgWb3LO66q+bqohRWbh4+OGOQXt5zJwZ2Fd5Pea5AAAAoeR0SpbnD/9P5v310t5dMsePyumcIvUbIOeSMXIi2wSOu3CIjCTzxQ45FDBcgSEkABAGqhcHDhzIDjqspLKnxLmo/rPVixZ1XYtVRQAAgE1O22h5Lh8rz8Q7FXHnffL8n1nyXPajquKFJDkJSVJiJ5kvdlpMiurogQEAYaSycHC2YSX1LSpU721xphVQal6fogUAANLx48e1YcMGbdmyRV9++aWKi4sVHR2tnj17atCgQbrssssUExNjO2ZYc/p8V2b3Dtsx8A0KGAAQRmqu7lE5rOTAgWylpCRXvT5bgaFm4UIKPjln5TwX9VnCFQCAcPL3v/9d77zzjgYPHqzRo0crJSVF7dq108mTJ3XgwAHt3LlTd999t0aMGKEJEybYjhu+unaTPnpbprRETlRb22nCHgUMAAhTZ+oxcbaCQ/VhInWtKlK9EELhAgCA08XHx+vRRx9VZGRkrX3nnXeeRowYobKyMq1bt85COlRyuqTISNLhbKlHb9txwh5zYABAGKucj6LmCiCVE3BWn9ui8vmZVhWpnOei8jUAAAjuRz/6UVXxoqCgIOgxxcXFuuqqq0KYCrV0TpEkmcMHLAeB5JICxquvvqo77rhDM2fO1JNPPmk7DgCElVmzCqt6SASbcDMtLdBZ7+GHOyolJTlo4aLy2GCvAQDAmd1xxx1Bt991110hToJaOn3T0/QQBQw3sD6EZPv27crKytJDDz2kyMhIHTt2zHYkAAhLM2eefUhJZWGj5rwZ1VG4AACgYYwxtbYVFxfL43HF981hzYmKkuISpNzDtqNALihgvPHGG7ruuuuquk/FxsZaTgQA4al64aFyMs+ZMwurhpNIrCoCAEBTmjJliiSprKys6nmloqIiXXLJJTZioabETjJ5ObZTQC4oYBw8eFCfffaZnn76aUVGRuoXv/iF+vbtG/TYzMxMZWZmSpLS09Pl8/lCGfU0Xq/X6vVxdrRRy0A7uc+8eVJaWntJtee5GDnSr8zMcs2ZEyGfz6d58yQpKvQhcRr+HbkfbdQy0E7u19ra6Pbbb5cxRvPmzdPtt99+2r64uDglJ9eeKBuh5yQkyez7wnYMKEQFjDlz5gSdmGbcuHHy+/0qKirS3LlztWfPHi1cuFCLFy+W4zi1jk9LS1NaWlrV69zc3OaMfUY+n8/q9XF2tFHLQDu509NPf7tUavXhIk8/fUi5udKUKRLN5h78O3I/2qhloJ3cz2YbNUcxYcCAAZKkFStWKCqKLwRcKyFJ+vh9Gb9fDsN6rApJAePee++tc98bb7yhYcOGyXEc9e3bVx6PR4WFhYqJiQlFNABAHWoOC2FVEQAAms4rr7yiK664QpGRkXUWL06dOqU333xTY8eODXE6nCaxk1ReLh0vCMyHAWusDyFJTU3V9u3bdcEFFyg7O1vl5eXq2LHj2X8QABASI0f6JTHPBQAATamgoEAzZszQ4MGDNWDAACUnJ6tt27YqKSlRdna2du7cqY8//lijRo2yHTXsOQlJMpKUl0MBwzLrBYzRo0dryZIlmjVrlrxer6ZNmxZ0+AgAwI7MzHKGiwAA0MRuvvlmXXPNNVq/fr3WrVunr776SidOnFCHDh3Uo0cPDR48WOPHj+fLXTdITJIkmfxcOX0sZwlz1gsYXq9XM2bMsB0DAAAAAEIqJiZG1157ra699lrbUXAmCYEChvJZicQ2ZiABAAAAAKAOTnR7qV17Ke+I7Shhz3oPDAAAAAAIZ8XFxXruuee0c+dOFRYWyhhTtW/p0qUWk6FKYpJMPgUM2+iBAQAAAAAWLV++XHv37tVPf/pTFRUVaeLEifL5fLr66qttR0OlhCR6YLgAPTAAAAAAwKJPPvlECxcuVMeOHeXxeJSamqo+ffpo/vz5uuaaaxp17lWrVmnz5s3yer3q3Lmzpk6dqvbt2zdR8vDhJCbJ7N5pO0bYowcGAAAAAFhkjFF0dLQkqW3btjpx4oTi4uJ06NChRp/7oosu0oIFC/TQQw+pa9euWrNmTaPPGZYSkqTiEzIni20nCWsUMAAAAADAop49e2rnzsC3++eff75WrFih5cuXq2vXro0+98CBAxURESFJ6t+/v/Lz8xt9zrCU2CnwyDwYVlHAAAAAAACLfv3rXyspKbBU58SJE9WmTRudOHFC06dPb9LrrFu3ToMGDWrSc4YLp2opVQoYNjEHBgAAAABYdPz4cfXr10+SFBMTo8mTJ0uSdu/eXa+fnzNnjgoKCmptHzdunFJTUyVJq1evVkREhEaOHFnneTIzM5WZmSlJSk9Pl8/nC3qc1+utc1+ohSpLhec7ypXUvrRY0We4Xji+N/XVFHkoYAAAAACARffff79WrlxZa/vcuXP1+OOPn/Xn77333jPuX79+vTZv3qzf//73chynzuPS0tKUlpZW9To3NzfocT6fr859oRaqLMZvpAivir7aq+IzXC8c35v6qitPcnJyvc9BAQMAAAAALPD7/ZICk3hW/ql0+PDhqrkrGmPr1q164YUXdN999ykqKqrR5wtXjscjJfhYStUyChgAAAAAYMH48eOrno8bN+60fR6PRz/5yU8afY0VK1aovLxcc+bMkST169dPkyZNavR5w1J8osxR9/RoCEcUMAAAAADAgsWLF8sYoz/+8Y+67777ZIyR4zhyHEcxMTFq06ZNo6+xaNGiJkgKSXLiEmX27rIdI6xRwAAAAAAACypXHlmyZImkwJCSY8eOKT4+3mYs1CUuUTqaV1VoQuhRwAAAAAAAi06cOKHly5frgw8+kNfr1apVq5SVlaXdu3fXGloCi+ITpPJT0olCqUOM7TRhyWM7AAAAAACEs7/85S+Kjo7WkiVL5PUGvmPu37+/Nm7caDkZqnPiEgNPCvLtBgljFDAAAAAAwKJt27bp1ltvPW3oSExMjI4dO2YxFWqpKmDk2c0RxihgAAAAAIBF0dHRKiwsPG1bbm4uc2G4TbxPkmTyWYnEFgoYAAAAAGDRmDFjtGDBAm3fvl3GGO3atUsZGRm64oorbEdDdfGJUpso6eB+20nCFpN4AgAAAIBF1113nSIjI7VixQpVVFRo6dKlSktL09ixY21HQzWOxyOl9JT5ep/tKGGLAgYAAAAAWOQ4jq6++mpdffXVtqPgLJyUnjJbP2QpVUsoYAAAAACAZdnZ2dq3b59KSkpO2z569GhLiRBUt17Su29KR/OkBJ/tNGGHAgYAAAAAWLR69Wo9//zz6tmzp6Kiok7bRwHDXZzzB8pIMtuy5Iy6ynacsEMBAwAAAAAseuWVV/TAAw+oZ8+etqPgbJK7S526ymx+T6KAEXKsQgIAAAAAFrVp00YpKSm2Y6AeHMeRM3yM9On/ynz2yTmfxxgjk/2V/C88pYrfTlLF5J/I//xKGWOaMG3rQw8MAAAAAAgxv99f9fymm27SX//6V/3sZz9TbGzsacd5PHzn7DZO2nUy72XKv2SenMuukhKSpAq/VHpSRREe+QuOSqUlUmmpTFmJVFYqlZdLFeXfPFZIRcelgjzJ8Ujnf09K7iHz2vNSt15yho2y/Vd0LQoYAAAAABBi48ePr7Vt7dq1tbY988wzoYiDBnCiouSZNVf+lY/KvLZaqtZr4oTHI7WJkqLanv7o9QYe20VLEV45yd2l/hfKGZgqJy5Rxl8h/wO/kVmzSiZ1ZGDJVtRCAQMAAAAAQmzx4sW2I6ARnMQkRcycI1NeLp0olDwRUlSUfF2TlZeX1/DzeSLkjPmxzF8XSnt3SX3Ob4bULR9lHQAAAAAIsaSkpKo/77///mmvK/98+OGHtmPiLByvV05svJyOMXLaRMlxnHM/18Chktcrs+X9JkzYulDAAAAAAACLnn/++QZtR+vkRLeXevaV2bfLdhTXYggJAAAAAFiwfft2SYEJPSufVzp8+LDatWtnIxYscrr3lvlwvYzfzzwYQVDAAAAAAAALli5dKkkqKyurei4FluqMi4vTxIkTbUWDLT16S+tfkXIPSZ2SbadxHQoYAAAAAGBBRkaGpMCEntOnT2+Wazz99NPKysqS4ziKjY3V1KlTlZCQ0CzXQuM5PfrISNL+vRQwgqCAAQAAAAAWNVfxQpKuvfZajRs3TpL0yiuv6J///KcmTZrUbNdDI3XpJjmOTPZ+Od+3HcZ9GFQDAAAAAK1UdHR01fPS0tJGrZKB5udERUmJnaSD+21HcSV6YAAAAABAK/aPf/xDGzZsUHR0tP7whz/UeVxmZqYyMzMlSenp6fL5fEGP83q9de4LNTdlkZomz9GeveU/clCJjTxPa3xvKGAAAAAAQAs2Z84cFRQU1No+btw4paamavz48Ro/frzWrFmj1157TTfeeGPQ86SlpSktLa3qdW5ubtDjfD5fnftCzU1ZpKbJ40/sIvO/WTqSc1iOJ8JqlqZUV57k5PrP9UEBAwAAAABasHvvvbdex40YMULp6el1FjDgEsndpfJTUu5hJvKsgTkwAAAAAKCVOnjwYNXzrKysBn3bDTucLt0CT7KZB6MmemAAAAAAQCv11FNP6eDBg3IcRz6fjxVIWoKu3SVJ5uDXcgYNsxzGXShgAAAAAEArNXv2bNsR0EBOdHspLkE6+JXtKK7DEBIAAAAAANyka3cZhpDUQg8MAAAAAABcxEnuIfPumzLGyHGcJj23yTsi88UO6cgh6VRZYMJQY5r0GrV4I6Vfz2r8aZogCgAAAAAAaCpdukmlJVJ+rpSY1CSnNMbIrFkl89pqyfgDGz2eQHEh4tyXa62XqHYUMAAAAAAAaG2c5O4yUmAejKYqYKx7WebVf8q5ZIyctGulLt3leFtWSYA5MAAAAAAAcJNqK5E0BVN0XOaFp6QLh8j51Qw53c5rccULiQIGAAAAAACu4nSMlTrESAebZiJPs/4V6WSxPD+d2ORzaoQSBQwAAAAAANwmubtMduOXUjX+Cpn1r0nfu1hOSo8mCGYPBQwAAAAAAFzG6dJdOvi1TGNXCNn9qXQsX85/Xd40wSyigAEAAAAAgNskd5eKi6RjRxt1GrN5oxTZRs73Lm6iYPZQwAAAAAAAwGWcnn0DT/7z2Tmfw/j9Mls2BibvbNuuiZLZQwEDAAAAAAC36dVXahMl8/n2cz/H7k+lgnw537+k6XJZRAEDAAAAAACXcbyRUt/vyuzces7zYJiNa6WodnIGDm3idHZQwAAAAAAAwIWc718iHfpa2tPwYST+wuMyWe/KSR3RKoaPSBQwAAAAAABwJWfopVK7aPlferrBvTCKX35WKi2Rk3ZtM6ULPQoYAAAAAAC4kNO2nZzrfy7t/Fjm78tkCvLr9XPmyCGdeOHv0pDhclJ6NnPK0PHaDgAAAAAAAIJzLhsr5eXIvPEvmfWvSh06ShGRkiPJmMCfDjFSbLycuAQpwiuz5X05Ho+cGyfajt+kKGAAAAAAAOBSjscj52cTZYaPkdm5VTp0QDL+QOHC45GMkSk6Lh07Glix5FSZ1P9CJfz3HSqIam87fpOigAEAAAAAgMs5KT0bNBzE6/NJubnNmCj0mAMDAAAAAFq5F198UTfeeKOOHz9uOwpwzihgAAAAAEArlpubq23btsnn89mOAjQKBQwAAAAAaMVWrlypCRMmyHEc21GARmEODAAAAABopbKyspSQkKBevXqd9djMzExlZmZKktLT0+vsseH1el3Tm8NNWSR35XFTFqlp8lDAAAAAAIAWbM6cOSooKKi1fdy4cVqzZo1+97vf1es8aWlpSktLq3qdW8cEkD6fr859oeamLJK78rgpi1R3nuTk5HqfwzHGmKYMBQAAAACw76uvvtKf/vQnRUVFSZLy8vIUHx+vefPmKS4uzm444BwwB8Y5uueee2xHwFnQRi0D7eR+tJH70UbuRxu1DLST+9FGDdOjRw8tX75cGRkZysjIUGJioubPn9/o4oWb2sFNWSR35XFTFqlp8lDAAAAAAAAArsccGAAAAAAQBjIyMmxHABqFHhjnqPrkNnAn2qhloJ3cjzZyP9rI/WijloF2cj/ayB3c1A5uyiK5K4+bskhNk4dJPAEAAAAAgOvRAwMAAAAAALgeBQwAAAAAAOB6TOJ5DrZu3arHH39cfr9fY8aM0fXXX287EqrJzc1VRkaGCgoK5DiO0tLSNHbsWNuxEITf79c999yjhIQE1y3zBOnEiRNatmyZ9u/fL8dxNGXKFPXv3992LNTw8ssva926dXIcR927d9fUqVPVpk0b27HC2pIlS7RlyxbFxsZqwYIFkqSioiItXLhQR44cUVJSku666y516NDBctLwFayNVq1apc2bN8vr9apz586aOnWq2rdvbzlpeAvWTpVefPFFPfnkk1q+fLliYmIsJQw/brgPmjZtmtq2bSuPx6OIiAilp6eH7DO2oZ/va9as0bp16+TxeHTrrbdq0KBBzZ7n2Wef1dq1a6v+XYwfP15Dhgxp9jx13YM1+ftj0CAVFRVm+vTp5tChQ+bUqVNm9uzZZv/+/bZjoZr8/HyzZ88eY4wxxcXFZsaMGbSRS7300kvmkUceMfPmzbMdBUEsWrTIZGZmGmOMOXXqlCkqKrKcCDXl5eWZqVOnmtLSUmOMMQsWLDBvvfWW3VAwO3bsMHv27DEzZ86s2rZq1SqzZs0aY4wxa9asMatWrbKUDsYEb6OtW7ea8vJyY0ygvWgj+4K1kzHGHDlyxNx///1mypQp5tixY5bShR+33AdNnTq1VruH6jO2IZ/v+/fvN7NnzzZlZWXm8OHDZvr06aaioqLZ8zzzzDPmhRdeqHVsc+ep6x6sqd8fhpA00O7du9WlSxd17txZXq9Xw4cP16ZNm2zHQjXx8fHq3bu3JKldu3ZKSUlRfn6+5VSoKS8vT1u2bNGYMWNsR0EQxcXF+vTTTzV69GhJktfr5ZtIl/L7/SorK1NFRYXKysoUHx9vO1LYGzBgQK1v/jZt2qRRo0ZJkkaNGsXvDpYFa6OBAwcqIiJCktS/f39+d3CBYO0kSStXrtSECRPkOI6FVOHLzfdBofqMbcjn+6ZNmzR8+HBFRkaqU6dO6tKli3bv3t3seerS3Hnqugdr6veHISQNlJ+fr8TExKrXiYmJ+uKLLywmwpnk5ORo79696tu3r+0oqOFvf/ubfv7zn+vkyZO2oyCInJwcxcTEaMmSJfryyy/Vu3dv3XLLLWrbtq3taKgmISFBP/7xjzVlyhS1adNGAwcO1MCBA23HQhDHjh2rKi7Fx8fr+PHjlhPhTNatW6fhw4fbjoEgsrKylJCQoF69etmOEnbcdB80d+5cSdIVV1yhtLQ0q5+xdV07Pz9f/fr1qzouISEhZIXR119/XRs2bFDv3r31y1/+Uh06dAhpnur3YE39/tADo4FMkFVnqf66U0lJiRYsWKBbbrlF0dHRtuOgms2bNys2NraqSgv3qaio0N69e3XllVfqwQcfVFRUlP71r3/ZjoUaioqKtGnTJmVkZOjPf/6zSkpKtGHDBtuxgBZt9erVioiI0MiRI21HQQ2lpaVavXq1brrpJttRwpJb7oPmzJmj+fPn67e//a1ef/117dy5M+QZ6iPY+xUKV155pRYtWqQHH3xQ8fHxeuKJJ0Kap773YOeahwJGAyUmJiovL6/qdV5eHt11Xai8vFwLFizQyJEjNWzYMNtxUMPnn3+urKwsTZs2TY888oi2b9+uRx991HYsVJOYmKjExMSqyvgPfvAD7d2713Iq1LRt2zZ16tRJMTEx8nq9GjZsmHbt2mU7FoKIjY3V0aNHJUlHjx5l0kGXWr9+vTZv3qwZM2bwBZULHT58WDk5OfrNb36jadOmKS8vT3fffbcKCgpsRwsLbrkPSkhIkBT4XE1NTdXu3butfsbWde2a71d+fn5V9uYUFxcnj8cjj8ejMWPGaM+ePSHLE+werKnfHwoYDdSnTx8dPHhQOTk5Ki8v18aNG3XxxRfbjoVqjDFatmyZUlJSdM0119iOgyBuvvlmLVu2TBkZGbrzzjt14YUXasaMGbZjoZq4uDglJiYqOztbUuBGuVu3bpZToSafz6cvvvhCpaWlMsZo27ZtSklJsR0LQVx88cV6++23JUlvv/22UlNTLSdCTVu3btULL7ygu+++W1FRUbbjIIgePXpo+fLlysjIUEZGhhITEzV//nzFxcXZjhYW3HAfVFJSUjX8uKSkRJ988ol69Ohh9TO2rmtffPHF2rhxo06dOqWcnBwdPHgwJMPaK4sFkvTRRx+pe/fuIclT1z1YU78/jrHVt6UF27Jli1auXCm/36/LL79cN9xwg+1IqOazzz7T73//e/Xo0aPq25PqywfBXXbs2KGXXnqJZVRdaN++fVq2bJnKy8vVqVMnTZ06lWUfXejZZ5/Vxo0bFRERoV69emny5MmKjIy0HSusPfLII9q5c6cKCwsVGxurG2+8UampqVq4cKFyc3Pl8/k0c+ZM/j1ZFKyN1qxZo/Ly8qp26devnyZNmmQ5aXgL1k6Vk0tLgeU0582bR4+mELJ9H3T48GE99NBDkgLDXUeMGKEbbrhBhYWFIfmMbejn++rVq/XWW2/J4/Holltu0eDBg5s9z44dO7Rv3z45jqOkpCRNmjSpqqdMc+ap6x6sX79+Tfr+UMAAAAAAAACuxxASAAAAAADgehQwAAAAAACA61HAAAAAAAAArkcBAwAAAAAAuB4FDAAAAAAA4HoUMAAAAAAAgOtRwAAAAAAAAK5HAQMAAAAAALgeBQwAQKt36NAh3XrrrfrPf/4jScrPz9dtt92mHTt2WE4GAACA+qKAAQBo9bp06aIJEyZo0aJFKi0t1dKlSzVq1ChdcMEFtqMBAACgnhxjjLEdAgCAUJg/f75ycnLkOI7mzZunyMhI25EAAABQT/TAAACEjTFjxmj//v266qqrKF4AAAC0MBQwAABhoaSkRCtXrtTo0aP13HPPqaioyHYkAAAANAAFDABAWHj88cd13nnnafLkyRoyZIgee+wx25EAAADQABQwAACt3qZNm7R161ZNmjRJkvSrX/1Ke/fu1TvvvGM5GQAAAOqLSTwBAAAAAIDr0QMDAAAAAAC4HgUMAAAAAADgehQwAAAAAACA61HAAAAAAAAArkcBAwAAAAAAuB4FDAAAAAAA4HoUMAAAAAAAgOtRwAAAAAAAAK73/wGilT2sUFyY7QAAAABJRU5ErkJggg==\n", "text/plain": [ "
" ] }, "metadata": {}, "output_type": "display_data" } ], "source": [ "#plot trajectory\n", "grid = plt.GridSpec(4, 5)\n", "\n", "plt.figure(figsize=(15,10))\n", "\n", "plt.subplot(grid[0:4, 0:4])\n", "plt.plot(track[0,:],track[1,:],\"b+\")\n", "plt.plot(x_sim[0,:],x_sim[1,:])\n", "plt.axis(\"equal\")\n", "plt.ylabel('y')\n", "plt.xlabel('x')\n", "\n", "plt.subplot(grid[0, 4])\n", "plt.plot(u_sim[0,:])\n", "plt.ylabel('a(t) [m/ss]')\n", "\n", "plt.subplot(grid[1, 4])\n", "plt.plot(x_sim[2,:])\n", "plt.ylabel('v(t) [m/s]')\n", "\n", "plt.subplot(grid[2, 4])\n", "plt.plot(np.degrees(u_sim[1,:]))\n", "plt.ylabel('delta(t) [rad]')\n", "\n", "plt.subplot(grid[3, 4])\n", "plt.plot(x_sim[3,:])\n", "plt.ylabel('theta(t) [rad]')\n", "\n", "plt.tight_layout()\n", "plt.show()" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "## Use Dynamics w.r.t Robot Frame\n", "\n", "explanation here...\n", "\n", "benefits:\n", "* faster mpc convergence time" ] }, { "cell_type": "code", "execution_count": 16, "metadata": {}, "outputs": [], "source": [ "def compute_path_from_wp(start_xp, start_yp, step = 0.1):\n", " \"\"\"\n", " Computes a reference path given a set of waypoints\n", " \"\"\"\n", " \n", " final_xp=[]\n", " final_yp=[]\n", " delta = step #[m]\n", "\n", " for idx in range(len(start_xp)-1):\n", " section_len = np.sum(np.sqrt(np.power(np.diff(start_xp[idx:idx+2]),2)+np.power(np.diff(start_yp[idx:idx+2]),2)))\n", "\n", " interp_range = np.linspace(0,1,np.floor(section_len/delta).astype(int))\n", " \n", " fx=interp1d(np.linspace(0,1,2),start_xp[idx:idx+2],kind=1)\n", " fy=interp1d(np.linspace(0,1,2),start_yp[idx:idx+2],kind=1)\n", " \n", " final_xp=np.append(final_xp,fx(interp_range))\n", " final_yp=np.append(final_yp,fy(interp_range))\n", " \n", " dx = np.append(0, np.diff(final_xp))\n", " dy = np.append(0, np.diff(final_yp))\n", " theta = np.arctan2(dy, dx)\n", "\n", " return np.vstack((final_xp,final_yp,theta))\n", "\n", "\n", "def get_nn_idx(state,path):\n", " \"\"\"\n", " Computes the index of the waypoint closest to vehicle\n", " \"\"\"\n", "\n", " dx = state[0]-path[0,:]\n", " dy = state[1]-path[1,:]\n", " dist = np.hypot(dx,dy)\n", " nn_idx = np.argmin(dist)\n", "\n", " try:\n", " v = [path[0,nn_idx+1] - path[0,nn_idx],\n", " path[1,nn_idx+1] - path[1,nn_idx]] \n", " v /= np.linalg.norm(v)\n", "\n", " d = [path[0,nn_idx] - state[0],\n", " path[1,nn_idx] - state[1]]\n", "\n", " if np.dot(d,v) > 0:\n", " target_idx = nn_idx\n", " else:\n", " target_idx = nn_idx+1\n", "\n", " except IndexError as e:\n", " target_idx = nn_idx\n", "\n", " return target_idx\n", "\n", "def normalize_angle(angle):\n", " \"\"\"\n", " Normalize an angle to [-pi, pi]\n", " \"\"\"\n", " while angle > np.pi:\n", " angle -= 2.0 * np.pi\n", "\n", " while angle < -np.pi:\n", " angle += 2.0 * np.pi\n", "\n", " return angle\n", "\n", "def get_ref_trajectory(state, path, target_v):\n", " \"\"\"\n", " modified reference in robot frame\n", " \"\"\"\n", " xref = np.zeros((N, T + 1))\n", " dref = np.zeros((1, T + 1))\n", " \n", " #sp = np.ones((1,T +1))*target_v #speed profile\n", " \n", " ncourse = path.shape[1]\n", "\n", " ind = get_nn_idx(state, path)\n", " dx=path[0,ind] - state[0]\n", " dy=path[1,ind] - state[1]\n", " \n", " xref[0, 0] = dx * np.cos(-state[3]) - dy * np.sin(-state[3]) #X\n", " xref[1, 0] = dy * np.cos(-state[3]) + dx * np.sin(-state[3]) #Y\n", " xref[2, 0] = target_v #V\n", " xref[3, 0] = normalize_angle(path[2,ind]- state[3]) #Theta\n", " dref[0, 0] = 0.0 # steer operational point should be 0\n", " \n", " dl = 0.05 # Waypoints spacing [m]\n", " travel = 0.0\n", " \n", " for i in range(T + 1):\n", " travel += abs(target_v) * DT #current V or target V?\n", " dind = int(round(travel / dl))\n", " \n", " if (ind + dind) < ncourse:\n", " dx=path[0,ind + dind] - state[0]\n", " dy=path[1,ind + dind] - state[1]\n", " \n", " xref[0, i] = dx * np.cos(-state[3]) - dy * np.sin(-state[3])\n", " xref[1, i] = dy * np.cos(-state[3]) + dx * np.sin(-state[3])\n", " xref[2, i] = target_v #sp[ind + dind]\n", " xref[3, i] = normalize_angle(path[2,ind + dind] - state[3])\n", " dref[0, i] = 0.0\n", " else:\n", " dx=path[0,ncourse - 1] - state[0]\n", " dy=path[1,ncourse - 1] - state[1]\n", " \n", " xref[0, i] = dx * np.cos(-state[3]) - dy * np.sin(-state[3])\n", " xref[1, i] = dy * np.cos(-state[3]) + dx * np.sin(-state[3])\n", " xref[2, i] = 0.0 #stop? #sp[ncourse - 1]\n", " xref[3, i] = normalize_angle(path[2,ncourse - 1] - state[3])\n", " dref[0, i] = 0.0\n", "\n", " return xref, dref" ] }, { "cell_type": "code", "execution_count": 19, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ "CVXPY Optimization Time: Avrg: 0.1598s Max: 0.1950s Min: 0.1460s\n" ] } ], "source": [ "track = compute_path_from_wp([0,3,4,6,10,12,14,6,1,0],\n", " [0,0,2,4,3,3,-2,-6,-2,-2],0.05)\n", "\n", "# track = compute_path_from_wp([0,10,10,0],\n", "# [0,0,1,1],0.05)\n", "\n", "sim_duration = 200 #time steps\n", "opt_time=[]\n", "\n", "x_sim = np.zeros((N,sim_duration))\n", "u_sim = np.zeros((M,sim_duration-1))\n", "\n", "MAX_SPEED = 1.5 #m/s\n", "MAX_ACC = 1.0 #m/ss\n", "MAX_D_ACC = 1.0 #m/sss\n", "MAX_STEER = np.radians(30) #rad\n", "MAX_D_STEER = np.radians(30) #rad/s\n", "\n", "REF_VEL = 1.0 #m/s\n", "\n", "# Starting Condition\n", "x0 = np.zeros(N)\n", "x0[0] = 0 #x\n", "x0[1] = -0.25 #y\n", "x0[2] = 0.0 #v\n", "x0[3] = np.radians(-0) #yaw\n", " \n", "#starting guess\n", "u_bar = np.zeros((M,T))\n", "u_bar[0,:] = MAX_ACC/2 #a\n", "u_bar[1,:] = 0.0 #delta\n", "\n", "for sim_time in range(sim_duration-1):\n", " \n", " iter_start = time.time()\n", " \n", " # dynamics starting state w.r.t. robot are always null except vel \n", " x_bar = np.zeros((N,T+1))\n", " x_bar[2,0] = x_sim[2,sim_time]\n", " \n", " #prediction for linearization of costrains\n", " for t in range (1,T+1):\n", " xt = x_bar[:,t-1].reshape(N,1)\n", " ut = u_bar[:,t-1].reshape(M,1)\n", " A,B,C = get_linear_model(xt,ut)\n", " xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n", " x_bar[:,t] = xt_plus_one\n", " \n", " #CVXPY Linear MPC problem statement\n", " x = cp.Variable((N, T+1))\n", " u = cp.Variable((M, T))\n", " cost = 0\n", " constr = []\n", "\n", " # Cost Matrices\n", " Q = np.diag([20,20,10,0]) #state error cost\n", " Qf = np.diag([30,30,30,0]) #state final error cost\n", " R = np.diag([10,10]) #input cost\n", " R_ = np.diag([10,10]) #input rate of change cost\n", "\n", " #Get Reference_traj\n", " #dont use x0 in this case\n", " x_ref, d_ref = get_ref_trajectory(x_sim[:,sim_time] ,track, REF_VEL)\n", " \n", " #Prediction Horizon\n", " for t in range(T):\n", "\n", " # Tracking Error\n", " cost += cp.quad_form(x[:,t] - x_ref[:,t], Q)\n", "\n", " # Actuation effort\n", " cost += cp.quad_form(u[:,t], R)\n", "\n", " # Actuation rate of change\n", " if t < (T - 1):\n", " cost += cp.quad_form(u[:,t+1] - u[:,t], R_)\n", " constr+= [cp.abs(u[0, t + 1] - u[0, t])/DT <= MAX_D_ACC] #max acc rate of change\n", " constr += [cp.abs(u[1, t + 1] - u[1, t])/DT <= MAX_D_STEER] #max steer rate of change\n", "\n", " # Kinrmatics Constrains (Linearized model)\n", " A,B,C = get_linear_model(x_bar[:,t], u_bar[:,t])\n", " constr += [x[:,t+1] == A@x[:,t] + B@u[:,t] + C.flatten()]\n", " \n", " #Final Point tracking\n", " cost += cp.quad_form(x[:, T] - x_ref[:, T], Qf)\n", "\n", " # sums problem objectives and concatenates constraints.\n", " constr += [x[:,0] == x_bar[:,0]] #starting condition\n", " constr += [x[2,:] <= MAX_SPEED] #max speed\n", " constr += [x[2,:] >= 0.0] #min_speed (not really needed)\n", " constr += [cp.abs(u[0,:]) <= MAX_ACC] #max acc\n", " constr += [cp.abs(u[1,:]) <= MAX_STEER] #max steer\n", " \n", " # Solve\n", " prob = cp.Problem(cp.Minimize(cost), constr)\n", " solution = prob.solve(solver=cp.OSQP, verbose=False)\n", " \n", " #retrieved optimized U and assign to u_bar to linearize in next step\n", " u_bar = np.vstack((np.array(u.value[0,:]).flatten(),\n", " (np.array(u.value[1,:]).flatten())))\n", " \n", " u_sim[:,sim_time] = u_bar[:,0]\n", " \n", " # Measure elpased time to get results from cvxpy\n", " opt_time.append(time.time()-iter_start)\n", " \n", " # move simulation to t+1\n", " tspan = [0,DT]\n", " x_sim[:,sim_time+1] = odeint(kinematics_model,\n", " x_sim[:,sim_time],\n", " tspan,\n", " args=(u_bar[:,0],))[1]\n", " \n", "print(\"CVXPY Optimization Time: Avrg: {:.4f}s Max: {:.4f}s Min: {:.4f}s\".format(np.mean(opt_time),\n", " np.max(opt_time),\n", " np.min(opt_time))) " ] }, { "cell_type": "code", "execution_count": 20, "metadata": {}, "outputs": [ { "data": { "image/png": "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\n", "text/plain": [ "
" ] }, "metadata": {}, "output_type": "display_data" } ], "source": [ "#plot trajectory\n", "grid = plt.GridSpec(4, 5)\n", "\n", "plt.figure(figsize=(15,10))\n", "\n", "plt.subplot(grid[0:4, 0:4])\n", "plt.plot(track[0,:],track[1,:],\"b+\")\n", "plt.plot(x_sim[0,:],x_sim[1,:])\n", "plt.axis(\"equal\")\n", "plt.ylabel('y')\n", "plt.xlabel('x')\n", "\n", "plt.subplot(grid[0, 4])\n", "plt.plot(u_sim[0,:])\n", "plt.ylabel('a(t) [m/ss]')\n", "\n", "plt.subplot(grid[1, 4])\n", "plt.plot(x_sim[2,:])\n", "plt.ylabel('v(t) [m/s]')\n", "\n", "plt.subplot(grid[2, 4])\n", "plt.plot(np.degrees(u_sim[1,:]))\n", "plt.ylabel('delta(t) [rad]')\n", "\n", "plt.subplot(grid[3, 4])\n", "plt.plot(x_sim[3,:])\n", "plt.ylabel('theta(t) [rad]')\n", "\n", "plt.tight_layout()\n", "plt.show()" ] }, { "cell_type": "code", "execution_count": null, "metadata": {}, "outputs": [], "source": [] } ], "metadata": { "kernelspec": { "display_name": "Python 3", "language": "python", "name": "python3" }, "language_info": { "codemirror_mode": { "name": "ipython", "version": 3 }, "file_extension": ".py", "mimetype": "text/x-python", "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython3", "version": "3.8.5" } }, "nbformat": 4, "nbformat_minor": 4 }