diff --git a/notebooks/1.0-lti-system-modelling.ipynb b/notebooks/1.0-lti-system-modelling.ipynb index 5fa3d00..db45409 100644 --- a/notebooks/1.0-lti-system-modelling.ipynb +++ b/notebooks/1.0-lti-system-modelling.ipynb @@ -14,8 +14,8 @@ "execution_count": 1, "metadata": { "ExecuteTime": { - "end_time": "2024-10-23T07:18:06.003291Z", - "start_time": "2024-10-23T07:18:05.220024Z" + "end_time": "2024-10-24T02:21:22.012892Z", + "start_time": "2024-10-24T02:21:21.029487Z" } }, "outputs": [], @@ -185,8 +185,8 @@ "execution_count": 2, "metadata": { "ExecuteTime": { - "end_time": "2024-10-23T07:18:06.008037Z", - "start_time": "2024-10-23T07:18:06.005433Z" + "end_time": "2024-10-24T02:21:22.017780Z", + "start_time": "2024-10-24T02:21:22.013940Z" } }, "outputs": [], @@ -233,8 +233,8 @@ "execution_count": 3, "metadata": { "ExecuteTime": { - "end_time": "2024-10-23T07:18:06.167910Z", - "start_time": "2024-10-23T07:18:06.008459Z" + "end_time": "2024-10-24T02:21:22.177869Z", + "start_time": "2024-10-24T02:21:22.016227Z" } }, "outputs": [ @@ -271,8 +271,8 @@ "execution_count": 4, "metadata": { "ExecuteTime": { - "end_time": "2024-10-23T07:18:06.382763Z", - "start_time": "2024-10-23T07:18:06.166338Z" + "end_time": "2024-10-24T02:21:22.400345Z", + "start_time": "2024-10-24T02:21:22.178469Z" } }, "outputs": [ @@ -324,11 +324,11 @@ }, { "cell_type": "code", - "execution_count": 17, + "execution_count": null, "metadata": { "ExecuteTime": { - "end_time": "2024-10-23T07:18:54.770415Z", - "start_time": "2024-10-23T07:18:54.762519Z" + "end_time": "2024-10-24T02:21:22.405520Z", + "start_time": "2024-10-24T02:21:22.401778Z" } }, "outputs": [], @@ -345,11 +345,10 @@ }, { "cell_type": "code", - "execution_count": 18, + "execution_count": null, "metadata": { "ExecuteTime": { - "end_time": "2024-10-23T07:18:55.153233Z", - "start_time": "2024-10-23T07:18:55.151535Z" + "start_time": "2024-10-24T02:21:22.403693Z" } }, "outputs": [], @@ -394,41 +393,13 @@ }, { "cell_type": "code", - "execution_count": 21, + "execution_count": null, "metadata": { "ExecuteTime": { - "end_time": "2024-10-23T07:19:24.277670Z", - "start_time": "2024-10-23T07:19:24.269670Z" + "start_time": "2024-10-24T02:21:22.404761Z" } }, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "CPU times: user 4.69 ms, sys: 3.46 ms, total: 8.15 ms\n", - "Wall time: 5.45 ms\n" - ] - }, - { - "name": "stderr", - "output_type": "stream", - "text": [ - "/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_16440/2229978461.py:17: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n", - " A[0, 2] = np.cos(theta)\n", - "/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_16440/2229978461.py:18: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n", - " A[0, 3] = -v * np.sin(theta)\n", - "/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_16440/2229978461.py:19: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n", - " A[1, 2] = np.sin(theta)\n", - "/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_16440/2229978461.py:20: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n", - " A[1, 3] = v * np.cos(theta)\n", - "/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_16440/2229978461.py:21: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n", - " A[3, 2] = v * np.tan(delta) / L\n", - "/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_16440/2229978461.py:26: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n", - " B[3, 1] = v / (L * np.cos(delta) ** 2)\n" - ] - } - ], + "outputs": [], "source": [ "%%time\n", "\n", @@ -458,23 +429,13 @@ }, { "cell_type": "code", - "execution_count": 22, + "execution_count": null, "metadata": { "ExecuteTime": { - "end_time": "2024-10-23T07:19:24.878011Z", - "start_time": "2024-10-23T07:19:24.817493Z" + "start_time": "2024-10-24T02:21:22.406154Z" } }, - "outputs": [ - { - "data": { - "text/plain": "
", - "image/png": "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" - }, - "metadata": {}, - "output_type": "display_data" - } - ], + "outputs": [], "source": [ "# plot trajectory\n", "plt.subplot(2, 2, 1)\n", @@ -506,7 +467,8 @@ "execution_count": null, "metadata": { "ExecuteTime": { - "start_time": "2024-10-23T07:18:06.387396Z" + "end_time": "2024-10-24T02:21:22.407303Z", + "start_time": "2024-10-24T02:21:22.406998Z" } }, "outputs": [], diff --git a/notebooks/2.4-MPC-kinematics.ipynb b/notebooks/2.4-MPC-kinematics.ipynb new file mode 100644 index 0000000..50245ed --- /dev/null +++ b/notebooks/2.4-MPC-kinematics.ipynb @@ -0,0 +1,1107 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# 2.4 阿克曼运动学MPC\n", + "本片笔记描述阿克曼底盘的运动学MPC控制算法" + ] + }, + { + "cell_type": "markdown", + "source": [ + "## 阿克曼运动学模型建模\n", + "\n", + "系统的状态变量为:\n", + "* $x$:机器人前向方向为正\n", + "* $y$:机器人左侧方向为正\n", + "* $\\theta$:机器人航向角\n", + "\n", + "系统的控制变量为:\n", + "* $v$:机器人速度\n", + "* $\\delta$:前轮转角\n", + "\n", + "根据两轮自行车模型,可以得到机器人的运动学模型:\n", + "* $\\dot{x} = v \\cos(\\theta)$\n", + "* $\\dot{y} = v \\sin(\\theta)$\n", + "* $\\dot{theta} = \\frac{v \\tan(\\delta)}{L}$\n", + "\n", + "其中,$L$为机器人的轴距\n", + "\n", + "离散化后,可以得到:\n", + "* $x_{t+1} = x_t + v_t \\cos(\\theta_t) \\Delta t$\n", + "* $y_{t+1} = y_t + v_t \\sin(\\theta_t) \\Delta t$\n", + "* $\\theta_{t+1} = \\theta_t + \\frac{v_t \\tan(\\delta_t)}{L} \\Delta t$\n", + "\n", + "这里,我们假设机器人的速度和转角是控制变量,即$v_t$和$\\delta_t$是已知的,我们可以通过上述公式计算出下一个时刻的状态。\n", + "\n", + "上述模型是一个非线性模型,我们可以通过线性化的方式来近似这个模型,这样就可以使用MPC来进行控制。\n", + "\n", + "使用泰勒级数在参考点$(\\bar{x}, \\bar{u})$处线性化模型(每步都需要重新线性化模型):\n", + "\n", + "$ f(x,u) \\approx f(\\bar{x}, \\bar{u}) + \\frac{\\partial f}{\\partial x} (x - \\bar{x}) + \\frac{\\partial f}{\\partial u} (u - \\bar{u})$\n", + "\n", + "重写为状态空间的形式:\n", + "\n", + "$ f(x,u) \\approx 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", + "其中\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 \\theta} \\\\\n", + "\\end{bmatrix}\n", + "\\quad\n", + "=\n", + "\\displaystyle \\left[\\begin{matrix}0 & 0 & - v \\sin{\\left(\\theta \\right)}\\\\0 & 0 & v \\cos{\\left(\\theta \\right)}\\\\0 & 0 & 0\\end{matrix}\\right]\n", + "$\n", + "\n", + "and\n", + "\n", + "$\n", + "B = \n", + "\\quad\n", + "\\begin{bmatrix}\n", + "\\frac{\\partial f(x,u)}{\\partial v} & \\frac{\\partial f(x,u)}{\\partial \\delta} \\\\\n", + "\\end{bmatrix}\n", + "\\quad\n", + "= \n", + "\\displaystyle \\left[\\begin{matrix}\\cos{\\left(\\theta \\right)} & 0\\\\ \\sin{\\left(\\theta \\right)} & 0\\\\ \\frac{\\tan{\\left(\\delta \\right)}}{L} & \\frac{v \\left(\\tan^{2}{\\left(\\delta \\right)} + 1\\right)}{L}\\end{matrix}\\right]\n", + "$\n", + "\n", + "矩阵A和B是雅可比矩阵\n", + "\n", + "所以,离散化后的模型为:\n", + "\n", + "* $ x_{t+1} = x_t + (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})) \\Delta t $\n", + "\n", + "* $ x_{t+1} = (I + A\\Delta t)x_t + B\\Delta t u_t + \\Delta t (f(\\bar{x}, \\bar{u}) - A\\bar{x} - B\\bar{u}) $\n", + "\n", + "写为矩阵形式:\n", + "\n", + "* $ x_{t+1} = A'x_t + B'u_t + C' $\n", + "\n", + "* $ A' = I + \\Delta t A|_{x=\\bar{x},u=\\bar{u}} $\n", + "\n", + "* $ B' = \\Delta t B|_{x=\\bar{x},u=\\bar{u}} $\n", + "\n", + "* $ C' = \\Delta t (f(\\bar{x}, \\bar{u}) - A|_{x=\\bar{x},u=\\bar{u}}\\bar{x} - B|_{x=\\bar{x},u=\\bar{u}}\\bar{u}) $\n" + ], + "metadata": { + "collapsed": false + } + }, + { + "cell_type": "markdown", + "source": [ + "## 常微分方程模型\n", + "用于仿真车辆运动,可作为真值来验证MPC控制的效果" + ], + "metadata": { + "collapsed": false + } + }, + { + "cell_type": "code", + "execution_count": 20, + "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", + "\n", + "plt.style.use(\"ggplot\")\n", + "\n", + "import time\n", + "\n", + "# 定义常量\n", + "N = 3 # 状态变量 x, y, theta\n", + "M = 2 # 控制变量 v, delta\n", + "T = 40 # 预测视野 \n", + "DT = 0.2 # 离散步长 [s]\n", + "L = 0.3 # 车辆长度 [m]\n", + "\n", + "# 使用连续性方程\n", + "def kinematics_ode_model(x,t,u):\n", + " \"\"\"\n", + " Returns the set of ODE of the vehicle model.\n", + " 返回车辆模型的ODE模型\n", + " \"\"\"\n", + "\n", + "\n", + " dxdt = u[0] * np.cos(x[2])\n", + " dydt = u[0] * np.sin(x[2])\n", + " dthetadt = u[0] * np.tan(u[1]) / L\n", + "\n", + " dqdt = [dxdt, dydt, dthetadt]\n", + "\n", + " return dqdt\n", + "\n", + "\n", + "def predict(x0, u):\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_ode_model, x0, tspan, args=(u[:, t - 1],))\n", + "\n", + " x0 = x_next[1]\n", + " x_[:, t] = x_next[1]\n", + "\n", + " return x_" + ], + "metadata": { + "collapsed": false, + "ExecuteTime": { + "end_time": "2024-10-24T03:04:45.623427Z", + "start_time": "2024-10-24T03:04:45.594094Z" + } + } + }, + { + "cell_type": "code", + "execution_count": 21, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "CPU times: user 1.82 ms, sys: 15 μs, total: 1.83 ms\n", + "Wall time: 1.84 ms\n" + ] + } + ], + "source": [ + "%%time\n", + "\n", + "u_bar = np.zeros((M, T))\n", + "u_bar[0, :] = 1.0 # 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] = np.radians(0)\n", + "\n", + "x_bar = predict(x0, u_bar)" + ], + "metadata": { + "collapsed": false, + "ExecuteTime": { + "end_time": "2024-10-24T03:04:46.199286Z", + "start_time": "2024-10-24T03:04:46.187194Z" + } + } + }, + { + "cell_type": "code", + "execution_count": 22, + "outputs": [ + { + "data": { + "text/plain": "
", + "image/png": "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" + }, + "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()" + ], + "metadata": { + "collapsed": false, + "ExecuteTime": { + "end_time": "2024-10-24T03:04:46.816219Z", + "start_time": "2024-10-24T03:04:46.759086Z" + } + } + }, + { + "cell_type": "markdown", + "source": [ + "## 线性化状态空间模型" + ], + "metadata": { + "collapsed": false + } + }, + { + "cell_type": "code", + "execution_count": 23, + "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", + " x = x_bar[0]\n", + " y = x_bar[1]\n", + " theta = x_bar[2]\n", + "\n", + " v = u_bar[0]\n", + " delta = u_bar[1]\n", + "\n", + " A = np.zeros((N, N))\n", + " A[0, 2] = -v * np.sin(theta)\n", + " A[1, 2] = v * np.cos(theta)\n", + " A_lin = np.eye(N) + DT * A\n", + "\n", + " B = np.zeros((N, M))\n", + " B[0, 0] = np.cos(theta)\n", + " B[1, 0] = np.sin(theta)\n", + " B[2, 0] = v * np.tan(delta) / L\n", + " B[2, 1] = v / (L * np.cos(delta) ** 2)\n", + " B_lin = DT * B\n", + "\n", + " f_xu = np.array(\n", + " [v * np.cos(theta), v * np.sin(theta), v * np.tan(delta) / L]\n", + " ).reshape(N, 1)\n", + " C_lin = DT * (\n", + " f_xu - np.dot(A, x_bar.reshape(N, 1)) - np.dot(B, u_bar.reshape(M, 1))\n", + " )\n", + "\n", + " return np.round(A_lin, 4), np.round(B_lin, 4), np.round(C_lin, 4)" + ], + "metadata": { + "collapsed": false, + "ExecuteTime": { + "end_time": "2024-10-24T03:04:48.033205Z", + "start_time": "2024-10-24T03:04:48.027595Z" + } + } + }, + { + "cell_type": "code", + "execution_count": 24, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "CPU times: user 2.04 ms, sys: 1.79 ms, total: 3.83 ms\n", + "Wall time: 2.54 ms\n" + ] + }, + { + "name": "stderr", + "output_type": "stream", + "text": [ + "/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_9821/761030008.py:14: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n", + " A[0, 2] = -v * np.sin(theta)\n", + "/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_9821/761030008.py:15: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n", + " A[1, 2] = v * np.cos(theta)\n", + "/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_9821/761030008.py:19: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n", + " B[0, 0] = np.cos(theta)\n", + "/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_9821/761030008.py:20: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n", + " B[1, 0] = np.sin(theta)\n", + "/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_9821/761030008.py:21: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n", + " B[2, 0] = v * np.tan(delta) / L\n", + "/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_9821/761030008.py:22: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n", + " B[2, 1] = v / (L * np.cos(delta) ** 2)\n" + ] + } + ], + "source": [ + "%%time\n", + "\n", + "u_bar = np.zeros((M, T))\n", + "u_bar[0, :] = 1.0 # 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] = 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)" + ], + "metadata": { + "collapsed": false, + "ExecuteTime": { + "end_time": "2024-10-24T03:04:48.720648Z", + "start_time": "2024-10-24T03:04:48.703990Z" + } + } + }, + { + "cell_type": "code", + "execution_count": 25, + "outputs": [ + { + "data": { + "text/plain": "
", + "image/png": "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" + }, + "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()" + ], + "metadata": { + "collapsed": false, + "ExecuteTime": { + "end_time": "2024-10-24T03:04:49.296366Z", + "start_time": "2024-10-24T03:04:49.239223Z" + } + } + }, + { + "cell_type": "markdown", + "source": [ + "对比两个轨迹,可以看到线性化的模型能够很好的近似真实的模型" + ], + "metadata": { + "collapsed": false + } + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "#### Linear MPC Formulation 线性MPC表述\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", + "线性MPC使用**LTI**(线性时不变)离散状态空间模型,该模型表示用于预测的运动模型。\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", + "LTI表述意味着**未来状态**与当前状态和执行器信号之间是线性相关的。因此,MPC试图找到一个有限长度视野上的**控制策略**U。\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", + "用于最小化(将状态驱动至0)的目标函数为:\n", + "\n", + "$\n", + "\\begin{equation}\n", + "\\begin{aligned}\n", + "\\min_{} \\quad & \\sum^{t+T-1}_{j=t} x^T_{j|t}Qx_{j|t} + u^T_{j|t}Ru_{j|t}\\\\\n", + "\\textrm{s.t.} \\quad & x(0) = x0\\\\\n", + " & x_{j+1|t} = Ax_{j|t}+Bu_{j|t}) \\quad \\textrm{for} \\quad t 0:\n", + " 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", + "\n", + "def get_ref_trajectory(state, path, target_v):\n", + " \"\"\"\n", + " Adapted from pythonrobotics\n", + " 获取参考轨迹\n", + " 从当前位置开始,截取路径上的一段作为参考轨迹,其中v=固定的,参考的方向转角为0\n", + " \"\"\"\n", + " xref = np.zeros((N, T + 1))\n", + " dref = np.zeros((M, 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] = path[2, ind] # Theta\n", + " dref[0, 0] = 0.0 # steer operational point should be 0\n", + " dref[1, 0] = 0.0 # speed\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] = path[2, ind + dind]\n", + " dref[0, i] = 0.0\n", + " dref[1, i] = target_v\n", + " else:\n", + " xref[0, i] = path[0, ncourse - 1]\n", + " xref[1, i] = path[1, ncourse - 1]\n", + " xref[2, i] = path[2, ncourse - 1]\n", + " dref[0, i] = 0.0\n", + " dref[1, i] = 0.0\n", + "\n", + " return xref, dref" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## MPC \n", + "\n", + "test single iteration\n", + "测试单次迭代" + ] + }, + { + "cell_type": "code", + "execution_count": 29, + "metadata": { + "ExecuteTime": { + "end_time": "2024-10-24T03:05:26.555645Z", + "start_time": "2024-10-24T03:05:26.481067Z" + } + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "===============================================================================\n", + " CVXPY \n", + " v1.5.3 \n", + "===============================================================================\n", + "(CVXPY) Oct 24 11:05:26 AM: Your problem has 203 variables, 243 constraints, and 0 parameters.\n", + "(CVXPY) Oct 24 11:05:26 AM: It is compliant with the following grammars: DCP, DQCP\n", + "(CVXPY) Oct 24 11:05:26 AM: (If you need to solve this problem multiple times, but with different data, consider using parameters.)\n", + "(CVXPY) Oct 24 11:05:26 AM: CVXPY will first compile your problem; then, it will invoke a numerical solver to obtain a solution.\n", + "(CVXPY) Oct 24 11:05:26 AM: Your problem is compiled with the CPP canonicalization backend.\n", + "-------------------------------------------------------------------------------\n", + " Compilation \n", + "-------------------------------------------------------------------------------\n", + "(CVXPY) Oct 24 11:05:26 AM: Compiling problem (target solver=OSQP).\n", + "(CVXPY) Oct 24 11:05:26 AM: Reduction chain: CvxAttr2Constr -> Qp2SymbolicQp -> QpMatrixStuffing -> OSQP\n", + "(CVXPY) Oct 24 11:05:26 AM: Applying reduction CvxAttr2Constr\n", + "(CVXPY) Oct 24 11:05:26 AM: Applying reduction Qp2SymbolicQp\n", + "(CVXPY) Oct 24 11:05:26 AM: Applying reduction QpMatrixStuffing\n", + "(CVXPY) Oct 24 11:05:26 AM: Applying reduction OSQP\n", + "(CVXPY) Oct 24 11:05:26 AM: Finished problem compilation (took 5.022e-02 seconds).\n", + "-------------------------------------------------------------------------------\n", + " Numerical solver \n", + "-------------------------------------------------------------------------------\n", + "(CVXPY) Oct 24 11:05:26 AM: Invoking solver OSQP to obtain a solution.\n", + "-------------------------------------------------------------------------------\n", + " Summary \n", + "-------------------------------------------------------------------------------\n", + "(CVXPY) Oct 24 11:05:26 AM: Problem status: optimal\n", + "(CVXPY) Oct 24 11:05:26 AM: Optimal value: 4.687e+02\n", + "(CVXPY) Oct 24 11:05:26 AM: Compilation took 5.022e-02 seconds\n", + "(CVXPY) Oct 24 11:05:26 AM: Solver (including time spent in interface) took 3.240e-03 seconds\n", + "CPU times: user 77.8 ms, sys: 7.17 ms, total: 85 ms\n", + "Wall time: 87.9 ms\n" + ] + }, + { + "name": "stderr", + "output_type": "stream", + "text": [ + "/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_9821/761030008.py:14: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n", + " A[0, 2] = -v * np.sin(theta)\n", + "/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_9821/761030008.py:15: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n", + " A[1, 2] = v * np.cos(theta)\n", + "/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_9821/761030008.py:19: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n", + " B[0, 0] = np.cos(theta)\n", + "/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_9821/761030008.py:20: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n", + " B[1, 0] = np.sin(theta)\n", + "/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_9821/761030008.py:21: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n", + " B[2, 0] = v * np.tan(delta) / L\n", + "/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_9821/761030008.py:22: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n", + " B[2, 1] = v / (L * np.cos(delta) ** 2)\n" + ] + } + ], + "source": [ + "%%time\n", + "\n", + "# 限制条件\n", + "MAX_SPEED = 1.5 # m/s\n", + "MAX_STEER = np.radians(30) # rad\n", + "REF_VEL = 1.0 # 目标路径参考速度\n", + "\n", + "#获取参考轨迹,线性插值,三个点[0,0],[3,0],[6,0]\n", + "track = compute_path_from_wp([0, 3, 6], [0, 0, 0], 0.05)\n", + "\n", + "# Starting Condition 初始条件\n", + "x0 = np.zeros(N)\n", + "x0[0] = 0 # x\n", + "x0[1] = -0.25 # y\n", + "x0[2] = np.radians(-0) # yaw\n", + "\n", + "# starting guess 开始猜测\n", + "u_bar = np.zeros((M, T))\n", + "u_bar[0, :] = REF_VEL # v\n", + "u_bar[1, :] = 0.1 # delta\n", + "\n", + "# dynamics starting state w.r.t world frame 与世界坐标系相关的动力学起始状态\n", + "x_bar = np.zeros((N, T + 1)) # 4x21\n", + "x_bar[:, 0] = x0\n", + "\n", + "# prediction for linearization of costrains 用于约束线性化的预测\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", + " A, B, C = get_linear_model(xt, ut) # 获取在t - 1时刻的线性近似模型\n", + " xt_plus_one = np.squeeze(np.dot(A, xt) + np.dot(B, ut) + C)\n", + " x_bar[:, t] = xt_plus_one # 获取t时刻的状态\n", + "\n", + "# x_bar是根据猜测的u_bar获取的预测状态估计\n", + "\n", + "# CVXPY Linear MPC problem statement CVXPY线性MPC问题陈述\n", + "x = cp.Variable((N, T + 1)) # 4x21维,状态向量\n", + "u = cp.Variable((M, T)) # 2x20维,控制向量\n", + "cost = 0\n", + "constr = []\n", + "\n", + "# Cost Matrices\n", + "Q = np.diag([10, 10, 10]) # state error cost 状态误差成本\n", + "Qf = np.diag([10, 10, 10]) # 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表示参考转角\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", + "\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 += [u[0, :] <= MAX_SPEED] # max speed 最大速度\n", + "constr += [u[0, :] >= 0.0] # min_speed (not really needed) 最小速度(实际上不需要)\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": 30, + "metadata": { + "ExecuteTime": { + "end_time": "2024-10-24T03:05:27.460730Z", + "start_time": "2024-10-24T03:05:27.349153Z" + } + }, + "outputs": [ + { + "data": { + "text/plain": "
", + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAnUAAAHWCAYAAAARl3+JAAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjkuMiwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy8hTgPZAAAACXBIWXMAAA9hAAAPYQGoP6dpAACcyElEQVR4nOzdd3wUZf7A8c8z2QQSQhIghARCSYCEGoqCgIUmRY0liopYLpazgO2sx3kWLHD5WfAO+4mCelgAUUSUCAiKCFiQ0AOEgJRAQhICJCFlnt8fCysxvezO7ub7fr3yIjvzzMz3mQ2z3515itJaa4QQQgghhEczrA5ACCGEEELUnyR1QgghhBBeQJI6IYQQQggvIEmdEEIIIYQXkKROCCGEEMILSFInhBBCCOEFJKkTQgghhPACktQJIYQQQngBSeqEEEIIIbyAJHVCCCGEEF7AZnUA7iAnJ4eSkpIqy7Ru3ZrMzEwXReRZ5NxUTs5N5Wp6bmw2Gy1atHBBRI1LTa574J1/w1Inz9CY61TX654kdUBJSQnFxcWVrldKOcrJVLllybmpnJybysm5sV511z3wzvdJ6uQZpE51I49fhRBCCCG8gCR1QgghhBBeQJI6IYQQQggvIEmdEEIIIYQXkI4SQgghhPBI+kgmeulC0CaqZz+I6YVq0tTqsCwjSZ0QQgghPIrOP4H+ap49oSux9+LWy74Amw269kT16o/qew4qrK3FkbqWJHVCCCGE8Ai6pAS98mv0oo/geJ59YWxvVJu26M3r4chh2LoBvXUDev5sjLsmo/qeY23QLiRJnRBCCCHcnt6/F/O1qXD4gH1BeCTGuESIG4BSyj72W8Z+9OZf0b/8ADu3Yr79IsajSaj2UZbG7irSUUIIIYQQbk3nn8B87Tl7Qtc8GHX9XRhPzUD1GegY1FcphYqIxLjwMowHn4PufeBkIeYrz6CP5lhbAReRpE4IIYQQbktrjTnr33D4ILRsjTHlVYxhF6F8fCrdRtlsGHc8Cm3aQXYW5qvPoYtOujBqa0hSJ4QQQgi3pb/5DNavAR8bxp1/RzUPqtF2qlkgxj2PQ0Ag7E5Fz57hNVOOVUba1AkhhBNs2bKFhQsXsnv3bnJycnjooYcYOHBgpeXXrl1LcnIy6enplJSUEBkZydVXX03fvn0dZVasWMFrr71WbtsPPvgAPz8/Z1RDCEvp1M3o+bMBUNfehorqWqvtVZu2GHf9HfPlJ9HrvoOISFT8eGeE6hYkqRNCCCc4efIknTp1Yvjw4bz44ovVlt+6dStxcXFcd911NGvWjG+//ZakpCSmTp1KVNQfjbz9/f3597//XWZbSeiENyrNOULpm/8HpokaOBQ17KI67Ud1i0NNuBP9/qvoz+egI6O8tkesxyZ1CxYsYN26dezfvx8/Pz9iYmK44YYbaNu2cY1JI4RwT/369aNfv341Lp+YmFjm9YQJE/j555/55ZdfyiR1SilCQkIaKEoh3JMuLeXI/z0GR7Mhoj3qxomODhF1YVwwBvPAXvSyLzA/fQ8jbgDK8L4WaB6b1G3ZsoUxY8bQuXNnSktL+eijj3j22Wd56aWXaNq08Y4mLYTwDqZpUlBQQGBgYJnlhYWFTJw4EdM06dSpE9dee22ZpE8Ib2Au+oiTKT9Dk6YYd/0d1dS/3vtUl01A/7AUDv4OG3+BPgMaIFL34rFJ3WOPPVbm9cSJE7nttttIS0ujR48eFkUlhBANY9GiRZw8eZLBgwc7lrVt25aJEyfSoUMHCgoKWLx4MY8//jjPP/88ERERFe6nuLiY4uJix2ulFP7+/o7fq3LmUBHeQurk/nR2Fvqr+QD4/OUeVNsODbJf1SwQPfQi9JJPMZfMx9a38jauzuCK98ljk7o/y8/PByj3rfZMdb24edt/mIYk56Zycm4qJ+emaqtWrWLu3Lk8/PDDBAcHO5bHxMQQExPjeB0bG8ujjz7KV199xS233FLhvhYsWMC8efMcr6OiokhKSqJ169Y1jic8PLwOtXBvUif3lf3pLE6UFNOkV39aX3ZNg14nSq//KweWfQE7ttAy5zBNevRpsH3XlDPfJ69I6rTWzJ49m27dutGhQ+UZfX0vbt7yH8YZ5NxUTs5N5eTclLd69WreeOMNHnjgAeLi4qosaxgGnTt3JiMjo9IyCQkJxMfHO16f/oDMzMykpKSkyv0rpQgPDycjI8NrhoKQOrk3nZlB6ZLPAAi68U4OHTrU4HVSg4ahV31D5v/ewufufzbovqs8bi3eJ5vNVqsvXo7t6hqcO5k5cyZ79+7l6aefrrJcXS9u3vQfpqHJuamcnJvKueLi5olWrVrF66+/zn333Uf//v2rLa+1Zs+ePbRv377SMr6+vvj6+la6fU1orb3ub1jq5J7MLz6C0lJUz3407dUfffBgwyd1YxLQPyxF/7YWc/+eBnu8W1POfJ88Pql75513+OWXX5gyZQqtWrWqsmx9L27e8B/GWeTcVE7OTeW8+dwUFhaWuYN2+PBh0tPTCQwMJDQ0lDlz5pCdnc3dd98N2BO6V199lcTERGJiYsjNzQXsw5UEBAQAMHfuXLp27UpERISjTV16ejq33nqry+snREPTGfvQP34LgHH5DU47jgqPhL7nwPo16CULUDff57RjuZrHJnVaa9555x3WrVvHU089RVhYmNUhCSGEw65du5gyZYrj9XvvvQfA0KFDmTRpEjk5OWRlZTnWL126lNLSUmbOnMnMmTMdy0+XBzhx4gRvvfUWubm5BAQEEBUVxZQpU+jSpYuLaiWE8+iFH4I2oc9AVHRM9RvUgzH2Ksz1a9BrV6Ivvx7VMtSpx3MVj03qZs6cyapVq3jkkUfw9/d3fKsNCAiQgTiFEJbr2bMnn3zySaXrTydqpz311FPV7jMxMbHceHZCeAO9bzf6p+8BMK643unHU9GxENMLUjehl36OusY77nZ7bFKXnJwMlL8QTpw4kWHDhrk+ICGEEELUifn5hwCoAeejIl0z7qIx9irM1E3o75LRl1yLalb56BmewmOTuqq+AQshhBDCM+jdO+C3NaAM1KXXue7AvfpDu46wfw96xWLUJde47thO4n1zZAghhBDCY5iffwDYhxpREZEuO65SCjX2SgD0t4vRpumyYzuLJHVCCCGEsITeuws2rwcfH9Sl411+fHX2eeDfzD7HbNo2lx+/oUlSJ4QQQghL6BVfAaDOOhfV2vWDkSubL+rUHLD6lx9dfvyGJkmdEEIIIVxO5x9Hr10BgBp2sWVxqH72+ZX1+h89ftxMSeqEEEII4XJ69XIoKrJ3VujS3bpAevYHvyZw5DDs2WldHA1AkjohhBBCuJTWGr3y1KPXYRc5pu20gmrSBHqfZY/rV89+BCtJnRBCCCFca1sKZOyHJv6oQcOsjgbVfwhgT+o8+RGsJHVCCCGEcCnzdAeJwcNRTQMsjgZU77PBZoND++HAXqvDqTNJ6oQQQgjhMjrniH2wYeyPXt2B8g+AHv0A0L+stjiaupOkTgghhBAuo79fAqYJXXug2nW0OhwHxyPY9Z7brk6SOiGEEEK4hC4pQX9nn7vdymFMKqL6DgTDgH3p6MMHrA6nTiSpE0IIIYRrbFhnn72heTCq/2CroylDNWsOsb0Bzx2IWJI6IYQQQriEuWIxAOr8MSibr8XRlOfpj2AlqRNCCCGE0+mDv9uHMlEG6oIxVodTIdVvECgFu1PR2ZlWh1NrktQJIYQQwun0qm/sv8SdjWrV2tpgKqGCWzhmt/DEgYglqRNCCCGEU+nSUvSaFQAY511obTDVON3WT//qeUObSFInhBBCCOfash7yciEwCHqdZXU0VVL97O3q2LkVnZdjbTC1JEmdEEIIIZxKr14OgDpnqFt2kDiTatUaOnQGrdFbNlgdTq1IUieEEEIIp9EnjqN/WwuAGjzC4mhqRnWLs/+yfaO1gdSSzeoAhBDCG23ZsoWFCxeye/ducnJyeOihhxg4cGC128yePZt9+/bRokULLrvsMkaPHl2mzJo1a/j44485dOgQbdq04brrrqt2v0JYSf+8CkqKoV1H6BBtdTg1omJ7oZMXoD0sqZM7dUII4QQnT56kU6dO3HLLLTUqf/jwYaZNm0b37t1JSkoiISGBd999lzVr1jjKpKam8vLLL3PBBRfw/PPPc8EFFzB9+nR27NjhrGoIUW/6x1OPXgePQCllcTQ11LWnfXaJzAyPGtpEkjohhHCCfv36MX78eM4555walU9OTiY0NJTExEQiIyMZOXIkw4cP54svvnCU+fLLL4mLiyMhIYF27dqRkJBAr169+PLLL51VDSHqRWfsh13b7GPTnTPU6nBqTPkHQMcuAOhtnnO3Th6/CiGEG9ixYwdxcXFllvXt25dvv/2WkpISbDYbqampXHLJJWXK9OnTh8WLF1e63+LiYoqLix2vlVL4+/s7fq/K6fUec3elBqROrmWu+RYA1bMfRotWNd7OHeqkYnujd6dC6ibUuSPrvz8X1EmSOiGEcAO5ubkEBweXWRYcHExpaSnHjh2jRYsW5ObmEhISUqZMSEgIubm5le53wYIFzJs3z/E6KiqKpKQkWreu+eCv4eHhNS7rKaROzqdNk4PrvqMUaHnJVQRERNR6H1bWqWDwULK+no+xcwsRdYi9Ms6sk0cndXVpiCyEEO7qz9/gtdYVLv9zmarWJyQkEB8fX+4YmZmZlJSUVBtPeHg4GRkZjlg8ndTJdcytGzAzM8C/GbmdYjl68GCNt3WHOulW4WAYlB46wIGNv6FC29Rrf7Wpk81mq9UXL8d2dQ3OHZxuiDx8+HBefPFFq8MRQog6q+iOW15eHj4+PgQGBlZa5ujRo+Xu8J3J19cXX9+KxwWr6Yel1tqtkoWGIHVyPr16GQBqwPlg861TbJbWqUlT6NQV0rZjbkvBOLdhZsJwZp08uqNEbRsiCyGEu+ratSspKSlllm3YsIHo6GhsNvv375iYGDZuLNtoOyUlhZiYGJfFKURN6MICx9ypaohnjE1XERXb2/6Lhwxt4tFJnRBCuKvCwkLS09NJT08H7EOWpKenk5WVBcCcOXN45ZVXHOVHjx5NVlaWY5y65cuXs3z5ci699FJHmYsvvpgNGzbw2WefsX//fj777DM2btxYrvOEEFbTv66Gk4UQ1haiY60Op85UN3tSp7dvdKu7oJXx6MevtVXXXmDu0AvHXcm5qZycm8o1hnOza9cupkyZ4nj93nvvATB06FAmTZpETk6OI8EDCAsLY/LkycyePZslS5bQokULbr75ZgYNGuQoExsby/33389HH33Exx9/THh4OPfffz9du3Z1XcWEqAH946ler0M8aGy6inTuDj42yM6CzAwIa7gOE87QqJK6+vYCc7eeRe5Ezk3l5NxUzpvPTc+ePfnkk08qXT9p0qRyy3r06EFSUlKV+x00aFCZRE8Id6OzMx2PK9WgYdYGU0+qSVOI6go7t6K3b0RJUuc+6toLzB164bgrOTeVk3NTOVf0AhNCWEOv/Q60hpheqFZhVodTbyq2N3rnVnuiev7o6jewUKNK6urbC8zdeha5Ezk3lZNzUzk5N0J4F601+vSAwx5+l+40Fdsb/eUnjnZ17vw42aOTusLCQjIyMhyvTzdEDgwMJDQ01MLIhBBCiEbo9zQ4sBdsvqizhlgdTcPo3A1sNsjNhkMHILyd1RFVyqOTuuoaIgshhBDCdfSPKwBQfQaiAgKtDaaBKL8m9h68qZvRqRtRktQ5R3UNkYUQQgjhGrq0FP3TdwCowcMtjqZhqdje6NTNsG0jXDDW6nAqJePUCSGEEKL+tm6AozkQ2Bx69rM6mgZ1ehBidx+vzqPv1AkhhDMcOHCA7OxsioqKCAoKom3btgQEBFgdlhBuzdFBYsD5KFvFnRI9VnQs2HwhLxcy9kFEe6sjqpAkdUIIAaSmpvLNN9/w22+/kZeXV2adYRh06tSJ888/n2HDhkmCJ8Sf6MIC9Po1AKhB3vXoFUD5+tk7TGzfiN62ESVJnRBCuJ/09HRmzZrF1q1badeuHeeccw7R0dEEBQXh5+fH8ePHOXToEDt27ODDDz/k448/dox5eXpOViEaO/3rj1B00j4tWJR3zkWsYnqht2+EnVth+MVWh1MhuSIJIRq1f/zjH5x33nncdNNNREdHV1m2sLCQ1atX8/nnn1NaWspVV13loiiFcG967QrAPjadO4/jVh8qOhYN6N3brQ6lUpLUCSEatRdffJGIiJpN/dO0aVNGjBjBsGHDyszbKkRjpnOPwNYUwHsGHK7Q6TuQmRnoY0dRzYOtjacC0vtVCNGo1TShO5NhGISFef70R0I0BPu0YCZ06Y5q7b3zOatmgRAeaX+RlmptMJWQpE4IIU65++67SU9Pr3Dd3r17ufvuu10bkBAe4I9pwbyvg8SfqVN369z1EawkdUIIcUpmZiYlJSUVrisuLiYzM9PFEQnh3vTvu2FfOvjYUGefa3U4zhcdC4BOk6ROCCE81qFDh/D397c6DCHcil693P5Ln4GoZs2tDcYF1KmkjvQdaNO0NpgKSEcJIUSjtmLFClauXOl4/fbbb5dL3oqKitizZw89evRwdXhCuC1dUuLo9WoMGWltMK7SriP4NYGCfPsgxG07WB1RGZLUCSEataKiojKDDZ84cYLi4uIyZXx9fRkyZAjXXHONq8MTwn1t/hWOHYXmwV43LVhllI8PdOoCqZvRadtRktQJIYT7GD16NKNHjwZg0qRJPPjgg3Tq1MnaoITwAObqZcCpseka0UDcKioWnboZdqfCeaOsDqeMxvMuCCFENV599VWrQxDCI+jjebDhJwDUkBEWR+NaKjrGPgixG3aWkI4SQohGra6DCGdnZzdwJEJ4Dr3uOygtgQ7RqMgoq8NxrdOdJfbvRRcWWBvLn8idOiFEo3bfffdx4YUXctFFFxEeXvXAqSUlJfz00098+umnnHPOOYwbN67K8kuWLGHhwoXk5uYSGRlJYmIi3bt3r7Dsq6++WqbDxmmRkZG89NJLgL1Tx2uvvVauzAcffICfn1+VsQjRkE73elWNpYPEGVRIK2gRCjlZsGcnxPa2OiQHSeqEEI3aP//5T2bPns3XX39Nly5d6NmzJ1FRUQQHB+Pr68vx48c5dOgQqampbNiwgcLCQi6++GLi4+Or3O/q1auZNWsWt912G7GxsSxdupSpU6cyffp0QkNDy5W/+eabuf766x2vS0tLefjhhxk0aFCZcv7+/vz73/8us0wSOuFKev8eezLjY0MNHGp1ONaIjoFfsuydJSSpE0II99C9e3f+9a9/sX79er755hu++uorioqKypULCwtjzJgxjBo1ihYtWlS730WLFjFixAhGjrTfyUhMTGTDhg0kJyczYcKEcuUDAgIICAhwvF63bh0nTpxg+PCyo/QrpQgJCallLYVoOI6x6XqfjWoeZG0wFlHRsehfVqPdbLowSeqEEALo168f/fr1o6SkhPT0dHJycigqKqJ58+ZERkbSsmXLGu+rpKSEtLQ0rrjiijLL4+Li2L69Zo2rly9fTu/evWndunWZ5YWFhUycOBHTNOnUqRPXXnstUVGVt2kqLi4uM0SLUsoxDp9SqsoYTq+vrpwnkTrVjy4t/WNsunNHOu2Y7v4+GdGxlAKcmi6sJnG6ok6S1AkhxBlsNhtdunSp1z7y8vIwTZPg4OAyy4ODg8nNza12+5ycHH777TfuvffeMsvbtm3LxIkT6dChAwUFBSxevJjHH3+c559/noiIiAr3tWDBAubNm+d4HRUVRVJSUrlksSrVtTX0RFKnuin4aRVZR3MwglvQdvSlTh/KxF3fJ7NFC/b7+MDRHMJsCltYxf//KuLMOklSJ9ySLjoJ21LQm35BjbwM1aat1SEJUWsVfSOvybf0FStW0KxZMwYOHFhmeUxMDDExMY7XsbGxPProo3z11VfccsstFe4rISGhTPu/08evap7bM8uGh4eTkZGB1rrauD2B1Kl+ShfZvyDoAeeT4cS5kD3ifYqMgj07ObTme4wB51dbvDZ1stlstfri5diu1lsI4SQ6Lwe96Vf0u2UbgdM6AjXqcmuCEo3OwYMH+eabb9i/f3+5tnVKKZ544olq9xEUFIRhGOXuyh09erTc3bs/01rz7bffcv7552Or5i6IYRh07tyZjIyMSsv4+vri6+tb6bFqQmvtvh+sdSR1qsP+TxxH/7YGADV4hEvOnzu/TyoqBr1nJ3rXdvTZ59V4O2fWSZI6YRl97Cjs2orevhm9PQV+312ujBo6FhUVU8HWQjS8vXv38thjj9GyZUsyMjLo2LEjx44dIzs7m1atWtGmTZsa7cdmsxEdHU1KSkqZu20pKSkMGDCgym23bNlCRkYGI0ZUP6Cr1po9e/bQvn37GsUlRH3odd9BSQlEdkJ1iLY6HOtFx8KKxejd7jMIsSR1wiV0QT7sS0fv2QnpO9C7d8DhA+ULduiMah2OLsjHuP8pt20kK7zThx9+SJ8+ffjb3/7GhAkTuPPOO4mOjubXX3/l9ddfZ/z48TXeV3x8PDNmzCA6OpqYmBiWLl1KVlYWo0bZpxWaM2cO2dnZ3H333WW2W758OV27dqVDh/JzSs6dO5euXbsSERHhaFOXnp7OrbfeWr+KC1ENrTX6uyUAqHMvtDga96CiY9EAe3ahS4pRtorviLuSJHWiQen845CxH52xDzL2oQ/8DvvS4cjhijeIaI/q2gO6xaFie6OCQlwZrhBl7N69m9tuu83xZeL0I5L+/ftz6aWXMmfOHKZMmVKjfQ0ZMoRjx44xf/58cnJyaN++PZMnT3a0k8nJySk3m0V+fj5r164lMTGxwn2eOHGCt956i9zcXAICAoiKimLKlCn17tghRLXSd8C+3eDrhxo8vPryjUFYBDRrDieOwe/pENXV6og8P6mrzYjtznQo/xAfbP2AG7rfQJuANjVeV59tLTnm0X0s+vldElqcR8iJYjhymCPHcinZuxsz8yDGieOVnqNjzfzwi+pO0849UR27QnQMqlnzM445s8Hq6epz6m7vsbvF8+f1Dyx/gBUHVzAsYhj/i/9fubJWOXHiBIGBgRiGgY+PDydOnHCsi46OLtOLtCbGjBnDmDFjKlw3adKkcssCAgL44IMPKt1fYmJipQmfEM7kuEt31rmO63Zjp5SCqBjY9At693aUGyR19Zr7NS0traHiqJPTI7ZfeeWVJCUl0b17d6ZOnVrnuRzr43D+YV769SUO55e/I1XVuvps29DH1CXF6KxDHNuyjp3fvEvpV/MwP3yL0lenUvrsA5Q+eBOhD00k8aOfCH59Ovq9V9BffkL+d8mQvsOR0BUHNbffeRt2MWr87RgPTWXb44/Rs+eP7Lr+Goz48ajeZ5W5MDR0PV19Tt3tPXa3eP68fn3WegDHv+6iZcuW5OXlAfZhB7Zs2eJYt3fvXpo2bWpVaEJYRhfk29vTAeqCir+kNFbq9Dywae7Rrq5ed+omT55Mly5dGDt2LIMHD662p1ZDq+2I7XWhNRQUKE6cgPx8RWUdVgoL//g3P1/VeF19tq3VOq0h/xgq+zAqO5Pm+3/jiT2RtJ39P4pPFKGOHoFjuSitiQJeIRp2LaGi6p4wSjFaReAX2h5ahhEYFUNek2bstOVx5c+38r/4xfRsGVdmm/zsFJeeA5ec02rWKfXH3407xONOxzTdszMbsbGxpKamMnDgQM477zzmzp1Lbm4uNpuNFStWcP751Q9bIIS30WtXQtFJiGgPXVz/JMydqagYNKC9IambOHEiS5Ys4ZVXXuG9995j5MiRjBo1ilatWjVUfJWqy4jtdRlZvaBA0aXL6YEC/zRgYOBBaH7Q/nvE73AZXHHX73CwNQRkggYKWpdfB2AaYJi137bKdYdp43OMTrqETmE/82i3thycPBM/s5hOTQ4T6HPSEXp74DbawKEtnOmkaSPDDOBgi/0cONyfg0c7c1D5crA4mIPHO7KvxX5y4++BLybBwf5/iudXuMy07hwcBQKy4EQohDTUOa3jOkf9DjTwe1zfeBr6b64Wx7z0b9AWrliQAH4FYMDR4qP0mNUDgH6h/Zhz6ZwK/x+6ypVXXklOTg4AV1xxBbm5uaxatQqlFIMHD+bGG2+0ND4hXM3eQeJrANQFo6Xz2p+dfuSamYE+cRzVLNDScJRugMFSdu7cyddff82PP/6IaZqcddZZXHTRRfTs2bMhYqxQdnY2d955J8888wyxsbGO5Z9++ikrV64sN+E1wCeffFLhyOpVOXECAit7j4Y9BcNq1mi6nPSh0Gll3bYFWhT7EFvgT2yBPzEF/sTmNyW2wJ/g0qrz9MO+xez3K2J/k5Ps8yvigF8R+5sUcdCviIN+xRyxlYCr/s/W8xy4PXernxXx1PKY+kk3vYXnhTIzM8t8ya2IUoqIiAgOHjzotmOF1ZbUqXZ0+g7M5x4Emy/G8++iAl0z16snvU+l/7gdMjMw/jYF1aNfpeVqUydfX1/rBh/u0qULd999NzfddBNLly5l6dKlPP3000RGRjJ27FiGDh2Kn59fQxyqnNqM2F6XkdW1hl27DNq0acOhQ4fKvBGH8xM4XDAEgM3ZG3ls7UM8d84L9GzZm+zCIygULZq2LLcOwMDA5B812vb/fniU6e3vp0eeL7Z9uwk6mEHT4xV3SDCVoiikBUea+/FNYQo9Y8fQIrI3RS1aUtyiFaU2HwBysjcy9dQxr6gm3qrW5ZzMpkWLFqgCg01HUpx2DmqyLiKgLTkns2nZpBUH8vfXe3/1WQfgo3xo0eoljhw5Uqtz46x4Gvp81/aYD34/iV3Hd9LEaMpJs9DxNxvsax+Mt19oPw4ePFjub7quI6vXxWuvvca4ceMICwsrty4zM5O5c+cyceJEl8QihDv4o4PEEJcldJ5GdeqKzsxA795RZVLnCg3aCM5ms9GkSRNH27qTJ0/y9ttv8+mnn/K3v/2tzPQ29VWXEdvrOrK6v79Js2b2f88s19G/NR2xf9g0bWpfflbbXvQO7VVm+6rW/Xl9r5bdYf9e9I7NsGsdvXZu4sbsvvDrinLbFbVsyUozjX59L6d1l7NR7TpgtInE19eXtKyNPLFgLF9fPI7Y0N5VHrM28f553ZnfPJo0MRvkHNQ9nj/quTFrY4PUrz7rHOfGv+7nxhnrrDrmq6NeYeyCsXx++Wdcu+hajhYfJdg3mC2JfzQBsPob+cqVKxk9enSFSd2xY8dYuXKlJHWi0dCF0kGiRjp1gZ++R6fvtDqShknq9uzZw5IlS1i1ahUlJSUMGjSIe++9ly5durBnzx7eeust/vvf//L88883xOGA+o3Y7k50cTH+6XuYeKAN7WfNxty7Hwr+GEbh9P3NopYtadK5J3TqiurUFTpEs/P4Tm5dMJavx4ymTQWJmxCi4Rw/frzSL4VCeCO97js4WQjh7aCr85pTeTrVqeupQYg9PKlbvXo1S5YsYdu2bQQFBREfH8/o0aMJCQlxlOnYsSPXXXcdzz33XH1jLae6EdtdKSwgjAf6P0BYQPlv+Geu00UnIW07OnUTOnUzpG0nqriIvxMJpNo3aOIPnbuhunYnt20YcwrWcXW/m8uN/RVm1uyY9YnXFeucsV9vr5+nxfPn9f1C+7Hi4Ar6hVr7qALs03KdOXTJsmXL+O2338qUKSoq4qeffiIyMtLF0QlhHf1dMgDq/DHSQaIqHTqDUpCThT6agwpuYVko9eooce2119KpUycuuugizjvvvEqHNDl06BDz5893ymOL04MPnx6x/S9/+Qs9evSo1T6qazBcnwabuiAfdm+3z2+augnSU+1z552peTB07YHq2gPVtSdERqF8fGp1HKt4UmNWV5NzUzlXNBiuqblz59ZoUOHQ0FDuuusuevUq/2jZE0lHCalTVfSenZjPPgA2G8b/zUI1d217Ok97n0qfmAQHf8e4+5+oPgMrLOP2HSWmTJlCt27dqi3Xpk0bp7VDqWrEdlfTBfmwN80+v+meneg9u+DQ/vIFQ1qiYnpBTC/7v+Ht5FuQEBa5/PLLGTt2LFpr/vrXv/LYY48RFRVVpoyvr68MPCwaFUcHif5DXJ7QeSLVqSv64O/o9B2VJnWuUK+kriYJnTfQxUWUZGag9+xEH8tDHzsKx/PgWB4cz0Mfy4WDv8OhA1Q4OnGrMPv8pjG9ULG9oHWEJHFCuAk/Pz9H7/xXXnmFFi1auHwgdSHciT5xDL1mBQDqgrHWBuMporrCj8st7ywhV64aKH3mfg4e+L1mhVuGQocuqE5dUB07Q8cuqOYV98YVQriX04879u/fz5YtWzh27BgjRowgJCSE7OxsAgMDnTY8kxDuQn+fbJ9BIjIKYqSDRE04Okuk70BrbdmNG0nqaiIwCHx8IDAYAptD82D7eD3Ng+zrmgejQsOhY2dUUIjV0Qoh6sg0Td58801WrFjhWNa3b19CQkJ46623iIqK4tprr7UuQCGcTJeUoJd/CYC68DJ5qlRTkZ3secLxPDhyGELbVLuJM0hSVwM+908hokNHMjIyPKLBphCibj799FNWrVrFjTfeSN++fXnwwQcd6/r168eKFSskqRNeTa9fAzlZ9psVA2Wu45pSvn7QrhPs3WUf2sSipM6w5KgeRvk1kW8rQjQCK1as4KqrriI+Pp62bduWWRcWFsbhw4ctikwI19DLFgKghl5kT1REjalO9nlg9e4dlsUgSZ0QQpySnZ1d6cw3vr6+FBYWVrhOCG+gd6fCrm3gY0MNu8jqcDxPpy6Afb5cq0hSJ4QQpwQHB1d6N+7AgQO0bNnSxREJ4Tp66RcAqAHnWzqArqc6faeOvbvQpmlJDJLUCSHEKf369ePTTz8lOzvbsUwpRX5+Pl999RVnnXWWhdEJ4Tw65wj6l1UAqAsvtTgaD9W2A/j5QUE+HD5gSQjSUUIIIU655pprWL9+PX/729/o2dM+lMOHH37I77//jo+PD+PGjbM4QiGcQ6/4CkpL7bMbdexidTgeSfn4QPto2LXNPghxuOunFZQ7dUIIcUpISAjTpk3j3HPPZffu3RiGwZ49e+jbty/PPvssgYGBVocoRIPTRSfR330FgDHyMouj8WyOR7AWDUIsd+qEEOIMISEh3H777Q2yr9NzU+fm5hIZGUliYiLdu3evsOzmzZuZMmVKueXTp0+nXbt2jtdr1qzh448/5tChQ7Rp04brrruOgQOtm5ZIeD69diUcPwatwqDvOVaH49ks7iwhSZ0QQjjB6tWrmTVrFrfddhuxsbEsXbqUqVOnMn36dEJDQyvd7uWXXyYgIMDxOijoj3k3U1NTefnll7n22msZOHAg69atY/r06Tz99NN07drVqfUR3klrjV52qoPEiEvsjxBFnTlmltibhi4tdfn5lKROCCHOsG3bNlatWkVmZiZFRUVl1imleOKJJ2q0n0WLFjFixAhGjhwJQGJiIhs2bCA5OZkJEyZUul1wcDDNmjWrcN2XX35JXFwcCQkJACQkJLBlyxa+/PJL7r///hrFJUQZKT/B/j3QpCnqvFFWR+P5wtqCf4C9s8SBvdA+yqWHl6ROCCFO+fbbb3njjTcIDAwkIiICX1/fMutrOqNMSUkJaWlpXHHFFWWWx8XFsX379iq3feSRRyguLiYyMpIrr7ySXr16OdalpqZyySWXlCnfp08fFi9eXKO4hDiT1hpz0ccAqGEXowKkzWh9KcOADp1h+0Z7ZwlJ6oQQwhoLFy5k8ODBTJo0qVxCVxt5eXmYpklwcHCZ5cHBweTm5la4TYsWLbj99tuJjo6mpKSE7777jmeeeYYnn3ySHj16AJCbm0tISEiZ7UJCQirdJ0BxcTHFxcWO10op/P39Hb9X5fR6b5pRR+r0B715PaTvAD8/jDEJbnVOPPl9UlEx6O0bYc9O1AVj/ljugjpJUieEEKdkZmZy88031yuhO1NFF+/KLuht27YtMzVZTEwMWVlZfPHFF46kriJa6yo/JBYsWMC8efMcr6OiokhKSqJ169Y1qQIA4eHhNS7rKRp7nbTWHH7pU4qAwIuuokVsxR14rOaJ71N+vwEc+Xo+tn3phEdElFvvzDpJUieEEKe0a9eOo0eP1ns/QUFBGIZR7g7a0aNHy929q0pMTAzff/+943VFd+Wq22dCQgLx8fGO16cTwMzMTEpKSqo8vlKK8PBwMjIyavzo2d1JnezMbSmYWzaAzZeC88dQePCgk6OsHU9+n3SI/QtTcfoODuzd45hDtzZ1stlstfri5diu9uEKIYR3uu6663j//ffp2bNnvaYEs9lsREdHk5KSUma4kZSUFAYMGFDj/ezevbvM49aYmBg2btxYJklLSUmpdL5asM9ZW9mdx5p+WGqtPe6DtTqNvU7mFx8B2DtHBLd023Phie+TbhEKzYPh2FH0nl3QuVvZ9U6skyR1QohGLSkpqczr/Px87rvvPjp16lRusGGlFI888kiN9hsfH8+MGTOIjo4mJiaGpUuXkpWVxahR9h6Gc+bMITs7m7vvvhuw92xt3bo17du3p6SkhO+//561a9fy4IMPOvZ58cUX8+STT/LZZ58xYMAAfvrpJzZu3MjTTz9dn1MgGhm9cwts3wg+NtTYq6wOx+sopaBTV9j4s72zxJ+SOmeSpE4I0ajt3bu3zGvDMAgKCiI7O7vMHLBQuwbOQ4YM4dixY8yfP5+cnBzat2/P5MmTHY9UcnJyyMrKcpQvKSnh/fffJzs7Gz8/P9q3b8/f//53+vfv7ygTGxvL/fffz0cffcTHH39MeHg4999/v4xRJ2rF0eN1yAhUq9o/4hPVU9Ex6I0/Q1oqjHTdcSWpE0I0aq+++qrj9y1bthAVFeXoHXqmwsJC0tLSarXvMWPGMGbMmArXTZo0qczryy+/nMsvv7zafQ4aNIhBgwbVKg4hTtO7U2HzejAM1EUyl7GzqKhYNKB3Vz2EUUOTuV+FEOKUKVOmsH///grXHThwoMJpvITwJOaXnwCgzhmGau15PUs9RtSpu+eZGehjeS47rCR1QghRAyUlJRiGXDKF59J7d8GGdaAM1MVXWx2OV1MBgRB+as7m9FSXHVcevwohGrX8/Hzy8/Mdr3Nzc8u0dQMoKipi5cqV5Qb+FcJTaK0x580CQA04H3U64RBOo6Ji0Bn70WmpqN5nu+SYHpvUffrpp/z666+kp6djs9mYNWuW1SEJITzQl19+WWZw3ueff77SsqfnXBXC42z8Gbbax6VTCTdYHU3jEBULP37r0nZ1HpvUlZSUMGjQIGJiYli+fLnV4QghPFSfPn1o2rQpWmv+97//MXbsWEJDQ8uU8fX1pUOHDlXO7CCEu9IlJZhz3wVAjbwUFdrG4ogaBxUdgwbYvaPamV8aiscmdddccw0AK1assDYQIYRHi4mJcQzee/LkSUaOHFmvgYeFcDf6+2TI2AeBQdKWzpXadQJfP8g/DocOQESk0w8prX6FEOKUq6++WhI64VV0/gn0wjkAqMsmoAKaWRxR46FsNugQDZwaSsYFPPZOXV0UFxdTXFzseK2UcoxHVdVt0dPrXHHr1NPIuamcnJvKybkRwjX04rlwPA8i2qMuqHjMROE8KioWvWsb7N4OQ0Y4/XhuldR98sknZRosV2TatGl07ty5TvtfsGBBmf1HRUWRlJRU40lzw8NlTJ/KyLmpnJybysm5EcJ5dGYGetlCAIxxiSgfH4sjaoSi7U07dFojvFM3duxYzj333CrL1DQBq0hCQkKZibBP3yXIzMykpKSk0u2UUoSHh5ORkeFxEws7m5ybysm5qVxtzo3NZqvX/3shGiu94H0oKYHufcBFQ2qIslTUqc4S+9LRxUVOP55bJXVBQUEEBQU5bf++vr74+vpWuK4mH7paa/lwroScm8rJuamcnBshnEPv2ob+6XtQCuPqW6Spg1VahUHzYDh2FPamQYeOTj2cx3aUyMrKIj09naysLEzTJD09nfT0dAoLC60OTQghhLCMLi3FnPMmAGrISFT7KIsjaryUUhAdC4BOc/54dW51p642Pv74Y1auXOl4/cgjjwDw5JNP0rNnT6vCEkIIISylv/kM9u6CgGaohButDqfRU1Ex6A3rXNID1mOTukmTJjFp0iSrwxBCCCHchs7Yj174IQDqmttQwS0sjkicblfnijt1Hvv4VQghhBB/0KaJ+f4rUFwEPfqiXDCEhqiBTl1BKcg6RGlutlMPJUmdEEII4QX0d0sgdTM0aYpx4yTpHOEmVEAzCLfPJlG0fZNTjyVJnRBCCOHhSjIzMOedmt814UaZ39XNqCj7eHWS1AkhhBCiUlprcl79FxQWQOduqOEXWx2S+LNTSd1JSeqEEEIIURm9biWFP60Cmw3jprtRhswc4W7UqZklilI3o03TaceRpE4IIYTwUDo7C/PDtwAw4sej2nawOCJRoXadwM8PnX8CMvY77TAeO6SJEEK4uyVLlrBw4UJyc3OJjIwkMTGR7t27V1h27dq1JCcnk56eTklJCZGRkVx99dX07dvXUWbFihW89tpr5bb94IMP8PPzc1Y1hJvSpaWYb78Ax4/h2zkWc+yVVockKqF8fKBjF9ixBb17Oyoi0inHkaROCCGcYPXq1cyaNYvbbruN2NhYli5dytSpU5k+fTqhoaHlym/dupW4uDiuu+46mjVrxrfffktSUhJTp04lKuqPGQH8/f3597//XWZbSegaJ73wQ9ixBZr60+rv/yJL2WTaPTemomLQO7ag01JRQ0Y65RiS1AkhhBMsWrSIESNGMHKk/eKdmJjIhg0bSE5OZsKECeXKJyYmlnk9YcIEfv75Z3755ZcySZ1SipCQEGeGLjyA3rIe/dVcAIyb7sG3bXs4eNDiqERVjMEjCDlrELktw512DEnqhBCigZWUlJCWlsYVV1xRZnlcXBzbt9dsVHnTNCkoKCAwMLDM8sLCQiZOnIhpmnTq1Ilrr722TNInvJ/OzcZ8+yXQGnXBWIyB51sdkqgB1T6KgIgIjh486LQ7qpLUCSFEA8vLy8M0TYKDg8ssDw4OJjc3t0b7WLRoESdPnmTw4MGOZW3btmXixIl06NCBgoICFi9ezOOPP87zzz9PREREhfspLi6muLjY8Vophb+/v+P3qpxe702D2Hp6nbRZip75Ehw7CpGdMMbf5vF1qojUqW4kqRNCCCep6OJdkwv6qlWrmDt3Lg8//HCZxDAmJoaYmBjH69jYWB599FG++uorbrnllgr3tWDBAubNm+d4HRUVRVJSEq1bt65xPcLDa/64qPTYUU6uX0vhrz9SvHc3/kOG0/zy61C+7tXurzZ1cidH57xF3rYUVFN/2jz+Ar6RnRzrPLVOVZE61Y4kdUII0cCCgoIwDKPcXbmjR4+Wu3v3Z6tXr+aNN97ggQceIC4ursqyhmHQuXNnMjIyKi2TkJBAfHy84/XppDIzM5OSkpIq96+UIjw8nIyMjCofF+ncI5grv0ZvXg+7d4D+Yxyuou2bOPrlPIzxf8WIG1Dl8VyhpnVyR+amXzDn/BcAdf1dZPk0gYMHPbpOlWnsdbLZbLX64uXYrq7BCSGEqJjNZiM6OpqUlBQGDhzoWJ6SksKAAZUnNqtWreL111/nvvvuo3///tUeR2vNnj17aN++faVlfH198fX1rXT7mtBaV1pWFxdhJv0dMs9ILNt1RPXsBy1C0V/Ph8MHMf/zNGbvszGuuRUV3q5Gx3WmqurkjvTvuzFfT7K3oztvFGrQsHLxe1qdakLqVDuS1AkhhBPEx8czY8YMoqOjiYmJYenSpWRlZTFq1CgA5syZQ3Z2NnfffTdgT+heffVVEhMTiYmJcdzl8/PzIyAgAIC5c+fStWtXIiIiHG3q0tPTufXWWy2pI4Bevsie0AW3QF1xA6pHP1TLP4Zs0eddiF70CXrpQtj4M+aW31CXXIOKv9ar2ks5k845gvmfp+FkAcT2Rl1/p9UhCTclSZ0QQjjBkCFDOHbsGPPnzycnJ4f27dszefJkxyOVnJwcsrKyHOWXLl1KaWkpM2fOZObMmY7lQ4cOZdKkSQCcOHGCt956i9zcXAICAoiKimLKlCl06dLFtZU7RR87iv7yEwBUwk0Y55Yfe0s1DUCNS0SfNwrzk5mw8Wf0wjmQmw3X3yFTWlVDF+bbE7rcIxAeiXHXZJSt4juvQkhSJ4QQTjJmzBjGjBlT4brTidppTz31VLX7S0xMLDeenZX0Fx9CQT50iEYNHl5lWRXeDp97n8D8bgn6g9fQ330NBSfglr+hbPJRVBFdWor55vOwbzc0D8a49wlUs8DqNxSNlsz9KoQQotb0wd/RK78GwLj6FpRRs48T44IxqL8+DD429E/fY742FV100pmheiStNfrDN2HTL+Dnh3HP46jW3tcTVDQsSeqEEELUmjlvFpgm9BmI6lZ1L90/MwachzHpMfDzs7ez+/dT6IJ85wTqofTiufakWSmMWx9ERcVUv5Fo9CSpE0IIUSt66wZI+Ql8fDDGJdZpH6r3WRj3TQH/AEjdjPniP9HH8xo2UA9lfvER+rMPAFBX34LqP7iaLYSwk6ROCCFEjWmzFPOTdwBQQy9ChUfWeV8qpifGg89BYBDs2WlP7I4dbahQPY7WGvOzD+wdSQCVcCPGqMstjkp4EknqhBBC1Jj+8Vt7w33/Zqj48fXen+rYGeORaRDcAvalY77wGDovpwEi9Sxaa/T82X/0Jr76ZoyLr7Y4KuFpJKkTQghRI7roJHrBqceC8degmgc1yH5VRHuMh56DkJZwYC/m84+hc7MbZN+eQGuN/mQmesmnAKjxt2OMTrA4KuGJJKkTQghRM9tS4Gg2hLRCDY+vvnwtqPBIjIenQstQyNiH+fw/0NlZ1W/o4XRpKfp/r9sHZwbUDRMxRjbsuRWNhyR1QgghakRv+hUA1WcAqpKpx+pDhbXFeGgqtAqDwwcwX/gHOutQgx/HXehjeZgvP+no5ar+cg/G0LFWhyU8mEeO+Hj48GHmz5/Ppk2byM3NpWXLlpx//vlceeWV2GQQSyGEcAq9+VRS17P6eWnrSrUOx3h4GuaLj0FmBua0hzHufhwV1dVpx7SC3puG+dpUOHIYmvhj3HK/9HIV9eaRGdCBAwfQWnP77bcTHh7O77//zptvvklhYSE33XST1eEJIYTX0YcPwuGD4OMDtRyXrrZUq9b2xO4/T8O+3ZgvTLaP1eYlSY+57jv07P9AURGERWBMfAzVroPVYQkv4JFJXd++fenbt6/jdZs2bThw4ADJycmS1AkhhBPozevtv3TujvIPcPrxVItWGI9Ow3zrBfsAxW/8CzXuZtSoy1FKOf34zqBLStCfvY9essC+oFd/jNsekqm/RIPxyKSuIvn5+QQGVv0fo7i4mOLiYsdrpRT+/v6O3ytzep2nXkicSc5N5eTcVE7OjedxPHrt5bxHr3+mmgZgTHoM/dF/0SsWo+e+A5kZMP6vKB8fl8XREPTuHZjvzYB96QCoi65CXXEDyvCsegj35hVJXUZGBl999VW1d+kWLFjAvHnzHK+joqJISkqidevWNTpOeLjMu1cZOTeVk3NTOTk3nkGXFNt7vgKqZz+XHlv5+MCEO6B1OHreu/bk7tB+jMR7US1rdu22kj5ZiP78f+ilX4A2IbA5xg0TUWeda3Vowgu5VVL3ySeflEm6KjJt2jQ6d+7seJ2dnc3UqVMZPHgwI0eOrHLbhIQE4uP/6Cp++i5BZmYmJSUllW6nlCI8PJyMjAy01jWpSqMh56Zycm4qV5tzY7PZavzFSziH3rkVThZCUAhERrn8+Eop1Ogr0KFtMGe+CFs3YD51D+rav6KGjHDbO756y3rM91+DUz141cChqPG3oZoHWxyZ8FZuldSNHTuWc8+t+tvLmRf37OxspkyZQkxMDLfffnu1+/f19cW3km74NfnQ1VrLh3Ml5NxUTs5N5eTceAbHUCY9+6EM60bCUv0HY7R9GfPdf0PadvSsf6N/XY1x4yRUSEvL4vozvWcX5qKP4bc19gUtQ+1353qfbW1gwuu5VVIXFBREUFDNRig/ndBFRUUxceJEDAsvNEII4c1Ot6fDiUOZ1JQKj8R49F/oJZ+hF/4PUn6y37Ub/1fUwAssTTr17lR7Mpfy06lgFWr4JaiEG1BNnd+5RAi3SupqKjs7m6eeeorQ0FBuuukm8vLyHOtCQkKsC0wIIbxM6ZFM+H23PUHp0dfqcABQhg/qoqvQcWdjvjMd9qahZ76EXjwXddE41IDzUS4as1SbJqRuwlzyKZy6o4kyUAPPR11yDSqivUviEAI8NKlLSUkhIyODjIwM7rzzzjLrPvnkE4uiEkII71P466lHiB27uF1bMNWuI8bkF9Bfz0cnL4CDv6PfmY7+/H+oMQmocy9E+TVp8ONqreH3NPTa79DrvoPcI/YVhoEaNBx18dWoNm0b/LhCVMcjk7phw4YxbNgwq8MQQgivV/jrj4BrhzKpDWWzoeKvRY+IR6/8Cv3N53DkMHrOm+gvPkL1PcfeY7dbn3qNB6cL82H3DnTqZvTPqyBj3x8r/ZvZ78yNuRLVWnp0C+t4ZFInhBDC+bRZSuH6tYDrhzKpLRXQDHXROPTIS9E/LEMv+dSe3H2fjP4+GZQBnbqgevUnv1dfdCno5sEQFGxPypRCFxfDiTw4ngfH8tDZWfYOGWnbYP9e+5Akp/n6oeIGoM4ZCr3OcspcuELUliR1QgghKpa+E/PYUfBvBlGxVkdTI8qvCWr4xejzR8O2DejN6+2zYRz8HXanonencuSLj8puZPMFHxucLKh6563CUNGx0Ks/qt9gl8ysIURtSFInhBBOsmTJEhYuXEhubi6RkZEkJibSvXv3Sstv2bKF2bNns2/fPlq0aMFll13G6NGjy5RZs2YNH3/8MYcOHaJNmzZcd911DBw40CnxO2aR6NHX42ZwUDab/Q5ar7MA0NlZ6K2/wdYUfI/lUJR1GPJyobAASortPwCGAc2aQ2AQBIWgOnZGRXeDzrGokFaW1UeImpCkTgghnGD16tXMmjWL2267jdjYWJYuXcrUqVOZPn06oaGh5cofPnyYadOmMXLkSO655x62b9/O22+/TVBQEIMGDQIgNTWVl19+mWuvvZaBAweybt06pk+fztNPP03Xrl0bvA7mJtdPDeYsqmWovePEeaNoExHBwYMH7eMkFp2EY0ehpMSeyPkHWDosihD1IX+5QgjhBIsWLWLEiBGMHDnScZcuNDSU5OTkCssnJycTGhpKYmIikZGRjBw5kuHDh/PFF184ynz55ZfExcWRkJBAu3btSEhIoFevXnz55ZcNHr8+cQzSUgFQbjA+nbMovyaoVmGoNm1RzQIloRMeTe7UCSFEAyspKSEtLY0rrriizPK4uDi2b99e4TY7duwgLi6uzLK+ffvy7bffUlJSgs1mIzU1lUsuuaRMmT59+rB48eJKYykuLqa4uNjxWimFv7+/4/fK6K0bQJvYOkajWrX2mpk/TtfZXacWqwupk2dwRZ0kqRNCiAaWl5eHaZoEB5cd1y04OJjc3NwKt8nNza2wfGlpKceOHaNFixbk5uaWG2A9JCSk0n0CLFiwoMyc2lFRUSQlJVU7n27272mcAPz7DyEk3PuG6QiXOnkEqVPtSFInhBBOUtE38qq+pf953em7Y1XeUdO6yvUJCQnEx8eXO0ZmZiYlJSWV7/fyG/Dpcw7NojqTkZHhVXfqwsPDpU5urrHXyWazVfvFq8Lt6hqcEEKIigUFBWEYRrk7aEePHi13N+60iu645eXl4ePjQ2BgYKVlqtongK+vL76VjKFW5QeLYaA6d8M3IgJ9qlOBN9FaS508gNSpdqRFqBBCNDCbzUZ0dDQpKSlllqekpBAbW/F4b127di1XfsOGDURHR2M7NY9pTEwMGzduLLfPmJiYBoxeCOGpJKkTQggniI+PZ9myZSxfvpx9+/Yxa9YssrKyGDVqFABz5szhlVdecZQfPXo0WVlZjnHqli9fzvLly7n00ksdZS6++GI2bNjAZ599xv79+/nss8/YuHFjuc4TQojGSR6/CiGEEwwZMoRjx44xf/58cnJyaN++PZMnT3a0k8nJySErK8tRPiwsjMmTJzN79myWLFlCixYtuPnmmx1j1AHExsZy//3389FHH/Hxxx8THh7O/fff75Qx6oQQnkeSOiGEcJIxY8YwZsyYCtdNmjSp3LIePXqQlJRU5T4HDRpUJtETQojT5PGrEEIIIYQXkDt14GiE3FDlGiM5N5WTc1O5mpwbOX/OUZvz6o3vgdTJMzTWOtW13kp7W19hIYQQQohGSB6/1kBBQQGPPvooBQUFVofiduTcVE7OTeXk3HgGb3yfpE6eQepUN5LU1YDWmt27d3vdAIgNQc5N5eTcVE7OjWfwxvdJ6uQZpE51I0mdEEIIIYQXkKROCCGEEMILSFJXA76+vowbN67S+RMbMzk3lZNzUzk5N57BG98nqZNnkDrVjfR+FUIIIYTwAnKnTgghhBDCC0hSJ4QQQgjhBSSpE0IIIYTwAt43/4YTLFmyhIULF5Kbm0tkZCSJiYl0797d6rAstWDBAtatW8f+/fvx8/MjJiaGG264gbZt21odmltZsGABH374IRdffDGJiYlWh+MWsrOz+eCDD/jtt98oKioiIiKCu+66i+joaKtDE2fw5Oveli1bWLhwIbt37yYnJ4eHHnqIgQMHOtZrrZk7dy7Lli3j+PHjdO3alVtvvZX27dtbGHXVanLN9bR6JScnk5ycTGZmJgCRkZGMGzeOfv36AZ5Xn4pU9BngzHrJnbpqrF69mlmzZnHllVeSlJRE9+7dmTp1KllZWVaHZqktW7YwZswYnnvuOf75z39imibPPvsshYWFVofmNnbu3MnSpUvp2LGj1aG4jePHj/P4449js9n4xz/+wUsvvcRNN91EQECA1aGJM3j6de/kyZN06tSJW265pcL1n3/+OV9++SW33HIL06ZNIyQkhGeffdatZy+oyTXX0+rVsmVLJkyYwLRp05g2bRq9evXi//7v//j9998Bz6vPn1X2GeDMeklSV41FixYxYsQIRo4c6fi2GhoaSnJystWhWeqxxx5j2LBhtG/fnk6dOjFx4kSysrJIS0uzOjS3UFhYyIwZM7jjjjto1qyZ1eG4jc8//5xWrVoxceJEunTpQlhYGL179yY8PNzq0MQZPP26169fP8aPH88555xTbp3WmsWLF5OQkMA555xDhw4dmDRpEidPnmTVqlUWRFsz1V1zPbFeZ599Nv3796dt27a0bduW6667jqZNm7Jjxw6PrM+ZKvsMcHa9JKmrQklJCWlpafTp06fM8ri4OLZv325RVO4pPz8fgMDAQIsjcQ9vv/02/fr1Iy4uzupQ3MrPP/9MdHQ0L730ErfddhuPPPIIS5cutToscQZvv+4dPnyY3NzcMvXz9fWlR48eHlW/P19zPb1epmnyww8/cPLkSWJiYjy+PpV9Bji7XtKmrgp5eXmYpklwcHCZ5cHBweTm5loTlBvSWjN79my6detGhw4drA7Hcj/88AO7d+9m2rRpVofidg4fPsw333zDJZdcQkJCAjt37uTdd9/F19eXoUOHWh2ewPuve6frUFH9POXxckXXXE+t1969e3nssccoLi6madOmPPTQQ0RGRjoSHE+rD1T9GeDs90mSuhpQStVoWWM1c+ZM9u7dy9NPP211KJbLyspi1qxZPPbYY/j5+VkdjtsxTZPOnTszYcIEAKKiovj9999JTk6WpM7NePt178918aRx+Ku65npavdq2bcvzzz/PiRMnWLt2La+++ipTpkxxrPe0+tT0M8BZ9ZKkrgpBQUEYhlHu2+nRo0fLZdmN1TvvvMMvv/zClClTaNWqldXhWC4tLY2jR4/y97//3bHMNE22bt3K119/zZw5czCMxtvqoUWLFkRGRpZZFhkZydq1ay2KSPyZt1/3QkJCAPsdkxYtWjiW5+XleUT9Krvmemq9bDabo01t586d2bVrF4sXL+byyy8HPK8+1X0GvPzyy4Dz6iVJXRVsNhvR0dGkpKSU6Q6fkpLCgAEDLIzMelpr3nnnHdatW8dTTz1FWFiY1SG5hd69e/PCCy+UWfb666/Ttm1bLr/88kad0AHExsZy4MCBMssOHDhA69atLYpI/Jm3X/fCwsIICQkhJSWFqKgowN6OcMuWLVx//fUWR1e56q65nlqvP9NaU1xc7LH1qe4zoE2bNk6tlyR11YiPj2fGjBlER0cTExPD0qVLycrKYtSoUVaHZqmZM2eyatUqHnnkEfz9/R3f6gMCAhr1Y0d/f/9y7QqbNGlC8+bNpb0hcMkll/D444/z6aefMmTIEHbu3MmyZcu4/fbbrQ5NnMHTr3uFhYVkZGQ4Xh8+fJj09HQCAwMJDQ3l4osvZsGCBURERBAeHs6CBQto0qQJ5513noVRV626a65SyuPqNWfOHPr160erVq0oLCzkhx9+YPPmzTz22GMeWR+o2WeAM+ultLs/oHYDpwfhzMnJoX379vzlL3+hR48eVodlqWuuuabC5RMnTmTYsGGuDcbNPfXUU3Tq1EkGHz7ll19+Yc6cOWRkZBAWFsYll1zChRdeaHVY4k88+bq3efPmMu2yThs6dCiTJk1yDP66dOlSTpw4QZcuXbj11lvd+otXTa65nlav119/nU2bNpGTk0NAQAAdO3bk8ssvd/QY9bT6VObPnwHOrJckdUIIIYQQXqBxN/ARQgghhPASktQJIYQQQngBSeqEEEIIIbyAJHVCCCGEEF5AkjohhBBCCC8gSZ0QQgghhBeQpE4IIYQQwgtIUieEEEII4QUkqRNCCCGE8AKS1AkhhBBCeAFJ6oQQQgghvIAkdcKjFRUV8cgjj3DPPfeQn5/vWJ6bm8tf//pXnnrqKUzTtDBCIYQQwjUkqRMezc/Pj7/97W/k5eXx2muvAWCaJv/5z38AuO+++zAM+TMXQgjh/eTTTni8iIgI7rjjDtatW8fixYuZN28emzdv5p577qFFixZWhyeEEEK4hM3qAIRoCEOGDGHLli28//77mKZJQkICcXFxVoclhBBCuIzcqRNeY/jw4ZSWluLj48PFF19sdThCCCGES0lSJ7xCYWEhr7zyChEREfj5+fHGG29YHZIQQgjhUpLUCa/w3//+l6ysLB566CHuvPNOfv75ZxYtWmR1WEIIIYTLSFInPN6yZcv4/vvvufXWW2nfvj2DBg1i7Nix/O9//2Pnzp1WhyeEEEK4hCR1wqPt3buXd999l6FDhzJs2DDH8htvvJGOHTsyffp0Tpw4YV2AQgghhIsorbW2OgghhBBCCFE/cqdOCCGEEMILSFInhBBCCOEFJKkTQgghhPACktQJIYQQQngBSeqEEEIIIbyAJHVCCCGEEF5AkjohhBBCCC8gSZ0QQgghhBeQpE4IIYQQwgtIUieEEEII4QUkqRNCCCGE8AKS1AkhhBBCeAFJ6oQQQgghvIAkdUIIIYQQXkCSOiGEEEIILyBJnRBCCCGEF5CkTgghhBDCC0hSJ4QQQgjhBWxWB+AOcnJyKCkpqbJM69atyczMdFFEruWtdfPWekHjqpvNZqNFixYWRuSdanLdA+/9W/PWeoH31s1b6wUNd92TpA4oKSmhuLi40vVKKUc5rbWrwnIJb62bt9YLpG6iYVR33QPvfT+8tV7gvXXz1npBw9ZNHr8KIYQQQngBSeqEEEIIIbyAJHVCCCGEEF5Akroa0PnHMfNPWB2GEEIIIUSlpKNEDZjzZ3Nw489wVSIMON/RqFEIIYQQoAvz0Rt/gV9/RO9OhbYdUN3iUN37QLuOKEPuIbmCJHXV0EUn0ds2orOz4L8vwMqvMSbcgWrX0erQhBBCCMvoE8fQ69egf/0Rtv4GZw6Rc+QweuPPaIDA5hDbG2PISFTcAIuibRwkqauG8muCz1P/IXD1Uo5+PBNSN2E+fR9qRDzq0utQAc2sDlEIIYRwGa01+sdv0R//F85smhTWFtV/MCq2N3r/HvS2FNixGY4fg19WY/6yGnXr3zAGDbcueC8nSV0NKF8/gsbfyvFeZ1P68dv228tLF6LXfYdx/Z2o/kOsDlEIIYRwOp2bjfnBa7BhnX1BRHvUwAtQ/QZD2/aO5kmqV38Yk4AuKYH0HejvvrYngu/+G+0fiOojd+ycQZK6WlCtwvC5azJ606+YH74Fhw9gvv4v1EXjUFdcjzJ8rA5RCCGEaHBaa/TaFegP/wv5x8HHhrrsOtSYK1E+lX/2KZsNunSH6FjQoNd8i/lmEsb9T6FiermwBo2DtFysA9WrP8ZTM1CjLgdAfzUPc8az6BPHrQ1MCCGEaGD6eB7ma1PRM6fbE7qOXTAen45x8dVVJnRnUoaB+ss90GcgFBdhvvIseu8uJ0fe+EhSV0fK1xfjmltRtz0Ivn6w6RfMqQ+i9++1OjQhhBCiQehDBzCnPQy/rbXfnbviBoy//1+dOgsqmw3j9ochpicU5GO+/BT60AEnRN14SVJXT8Y5QzEeTYKWreHwQcxpD6F/XW11WEIIIUS96NTN9oTu8EFoFYbx2IsYl1xjf6RaR8qvCcakf0KHaDh2FHP6E+jcIw0YdeMmSV0DUB07Y/zzJYjtDScLMV//F+Y3n1sdlhBCCFEn5tqVmNMfhxPHICoG4x/Po9pHNci+VUAzjPuegrC29qFP5r/XIPsVktQ1GNU8GONvT6OGXwKA/mQm5rxZaK0tjkwIIYSoGa015qKP0W+/aB93rv8QjAefQwW1aNDjqKAQjL8+aD/m2hXo/XsadP+NlVv0ft2yZQsLFy5k9+7d5OTk8NBDDzFw4MBqt5k9ezb79u2jRYsWXHbZZYwePdpFEVdM+fjAdbdDi1D0p7PRSz6FvFy46e563a4WQgghnE2bpej3XkX/sBQANToBddVfnDYbhOrUFfoPgV9XY372P3wm/cMpx2lM3OJO3cmTJ+nUqRO33HJLjcofPnyYadOm0b17d5KSkkhISODdd99lzZo1To60ekopjIuuQiXeC4aB/nG5vdfQyUKrQxNCCCEqpEtK0G+/ZE/olIG6/i6Mq292+vRexhXXgzLgtzXotO1OPVZj4BZJXb9+/Rg/fjznnHNOjconJycTGhpKYmIikZGRjBw5kuHDh/PFF184OdKaM869EGPiY+DnBxt/xnzpcfTxPKvDEkIIIcrQxcWYb/4f+qfvwceGceejGMMucsmxVUR71GD7DBPmZx+45JjezC2SutrasWMHcXFxZZb17duXtLQ0Ss6ce+5PiouLyc/Pd/wUFBQ41imlqvypSZk//xh9B+LzwLMQEAhp2zFfsjc6re1+nP1Tl7p5wo+31qux1U0I4Ty6uAjz9Wnw2xqw+WJMnIzqP9ilMajLrgMfG2zdgN66waXH9jYe2dArNzeX4ODgMsuCg4MpLS3l2LFjtGhRcYPOBQsWMG/ePMfrqKgokpKSaN26dY2OGx4eXvtgIyIo7tiJw/+4C/P33Rj/mULrqa/j0zy4+m1dqE518wDeWi+Qugkh6kefLMR89TnYugH8/DAmPYbq0c/lcahWYaihY9HLF2EueB+jW5x8oasjj0zqgHJv+OleplX9ISQkJBAfH19uH5mZmVXe4VNKER4eTkZGRt16s/r6o/72DLzwD4rTUjnwyF/xefA5VLPA2u+rgdW7bm7KW+sFja9uNputxl+8hBA1owsLMGc8DamboYk/xj2Po2Ktm7ZLXXI1etU3sDvVPtBxv0GWxeLJPDKpCwkJITc3t8yyvLw8fHx8CAysPFHy9fXF19e3wnU1+XDUWtf9QzQiEuPBZzFfeAz2plH60uMYDzyNCrA+sYN61s2NeWu9QOomhKgbffIk5oxn7AmdfwDGfU+hOnezNCYV1AJ14WXoxXMxP/sAo88AmU+9DjyyTV3Xrl1JSUkps2zDhg1ER0djc+OhQ1TbDhgPPguBQbBnJ+b0J9H5Ml+sEEII19DFRZivTYXUTfaE7m/PWJ7QnabGJNjboB/Yi177ndXheCS3SOoKCwtJT08nPT0dsA9Zkp6eTlZWFgBz5szhlVdecZQfPXo0WVlZjnHqli9fzvLly7n00kutCL9WVLuOpxK75pC+wz73XWFB9RsKIYQQ9aBL7L1c2bIemjTFuPdJVFRXq8NyUAGBqLFXAaC/+BBtmhZH5HncIqnbtWsXjzzyCI888ggA7733Ho888ggff/wxADk5OY4EDyAsLIzJkyezZcsWHnnkEebPn8/NN9/MoEGe8QxeRXbCeOBZaNYcdqdivpmErqJNnxBCuJre+DOls/7DieWLrQ5FNABdWor59ouwYR34+mHc/U9Ul+5Wh1WOGnEJ+DeDzAzYJj1ha8stnlX27NmTTz75pNL1kyZNKresR48eJCUlOTMsp1LtozDufQLzxcdg06/o91+FxHulx48Qwi3oPbvQq76hsEkT6O76HpGi4WizFD3r3/DLarDZ7MOWdIurfkMLqCZNUYOGob/9EvO7JfhY0BvXk7nFnbrGSkXHYtz+qH3midXL0J/9z+qQhBDCrk1bAEoO7LU4EFEfWmv0B6+j16wAHx+MOx5B9TrL6rCqpC4YY//lt7XovBxrg/EwbnGnrjFTfQagbpiIfu8V9OJPMFu0xBh2sdVhCSFcZMmSJSxcuJDc3FwiIyNJTEyke/eKH4utXbuW5ORk0tPTKSkpITIykquvvpq+ffs2eFwqrC0aKDnwu3z792B6wfvo75PtU3/d+iCqr/s3U1KRnSAqBnanolcvd7SzE9WT/6tuwDh/NOrS6wDQc95Cr7d+DlshhPOtXr2aWbNmceWVV5KUlET37t2ZOnVqmTbEZ9q6dStxcXFMnjyZf/3rX/Ts2ZOkpCR2797d8MG1iQDAPJqDzj/R8PsXTmd+8zn6K/uA++rGiRgDzrM4opo7fbdOf58swxvVgiR1bkJdOh51/mjQJuZ/X0Dv2mZ1SEIIJ1u0aBEjRoxg5MiRjrt0oaGhJCcnV1g+MTGRyy+/nC5duhAREcGECROIiIjgl19+afDYVNMACAqxvzh8oMH3L5zL/HE5+pOZAKiEGzHOH21xRLWjBpwPTf3h8EHYvtHqcDyGJHVuQimFuv4u6DMQTo0jpLMr/rYuhPB8JSUlpKWl0adPnzLL4+Li2L59e432YZomBQUFVQ66Xi+n2tXpQ5LUeZKCdasw3/03AOrCy1EXjbM4otpTTZqizhkKgP5uicXReA5pU+dGlI8Pxl8fwvzXo7BvN+ZrUzEemYbya2J1aEKIBpaXl4dpmhXOY/3nGXMqs2jRIk6ePMngwZVPwF5cXExxcbHjtVIKf39/x+9VUWFt0Tu2wOGDXtUz/3RdvKlOp+mdWzky/XEwTdSgYRjX3IIyPPP+jTF0LKUrv0av/xGO5wERXvmeNeTfoyR1bkY1aYox6R+Yzz0Ae3bahzq55W9e+YcshKj4Ql6T/++rVq1i7ty5PPzww+USwzMtWLCAefPmOV5HRUWRlJRUo/l087rEcvSHpTTNy6ZVRES15T1NeHi41SE0qOK9aRya8Qz65Emann0uoZP/hXLjWZaqFRFBRtceFO/YQuCmn6BrrNe9Z2dqiLp58LvtvVRoG4w7HsWc/oS9G3r7KNToBKvDEkI0oKCgIAzDKHdX7ujRo1UmaWDvYPHGG2/wwAMPEBdX9XhjCQkJxMfHO16fThgzMzMpqWbQcx3QHICCPWkcPHiwyrKeRClFeHg4GRkZXtMIX+ceoXTqw3DiGH7d4ii55W9kZGZaHVa9mYOGw44t5C6aR+AV13Po0CGvec9Oq+jv0Waz1eiL159JUuemVLc41LW3oT98Cz1vNrptR1Sv/laHJYRoIDabjejoaFJSUhg4cKBjeUpKCgMGDKh0u1WrVvH6669z33330b9/9dcEX19ffH19K1xX7Ydj2B9t6rztgxROjeHmBfXShfmY/54C2ZnQph2hT77E4RMFXlE3Bp4Pn8yEjH2c3Lwe3SrCO+pVgYb4e/TMB+2NhBp+CercC0/1iH0eLT3QhPAq8fHxLFu2jOXLl7Nv3z5mzZpFVlYWo0aNAsrPe71q1SpeffVVbrrpJmJiYsjNzSU3N5f8/HznBBh26pHriWPoE8eccwxRL7qkBPONJPh9NzQPxuf+p/A53WvZC6imAaiBFwBw4qsFFkfj/uROnRtTSsH1d6EP/g5p2zFfeQ7jsRdRTZpaHZoQogEMGTKEY8eOMX/+fHJycmjfvj2TJ092PHb587zXS5cupbS0lJkzZzJz5kzH8qFDh1Y4nWJ9qSZN8WnVmtIjmXDoAETHNvgxRN1prdH/ex02rwe/Jhj3PIFq7X1tztT5Y9DfJ5P/wzJ8rrgRmjmpt7cXkKTOzSlfX4y7JmM++wAc/B39vzdQt9xvdVhCiAYyZswYxowZU+G6PydqTz31lAsiKsvWtj2lRzLRhw+gJKlzK/rLj9GrvgFlYNz+CCqqq9UhOUenLtA+Gn5PQ6/7DjVcZl2qjDx+9QAqpCXGXx8CZaB/XI65epnVIQkhGglb2w72Xw55T0cJb2CuXo7+fA4AasIdqD6Vt8P0dEopjMHDATB//t7iaNybJHUeQsX2Ql02HgD9vzfsj2SFEMLJbG3b23+RNr1uQ2/dgH5vBgBq7FUYwy6yOCLnU2efa/9lxxZ07hFrg3FjktR5EHXx1dC9DxSdxHzz/9AnT1odkhDCy52+UyezSrgHfWAv5uv/gtJS1IDzUQk3Wh2SS6iWrfHrHgdao39ZbXU4bkuSOg+iDB+MWx+wz8e4fw/64/9aHZIQwsv9cafuoNcOJeEpdF4O5n+ehoIT0KU76ub7PHa2iLoIuMA+f63+SR7BVqbx/DV4CRXcAuO2B0Ep9PfJmGtXWh2SEMKL2SIi7b8UnDg1VZOwgj55EnPGs3DkMIRFYEx8DOXrZ3VYLhVw7khQCnZtQ2d7/sDKziBJnQdS3fugLrkGAP3+a+iM/RZHJITwVkaTptAy1P5CHsFaQpulmG+/COk7ILA5xr1PopoHWR2Wy/m0ag1dewCgf/7B4mjckyR1HkpdOh5iesHJAsyZL6Grme5HCCHqSp2eWUI6S1hCz50Fv60Bm81+h65NW6tDsoxx9vkA6J9XWRyJe5KkzkM52tcFNIP0HejFc60OSQjhrU4nETKsicuZyxahl34OgLr5ftSpO1WNlTprCCgDdqeisw5ZHY7bcavBh5csWcLChQvJzc0lMjKSxMREunfvXmn577//noULF3Lw4EECAgLo27cvN954I82bN3dh1NZRLUNRE+5Ev/2ifRDK3mehomKsDksI4WVUWFs0yLAmLqZ/W+PoEKcSbsQ4NV1WY6aCW0BsL9iWgv55FWrsVVaH5Fbc5k7d6tWrmTVrFldeeSVJSUl0796dqVOnlpki50zbtm3jlVdeYfjw4bz00ks88MAD7Nq1izfeeMPFkVvLOGcoasD5YJqYM6fLMCdCiIbXRh6/uprenYr53xdAa9QFY1AXjbM6JLehzj4PAP2TPIL9M7dJ6hYtWsSIESMYOXKk4y5daGgoycnJFZZPTU0lLCyMiy++mLCwMLp168aFF15IWlqaiyO3nrr+TghpCYf2o+e/a3U4Qggvc7pNHYdkWBNX0JkZmDOegaIi6HUWasKd9rnABQCq/2AwDNi7S75o/IlbJHUlJSWkpaXRp0+fMsvj4uLYvn17hdvExsZy5MgRfv31V7TW5ObmsmbNGvr161fpcYqLi8nPz3f8FBQUONYppar8qUkZq36MwCCMm+8HQH+7GL15fa22d+e61efHW+vV2Oom3EDrNvahJE4WQF6u1dF4NX3iGOZ/psCxo9AhGuOOh1E+PlaH5VZU82DoFgfI3bo/c4s2dXl5eZimSXBwcJnlwcHB5ObmVrhNbGws9957Ly+//DLFxcWUlpZy9tlnc8stt1R6nAULFjBv3jzH66ioKJKSkmjdunWN4gwPD69ROUtERJCzczPHv/gY3ptB2Ksf4RMUUuPN3bpu9eCt9QKpm3Ad5esHLVvbx0g7dACCW1gdklfSxUWYrzwHGfuhZSjGPY+jmgZYHZZbUmefh97ym31ok1NDfAk3SepOq+hbeWXf1Pft28e7777LuHHj6NOnDzk5OXzwwQf897//5a677qpwm4SEBOLj48vtOzMzk5IqhgRRShEeHk5GRoZbP3rQY8fBTz9gZuzj4ItP4XPno9Vu4yl1qy1vrRc0vrrZbLYaf/ESThQWAUcOow8fQMX0tDoar6NNE/3Oy7BzC/g3w7j3KVRIK6vDcluq/2D0/16HfbvRGftQ4ZFWh+QW3CKpCwoKwjCMcnfljh49Wu7u3WkLFiwgNjaWyy67DICOHTvStGlTnnjiCcaPH0+LFuW/Sfr6+uLr61vh/mry4ai1du8PUb8mGLf+DfNfj6B/XoX5y3mo/kNqtKnb162OvLVeIHUTrqXatEVv3QCHZViThqa1Rn8y0z72mo8N466/o9p1sDost6aaNYfufWHTL+ifVtnHbhXu0abOZrMRHR1NSkpKmeUpKSnExsZWuM3JkyfL3cUzTs2B15g/DFSnrqgx9i7e5v/eQJ84ZnFEQgivIAMQO41e8il62RcAqFvuR3XvU80WAkANONUL9heZXeI0t0jqAOLj41m2bBnLly9n3759zJo1i6ysLEaNGgXAnDlzeOWVVxzlzz77bNatW0dycjKHDh1i27ZtvPvuu3Tp0oWWLVtaVQ23oOKvgfBIyMtFf/KO1eEIIbzAmT1gRcMxf/wWPX82AOqaW2UsulpQfc6x94LdvwedmWF1OG7BLR6/AgwZMoRjx44xf/58cnJyaN++PZMnT3a0pcnJySkzZt2wYcMoKCjg66+/5r333qNZs2b07NmTG264waoquA3l64eReC9m0qPo1cvQA85H9epvdVhCCE/WJsL+b6Z9WBPpmVx/etOv6Nn/AUCNTsAYdbnFEXkW1SwQuvaE7RvRKT+hRl5qdUiWc5ukDmDMmDGMGTOmwnWTJk0qt+yiiy7ioosucnZYHkl17oYaEY9e9gXm+69iTJkhvaiEEHUX2sY+PdPJQjiaDdKIv150+g7MN/4FpaWoc4airvqL1SF5JBU3AL19I3rDOpCkzn0ev4qGp664AVqFQXYm+tP3rQ5HCOHBlM0XQsPsL+QRbL3ojP2Y/3naniB374NKvBdlyMdxXag+A+2/pG5C55+wNhg3IH9FXkw19ce46W4A9LdfondssTgiIYRHC7M/gpXOEnWnj2RiTn/8j8GFJ062J8yiTlSbthDRHkpL0Zt/tTocy0lS5+VUj76o8+ydTczZM9BFMjesEKJu/ugsIUldXei8HMzpT0B2FoRHYtw/RZrFNAAVN8D+y2/rrA3EDUhS1wioq2+G4FNzw375idXhCCE8VRsZ1qSudP5xzOlPwaH90CoM429P26e7EvWm+tofwepNP6OrmEigMXCrjhLCOVRAIMaE2zFf/xd6yQL0oGGoiPZWhyWEAJYsWcLChQvJzc0lMjKSxMREunfvXmHZnJwc3nvvPdLS0sjIyOCiiy4iMTHRZbGqsLZokAGIa0mfLLS3odu3G4JC7Aldy1Crw/Ie0bEQGATH82DXVojtbXVElpE7dY1Fv8HQ+2woLbEPStyIB2gWwl2sXr2aWbNmceWVV5KUlET37t2ZOnVqmeGbzlRcXExQUBBXXnklHTt2dHG0/DGsyeGDaNN0/fE9kC4uxnxtGuzaBgHNMP42xd4OTDQYZfigep8NgG7kj2AlqWsklFIY190Ofn72MX3WrLA6JCEavUWLFjFixAhGjhzpuEsXGhpKcnJyheXDwsK4+eabGTp0KAEBFrTFatUGbDYoLoIjh11/fA+jS4ox3/o/2LIemjTFuPdJVGSU1WF5Jccj2A1rG/VNC0nqGhHVOhwVb58fT899R6YQE8JCJSUlpKWl0adP2Smh4uLi2L59u0VRVU35+NhnqwE4sNfaYNycLinBfPN5+G0t2HwxJv4D1bmb1WF5rx797F84MjMgY5/V0VhG2tQ1MmrU5egfv4WDv6M/fQ9ODXkiRGNWVFREbm4uRUVFNG/enOBg5zdgz8vLwzTNcscKDg4mNze3wY5TXFxMcXGx47VSCn9/f8fvVTm9/sxyql1H9L50OLAX1fecBovTlSqqV0PSJSXo/z4Pv62xJ3R3/xOjZz+nHOvPnF03q1RXL+UfgO4Wh970K2xYh2rbwZXh1UtDvmd1Tup+//13tm/fTnZ2tuNCGBkZSffu3a15LCBqRNl8MW64C/P5f6C/W4I+90KIiLA6LCFcLjs7m6VLl7J+/XrS09Mxz2gj1rx5c3r06MH555/PWWedheHEgWErupA35AfyggULmDdvnuN1VFQUSUlJjikYayI8PNzxe163Xhxdu5Km2Ydp5eHXjjPr1VB0SQlH/u8fFPz6I9h8CX38BfzPPrfBj1MdZ9TNHVRVr+MXjCZn06/Ytv5Gm1vucWFUDaMh3rNaJXXHjx9n6dKlLF26lMzMzArLGIZBv379uPjii+nVq1e9AxQNT8X0Qp07Ev3DMkrffxU9+HyrQxLCZXJycvjwww/5/vvvadq0KTExMVx++eUEBwfj6+vL8ePHOXz4MDt27OCFF14gNDSUCRMmcO65DfvBHBQUhGEY5e7KHT16tEHvFCYkJBAfH+94fTphzMzMpKSa4R+UUoSHh5ORkeFop2QGtQQgf8c2ig56Zi/YiurVEHRpKeZ/n0f//APYbBgT/0Fuu2hyXXienFU3q9WkXrpTDABFW1M4kLrNY4aMqahuNputVl+8TqtxUrd48WLmzZuHUorBgwfTs2dPoqKiyl0IU1NT+emnn3jmmWeIi4vj1ltv9dpvDJ5MXXWzvZfQvnSOff4RDB5pdUhCuMR9991Hly5duP/++znrrLOw2Sq/DB46dIhvv/2WmTNnkp2dzaWXNtzckjabjejoaFJSUhg4cKBjeUpKCgMGDGiw4/j6+uLrW/GMBTX90Nda/1H29GOtjH2YxcWoKs6fuytTr/ruq6QE/c50e0LnY8O4czKq91mWJVYNWTd3UmW9WoRCh2jYm4a54SeMcz3rc60h3rMa/2/86quv+Mtf/sK5555b4UUwJCSEkJAQYmJiiI+PJyMjg08//ZTVq1dz5ZVX1itI0fBU8yDUVX9Bv/cKeXPewuje1z5AsRBe7pFHHqnxU4Q2bdowfvx4LrvsMg4fbvjenvHx8cyYMYPo6GhiYmJYunQpWVlZjBplnwVmzpw5ZGdnc/fdf7R9TU9PB6CwsJC8vDzS09Ox2WxERkY2eHwVahUGTfzhZAEcPvBHkteI6eIizLdOdYrwsWHc9XdUn4ZLzEXNqT4D0XvT0CnrwMOSuoZQ46Tu5ZdfxsfHp8Y7Dg8PZ+LEiWXaqQj3os69EL3qG3Tadsx5szBufcDqkIRwuro0CwkICKBTp04NHsuQIUM4duwY8+fPJycnh/bt2zN58mTHY5ecnJxyY9Y98sgjjt/T0tJYtWoVrVu35tVXX23w+CqilIJ2HSBtO3r/Ho9qkO4M+mQh5qvPwdYN9k4Rd0pCZyXVZyD6i49g83p0cRHK18/qkFyqxkndmQldVlYWISEhFd6xKy0tJScnh9BQ+2jZzmxgLOpHGQY+E+6g9LkH0WtWoIeORXXpYXVYQrjMlClTuO2222jXrl25dQcOHOC///0vTz75pFNjGDNmDGPGjKlw3aRJk8ot++QT66f6U+06otO2w/49MKDxtsnV+cftM0Xs2mYfh27SY6jufarfUDhPh84Q0gpyj8D2jdDrLKsjcqk6ZVyTJk1yPAL4sz179lR4IRLuSXXqSrPRlwNgfvgW2iy1OCIhXGfLli0UFBRUuK6wsJAtW7a4OCIP0c4+m4Xe33jHqtPH8jBf/OcZM0U8LQmdG1BKoXrbEzm9eb3F0bheg99GM03T68bH8XbBf5kE/s1gbxr6+2+sDkcIt5CTk0OTJk2sDsMtOR657k+3NA6r6NwjmM9Phr1p0DwY48HnZGBhN6JOjQmoN/1qcSSu16DdloqLi1m/fj3NmzdvyN0KJ/MJboFx+QTMj/6L/ux99NnnoprJeyi8008//cRPP/3keD1v3jyCgoLKlCkqKmLLli1ERcmUThU6daeOrEPok4WoJk2tjceFdMZ+zJeftE+TFtIK44FnUBEu6qQiaqZ7HzAMyNiHPpKJalX7oUE8VY2Turlz55YZwPKxxx6rtOzIkY2vx4mnU8Mvge+TYf8e9Of/Q0240+qQhHCKffv2sWbNGsfrzZs3l3u64OvrS4cOHUhMTHRxdJ5BBYVA82A4dhQO/g6dulodkkvo3Tsw/zMFjudBWATG/VNQrWXILnejAgIhKgZ2bUNv/hV1QcVtVr1RjZO6Ll26MGbMGLTWJCcnc8455xASElJ2ZzYbHTp04LzzzqtTMEuWLGHhwoXk5uY6Jrfu3r17peWLi4uZN28e33//Pbm5ubRq1YqEhARGjBhRp+M3ZsrHB2P8XzFf/Cd6xdfo88eg2stdCuF9EhISSEhIAODaa6/lySefpEuXLhZH5YHadYRtKfYesI0gqdNb1mO+Ng1OFkLHLhj3PmFPboVbUj37o3dts7erk6SuvH79+tGvn/059cmTJxk3bhxhYWENFsjq1auZNWsWt912G7GxsSxdupSpU6cyffp0R0/aP5s+fTpHjx7lzjvvJDw8nLy8PEpLpaF/XalucaizzkX/8gPmh29iPDxN2kcKr/bxxx9bHYLHUu06orel2HvAejlz7Ur0u/+G0hLo3gdj4mRUU5kO052pnv3QC+fA1g3o0lJULYZk82R16igxceLEBk3oABYtWsSIESMYOXKk4y5daGgoycnJFZb/7bff2LJlC5MnTyYuLo6wsDC6dOlCbGxsg8bV2KirbwE/P9ixBf3zKqvDEaLBFRYWunQ7r9VIesCayxah334RSktQA86336GThM79deoCzZpDwQnYvd3qaFymxknd6tWra73z7Oxstm3bVm25kpIS0tLS6NOnbHfwuLg4tm+v+M34+eef6dy5M59//jl33HEH9913H++99x5FRUW1jlP8QbVqjRo7DgA9fza6WM6n8C533303ixYtIj8/v0bld+7cSVJSEosWLXJyZJ7ljx6w3nunzlw8F/3RWwCoEfGo2x5E2Sqeck24F2X4OIaYaUxDm9T48evMmTNZsGABY8eOZfDgwQQEVP5NJS0tjeXLl7Ny5UpuuOEGunWruqt3Xl4epmmWm8Q6ODi43GTXpx06dIht27bh6+vLww8/TF5eHjNnzuT48eNMnDixwm2Ki4spLi52vFZK4e/v7/i9MqfXeeOjyIrqZoxJoPT7ZHvvrqULURdfbVV4ddbY3jNv4Yq63XjjjXz00Ud8/PHHnHXWWRXOY33o0CF27NjBTz/9xL59+xg8eLC01f2zdqeSuqPZ6ON5qMCgqst7EK01euEc9CL743l16XjUpdd55f85r9arP/y8yp7UXX691dG4RI2TuhkzZvDJJ58wa9Ys3nnnHTp16lTphTAnJ4cOHTrw4IMP0rdv3xoHU9F/mMr+E52e9Pbee+91JJjFxcW89NJL3Hbbbfj5lZ8aZMGCBWV68EZFRZGUlOSYkqc64eHe28vpz3U7ccu9ZL/4BPqreYRdeT0+LVpZFFn9NKb3zJs4s25Dhw5l8ODBrFixgm+++YYff/yxwnJ+fn6cc845TJo0iejoaKfF46lU0wD7PLBHDsOBvRBT++nX3JHWGj1vFjp5AQDqqr9gjL3K4qhEXage/dAA6Tu87otHZWqc1AUEBJCYmMi4ceNYsWIF69evZ+XKlWUed4aFhdG3b1/OO++8Ws2vGBQUhGEY5e7KHT16tNzdu9NCQkJo2bJlmTuG7dq1Q2vNkSNHiIiIKLdNQkIC8fHxjtenE8bMzExKSkoqjU8pRXh4OBkZGY5k0ltUVjcd2wc6dUWn7+DgWy/hc9PdVezF/TTG98wbVFQ3m81W4y9eNeXn58fo0aMZPXo02dnZbN++nZycHIqKimjevDnt2rWjS5cuFU6FKM7QriMcOWzvAesFSZ02TfRH/0V/+yUAavxfMUZeanFUoq5Ui1b2v9H9e9BbN6AawZR2tb5iBQYGEh8f70iO8vPzKSoqIjAwsM4XQJvNRnR0NCkpKQwcONCxPCUlhQEDKp4YuVu3bqxZs4bCwkKaNrUPfHnw4EGUUrRqVfFdJV9fX3x9K24PUZMPR621132InlaubkphXHsrZtLf0d9/gzn8YlSk5w1x0qjeMy/iyrq1bNmSwYMHu+RY3ka164hO+ckr2tVpsxT9wevo75NBKdQNd2FcMNbqsEQ9qZ790Pv3wKZfG8U8xfWeJiwgIICQkJB6f6ONj49n2bJlLF++nH379jFr1iyysrIYNWoUAHPmzOGVV15xlD/vvPNo3rw5r732Gvv27WPLli188MEHDB8+vMJHr6L2VJceqLPPA21ifvKO1yYQQog68pIesNo00e+/diqhM1A33y8JnZdwTBm2ZX2j+Ayr97OFvLy8CnucVja2XGWGDBnCsWPHmD9/Pjk5ObRv357Jkyc7Hrvk5OSQlZXlKN+0aVP++c9/8s477/D3v/+d5s2bM3jwYMaPH1+/Coky1JU3oX9bA1s3QMpP0Gdg9RsJ4UG2bdvGqlWryMzMLHctU0rxxBNPWBSZ+1PtOtjbLO3fg9baIzsSaK3RH76FXvWNPaH764MYjeCOTqPRtad9mK7cbPsd5chOVkfkVHVK6goKCpg9ezY//PBDpUOI1GVQzzFjxjBmTMUjP0+aNKncsnbt2vH444/X+jii5lTrcNSFl6O/no85912Mnv1R0s5IeIlvv/2WN954g8DAQCIiIso1z2gM3+zrJTwSfHzsY4HlHIGWtfsybzWtNXruO+gVi+2PXG+5TxI6L6N8/SCmN2z6Bb15PUqSuvJmzZrFqlWrGDFiBB07dpTGxF5OXXw1+oelcGg/euVXKGk4LLzEwoULGTx4MJMmTaq0va2onLL5Qlhb+/yvB/Z4XFJnfvYB+pvPAVA3TsIYNNziiIQzqJ790Jt+QW/+FcYkWB2OU9UpG/v111+5/vrrufjiixs6HuGGlH8A6orr7W1OvvgIPXi4fcJkITxcZmYmN998syR09aAiO6EP/m7vAdvrLKvDqbGjH72N/vITANSEOzDOH21xRMJZVM/+9mYCOzajTxaimjS1OiSnqVNHieLiYjp06NDQsQg3ps4dBRHt4cQx9OK5VocjRINo164dR48etToMz+aBM0uYSxaQ9/4bAKirb8YYfonFEQmnCm8HLVtDSQmkbrI6GqeqU1LXr18/tm7d2tCxCDemfHwwxiUCoJctQh85bG1AQjSA6667js8++4zs7GyrQ/FYysN6wJo/LMWc+w4AxhU3YIz27sdxwt7hydEL1sunDKvT49errrqKF198EX9/f8466yyaN29erkxgoDye8zq9z4bY3rB9I3rB+6jbHrQ6IiHqZcmSJeTn53PffffRqVOnctctpRSPPPKIRdF5iFNJHQd/R5ulKMPH2niqoH9bg55tHxqr+VU3UnDRNdIZppFQPfujv09Gb/nN6lCcqk5J3YMP2j/M33//fd5///0Ky9Sl96twb0opjKtvxnz2AfTalehRV6A6drY6LCHqbO/evRiGQVBQENnZ2eXu2HniEB0uF9rGPmREUREczrA/6nJDOnUT5pvPgzZR515I8M33UpCRYXVYwlW69Qal7F8+co+gQjxz6svq1PlOnVzsGifVsQvqnKHotSsx572L8cAz8rcgPNarr75qdQgeTxkGRHSAPTvt7ercMKnTe9MwX3kWSoqhz0CMm+6W61Yjo5o1hw6dYc9O9LYUlJf2dK5TUnfNNdc0dBzCg6iEG9G/rIZtKbDpF/tjWSFEo6UiO6L37ETvTUOdNcTqcMrQhw9i/vspKMiHmJ4Ytz+M8nHfR8TCeVS3OPSenbA1Bbw0qav3NGGi8VGtwlAj7XP/mvNmoUtLLY5ICM+1ZMkSJk2axPXXX8+jjz5abSe0LVu28Oijj3L99ddz9913k5yc7KJIq9C1FwB6408WB1KWPpqD+fKTkJcLkVEYk/6J8mtidVjCIqp7HwD0tg1e25ayxnfqVq5cSf/+/WnevDkrV66stvzQoUPrFZhwb+riq9GrlsKBvejVy1AyxpPwENdeey3PPfccXbp04dprr62yrFKKjz76yGmxrF69mlmzZnHbbbcRGxvL0qVLmTp1KtOnT69wqsXDhw8zbdo0Ro4cyT333MP27dt5++23CQoKYtCgQU6LszoqbgBaGfD7bvSRw6hWYZbFcpouzMf8zxTIzIDW4Rj3P4UKaGZ1WMJKXXqAzQbZWXD4ILRpa3VEDa7GSd1rr73Gc889R/PmzXnttdeqLS9JnXdTAYGo+GvQH89Efz4HPfACrx7QUXiPcePG0bJlS8D69sGLFi1ixIgRjBw5EoDExEQ2bNhAcnIyEyZMKFc+OTmZ0NBQEhMTAYiMjGTXrl188cUX1iZ1zYOgaw9I3YT+ba3ls87okhLM15Ngbxo0D7YndMEtLI1JWE81aQLR3ex/p1s3oBpzUvfKK6/QokULx+9CqGEXo5d/CZkZ6OTPUJeOtzokIap19dVXO363sn1wSUkJaWlpXHHFFWWWx8XFsX379gq32bFjB3FxcWWW9e3bl2+//ZaSkhJLp2xUfc9Bp25Cr18DFiZ1Wmv0ezNgy3rwa4JxzxOoMO/78BZ1o7rH2f9Ot22AYRdZHU6Dq3GbutatWzsuGK1bt67250wrV67k+PHjDRu5sJyy+aISbgJAL/kUfTTH4oiEcB7TNLn22mtJS0trkP3l5eVhmibBwcFllgcHB5Obm1vhNrm5uRWWLy0t5dixYxVuU1xcTH5+vuOnoKDAsU4pVe1PTcsZ/U7dKdyxGU4cr9E2zvjRn/8P/eO3YBgYdz6KER1Tr3p54o+31q0h6mV072v/O92+EbS2vE6V1a2unP61zjRNXnvtNaZNmyYDEnshdfa56G9iYHcqeuGHqBsnWh2SEB6logt4VRf1P6873eC7sm0WLFjAvHnzHK+joqJISkoq9+W7KuHh4dUXioggI6orxbt3EPz7DpqNcP3UW8cXzyPn1HyuLe7+B4FjLquyfI3q5aG8tW71rZdu3Zr9/gHo48cILTyGX+duDRRZ/TXEe2bdvXrhFZRSGFffgvl/f7eP1j0yHtVW5gUWojpBQUEYhlHurtzRo0fL3Y07LSQkpFz5vLw8fHx8Kv3SnJCQQHx8vOP16eQvMzOTkpKSKmNUShEeHk5GRkaNeguW9uwPu3eQ8+3X5HXvX235hmT+thbztf8DwLhsAsfizuHYwYMVlq1tvTyJt9atQevVtQek/Ezm98swAir+v+ZKFdXNZrPV6ovXaTKkiag31bUH9B0E2sScP9vqcITwCDabjejoaFJSUsosT0lJITY2tsJtunbtWq78hg0biI6OrrQ9na+vLwEBAY4ff39/xzqtdbU/NS2ntUb1tT+C1Zt+xTxZWOPt6vtj7tyK+db/2WeLOH80xF/boPXytB9vrVtD1Ytu9qFNzK0bLK9TZXWrK0nqRIMwrroJDANSfkJv32h1OEJ4hPj4eJYtW8by5cvZt28fs2bNIisri1GjRgEwZ86cMh3TRo8eTVZWFrNnz2bfvn0sX76c5cuXc+ml1vY2degQDS1DoegkbN3gkkPqjH2YM56xT1PW+2zU9XfVq02S8H6q+6nORqmb0SXF1gbTwOTxq2gQKjwSNXQs+tvFmHPfxfjHC/bpg4QQlRoyZAjHjh1j/vz55OTk0L59eyZPnux47JKTk0NWVpajfFhYGJMnT2b27NksWbKEFi1acPPNN1s6nMmZlFKoPuegv/3SPrRJn4FOPZ7OzcZ8+Sk4cQyiYjDueERmixDVa9sRmgfDsaOQlgoxPa2OqMFIUicajLr0Onuvsz070T99jzpHxioUojpjxoxhzJgxFa6bNGlSuWU9evQgKSnJ2WHVmeo3yJ7UbViHNktRhnOSLF1wanDhI4chLALjnsdlrExRI8ow7FOG/fQ9etsGlBcldXIrRTQY1TwYNfYqAPSC99HFRRZHJIRwua49IaCZ/S7IrorH26svXVKM+fo0+H23fXDh+55CNbe+wbvwIN3sj2D11pRqCnqWOiV1e/fubeg4gNrPgXjatm3bGD9+PA8//LBT4hI1py68HEJawZHD6OWLrA5HiAajlGLo0KEEBQVZHYpbUzYbKm4AAPq3tQ2+f22a6Nkz7G32mjTFuPcJVFhEgx9HeLfT88Cyezu6sKDqwh6kTo9fH374YaKjoxk+fDjnnnsuzZpVPp+eYRg8+eSTtG1b9YjetZ0D8bT8/HxeffVVevfuXemAncJ1VJMmqCtuQM/6N3rxXPR5o1HNZHxC4T6qm+/1zz7++GPAntRNnCjjMNaE6nsOes0K9Pof0eMSG6zjgtYa/eFb6DUrHIMLq05dG2TfopEJbQOtwuyP73dsgd5nWR1Rg6jTnbpbb70VwzCYOXMmd9xxB//+97/LdbM/U48ePWjatOq2DmfOgRgZGUliYiKhoaEkJydXud1bb73FueeeS9eu8h/bXajBw6BdR8g/gf56vtXhCFHGVVddxbhx4xw/oaGhBAYGMnToUC6//HIuuOACAgMDadWqFePGjbM6XM/Usx/YfCEzAw783iC71FqjP34bvWIxKIVKvA/Vyzs+iIXrKaVQpx/BbnNNT21XqNOdutGjRzN69Gj27dvHihUr+P7771m9ejUtW7Zk2LBhDB06tFYjI9dlDkSAb7/9lkOHDnHPPfcwf74kD+5CGT4YCTdhvvIMetkX6OGXoFpWfrdVCFc6c77XL774gpCQEB5//PEyXzwLCgp45plnaNKkiRUhejzVNAC694GNP6N/W4NqV78BybXW6Pmz0Mu+sO//xkkYg4c3RKiiMeveB35Yit7mPe3q6tVRIjIykhtuuIHXX3+dRx99lK5du7Jw4ULuv//+Wu2nLnMgHjx4kDlz5nDPPffgU8Mu7PWZA7EmZTz1xyl16zPA3mC6uAi96CPvqZeb/DSmujlTcnIyl112WbknCf7+/lx22WUsWbLEqcf3ZqrvOQDoX1fXazBVwD6f65IF9v1efxfG+aPrHZ8Qp+/U8ftu9LE8a4NpIA0ypIlhGISHh9OmTRsCAgLIy6vbyanoAl7RMtM0+c9//sPVV19dbVu9M9V3DkRvnUsPnFO3k3c8yOGHbkH/sJTQ62/Ht32nBj9GdeQ980yuqlt2dnalXwp9fHyknW49qL4D0R++CXvT0AvnoC6/vk77MRd9hD41n6sa/1eMYRc1ZJiiEVPBLaBtBziwF1I3wVlDrA6p3uqV1BUUFLB69WpWrFhBamoqvr6+DBw4kGHDhtVqP7WdA7GgoIBdu3axe/du3nnnHeCP6TXGjx/PP//5T3r16lVuu7rOgaiUd86lB06uW0hre4Pp39Zy6M0X8Zn0j4bdfxXkPfNMFdWtrnMg1kS7du1YtGgRffv2LTPNVklJCYsWLaJdu3ZOOW5joIJaoK6/Cz17BnrRx5itIzCGjKjx9rq01H6H7iv7F3F19c0YI91k5gzhNVT3PugDe9HbUlCNNanbtGkTK1asYO3atRQVFdG5c2duvfVWzjvvPAICAmofxBlzIA4c+McI5CkpKQwYMKBceX9/f1544YUyy5KTk9m0aRMPPPAAYWFhFR7H19cXX1/fCtfV5MOxvnOyuTNn1U0l3Ije8BN6/Y+YO7eiOndr8GNURd4zz+Squo0fP57nn3+ee+65h4EDBxISEkJubi7r1q0jNzdXhkmqJ+O8UZiHD6C/mo9+7xV0qzBUbPkv3H+ms7Mw337B3isRUFfcgDE6wdnhikZIdettb/vtJe3q6pTUPfPMMwQFBTFq1ChGjBhBZGRkvQOJj49nxowZREdHExMTw9KlS8vNgZidnc3dd9+NYRh06FC24W1QUBC+vr7llgtrqbYdUENGoH9YivnpbIyHpjq9nZQQNdW/f3/+8Y9/8NFHH7FkyRJHItmlSxfuuusu4uLiLI7Q86krboTDGehffsB8bSrG5OdR4ZXfAdUb1mG++2/71F9N/FE33IUxaJjrAhaNS9deoBRk7EPnHkGFtLI6onqpU1L30EMPcdZZZ2E04NyetZ0DUXgOddl16HXfQepm2PQL9D7b6pCEcOjduze9e/fm5MmTnDhxgmbNmkmv1wakDANuuR+dnQm7UzFnPI3x9+dRzcsO4qyLi8v0cKVDZ4w7HkaF1bzdtBC1pZoFQofO9uktt21EefgXiDoldRU9Em0ItZ0D8UzXXHNNmaEKhPtQLVujRlyCXrIAc/5sjJ79nDYfpBB11aRJE0nmnET5NcG4+zHMqQ/D4YOYrz5rH2PueB4cO4o+dhQOH7QPBIt9Zhp15U2oSprLCNGQVLfe6D07YVsKNMakTojaUheNQ3+fDPv3oH9ahTpnqNUhCSFcSAW1wLj3Ccx/PQK7tqF3bStfKLA5RuL99iGRhHAR1S0OvWSBV7Srk6ROuIRq1hw1OgH92QfohXPQZ52LssmfnxCNiWrbAeOeJzCXLUT5N4PmQRAYDM2D7Y9jo2JlWkHhel16gI+Pfc7yzAxUa88dLko+VYXLqJGX2tvLHD6I/nE5SgYQFaLRUV174NO1h9VhCOGgmvpDVAzs3Gof2sSDk7qG6+kgRDVUU3/Uxfa5NPWij9DFxRZHJIQQQpwxu8T2jdYGUk+S1AmXUkMvghahkJ2F/u5rq8MRQgghHEmd3rbRo8f/lKROuJTy9UPF23sp6y8/QZ8stDgiIYQQjV50LPj6wdFsyNhvdTR1JkmdcDk15EJoHW4fyuD0mFRCCCGERZSvH3TpDuDRvWAlqRMup2w21GXXAaCXfIrOP25xREIIIRo7FdsbkKROiFpTAy+AiPaQfwKd/JnV4QghhGjkzuwsoU3T2mDqSJI6YQll+GBccT0AeukX9hHlhRBCCKt07AJN/O3zDu9LtzqaOpGkTlin32D7f6KTBeiv5lkdjRBCiEZM2WwQ0xPw3EewktQJyyil/rhbt+IrdG62xREJ4TrHjx9nxowZ/OUvf+Evf/kLM2bM4MSJE1Vus3btWp577jluvfVWrrnmGtLT010TrBCNhOrm2e3qJKkT1urZHzp3g+Ii9NfzrY5GCJf5z3/+Q3p6Oo899hiPPfYY6enpzJgxo8ptTp48SWxsLBMmTHBRlEI0Lo52dTs2o0tLrQ2mDiSpE5ZSSmGc7gm78mt07hGLIxLC+fbt28dvv/3GnXfeSUxMDDExMdxxxx38+uuvHDhwoNLtLrjgAsaNG0fv3r1dGK0QjUhkFAQEQmEB7NlpdTS1JkmdsF73vvYJlUuK0YulbZ3wfqmpqQQEBNC1a1fHspiYGAICAti+fbuFkQnRuCnDAA9+BGuzOgAhlFIYl0/AfPGf6O+XoMdeiWrZ2uqwhHCa3NxcgoODyy0PDg4mNze3QY9VXFxM8RnzLCul8Pf3d/xeldPrqyvnaby1XuC9dXNlvYxufTB//RG2bkBdco3Tj9eQdZOkTrgF1S0OYnvbxwdaPBd1w0SrQxKi1j755BPmzav6bvO0adMqXae1bvAPrQULFpSJKSoqiqSkJFq3rvkXp/Dw8AaNyV14a73Ae+vminoVDxtNxpw30Du30CYkGMM/wOnHhIapmyR1wm0Yl12H+fxG9Kql6IvGoVqFWR2SELUyduxYzj333CrLtG7dmj179nD0aPmxGfPy8iq8g1cfCQkJxMfHO16fThozMzMpKSmpclulFOHh4WRkZHj0JOd/5q31Au+tmyvrpZXNPpVlZgYHV3yD0XegU49XUd1sNlutvnidJkmdcBsqphd07wNbN6C//AR1091WhyRErQQFBREUFFRtuZiYGPLz89m5cyddunQBYMeOHeTn5xMbG9ugMfn6+uLr61vhupp+OGqtvSpBOM1b6wXeWzdX1Uv17GcfamvzL+g+A5x+PGiYuklHCeFWHD1hVy9DZ2ZYHI0QzhEZGUnfvn158803SU1NJTU1lTfffJP+/fvTtm1bR7n777+fdevWOV4fP36c9PR09u3bB8CBAwdIT09v8HZ4QjR2qmd/APSmXy2OpHbc6k7dkiVLWLhwIbm5uURGRpKYmEj37t0rLLt27VqSk5NJT0+npKSEyMhIrr76avr27evaoEWDUl16QI9+sGW9/W5d4r1WhySEU9x777288847PPfccwCcddZZ3HrrrWXKHDhwgPz8fMfrn3/+mddee83x+uWXXwZg3LhxXHON8xt0C9FodOsNPj6QmYE+fAAV1rb6bdyA2yR1q1evZtasWdx2223ExsaydOlSpk6dyvTp0wkNDS1XfuvWrcTFxXHdddf9f3v3HldVme9x/PNsQBO5eiFwIBUV80Zio5l60nSUpki7aDMxncJbU3m0jtnFl5X6OiqD06SVnsoRxZky02kos2ZkEOeUWlZWMsJkKKDh5SgdLipe2Kzn/LFzT8RFEGRd+L1fL1/J2mvj79vePPz2Ws96Fu3bt2f79u2kpKSwZMkSunfvbkIC0Vxc4+/FyP0S/XEW+taJtvlhEqIxAgICmDWr/g8tGzdurPb1qFGjGDVq1BWsSggBoK7y9yy1tf8f6JwvbfN7yDKnX7ds2cLo0aMZM2aM9yhdp06dyMjIqHX/pKQkJkyYQM+ePYmIiCAxMZGIiAj27NnTwpWL5qZ6XAv9rwfDQG/ZeOknCCGEEM3Mewo250uTK2k4Sxypc7vd5Ofnc8cdd1TbHhsb2+CFOA3D4OzZswQEBNS5z+Wu1+TUdX/Autl8xidStW8P+pO/Q8IvUFc37lOSVXM1B8kmhBBXnuoXh/7zOvg6G11ZiarjgiMrsURTV15ejmEYNS7lb8xCnFu2bOH8+fPceOONde7T1PWanLruD1gwW0QEJweP4NxnO2ibtZmOsxde1rexXK5mJNmEEOIKiuoOwaFQVgIHcj2rM1icJZq6i2r7dN6QT+w7duxg06ZNPPHEE/Wu8XS56zU5dd0fsHY2HX8XfLaDiqy/cP7m21HhP2nwc62cq6laW7bLXa9JCCGaQimF6jsQ/fF2z7w6aeoaJigoCJfLVeOoXFlZ2SUX4ty1axevvvoqs2fPJjY2tt59m7pek1PX/QGLZuvaE2IHQ/ZnGFs24Jo6u9HfwpK5molkE0KIK6zfIPh4OzrnC5iYZHY1l2SJCyV8fX2Jjo4mO7v6zXOzs7PrXYhzx44drFy5klmzZjFo0KArXaYwgXfdut0foo8XmVyNEEKI1kT1jQOloKgQXfqd2eVckiWaOoCEhAS2bdtGVlYWRUVFpKWlUVxczNixYwFYv349K1as8O5/saG7//77iYmJobS0lNLS0mprOgn7U117wnVDQBvo994yuxwhhBCtiAoM8pw1AnTOV+YW0wCWOP0KMGzYME6dOsXbb79NSUkJUVFRzJ071zuXpqSkhOLiYu/+mZmZVFVVkZqaSmpqqnf7yJEjmTFjRovXL64c1/h7MfZ+iv7sQ3TCL1ARkWaXJIQQopVQ/QehC/Mg5wsYPsbscuplmaYOID4+nvj4+Fof+3GjtmDBghaoSFiBuqYHDBwKX32C3rIBNX2O2SUJIYRoJVS/OPSWt9C5X6GNKpTLx+yS6mSZ069C1Md1+y8B0J99hD562ORqhBBCtBrde0O79nDmFBQeMLuaeklTJ2xBXRMNcUNBa4zN680uRwghRCuhfHy8a9RZ/e4S0tQJ23CNT/RchbRnF/rQQbPLEUII0Uqo/hdvGfaFyZXUT5o6YRsqshtqyE0AGOl/MLkaIYQQrYXqF+f5S/436NPl5hZTD2nqhK2o8Yng4wM5X6L37zO7HCGEEK2A6tAZron2LK/12Udml1MnaeqEraiwCNS/jQM8R+vkrgNCCCFagrpxNAB65zaTK6mbNHXCdtRt90CbNnDwa8j+3OxyhBBCtALqhpGeM0WHDqCPHDK7nFpJUydsR4V0RN2cAIDxzh/RhmFyRUIIIZxOBQbDgMEA6F1ZJldTO2nqhC2pn98N7fw99+Oz8PwGIYQQzuH6/o4S+pPt6Koqk6upSZo6YUuqfSBq3J0A6HffQLvdJlckhBDC8fpfD4HBUF7quW2YxUhTJ2xL/Wy854fr5HH0rkyzyxFCCOFwytcXdcMoAAwLXjBhqXu/CtEY6qp2qNvuQW/4Pfq9DejBN6Ha+ZtdVqukq6o8p8G/3os+cxoqzkDF9/89VwFhXVAx/VC9+kGvfqj2AWaXLIQQl0UNH43OfBf2foo+XY4KCDK7JC9p6oStqZtuQW97z3O07p3XUfc+aHZJrYq+cB69cxt665/huxN171iYhy7MQ2e847kryE+6onr1Q918GyoissXqFUKIplKR3T1r1h3OR3/6IWp0gtkleUlTJ2xN+fnhuu9hjGXz0dvfRw+5CdXjWrPLcjx9tgL9P39B/+1dz9wSgMBg1Iix0DEM/Nuj/APAvz20aYv+tgDyctDf7IPjRzwXuBQVom682dQcQghxOdSwn6EPr/JcBStNnRDNR/WNQ914M/rj7Rh/XInrmRdQfm3MLsux9N7PMNYuhzOnPBs6dEbF34kaPhbVtm2tz1E/6QpDR3meX14CebnovFyIim6Zoi3o9OnTrF27ls8/96y1+NOf/pQpU6bQvn37Wvd3u91s2LCBL7/8khMnTuDv78+AAQNITEykQ4cOLVm6EK2eGnITetMaz5p1RYWoyG5mlwTIhRLCIdSkqRAQBEcOobemm12OI2mjCiP9dYwV/+Vp6MIjUZMfxbX4NVyjE+ps6H5MBYWirh+O65fTUb6t93PlSy+9RGFhIfPmzWPevHkUFhby8ssv17n/hQsXKCgo4O677yYlJYXHH3+cY8eOsXTp0hasWggBoAKD4LqLa9ZZ54IJaeqEI6jAINQvpgGgt7yFPn7E5IqcRZ8qx3hxIfqDjQCo0Qm45r+Ia9iYVt2YXa6ioiK++uorHnroIWJiYoiJieHXv/41X3zxBUePHq31Of7+/jz77LMMGzaMLl26EBMTw+TJk8nPz6e4uLiFEwghXMMurln3d8ssqyVNnXAMdcNI6BcH7kqq/rBC7gvbTHRBHsai/4Tcr6BNW9S0x3Hd+yDK18/s0mzrm2++wd/fn169enm3xcTE4O/vz/79+xv8fSoqKlBK4e8vV30L0eL6DfIsq3WqDPY17JaVV/oOSPIRWziGUgrXrx7GWDATvtnHmYx3IfYGs8uyLa01+sOt6A2rwO2GsAhcD8+1zNwROystLSU4OLjG9uDgYEpLSxv0PS5cuMD69esZPnx4vU1dZWUllZWV3q+VUrRr18779/pcfPxS+9mNU3OBc7NZMZfy80PfeDM64x2M11/BJzwSFRFV5/66MA9jzXJ8HpmLCv/XVf/Nmc1STd3WrVvZvHkzpaWlREZGkpSURJ8+fercPzc3l3Xr1lFUVERoaCjjx49n3LhxLVixsBrVORw1IRG9aS2lqS/iem45dOhsdlm2o8+fR7/+3+hPtns2DByKa/KjKP/aJ/ELj40bN/KnP/2p3n2Sk5PrfExr3aCB3e12s3z5crTWTJs2rd5909PTq9XUvXt3UlJS6Ny54T8X4eHhDd7XTpyaC5ybzWq5qqbM5GReDpUFeegXnqVz8mv4RXWrsV/FR3/j/5YtgPPnabNlA52e/V2NfZojm2Waul27dpGWlsa0adPo3bs3mZmZLFmyhGXLltGpU6ca+584cYLk5GTGjBnDzJkz2b9/P6tXryYoKIihQ4eakEBYhRozHr37Q/Thg1TN/w/Unf+OGvVzlMvH7NJsQR8/gvHqb+DIIVAuz/+/W+6y1Cdkq7rlllsYPnx4vft07tyZQ4cOUVZWVuOx8vLyWo/g/ZDb7WbZsmWcPHmS55577pKnXu+8804SEv615MLF1/HkyZO4LzEPSClFeHg4x48fd9R0BqfmAudms3IuPWs+/O4ZjKJCjj81HZ85i71H7LTW6Pc2YGxeD4Dqfz0XfvUIx44d8z6/tmy+vr6N+uB1kWWaui1btjB69GjGjPFMPExKSmLv3r1kZGSQmJhYY/+MjAw6depEUlISAJGRkRw8eJD33ntPmrpWTvn44PPw0/ise4kLX/8D/eYq9Cd/x3XfI6hrWu8SGg2hv9iFsfZFOHcWgkJwPfgEqvcAs8uyjaCgIIKCLr26fExMDBUVFRw4cICePXsCkJeXR0VFBb17967zeRcbuuPHjzN//nwCAwMv+W/5+fnh51f7/MeG/nLUWlvuF2lzcGoucG42S+YKCMI1exHGC89AUSFVz8/DNWcxdOiMTnvJc7cdQP1sAmpSErh8as3QHNks0dS53W7y8/O54447qm2PjY2tc9JwXl4esbGx1bYNHDiQ7du343a78ZUr8lo11TmcsKWrOfrWWow//wEKvsFYPNvzQzX6NlANvEbIikenlMLt54Mu+a76ANCYwcCogtPlcKocfaoMTpdB0SH0x1mex3v1xfXgk6gQWf/sSoiMjGTgwIG89tprTJ8+HYBVq1YxaNAgunTp4t3vscceIzExkSFDhlBVVcULL7xAQUEBTz31FIZheOffBQQEyJgnhIlU4PeN3e/mwZFDGM/Pg5COcOgA+PigfvUwrn+78tPDLDEKlJeXYxhGjdMO9U0arm2icXBwMFVVVZw6dYrQ0NAaz7ncCcNWnKDZXJyaTSnlOWI3OgEVNxRjw+/Rn+9EZ6SjM+y/jt2xS+9y2VT8Xbjuuh/l0/Knq536fqzNrFmzWLNmDYsXLwbg+uuvZ+rUqdX2OXr0KBUVFQB899133oWKn3zyyWr7zZ8/n379+rVA1UKIuqjAIFyPL/Y2dpSVQEAgrofmonr3b5EaLNHUXVTbQN6QZuuii0ct6npOUycMW22CZnNyarbw8HAID4eFL3L2048oXb0M9//Wvg5Ya6JcPrgCg3EFh+AKDsUnOBRXcCjtBg/nqjjzpy849f34QwEBAcyaNavefTZu3Oj9e1hYWLWvhRDW423sXv0NVLlxTZ2N6txy45klmrqgoCBcLleNo3JlZWV1ThoOCQmpsX95eTk+Pj4EBATU+pzLnTBs5QmaTeXUbLXmiuoJC1da403fBM35mmmg6vs/AOcAjl3J44D1a84Jw0IIYQYVGITPE0tM+bct8fvN19eX6OhosrOzGTJkiHd7dnY2gwcPrvU5vXr1Ys+ePdW27d27l+jo6DrnljR1wrAlJ2g2E6dmc2oukGxCCCGqs8wdJRISEti2bRtZWVkUFRWRlpZGcXExY8eOBWD9+vWsWLHCu/+4ceMoLi72rlOXlZVFVlYWt99+u1kRhBBCCCFMY4kjdQDDhg3j1KlTvP3225SUlBAVFcXcuXO9p11KSkqq3d8wLCyMuXPnsm7dOrZu3UpoaCiTJ0+W5UyEEEII0SpZpqkDiI+PJz4+vtbHZsyYUWNb3759SUlJudJlCSGEEEJYnmVOvwohhBBCiMtnqSN1Zmnoop1OXtzTqdmcmgtaTzYn5zRTY/6/OvU1cGoucG42p+aC5hn3lJZLzIQQQgghbE9OvzbA2bNneeqppzh79qzZpTQ7p2Zzai6QbKLlOPX1cGoucG42p+aC5s0mTV0DaK0pKChw5LpZTs3m1Fwg2UTLcerr4dRc4NxsTs0FzZtNmjohhBBCCAeQpk4IIYQQwgGkqWsAPz8/Jk6cWOctxuzMqdmcmgskm2g5Tn09nJoLnJvNqbmgebPJ1a9CCCGEEA4gR+qEEEIIIRxAmjohhBBCCAeQpk4IIYQQwgGkqRNCCCGEcADn3kStGW3dupXNmzdTWlpKZGQkSUlJ9OnTx+yyGiU3N5fNmzdTUFBASUkJc+bMYciQId7HtdZs2rSJbdu2cfr0aXr16sXUqVOJiooysepLS09P59NPP+XIkSO0adOGmJgY7rvvPrp06eLdx47ZMjIyyMjI4OTJkwBERkYyceJE4uLiAHtmqk16ejpvvvkmt956K0lJSYBzstmdjHvW5dRxD2Tsa2o2OVJ3Cbt27SItLY277rqLlJQU+vTpw5IlSyguLja7tEY5f/483bp1Y8qUKbU+/u677/L+++8zZcoUkpOTCQkJYdGiRZa/JUtubi7x8fEsXryYZ555BsMwWLRoEefOnfPuY8dsHTp0IDExkeTkZJKTk+nfvz9Lly7l22+/BeyZ6ccOHDhAZmYmXbt2rbbdCdnsTsY9a7/XnDrugYx9Tc6mRb3mzp2rV61aVW3bY489pt944w2TKmq6SZMm6d27d3u/NgxDT58+Xaenp3u3XbhwQT/wwAM6IyPDhAovX1lZmZ40aZLOycnRWjsrW1JSkt62bZsjMp09e1bPmjVL7927V8+fP1+vXbtWa+2s18vOZNyz13vNyeOe1jL2NSabHKmrh9vtJj8/n+uuu67a9tjYWPbv329SVc3vxIkTlJaWVsvp5+dH3759bZezoqICgICAAMAZ2QzDYOfOnZw/f56YmBhHZFq9ejVxcXHExsZW2+6EbHYn45793mtOHPdAxr7LySZz6upRXl6OYRgEBwdX2x4cHExpaak5RV0BF7PUltNOp1u01qxbt45rr72Wa665BrB3tsOHDzNv3jwqKyu56qqrmDNnDpGRkd4fcDtmAti5cycFBQUkJyfXeMzOr5dTyLhnr/ea08Y9kLHvhxqbTY7UNYBSqkHb7O7HmbTNbjaSmprK4cOHefTRR2s8ZsdsXbp04be//S2LFy9m3LhxrFy5kqKiIu/jdsxUXFxMWloaM2fOpE2bNnXuZ8dsTiPjnj04bdwDGft+qLHZ5EhdPYKCgnC5XDU+nZaVldXopu0sJCQE8HxSCA0N9W4vLy+3Tc41a9awZ88eFi5cSMeOHb3b7ZzN19eX8PBwAHr06MHBgwf54IMPmDBhAmDPTPn5+ZSVlfH00097txmGwT//+U/++te/snz5csCe2ZxCxj37vNecOO6BjH1NySZH6urh6+tLdHQ02dnZ1bZnZ2fTu3dvk6pqfmFhYYSEhFTL6Xa7yc3NtXxOrTWpqans3r2b5557jrCwsGqP2znbj2mtqaystHWmAQMG8Pzzz7N06VLvnx49ejBixAiWLl3K1VdfbdtsTiHjnvXfa61p3AMZ+xqTTY7UXUJCQgIvv/wy0dHRxMTEkJmZSXFxMWPHjjW7tEY5d+4cx48f93594sQJCgsLCQgIoFOnTtx6662kp6cTERFBeHg46enptG3blhEjRphY9aWlpqayY8cOnnzySdq1a+c9uuDv70+bNm1QStky2/r164mLi6Njx46cO3eOnTt3kpOTw7x582ybCaBdu3beeT8XtW3blsDAQO92u2ZzEhn3rP1ec+q4BzL2NTWb0nY4GW2yi4twlpSUEBUVxQMPPEDfvn3NLqtRcnJyWLhwYY3tI0eOZMaMGd5FDzMzMzlz5gw9e/Zk6tSpNd6EVnPPPffUuv2RRx5h1KhRALbM9sorr7Bv3z5KSkrw9/ena9euTJgwwXvFlB0z1WXBggV069atxgKcTshmZzLuWZdTxz2Qsa+p2aSpE0IIIYRwAJlTJ4QQQgjhANLUCSGEEEI4gDR1QgghhBAOIE2dEEIIIYQDSFMnhBBCCOEA0tQJIYQQQjiANHVCCCGEEA4gTZ0QQgghhANIUyeEEEII4QDS1AkhhBBCOIA0dUIIIYQQDiBNnRBCCCGEA/w/O1yplVHaYPsAAAAASUVORK5CYII=" + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "x_mpc = np.array(x.value[0, :]).flatten()\n", + "y_mpc = np.array(x.value[1, :]).flatten()\n", + "theta_mpc = np.array(x.value[2, :]).flatten()\n", + "v_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((v_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, :]) #根据mpc优化后的a和delta,预测的轨迹\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(v_mpc)\n", + "plt.ylabel(\"v_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()\n", + "\n", + "# 下图展示的结果并不准确\n", + "# 这是因为在做约束条件中,xt+1 = Axt + But + C时,A,B,C是线性化的模型,且是基于猜测的x_bar和u_bar来线性化的\n", + "# 所以需要通过滚动优化,获得更准确的猜测和状态猜测\n", + "# 这里有一个问题,那是否要将这次计算的u,作为下一次的猜测基础?" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## full track demo " + ] + }, + { + "cell_type": "code", + "execution_count": 31, + "metadata": { + "ExecuteTime": { + "end_time": "2024-10-24T03:11:52.521780Z", + "start_time": "2024-10-24T03:11:26.227974Z" + } + }, + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_9821/761030008.py:14: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n", + " A[0, 2] = -v * np.sin(theta)\n", + "/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_9821/761030008.py:15: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n", + " A[1, 2] = v * np.cos(theta)\n", + "/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_9821/761030008.py:19: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n", + " B[0, 0] = np.cos(theta)\n", + "/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_9821/761030008.py:20: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n", + " B[1, 0] = np.sin(theta)\n", + "/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_9821/761030008.py:21: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n", + " B[2, 0] = v * np.tan(delta) / L\n", + "/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_9821/761030008.py:22: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n", + " B[2, 1] = v / (L * np.cos(delta) ** 2)\n" + ] + }, + { + "name": "stdout", + "output_type": "stream", + "text": [ + "CVXPY Optimization Time: Avrg: 0.1320s Max: 0.1657s Min: 0.1066s\n" + ] + } + ], + "source": [ + "track = compute_path_from_wp(\n", + " [0, 3, 4, 6, 10, 12, 14, 6, 1, 0], [0, 0, 2, 4, 3, 3, -2, -6, -2, -2], 0.05\n", + ")\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", + "x_sim[0,0] = 0 # x\n", + "x_sim[1,0] = -0.25 # y\n", + "x_sim[2,0] = np.radians(0.0) # yaw\n", + "u_sim = np.zeros((M, sim_duration - 1))\n", + "\n", + "MAX_SPEED = 1.5 # m/s\n", + "MAX_D_ACC = 0.5 # m/s^2\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 = x_sim[:, 0]\n", + "\n", + "# starting guess\n", + "u_bar = np.zeros((M, T))\n", + "u_bar[0, :] = 1.0 # v\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_sim是通过ode计算出的真值\n", + " x_bar = np.zeros((N, T + 1))\n", + " x_bar[:, 0] = x_sim[:, sim_time]\n", + "\n", + " # prediction for linearization of costrains\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", + " 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", + " # 构建MPC问题和求解器\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, 0]) # state error cost\n", + " Qf = np.diag([30, 30, 0]) # state final error cost\n", + " R = np.diag([10, 10]) # input cost\n", + " R_ = np.diag([30, 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 += [\n", + " cp.abs(u[0, t + 1] - u[0, t]) / DT <= MAX_D_ACC\n", + " ] # max acc rate of change\n", + " constr += [\n", + " cp.abs(u[1, t + 1] - u[1, t]) / DT <= MAX_D_STEER\n", + " ] # 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 += [u[0, :] <= MAX_SPEED] # max speed\n", + " constr += [u[0, :] >= 0.0] # min_speed (not really needed)\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作为下次猜测的起点\n", + " u_bar = np.vstack(\n", + " (np.array(u.value[0, :]).flatten(), (np.array(u.value[1, :]).flatten()))\n", + " )\n", + " \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", + " # 用ode模型仿真车辆运动\n", + " # move simulation to t+1\n", + " tspan = [0, DT]\n", + " x_sim[:, sim_time + 1] = odeint(\n", + " kinematics_ode_model, x_sim[:, sim_time], tspan, args=(u_bar[:, 0],)\n", + " )[1]\n", + "\n", + "print(\n", + " \"CVXPY Optimization Time: Avrg: {:.4f}s Max: {:.4f}s Min: {:.4f}s\".format(\n", + " np.mean(opt_time), np.max(opt_time), np.min(opt_time)\n", + " )\n", + ")" + ] + }, + { + "cell_type": "code", + "execution_count": 33, + "metadata": { + "ExecuteTime": { + "end_time": "2024-10-24T03:14:58.916991Z", + "start_time": "2024-10-24T03:14:58.730488Z" + } + }, + "outputs": [ + { + "data": { + "text/plain": "
", + "image/png": "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" + }, + "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(\"v(t) [m/ss]\")\n", + "\n", + "plt.subplot(grid[1, 4])\n", + "plt.plot(np.degrees(u_sim[1, :]))\n", + "plt.ylabel(\"delta(t) [rad]\")\n", + "\n", + "plt.subplot(grid[2, 4])\n", + "plt.plot(x_sim[2, :])\n", + "plt.ylabel(\"theta(t) [rad]\")\n", + "\n", + "plt.tight_layout()\n", + "plt.show()" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "outputs": [], + "source": [], + "metadata": { + "collapsed": false + } + } + ], + "metadata": { + "kernelspec": { + "name": "python3", + "language": "python", + "display_name": "Python 3 (ipykernel)" + }, + "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 +}