mpc_python_learn/notebooks/old_scipy_implementation/MPC_tracking_cvxpy.ipynb

1249 lines
268 KiB
Plaintext

{
"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",
"\n",
"plt.style.use(\"ggplot\")\n",
"\n",
"import time"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"### kinematics model equations\n",
"\n",
"The variables of the model are:\n",
"\n",
"* $x$ coordinate of the robot\n",
"* $y$ coordinate of the robot\n",
"* $\\theta$ heading of the robot\n",
"* $\\psi$ heading error = $\\psi = \\theta_{ref} - \\theta$\n",
"* $cte$ crosstrack error = lateral distance of the robot from the path \n",
"\n",
"The inputs of the model are:\n",
"\n",
"* $v$ linear velocity of the robot\n",
"* $w$ angular velocity of the robot\n",
"\n",
"These are the differential equations f(x,u) of the model:\n",
"\n",
"* $\\dot{x} = v\\cos{\\theta}$ \n",
"* $\\dot{y} = v\\sin{\\theta}$\n",
"* $\\dot{\\theta} = w$\n",
"* $\\dot{\\psi} = -w$\n",
"* $\\dot{cte} = v\\sin{-\\psi}$\n",
"\n",
"The **Continuous** State Space Model is\n",
"\n",
"$ {\\dot{x}} = Ax + Bu $\n",
"\n",
"with:\n",
"\n",
"$ A =\n",
"\\quad\n",
"\\begin{bmatrix}\n",
"\\frac{\\partial f(x,u)}{\\partial x} & \\frac{\\partial f(x,u)}{\\partial y} & \\frac{\\partial f(x,u)}{\\partial \\theta} & \\frac{\\partial f(x,u)}{\\partial \\psi} & \\frac{\\partial f(x,u)}{\\partial cte} \\\\\n",
"\\end{bmatrix}\n",
"\\quad\n",
"=\n",
"\\quad\n",
"\\begin{bmatrix}\n",
"0 & 0 & -vsin(\\theta) & 0 & 0 \\\\\n",
"0 & 0 & vcos(\\theta) & 0 & 0 \\\\\n",
"0 & 0 & 0 & 0 & 0 \\\\\n",
"0 & 0 & 0 & 0 & 0 \\\\\n",
"0 & 0 & 0 & -vcos(-\\psi) & 0 \n",
"\\end{bmatrix}\n",
"\\quad $\n",
"\n",
"\n",
"$ B = \\quad\n",
"\\begin{bmatrix}\n",
"\\frac{\\partial f(x,u)}{\\partial v} & \\frac{\\partial f(x,u)}{\\partial w} \\\\\n",
"\\end{bmatrix}\n",
"\\quad\n",
"=\n",
"\\quad\n",
"\\begin{bmatrix}\n",
"\\cos{\\theta_t} & 0 \\\\\n",
"\\sin{\\theta_t} & 0 \\\\\n",
"0 & 1 \\\\\n",
"0 & -1 \\\\\n",
"-\\sin{(-\\psi_t)} & 0 \n",
"\\end{bmatrix}\n",
"\\quad $\n",
"\n",
"discretize with forward Euler Integration for time step dt:\n",
"\n",
"* ${x_{t+1}} = x_{t} + v_t\\cos{\\theta}*dt$\n",
"* ${y_{t+1}} = y_{t} + v_t\\sin{\\theta}*dt$\n",
"* ${\\theta_{t+1}} = \\theta_{t} + w_t*dt$\n",
"* ${\\psi_{t+1}} = \\psi_{t} - w_t*dt$\n",
"* ${cte_{t+1}} = cte_{t} + v_t\\sin{-\\psi}*dt$\n",
"\n",
"The **Discrete** State Space Model is then:\n",
"\n",
"${x_{t+1}} = Ax_t + Bu_t $\n",
"\n",
"with:\n",
"\n",
"$\n",
"A = \\quad\n",
"\\begin{bmatrix}\n",
"1 & 0 & -v\\sin{\\theta}dt & 0 & 0 \\\\\n",
"0 & 1 & v\\cos{\\theta}dt & 0 & 0 \\\\\n",
"0 & 0 & 1 & 0 & 0 \\\\\n",
"0 & 0 & 0 & 1 & 0 \\\\\n",
"0 & 0 & 0 & -vcos{(-\\psi)}dt & 1 \n",
"\\end{bmatrix}\n",
"\\quad\n",
"$\n",
"\n",
"$\n",
"B = \\quad\n",
"\\begin{bmatrix}\n",
"\\cos{\\theta_t}dt & 0 \\\\\n",
"\\sin{\\theta_t}dt & 0 \\\\\n",
"0 & dt \\\\\n",
"0 & -dt \\\\\n",
"-\\sin{-\\psi_t}dt & 0 \n",
"\\end{bmatrix}\n",
"\\quad\n",
"$\n",
"\n",
"This State Space Model is **non-linear** (A,B are time changing), to linearize it the **Taylor's series expansion** is used around $\\bar{x}$ and $\\bar{u}$:\n",
"\n",
"$ \\dot{x} = f(x,u) \\approx f(\\bar{x},\\bar{u}) + A(x-\\bar{x}) + B(u-\\bar{u})$\n",
"\n",
"So:\n",
"\n",
"$ x_{t+1} = x_t + (f(\\bar{x},\\bar{u}) + A(x_t-\\bar{x}) + B(u_t-\\bar{u}) )dt $\n",
"\n",
"$ x_{t+1} = (I+dtA)x_t + dtBu_t +dt(f(\\bar{x},\\bar{u}) - A\\bar{x} - B\\bar{u}))$\n",
"\n",
"The Discrete linearized kinematics model is\n",
"\n",
"$ x_{t+1} = A'x_t + B' u_t + C' $\n",
"\n",
"with:\n",
"\n",
"$ A' = I+dtA $\n",
"\n",
"$ B' = dtB $\n",
"\n",
"$ C' = dt(f(\\bar{x},\\bar{u}) - A\\bar{x} - B\\bar{u}) $"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"------------------\n",
"NB: psi and cte are expressed w.r.t. the track as reference frame.\n",
"In the reference frame of the veicle the equtions would be:\n",
"* psi_dot = w\n",
"* cte_dot = sin(psi)\n",
"-----------------"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"-----------------\n",
"[About Taylor Series Expansion](https://courses.engr.illinois.edu/ece486/fa2017/documents/lecture_notes/state_space_p2.pdf):\n",
"\n",
"In order to linearize general nonlinear systems, we will use the Taylor Series expansion of functions.\n",
"\n",
"Typically it is possible to assume that the system is operating about some nominal\n",
"state solution $\\bar{x}$ (possibly requires a nominal input $\\bar{u}$) called **equilibrium point**.\n",
"\n",
"Recall that the Taylor Series expansion of f(x) around the\n",
"point $\\bar{x}$ is given by:\n",
"\n",
"$f(x)=f(\\bar{x}) + \\frac{df(x)}{dx}|_{x=\\bar{x}}(x-\\bar{x})$ + higher order terms...\n",
"\n",
"For x sufficiently close to $\\bar{x}$, these higher order terms will be very close to zero, and so we can drop them.\n",
"\n",
"The extension to functions of multiple states and inputs is very similar to the above procedure.Suppose the evolution of state x\n",
"is given by:\n",
"\n",
"$\\dot{x} = f(x1, x2, . . . , xn, u1, u2, . . . , um) = Ax+Bu$\n",
"\n",
"Where:\n",
"\n",
"$ A =\n",
"\\quad\n",
"\\begin{bmatrix}\n",
"\\frac{\\partial f(x,u)}{\\partial x1} & ... & \\frac{\\partial f(x,u)}{\\partial xn} \\\\\n",
"\\end{bmatrix}\n",
"\\quad\n",
"$ and $ B = \\quad\n",
"\\begin{bmatrix}\n",
"\\frac{\\partial f(x,u)}{\\partial u1} & ... & \\frac{\\partial f(x,u)}{\\partial um} \\\\\n",
"\\end{bmatrix}\n",
"\\quad $\n",
"\n",
"Then:\n",
"\n",
"$f(x,u)=f(\\bar{x},\\bar{u}) + \\frac{df(x,u)}{dx}|_{x=\\bar{x}}(x-\\bar{x}) + \\frac{df(x,u)}{du}|_{u=\\bar{u}}(u-\\bar{u}) = f(\\bar{x},\\bar{u}) + A_{x=\\bar{x}}(x-\\bar{x}) + B_{u=\\bar{u}}(u-\\bar{u})$\n",
"\n",
"-----------------"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"### Kinematics Model"
]
},
{
"cell_type": "code",
"execution_count": 2,
"metadata": {},
"outputs": [],
"source": [
"# Control problem statement.\n",
"\n",
"N = 5 # number of state variables\n",
"M = 2 # number of control variables\n",
"T = 20 # Prediction Horizon\n",
"dt = 0.25 # discretization step\n",
"\n",
"x = cp.Variable((N, T + 1))\n",
"u = cp.Variable((M, T))"
]
},
{
"cell_type": "code",
"execution_count": 3,
"metadata": {},
"outputs": [],
"source": [
"def get_linear_model(x_bar, u_bar):\n",
" \"\"\" \"\"\"\n",
"\n",
" x = x_bar[0]\n",
" y = x_bar[1]\n",
" theta = x_bar[2]\n",
" psi = x_bar[3]\n",
" cte = x_bar[4]\n",
"\n",
" v = u_bar[0]\n",
" w = u_bar[1]\n",
"\n",
" A = np.zeros((N, N))\n",
" A[0, 2] = -v * np.sin(theta)\n",
" A[1, 2] = v * np.cos(theta)\n",
" A[4, 3] = -v * np.cos(-psi)\n",
" A_lin = np.eye(N) + dt * A\n",
"\n",
" B = np.zeros((N, M))\n",
" B[0, 0] = np.cos(theta)\n",
" B[1, 0] = np.sin(theta)\n",
" B[2, 1] = 1\n",
" B[3, 1] = -1\n",
" B[4, 0] = -np.sin(-psi)\n",
" B_lin = dt * B\n",
"\n",
" f_xu = np.array(\n",
" [v * np.cos(theta), v * np.sin(theta), w, -w, v * np.sin(-psi)]\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 A_lin, B_lin, C_lin"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"Motion Prediction: using scipy intergration"
]
},
{
"cell_type": "code",
"execution_count": 4,
"metadata": {},
"outputs": [],
"source": [
"# Define process model\n",
"def kinematics_model(x, t, u):\n",
" \"\"\" \"\"\"\n",
"\n",
" dxdt = u[0] * np.cos(x[2])\n",
" dydt = u[0] * np.sin(x[2])\n",
" dthetadt = u[1]\n",
" dpsidt = -u[1]\n",
" dctedt = u[0] * np.sin(-x[3])\n",
"\n",
" dqdt = [dxdt, dydt, dthetadt, dpsidt, dctedt]\n",
"\n",
" return dqdt\n",
"\n",
"\n",
"def predict(x0, u):\n",
" \"\"\" \"\"\"\n",
"\n",
" x_bar = np.zeros((N, T + 1))\n",
"\n",
" x_bar[:, 0] = x0\n",
"\n",
" # solve ODE\n",
" for t in range(1, T + 1):\n",
"\n",
" tspan = [0, dt]\n",
" x_next = odeint(kinematics_model, x0, tspan, args=(u[:, t - 1],))\n",
"\n",
" x0 = x_next[1]\n",
" x_bar[:, t] = x_next[1]\n",
"\n",
" return x_bar"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"Validate the model, here the status w.r.t a straight line with constant heading 0"
]
},
{
"cell_type": "code",
"execution_count": 5,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"CPU times: user 4.59 ms, sys: 294 µs, total: 4.89 ms\n",
"Wall time: 4.68 ms\n"
]
}
],
"source": [
"%%time\n",
"\n",
"u_bar = np.zeros((M, T))\n",
"u_bar[0, :] = 1 # m/s\n",
"u_bar[1, :] = np.radians(-10) # rad/s\n",
"\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0\n",
"x0[1] = 1\n",
"x0[2] = np.radians(0)\n",
"x0[3] = 0\n",
"x0[4] = 1\n",
"\n",
"x_bar = predict(x0, u_bar)"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"Check the model prediction"
]
},
{
"cell_type": "code",
"execution_count": 6,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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\n",
"text/plain": [
"<Figure size 432x288 with 4 Axes>"
]
},
"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",
"plt.subplot(2, 2, 3)\n",
"plt.plot(np.degrees(x_bar[3, :]))\n",
"plt.ylabel(\"psi(t) [deg]\")\n",
"# plt.xlabel('time')\n",
"\n",
"plt.subplot(2, 2, 4)\n",
"plt.plot(x_bar[4, :])\n",
"plt.ylabel(\"cte(t)\")\n",
"\n",
"plt.tight_layout()\n",
"plt.show()"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"the results seems valid:\n",
"* the cte is correct\n",
"* theta error is correct"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"Motion Prediction: using the state space model"
]
},
{
"cell_type": "code",
"execution_count": 7,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"CPU times: user 4.24 ms, sys: 0 ns, total: 4.24 ms\n",
"Wall time: 4.74 ms\n"
]
}
],
"source": [
"%%time\n",
"\n",
"u_bar = np.zeros((M, T))\n",
"u_bar[0, :] = 1 # m/s\n",
"u_bar[1, :] = np.radians(-10) # rad/s\n",
"\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0\n",
"x0[1] = 1\n",
"x0[2] = np.radians(0)\n",
"x0[3] = 0\n",
"x0[4] = 1\n",
"\n",
"x_bar = np.zeros((N, T + 1))\n",
"x_bar[:, 0] = x0\n",
"\n",
"for t in range(1, T + 1):\n",
" xt = x_bar[:, t - 1].reshape(5, 1)\n",
" ut = u_bar[:, t - 1].reshape(2, 1)\n",
"\n",
" A, B, C = get_linear_model(xt, ut)\n",
"\n",
" xt_plus_one = np.dot(A, xt) + np.dot(B, ut) + C\n",
"\n",
" x_bar[:, t] = np.squeeze(xt_plus_one)"
]
},
{
"cell_type": "code",
"execution_count": 8,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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\n",
"text/plain": [
"<Figure size 432x288 with 4 Axes>"
]
},
"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(x_bar[2, :])\n",
"plt.ylabel(\"theta(t)\")\n",
"# plt.xlabel('time')\n",
"\n",
"plt.subplot(2, 2, 3)\n",
"plt.plot(x_bar[3, :])\n",
"plt.ylabel(\"psi(t)\")\n",
"# plt.xlabel('time')\n",
"\n",
"plt.subplot(2, 2, 4)\n",
"plt.plot(x_bar[4, :])\n",
"plt.ylabel(\"cte(t)\")\n",
"\n",
"plt.tight_layout()\n",
"plt.show()"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"The results are the same as expected"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"------------------\n",
"\n",
"the kinematics model predictits psi and cte for constant heading references. So, for non-constant paths appropriate functions have to be developed.\n",
"\n",
"-----------------"
]
},
{
"cell_type": "code",
"execution_count": 9,
"metadata": {},
"outputs": [],
"source": [
"def calc_err(state, path):\n",
" \"\"\"\n",
" Finds psi and cte w.r.t. the closest waypoint.\n",
"\n",
" :param state: array_like, state of the vehicle [x_pos, y_pos, theta]\n",
" :param path: array_like, reference path ((x1, x2, ...), (y1, y2, ...), (th1 ,th2, ...)]\n",
" :returns: (float,float)\n",
" \"\"\"\n",
"\n",
" dx = state[0] - path[0, :]\n",
" dy = state[1] - path[1, :]\n",
" dist = np.sqrt(dx**2 + dy**2)\n",
" nn_idx = np.argmin(dist)\n",
"\n",
" try:\n",
" v = [\n",
" path[0, nn_idx + 1] - path[0, nn_idx],\n",
" path[1, nn_idx + 1] - path[1, nn_idx],\n",
" ]\n",
" v /= np.linalg.norm(v)\n",
"\n",
" d = [path[0, nn_idx] - state[0], path[1, nn_idx] - state[1]]\n",
"\n",
" if np.dot(d, v) > 0:\n",
" target_idx = nn_idx\n",
" else:\n",
" target_idx = nn_idx + 1\n",
"\n",
" except IndexError as e:\n",
" target_idx = nn_idx\n",
"\n",
" # front_axle_vect = [np.cos(state[2] - np.pi / 2),\n",
" # np.sin(state[2] - np.pi / 2)]\n",
" path_ref_vect = [\n",
" np.cos(path[2, target_idx] + np.pi / 2),\n",
" np.sin(path[2, target_idx] + np.pi / 2),\n",
" ]\n",
"\n",
" # heading error w.r.t path frame\n",
" psi = path[2, target_idx] - state[2]\n",
" # psi = -path[2,target_idx] + state[2]\n",
"\n",
" # the cross-track error is given by the scalar projection of the car->wp vector onto the faxle versor\n",
" # cte = np.dot([dx[target_idx], dy[target_idx]],front_axle_vect)\n",
" cte = np.dot([dx[target_idx], dy[target_idx]], path_ref_vect)\n",
"\n",
" return target_idx, psi, cte\n",
"\n",
"\n",
"def compute_path_from_wp(start_xp, start_yp, step=0.1):\n",
" \"\"\"\n",
" Interpolation range is computed to assure one point every fixed distance step [m].\n",
"\n",
" :param start_xp: array_like, list of starting x coordinates\n",
" :param start_yp: array_like, list of starting y coordinates\n",
" :param step: float, interpolation distance [m] between consecutive waypoints\n",
" :returns: array_like, of shape (3,N)\n",
" \"\"\"\n",
"\n",
" final_xp = []\n",
" final_yp = []\n",
" delta = step # [m]\n",
"\n",
" for idx in range(len(start_xp) - 1):\n",
" section_len = np.sum(\n",
" np.sqrt(\n",
" np.power(np.diff(start_xp[idx : idx + 2]), 2)\n",
" + np.power(np.diff(start_yp[idx : idx + 2]), 2)\n",
" )\n",
" )\n",
"\n",
" interp_range = np.linspace(0, 1, int(section_len / delta))\n",
"\n",
" fx = interp1d(np.linspace(0, 1, 2), start_xp[idx : idx + 2], kind=1)\n",
" fy = interp1d(np.linspace(0, 1, 2), start_yp[idx : idx + 2], kind=1)\n",
"\n",
" final_xp = np.append(final_xp, fx(interp_range))\n",
" final_yp = np.append(final_yp, fy(interp_range))\n",
"\n",
" dx = np.append(0, np.diff(final_xp))\n",
" dy = np.append(0, np.diff(final_yp))\n",
" theta = np.arctan2(dy, dx)\n",
"\n",
" return np.vstack((final_xp, final_yp, theta))"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"test it"
]
},
{
"cell_type": "code",
"execution_count": 10,
"metadata": {},
"outputs": [],
"source": [
"track = compute_path_from_wp([0, 5], [0, 0])\n",
"\n",
"u_bar = np.zeros((M, T))\n",
"u_bar[0, :] = 1 # m/s\n",
"u_bar[1, :] = np.radians(-10) # rad/s\n",
"\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0\n",
"x0[1] = 1\n",
"x0[2] = np.radians(0)\n",
"_, psi, cte = calc_err(x0, track)\n",
"x0[3] = psi\n",
"x0[4] = cte\n",
"\n",
"x_bar = np.zeros((N, T + 1))\n",
"x_bar[:, 0] = x0\n",
"\n",
"for t in range(1, T + 1):\n",
" xt = x_bar[:, t - 1].reshape(5, 1)\n",
" ut = u_bar[:, t - 1].reshape(2, 1)\n",
"\n",
" A, B, C = get_linear_model(xt, ut)\n",
"\n",
" xt_plus_one = np.squeeze(np.dot(A, xt) + np.dot(B, ut) + C)\n",
"\n",
" _, psi, cte = calc_err(xt_plus_one, track)\n",
" xt_plus_one[3] = psi\n",
" xt_plus_one[4] = cte\n",
"\n",
" x_bar[:, t] = xt_plus_one"
]
},
{
"cell_type": "code",
"execution_count": 11,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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\n",
"text/plain": [
"<Figure size 432x288 with 4 Axes>"
]
},
"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(track[0, :], track[1, :], \"b-\")\n",
"plt.axis(\"equal\")\n",
"plt.ylabel(\"y\")\n",
"plt.xlabel(\"x\")\n",
"\n",
"plt.subplot(2, 2, 2)\n",
"plt.plot(x_bar[2, :])\n",
"plt.ylabel(\"theta(t)\")\n",
"# plt.xlabel('time')\n",
"\n",
"plt.subplot(2, 2, 3)\n",
"plt.plot(x_bar[3, :])\n",
"plt.ylabel(\"psi(t)\")\n",
"# plt.xlabel('time')\n",
"\n",
"plt.subplot(2, 2, 4)\n",
"plt.plot(x_bar[4, :])\n",
"plt.ylabel(\"cte(t)\")\n",
"\n",
"plt.tight_layout()\n",
"plt.show()"
]
},
{
"cell_type": "code",
"execution_count": 12,
"metadata": {},
"outputs": [],
"source": [
"track = compute_path_from_wp([0, 2, 4, 5, 10], [0, 0, 3, 1, 1])\n",
"\n",
"u_bar = np.zeros((M, T))\n",
"u_bar[0, :] = 1 # m/s\n",
"u_bar[1, :] = np.radians(10) # rad/s\n",
"\n",
"x0 = np.zeros(N)\n",
"x0[0] = 2\n",
"x0[1] = 2\n",
"x0[2] = np.radians(0)\n",
"_, psi, cte = calc_err(x0, track)\n",
"x0[3] = psi\n",
"x0[4] = cte\n",
"\n",
"x_bar = np.zeros((N, T + 1))\n",
"x_bar[:, 0] = x0\n",
"\n",
"for t in range(1, T + 1):\n",
" xt = x_bar[:, t - 1].reshape(5, 1)\n",
" ut = u_bar[:, t - 1].reshape(2, 1)\n",
"\n",
" A, B, C = get_linear_model(xt, ut)\n",
"\n",
" xt_plus_one = np.squeeze(np.dot(A, xt) + np.dot(B, ut) + C)\n",
"\n",
" _, psi, cte = calc_err(xt_plus_one, track)\n",
" xt_plus_one[3] = psi\n",
" xt_plus_one[4] = cte\n",
"\n",
" x_bar[:, t] = xt_plus_one"
]
},
{
"cell_type": "code",
"execution_count": 13,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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\n",
"text/plain": [
"<Figure size 432x288 with 4 Axes>"
]
},
"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(track[0, :], track[1, :], \"b-\")\n",
"plt.axis(\"equal\")\n",
"plt.ylabel(\"y\")\n",
"plt.xlabel(\"x\")\n",
"\n",
"plt.subplot(2, 2, 2)\n",
"plt.plot(x_bar[2, :])\n",
"plt.ylabel(\"theta(t)\")\n",
"# plt.xlabel('time')\n",
"\n",
"plt.subplot(2, 2, 3)\n",
"plt.plot(x_bar[3, :])\n",
"plt.ylabel(\"psi(t)\")\n",
"# plt.xlabel('time')\n",
"\n",
"plt.subplot(2, 2, 4)\n",
"plt.plot(x_bar[4, :])\n",
"plt.ylabel(\"cte(t)\")\n",
"\n",
"plt.tight_layout()\n",
"plt.show()"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"### MPC Problem formulation\n",
"\n",
"**Model Predictive Control** refers to the control approach of **numerically** solving a optimization problem at each time step. \n",
"\n",
"The controller generates a control signal over a fixed lenght T (Horizon) at each time step."
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"![mpc](img/mpc_block_diagram.png)\n",
"\n",
"![mpc](img/mpc_t.png)"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"#### Linear MPC Formulation\n",
"\n",
"Linear MPC makes use of the **LTI** (Linear time invariant) discrete state space model, wich represents a motion model used for Prediction.\n",
"\n",
"$x_{t+1} = Ax_t + Bu_t$\n",
"\n",
"The LTI formulation means that **future states** are linearly related to the current state and actuator signal. Hence, the MPC seeks to find a **control policy** U over a finite lenght horizon.\n",
"\n",
"$U={u_{t|t}, u_{t+1|t}, ...,u_{t+T|t}}$\n",
"\n",
"The objective function used minimize (drive the state to 0) is:\n",
"\n",
"$\n",
"\\begin{equation}\n",
"\\begin{aligned}\n",
"\\min_{} \\quad & \\sum^{t+T-1}_{j=t} x^T_{j|t}Qx_{j|t} + u^T_{j|t}Ru_{j|t}\\\\\n",
"\\textrm{s.t.} \\quad & x(0) = x0\\\\\n",
" & x_{j+1|t} = Ax_{j|t}+Bu_{j|t}) \\quad \\textrm{for} \\quad t<j<t+T-1 \\\\\n",
"\\end{aligned}\n",
"\\end{equation}\n",
"$\n",
"\n",
"Other linear constrains may be applied,for instance on the control variable:\n",
"\n",
"$ U_{MIN} < u_{j|t} < U_{MAX} \\quad \\textrm{for} \\quad t<j<t+T-1 $\n",
"\n",
"The objective fuction accounts for quadratic error on deviation from 0 of the state and the control inputs sequences. Q and R are the **weight matrices** and are used to tune the response.\n",
"\n",
"Because the goal is tracking a **reference signal** such as a trajectory, the objective function is rewritten as:\n",
"\n",
"$\n",
"\\begin{equation}\n",
"\\begin{aligned}\n",
"\\min_{} \\quad & \\sum^{t+T-1}_{j=t} \\delta x^T_{j|t}Q\\delta x_{j|t} + u^T_{j|t}Ru_{j|t}\n",
"\\end{aligned}\n",
"\\end{equation}\n",
"$\n",
"\n",
"where the error w.r.t desired state is accounted for:\n",
"\n",
"$ \\delta x = x_{j,t,ref} - x_{j,t} $\n",
"\n",
"#### Non-Linear MPC Formulation\n",
"\n",
"In general cases, the objective function is any non-differentiable non-linear function of states and inputs over a finite horizon T. In this case the constrains include nonlinear dynamics of motion.\n",
"\n",
"$\n",
"\\begin{equation}\n",
"\\begin{aligned}\n",
"\\min_{} \\quad & \\sum^{t+T}_{j=t} C(x_{j|t},{j|t})\\\\\n",
"\\textrm{s.t.} \\quad & x(0) = x0\\\\\n",
" & x_{j+1|t} = f(x_{j|t},u_{j|t}) \\quad \\textrm{for} \\quad t<j<t+T-1 \\\\\n",
"\\end{aligned}\n",
"\\end{equation}\n",
"$\n",
"\n",
"Other nonlinear constrains may be applied:\n",
"\n",
"$ g(x_{j|t},{j|t})<0 \\quad \\textrm{for} \\quad t<j<t+T-1 $"
]
},
{
"cell_type": "code",
"execution_count": 17,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"CPU times: user 109 ms, sys: 81 µs, total: 109 ms\n",
"Wall time: 108 ms\n"
]
}
],
"source": [
"%%time\n",
"\n",
"track = compute_path_from_wp([0, 10], [0, 0])\n",
"\n",
"MAX_SPEED = 2.5\n",
"MIN_SPEED = 0.5\n",
"MAX_STEER_SPEED = 1.57 / 2\n",
"\n",
"# starting guess\n",
"u_bar = np.zeros((M, T))\n",
"u_bar[0, :] = 0.5 * (MAX_SPEED + MIN_SPEED)\n",
"u_bar[1, :] = 0.01\n",
"\n",
"# Starting Condition\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0\n",
"x0[1] = 1\n",
"x0[2] = np.radians(-0)\n",
"_, psi, cte = calc_err(x0, track)\n",
"x0[3] = psi\n",
"x0[4] = cte\n",
"\n",
"# Linearized Model Prediction\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].reshape(5, 1)\n",
" ut = u_bar[:, t - 1].reshape(2, 1)\n",
"\n",
" A, B, C = get_linear_model(xt, ut)\n",
"\n",
" xt_plus_one = np.squeeze(np.dot(A, xt) + np.dot(B, ut) + C)\n",
"\n",
" _, psi, cte = calc_err(xt_plus_one, track)\n",
" xt_plus_one[3] = psi\n",
" xt_plus_one[4] = cte\n",
" x_bar[:, t] = xt_plus_one\n",
"\n",
"\n",
"# CVXPY Linear MPC problem statement\n",
"cost = 0\n",
"constr = []\n",
"\n",
"for t in range(T):\n",
"\n",
" # Tracking\n",
" if t > 0:\n",
" idx, _, _ = calc_err(x_bar[:, t], track)\n",
" delta_x = track[:, idx] - x[0:3, t]\n",
" cost += cp.quad_form(delta_x, 10 * np.eye(3))\n",
"\n",
" # Tracking last time step\n",
" if t == T:\n",
" idx, _, _ = calc_err(x_bar[:, t], track)\n",
" delta_x = track[:, idx] - x[0:3, t]\n",
" cost += cp.quad_form(delta_x, 100 * np.eye(3))\n",
"\n",
" # Actuation rate of change\n",
" if t < (T - 1):\n",
" cost += cp.quad_form(u[:, t + 1] - u[:, t], 25 * np.eye(M))\n",
"\n",
" # constrains\n",
" A, B, C = get_linear_model(x_bar[:, t], u_bar[:, t])\n",
" constr += [x[:, t + 1] == A @ x[:, t] + B @ u[:, t] + C.flatten()]\n",
"\n",
"# sums problem objectives and concatenates constraints.\n",
"constr += [x[:, 0] == x0]\n",
"constr += [u[0, :] <= MAX_SPEED]\n",
"constr += [u[0, :] >= MIN_SPEED]\n",
"constr += [cp.abs(u[1, :]) <= MAX_STEER_SPEED]\n",
"\n",
"\n",
"prob = cp.Problem(cp.Minimize(cost), constr)\n",
"solution = prob.solve(solver=cp.OSQP, verbose=False)"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"Print Results:"
]
},
{
"cell_type": "code",
"execution_count": 18,
"metadata": {},
"outputs": [
{
"name": "stderr",
"output_type": "stream",
"text": [
"No handles with labels found to put in legend.\n"
]
},
{
"data": {
"image/png": "iVBORw0KGgoAAAANSUhEUgAABDAAAALICAYAAACJhQBYAAAABHNCSVQICAgIfAhkiAAAAAlwSFlzAAALEgAACxIB0t1+/AAAADh0RVh0U29mdHdhcmUAbWF0cGxvdGxpYiB2ZXJzaW9uMy4yLjIsIGh0dHA6Ly9tYXRwbG90bGliLm9yZy+WH4yJAAAgAElEQVR4nOzdd3hUVeLG8ffcTAohEMqAGAggRQ0q0quohKC/BRVkd7Fig1UUe+8FIQYx4rqKBSwsLiIqthVFE1x0UYiYiCKKwsoiAYUQSiAJJLnn90fWWAAFMpM75ft5Hh4yNzPnvucMD0xebjHWWisAAAAAAIAQ5ngdAAAAAAAA4PdQYAAAAAAAgJBHgQEAAAAAAEIeBQYAAAAAAAh5FBgAAAAAACDkUWAAAAAAAICQ5/M6AAAAQDiYOnWq8vPzlZycrOzs7FqNtXz5cs2YMaPm8fr163XVVVepV69e+z3GqlWrdNttt+maa65Rnz599rqPmTNnqrKyUocddpguvfRSxcTEaMeOHXrsscf0ww8/KDY2Vpdeeqlat24tSZo3b55yc3NlrdWgQYM0dOhQSdKaNWs0bdo0lZeXq1mzZrryyiuVmJhYqzV4++239eabb+qHH37Q9OnT1bBhw1qNBwCIfByBAQAAsB9OPPFE3XrrrQEZ6+ijj9bkyZM1efJk3XXXXYqLi9Oxxx67x/PGjRu319e7rqt//OMf6tKlyz6//+ijj+qqq65Sdna2mjVrpoULF0qSXnnlFbVt21YPPPCALr/8cj377LOSpLVr1yo3N1eZmZmaPHmy8vPztWHDBknSE088oXPOOUfZ2dnq1auXXn/99VqvwRFHHKE77rhDzZo1q/VYAIDoQIEBAACwHzp16qSkpKRfbPv+++81ceJE3XTTTbrzzjtVWFh4wOMuXrxYXbt2VXx8/H6/5q233lLv3r33edTCjh075PP5lJKSIknq3LmzlixZIklat26djjnmGElSy5YttWnTJm3dulWFhYXq2LGj4uPjFRMTo7S0NOXl5UmqPkIkLS1tj7Fc19XMmTN1yy236Prrr9e7776733M47LDD1Lx58/1+PgAAFBgAAAAH6cknn9RFF12kSZMmadSoUZo+ffoBj7Fo0SL1799/v59fXFysvLw8nXTSSft8ToMGDVRVVaXVq1dLqi5JioqKJElt2rSpKSBWrVqlTZs2qbi4WKmpqfryyy9VUlKiXbt2qaCgQJs3b5YkpaamaunSpTVj/bh9wYIFSkxM1H333af77rtPubm52rhx4wGvAQAA+4NrYAAAAByE8vJyrVy5Ug8++GDNtsrKSknSkiVLNGfOnD1e06RJE9122201j7ds2aK1a9f+4vSR6dOna+XKlZKqy4obbrhBktS3b1+NGDFCzz77rM455xw5zr7/H8oYo6uvvlozZsxQRUWFjj32WMXExEiShg8frmeffVY33HCDWrdurcMOO0yO46hVq1YaNmyYJkyYoISEBLVp06ZmH5deeqmeeeYZvfTSS+rRo4d8vuqPkMuWLdPatWu1ePFiSVJpaak2bNggv99fk/vXLr30UnXo0OF3VhcAgD1RYAAAABwE13VVv359TZ48eY/v9e7dW7179/7dMT766CP16tWrphCQpDFjxtR8PW7cuD3GX716tf76179KkrZv366CggI5jrPHBUAPP/xwjR8/XlJ10bB+/XpJUmJioi677DJJkrVWl19+ec2pHOnp6UpPT5ckzZo1S02bNpVUfarJ7bffLqn6dJL8/Pya11944YV7vRZHbS90CgDAr3EKCQAAwEFITExU8+bN9dFHH0mq/mF+zZo1BzTGgZ4+IkmPPvpoza8+ffpozJgxe717ybZt2yRJFRUVeu2112pOOdm5c2fNkSK5ublKS0uruaPIj68pKipSXl5eTbYft7uuq7lz52rw4MGSpC5duuidd96pGW/9+vUqLy8/oPkAALC/OAIDAABgPzz00ENasWKFSkpKNHbsWI0cOVJXXnmlpk2bprlz56qyslL9+/dX27Zt92u8jRs3qqioSJ06dQpYxvvuu0+XXHKJmjRpotdff135+flyXVcnnXSSjj76aElSYWGhHnnkkZrTRsaOHVvz+uzsbJWUlMjn82n06NE1Fy1dtGiR5s+fL0nq1auXBg4cKKn6iI2NGzfqpptukiQ1bNhwn6eO/Nq8efP0+uuva+vWrbrhhhvUtWvXX2QBAODXjLXWeh0CAAAAAADgt3AKCQAAAAAACHlhWWC4rqsbb7xRWVlZXkcBAAAAAAB1ICyvgTFv3jy1bNlSZWVl+/X8H6+6HQh+v7/mPuoILNY2uFjf4GFtg4v1Da5Ar29KSkrAxgo1gfw8IUXHn+1omKMUHfNkjpGBOUaOSJ/nvj5PhN0RGJs3b1Z+fr4GDRrkdRQAAAAAAFBHwq7AePbZZ3XuuefKGON1FAAAAAAAUEfC6hSSTz75RMnJyWrXrp2++OKLfT4vJydHOTk5kqSsrCz5/f6AZfD5fAEdDz9hbYOL9Q0e1ja4WN/gYn0BAEC4CKsCY+XKlVq6dKkKCgq0e/dulZWV6eGHH9aVV175i+dlZGQoIyOj5nEgzw2K9HONvMTaBhfrGzysbXCxvsHFNTAAAEC4CKsC4+yzz9bZZ58tSfriiy/0xhtv7FFeAAAAAACAyBN218AAAAAAAADRJ6yOwPi5o446SkcddZTXMQAAAAAAQB3gCAwAAAAAABDyKDAAAAAAAEDIo8AAAAAAAAAhjwIDAAAAAACEPAoMAAAAAABwQGzhWtmKijrdJwUGAAAAAADYb7a8TO5Dd8mdnl2n+6XAAAAAAAAA+83Oe1HaulnO4NPqdL8UGAAAAAAAYL/Yjetl331Vps+JMh061em+KTAAAAAAAMB+cec8LcXEyvzx/DrfNwUGAAAAAAD4XfbzT6RleTKnjJRp1LTO90+BAQAAAAAAfpOtrJA7e5rUPEVmUN1e++JHFBgAAAAAAOA32dw3pI3r5Zz5F5nYWE8y+DzZKwAAQIBMnTpV+fn5Sk5OVnZ29e3cduzYoSlTpmjTpk1q1qyZrrnmGiUlJUmSXnnlFS1YsECO4+jCCy9Uly5dvIwPAEDIs1s3y77xgtS5p8wx3T3LwREYAAAgrJ144om69dZbf7Ht1Vdf1THHHKOHH35YxxxzjF599VVJ0rp16/Thhx/qwQcf1G233aannnpKrut6ERsAgLBhX/67VFUh54zRnuagwAAAAGGtU6dONUdX/Ojjjz/WCSecIEk64YQT9PHHH9ds79evn2JjY9W8eXO1aNFCq1atqvPMAACEC7vqS9nF78kMHi7TPMXTLJxCAgAAIs62bdvUuHFjSVLjxo21fft2SVJxcbE6duxY87wmTZqouLh4r2Pk5OQoJydHkpSVlSW/3x/QjD6fL+BjhppomKMUHfNkjpGBOUaOupqnrapS8YtPS038ajpqrJx6iUHf52+hwAAAAFHDWrvfz83IyFBGRkbN46KiooBm8fv9AR8z1ETDHKXomCdzjAzMMXLU1Tzd9+fL/melzJjrVLyzVNpZGvR9SlJKyt6P9OAUEgAAEHGSk5O1ZcsWSdKWLVvUsGFDSVLTpk21efPmmucVFxerSZMmnmQEACCU2Z07ZF+ZKXXoJNPreK/jSKLAAAAAEahHjx5auHChJGnhwoXq2bNnzfYPP/xQFRUV2rhxozZs2KAOHTp4GRUAgJBk33he2rlDzlkXyxjjdRxJnEICAADC3EMPPaQVK1aopKREY8eO1ciRIzV8+HBNmTJFCxYskN/v17XXXitJSk1NVd++fXXttdfKcRyNHj1ajsP/5wAA8HO28L+y770pc/xJMq3beR2nBgUGAAAIa1dfffVet99555173T5ixAiNGDEimJEAAAhb1lq5zz8pJSTKDD/X6zi/wH85AAAAAACAavkfSis/lxl+rkxSQ6/T/AIFBgAAAAAAkN21S+6cp6VWbWWOP9nrOHugwAAAAAAAALJvvywVb6q+cGdMjNdx9kCBAQAAAABAlLObvpd9+2WZngNkDj/a6zh7RYEBAAAAAECUc198WnIcmT9d6HWUfaLAAAAAAAAgitkVBVLBYpkhf5Zp4vc6zj5RYAAAAAAAEKVsZaXc2dOlZi1kThrudZzfRIEBAAAAAECUsu+9KW34Ts7I0TKxcV7H+U0UGAAAAAAARCG7fYvsG89LR3eTju3ldZzfRYEBAAAAAEAUsnNnSrt3yTljjIwxXsf5XRQYAAAAAABEGfvt17KLcmQGnSbTopXXcfYLBQYAAAAAAFHEuq7c55+UkhvLnHKG13H2GwUGAAAAAABRxH70nvTt1zIjzpepl+h1nP1GgQEAAAAAQJSwpTtl586Q2h0h0+dEr+McEJ/XAQ7E7t27ddddd6myslJVVVXq06ePRo4c6XUsAAAAAADCgv3nbKlkm5wr7pBxwuuYhrAqMGJjY3XXXXcpISFBlZWVuvPOO9WlSxcdfvjhXkcDAAAAACCk2Q3fyS74p8xxg2XadvQ6zgELq7rFGKOEhARJUlVVlaqqqsLiVi8AAAAAAHjJWit39nQpLkFm+LlexzkoYXUEhiS5rqubbrpJ33//vU4++WR17Lhna5STk6OcnBxJUlZWlvx+f8D27/P5AjoefsLaBhfrGzysbXCxvsHF+gIAECU+XSKtKJA58y8yDRt5neaghF2B4TiOJk+erJ07d+qBBx7Q2rVr1bp16188JyMjQxkZGTWPi4qKArZ/v98f0PHwE9Y2uFjf4GFtg4v1Da5Ar29KSkrAxgIAAIFhd++S+8J0KaW1zAl/8DrOQQurU0h+rn79+urUqZM+/fRTr6MAAAAAABCy7DuvSps3yjnzLzK+sDuOoUZYFRjbt2/Xzp07JVXfkeTzzz9Xy5YtPU4FAAAAAEBosps3yb71otS9n0zasV7HqZWwql62bNmiRx99VK7rylqrvn37qnv37l7HAgAAAAAgJNmXnpGs5Pz5Iq+j1FpYFRht2rTR/fff73UMAAAAAABCnl35uezSf8ucepZM0+Zex6m1sCowAAAAAADAb7ObN8q++5rsB+9ITZvL/N8IryMFBAUGAAAAAAARwH73rez8ubIffyAZI9PrBJlTzpCJi/c6WkBQYAAAAAAAEKastdLKz+XOnystz5fi68kMOlUm4zSZJs28jhdQFBgAAAAAAIQZ61ZJBYvlvj1XWvON1CBZZvi5MicOkamf5HW8oKDAAAAAAAAgTNiK3Sp951W5Lz8nbVwvNT9U5tzLZPqly8TGeR0vqCgwAAAAAAAIcbZ0h+y/3pLNfUMl27dKbTrIGXuT1LWPjBPjdbw6QYEBAAAAAECIssVFsrmvyy6cL+0qk47qqsZnXKRtLVrLGON1vDpFgQEAAAAAQIix69fKzn9FdslCyboyPQbI/N8ImdTDFOf3yxQVeR2xzlFgAAAAAAAQIuw3K6rvKLIsT4qLkznh/2QGD5PxH+J1NM9RYAAAAAAA4CHrutJnedV3FFn9lZTUQObUs2QGDpVp0NDreCGDAgMAAAAAAI/YL5fJff5JacN3UtPmMmddLNN/sEx8vNfRQg4FBgAAiEjz5s1Tbm6urLUaNGiQhg4dqjVr1mjatGkqLy9Xs2bNdOWVVyoxMdHrqACAKGUL/yv30YlSo6YyY66T6XGcTEx03FHkYFBgAACAiLN27Vrl5uYqMzNTPp9PmZmZ6tatm5544gmNGjVKnTp10oIFC/T666/rzDPP9DouACAK2Z0l1eVFQj05102QadzU60ghz/E6AAAAQKAVFhaqY8eOio+PV0xMjNLS0pSXl6f169crLS1NktS5c2ctWbLE46QAgGhkq6rkPvmAVFwkZ+zNlBf7iSMwAABAxElNTdXs2bNVUlKiuLg4FRQUqH379kpNTdXSpUvVs2dPLV68WJs3b97nGDk5OcrJyZEkZWVlye/3BzSjz+cL+JihJhrmKEXHPJljZGCOoaNkxqMqXVGgBpfdrMQ+Aw749eEyz0CjwAAAABGnVatWGjZsmCZMmKCEhAS1adNGjuPo0ksv1TPPPKOXXnpJPXr0kM+3749CGRkZysjIqHlcVFQU0Ix+vz/gY4aaaJijFB3zZI6RgTmGBnfJQtlX/yFz4hCVdu2n0oPIGw7zrI2UlJS9bqfAAAAAESk9PV3p6emSpFmzZqlp06Zq2bKlbr/9dknS+vXrlZ+f72VEAECUsf9dLTvjb1LHTjJnjPY6TtjhGhgAACAibdu2TVL1kRN5eXnq379/zTbXdTV37lwNHjzYy4gAgChit2+VOzVTSmpYfd0LX6zXkcIOR2AAAICIlJ2drZKSEvl8Po0ePVpJSUmaN2+e5s+fL0nq1auXBg4c6HFKAEA0sJWVcp+YJJVsk3NTlkzDRl5HCksUGAAAICKNHz9+j21DhgzRkCFDPEgDAIhmds5T0tdfyIy+VqZNB6/jhC1OIQEAAAAAIEjcf78r+96bMicNl9PnRK/jhDUKDAAAAAAAgsCu/kr2H49JnbrIjDjf6zhhjwIDAAAAAIAAs1s3y30sS2rsl3PxDTIxMV5HCnsUGAAAAAAABJCtqKguL8pL5Vx2q0z9Bl5HiggUGAAAAAAABIi1VnbW49J/Vsq58GqZVm29jhQxKDAAAAAAAAgQ+6+3ZP/9rsyQkTLd+3kdJ6JQYAAAAAAAEAD26+WyL0yTOveUGXa213EiDgUGAAAAAAC1ZDdvkvv4JKlZCzmjr5Vx+HE70FhRAAAAAABqwe7aJXfqRKmyQs6422QS63sdKSJRYAAAAAAAcJCstbJ/f0T67ls5Y66TadHK60gRiwIDAAAAAICDZN99VTZvocywc2Q69/Q6TkSjwAAAAAAA4CDYLwpkX5ohde8nM+TPXseJeBQYAAAAAAAcILtxg9wnJ0spqXIuuErGGK8jRTwKDAAAAAAADoAtL5M7NVMypvqinQn1vI4UFSgwAAAAAADYT9Z15T7zkLT+OzkX3yDTrIXXkaKGz+sAB6KoqEiPPvqotm7dKmOMMjIyNGTIEK9jAQAAAACihJ33opT/kcyfL5Lp1MXrOFElrAqMmJgYjRo1Su3atVNZWZluvvlmde7cWa1acZsaAAAAAEBw2WV5sq/9Q6bPiTKDh3kdJ+qE1SkkjRs3Vrt27SRJ9erVU8uWLVVcXOxxKgAAAABApLMb1smdni216SAzahwX7fRAWB2B8XMbN27Ut99+qw4dOuzxvZycHOXk5EiSsrKy5Pf7A7Zfn88X0PHwE9Y2uFjf4GFtg4v1DS7WFwCA32dLd8h9dKIUGyfnsltk4uK9jhSVwrLAKC8vV3Z2ti644AIlJibu8f2MjAxlZGTUPC4qKgrYvv1+f0DHw09Y2+BifYOHtQ0u1je4Ar2+KSkpARsLAIBQYH9YL/ex+6Si7+VcO0GmSTOvI0WtsCswKisrlZ2drQEDBqh3795exwEAAAAARCj76WK5Tz8kxcTIufJOmcOP8jpSVAurAsNaq8cff1wtW7bUKaec4nUcAAAAAEAEsm6V7Guzqu840qaDnEtvlmna3OtYUS+sCoyVK1fq/fffV+vWrXXDDTdIks466yx169bN42QAAAAAgEhgS7bLnTZZ+nKZzICTZM66WCY2zutYUJgVGEceeaTmzJnjdQwAAAAAQASy334j9/EsaftWmfMulzPgJK8j4WfCqsAAAAAAACAY3Pfnyz7/hJTcRM7Nk2Ta7HnHS3iLAgMAAAAAELXs7l2ys56QXZQjHdVVzpjrZJIaeh0Le0GBAQAAAACISrboB7mPZUlrV8uccobMqWfKODFex8I+UGAAAAAAAKKOXZ4vd3q25LpyLr9d5theXkfC76DAAAAAAABEDeu6svNelH19ltSyTfUtUpuneB0L+4ECAwAAAAAQFWzpDrlPTZE++1im9wkyoy6XiY/3Ohb2EwUGAAAAACDi2XXfyp16n1S8SebsS2ROHCJjjNexcAAoMAAAAAAAEc1d/J7szEelxCQ512fKdEjzOhIOAgUGAAAAACAi2coK2TlPyb43Tzr8aDkX3yCT3NjrWDhIFBgAAAAAgIhjt2yW+8QkafVXMicNlxlxvkwMt0gNZxQYAAAgIs2bN0+5ubmy1mrQoEEaOnSo1qxZo2nTpmn37t2KiYnRmDFj1KFDB6+jAgACzK78XO4T90u7d8m55EaZHsd5HQkBQIEBAAAiztq1a5Wbm6vMzEz5fD5lZmaqW7dueu655/SnP/1JXbt2VX5+vp577jndfffdXscFAASItVbuO6/IvjxDan6onBsyZQ5N9ToWAoQCAwAARJzCwkJ17NhR8f+7NV5aWpry8vJkjFFZWZkkqbS0VI0bcx40AEQKW16mbZNvl/3oPalbPzkXXClTL9HrWAggCgwAABBxUlNTNXv2bJWUlCguLk4FBQVq3769zj//fE2cOFEzZ86U67qaMGHCPsfIyclRTk6OJCkrK0t+vz+gGX0+X8DHDDXRMEcpOubJHCNDJM/R3blDWx+4Vbu+WaGk88YpcfjZEX2L1Eh+L3+LsdZar0ME2/r16wM2lt/vV1FRUcDGw09Y2+BifYOHtQ0u1je4Ar2+KSkpARurthYsWKD58+crISFBLVu2VFxcnFzXVadOndSnTx99+OGHys3N1R133LFf4wXy84QUHX+2o2GOUnTMkzlGhkido92xXe5Dd0vr1ij5unu0o+MxXkcKukh9L3+0r88TTh3nAAAAqBPp6emaNGmS7rnnHiUlJenQQw/VwoUL1bt3b0lS3759tWrVKo9TAgBqw27fKveB26TC/8q57BYl9B3odSQEEQUGAACISNu2bZMkFRUVKS8vT/3791eTJk20YsUKSdLy5cvVokULLyMCAGrBbt0sd/Kt0qYNcq64Q6ZzT68jIci4BgYAAIhI2dnZKikpkc/n0+jRo5WUlKRLLrlEzzzzjFzXVWxsrC655BKvYwIADoLdvFFu9u3S9m1yrrpb5vCjvY6EOkCBAQAAItL48eP32HbkkUdq0qRJHqQBAASK3bihurwoK5VzzT0y7Y/0OhLqCAUGAAAAACAs2A3r5D54u1RZIee6CTJt2nsdCXWIAgMAAAAAEPLsujVyH7xDMkbO9ZkyLdt4HQl1jIt4AgAAAABCmv3vquq7jcT45NxAeRGtOAIDAAAAABCy7Oqv5P71HimxfvVpI824g1S0osAAAAAAAIQku3K53L+Nl5IbV5cXTZp5HQkeosAAAAAAAIQc+0WB3KkTpaaHyLn2XplGTbyOBI9RYAAAAAAAQopdlif38SypRaqca8fLNEj2OhJCAAUGAAAAACBk2E8WyZ32gJTaTs7Vd8vUb+B1JIQICgwAAAAAQEhwF78n+/RfpfZHyLnyLpl6iV5HQgihwAAAAAAAeM794B3ZmY9Khx8t5/LbZRLqeR0JIYYCAwAAAADgKXfBP2Wff1I6upucS2+RiYv3OhJCEAUGAAAAAMAz7vy5si89K3XpLefiG2ViY72OhBBFgQEAAAAAqHPWWtk3X5B9bZZMzwEyF10j4+NHVOwbfzoAAAAAAHXKWiv7ykzZt16S6Zsuc8EVMk6M17EQ4igwAAAAAAB1xlor+8J02dw3ZE74P5mzx8o4jtexEAYoMAAAAAAAdcK6ruysx2UXvi2TcZrMyNEyxngdC2EirAqMqVOnKj8/X8nJycrOzvY6DgAAAABgP9ldu+Q+lS0VLJb5w59kTh9FeYEDElbH6Zx44om69dZbvY4BAAAAADgAdmux3Mm3SJ8ukTljDOUFDkpYHYHRqVMnbdy40ZN921275N5zhYqb+FVVL0mmYSPpf79M80Ol9kfKJNTzJBsAAAAAhCq77lu5f7tX2rlDzrjbZI7t5XUkhKmwKjD2V05OjnJyciRJWVlZ8vv9tR7T3bFdJWmdZbdtka94o6r+85VsyTbJWllJiolRbIc0xR3dTbHHdFfckcfIxCfUer/RxOfzBeS9wt6xvsHD2gYX6xtcrC8AIJjs55/IffJ+KaGenBvvk2nd3utICGMRWWBkZGQoIyOj5nFRUVFgBh51ufx+v4qKiuRIslVVUslWqXCt7MrPVbHyc1W88pz08t8lX6xMl94yfQdKnbpyP+P98OPaIjhY3+BhbYOL9Q2uQK9vSkpKwMYCAIQ39703ZZ+fJqW2lXP5HTKNm3odCWGOn6prwcTESI2aSo2ayhzVVZJky0ulb76U/Xyp7Mfvyy79t9QgWab3CTJ9B9I4AgAAAIho1q2SnfO0bO4b0rG95Iy5jtPtERAUGAFmEhKlY7rLHNNdduRF0vJ8uR+9J/uvebI5r0ttO8oMHCLTc4BMbJzXcQEAAAAgYGx5mdzp2dKyvOrbpP75QhknxutYiBBhVWA89NBDWrFihUpKSjR27FiNHDlS6enpXsfaJ+OLlbr0VkyX3rI7S2SXLJT911uyz/xV9sWnZY47SeaE/5PxH+J1VAAAAACoFVtcJPeRe6V1/5U5e6ycgUO8joQIE1YFxtVXX+11hINm6jeQST9FduBQ6avP5P5rnuw7r8jOnysd00POiUOko7rKOGF1Z1sAAAAAkF27uvpOI2Vlcq64Q+aY7l5HQgQKqwIjEhhjpLRjFZN2rGxxkez7b8t+8I7ch++R/IdUH5HRf7BMg4ZeRwUAAACA32WX5cmd9oBUP0nOzVkyrQ7zOhIiFAWGh0wTv8zwc2VPOUO2YEn1dTJeniH72j+qL3bTN106qht3MAEAAAAQcqy1srmvy855WmrdXs7lt8s0auJ1LEQwfjIOAcYXK9PzOKnncbKFa2U/mC+7ZKHcTz6UkhpWX/Cz78DqC4Aa43VcAAAAAFHOVlXJzp4m+695Utc+ckZfJxMf73UsRDgKjBBjWraWOfMvsn+6UPqiQHbxe7IfvCP73ptSk2YynXvKdO4pHXG0TBx/QQAAAACoW7asVO6T90vL82VOPl1mxPlcyw91ggIjRBmfTzq2p8yxPWVLd8rmfyi7LE/2w9zqljMuTkrrItOpi0z7NKlVW5kYbk8EAAAAIHjs5k1y/zZe2vCdzKhxco4/2etIiCIUGGHAJNaXOW6wdNxg2Yrd0srlsp99XP1rWZ6sJMXFV86W3YAAACAASURBVJ9i0v4ImcOOkFJaV18UlFIDAAAAQADYb7+pvk1qxW45V90l06mr15EQZSgwwoyJjZOO7iZzdDfZsy6WijfJrv5K+s9K2dVfyb7zqmxVVfWTY3xS80OlFi1lWrSUmjSvvqhOchMpubHUsBEXCAUAAADwu2z+h3KfelBq0EjOdRNkUlp7HQlRiJ9ew5gxRmraXKZpc6nX8ZIku3uXtG6N7PfrpO/XyW4olDask/3sY6mqqvpojZ8GkOonSfXqSwn1qn+vlyiTUE+KjZN8vuoSxOeTYmKlGEeSqX6d0U9fWyu5bvXv1v3psVv1v99/9nVVVfXXVdXb7I/fq6rSFl+MqsrLf3qedX/5+l/vx7U/PUf6aZusZK3MEcfI+cv1dfqeAAAAAJHEWiv7ziuyL8+Q2naUc/ltMg0bex0LUYoCI8KYuHip3REy7Y74xXZbVSVt3yptK5a2Fstu21L9dck2qaxUtrxMKttZfURHeZlUUSFVVUqVlVJVRfXvPxYFvxnAkZz/FRtOjOQ4P/vdqS5Ear6O+cVz3Pj46n3UfC/2l683RnIcGeP89NiY6n0aU71fVT9HktSyTeAXGAAQFOXl5dq5c6fq16+vhIQEr+MAACTZykrZWY/LfvCOTPf+MhddzY0E4CkKjChhYmKkxk2rf+l/B1AcIGurj2yoPsJBP339vwKhtlcebur3q6ioqFZjAADCx9q1a5WTk6P8/Hxt2rSpZnvz5s3VpUsXDR48WK1bH/whyvPmzVNubq6stRo0aJCGDh2qKVOmaP369ZKk0tJSJSYmavLkybWeCwBEGlu6Q+7jk6Qvl8kM+bPMsHO40wg8R4GB/WZ+POIBAIBaeuihh7Ru3Tr169dPV1xxhVq2bKl69eqprKxMhYWFWrFihR5++GG1atVKV1999QGPv3btWuXm5iozM1M+n0+ZmZnq1q2brrnmmprn/P3vf1diYmIgpwUAEcFu+l7u3+6VNq6XueBKOf0zvI4ESKLAAAAAHjjuuOPUo0ePPbYnJSXpiCOO0BFHHKHTTz9dn3zyyUGNX1hYqI4dOyo+vvpQ57S0NOXl5WnYsGGSqo8q/Oijj3TnnXce/CQAIALZb1bInZopua6cq++RObKz15GAGhQYAACgzv28vPjmm2/UsWPHPZ6zatUqde/e/aDGT01N1ezZs1VSUqK4uDgVFBSoffv2Nd//8ssvlZycrEMPPXSfY+Tk5CgnJ0eSlJWVJb/ff1BZ9sXn8wV8zFATDXOUomOezDEy/N4cy957S9unZimmWQs1um2yfC3D704j0fA+StEzz1+jwAAAAJ6aMGGCZsyYscf2iRMn6plnnjmoMVu1aqVhw4ZpwoQJSkhIUJs2beT87NztRYsWqX///r85RkZGhjIyfjpsOtDXafJHwbWfomGOUnTMkzlGhn3N0bqu7KszZd96WTqys+zYm7Q1PlEKw/WIhvdRivx5pqSk7HV7QAuMGTNm6IQTTlDbtm0DOSwAAIhA7v/ubmWtrfn1ox9++EExMTG1Gj89PV3p6emSpFmzZqlp0+oLWVdVVSkvL09ZWVm1Gh8AIoHdVS73qQelgsUyx58sc9YlMj7+nxuhKaB/MquqqjRx4kQ1bNhQAwYM0IABA2o+LAAAAPzcWWedVfP1mWee+YvvOY6j008/vVbjb9u2TcnJySoqKlJeXp4mTJggSfr888+VkpLCZxQAUc9u2Sz3kXul79bInDFaZtBp1RfuB0JUQAuMiy66SBdccIEKCgr0wQcfaO7cuerYsaOOP/549e7dm/u6AwCAGo888oistbr77rt1zz331Gw3xqhhw4aKi4ur1fjZ2dkqKSmRz+fT6NGjlZSUJGn/Th8BgEhn13wj95GJUnmZnMtvk+nc0+tIwO8K+LFBjuOoe/fu6t69u7777js9/PDDmjp1qqZPn67+/ftr5MiRatKkSaB3CwAAwkyzZs0kSVOnTg3K+OPHj9/r9nHjxgVlfwAQLuwni+Q+PUVq0EjOzZNkWrX1OhKwX5zff8qBKS0t1YIFC3TPPfforrvuUocOHXTPPfdoypQpSkhIUGZmZqB3CQAAwsyMGTO0devW33zO1q1b93pxTwDAwbHWyn1zjtzHJ0mp7eTc+gDlBcJKQI/AyM7O1rJly5SWlqbBgwerZ8+eio2Nrfn+eeedpwsuuCCQuwQAAGEoJSVFt9xyi1q1aqW0tDSlpKSoXr16Kisr04YNG7RixQqtX79eI0aM8DoqAEQEW7Fb2x+6R/b9d2R6nyBz/hUysbU7VQ+oawEtMDp27KjRo0erUaNGe/2+4ziaNm1aIHcJAADC0ODBgzVw4EAtXbpUBQUF+vjjj1VaWqr69eurdevWGjx4sLp3717rO5EAACS7favcqZkqX/2VzLBzZIaO5GKdCEsBLTBOO+20331OfHx8IHcJAADClM/nU58+ffTll19q9OjR6tChg9eRACDi2ML/yv3bvVLJViVfP0E7jujsdSTgoHGDXwAA4CljjCZPnqz4+Hgdd9xxOu6445SSkuJ1LAAIe/bzpXKfnCzF15Nzw31K6NFXO4qKvI4FHDQKDAAA4KkLLrhA5513npYvX65///vfuu2229S8eXMNGDBAp5xyitfxACDsWGtlc1+XnfOMlNpWzrjbZZr4vY4F1BoFBgAA8JzjOOrcubM6d+6s4uJiTZ06VTNnzqTAAIADZCsrZZ9/Qvb9+VKXPnLGXCsTn+B1LCAgKDAAAIDnysvLlZeXp0WLFmnFihXq1KmTxo0b53UsAAgrducOuY9nSV99JvOHP8oMHyXjOF7HAgKGAgMAAHjqwQcfVEFBgdq1a6f+/ftr3LhxatiwodexACCs2B/WV1+ss+gHmQuvktNvkNeRgICjwAAAAJ5q166dzjvvPPn9nJ8NAAfDfvWZ3MeyJMfIufZemcOP8joSEBQUGAAAwFPDhw/3OgIAhC33/fmysx6XmqfIueIOmWYtvI4EBA0FBgAAAACEGVtVJfvSs7I5r0lHdZVz8Y0yifW9jgUEFQUGAAAAAIQRW7Jd7rTJ0pfLZNJPkRk5WiYmxutYQNBRYAAAAABAmLBrV8udep+0rVjm/CvkHDfY60hAnaHAAAAAAIAw4C5+T/bvj0pJDeXcmCVz2OFeRwLqFAUGAAAAAIQwW1kp+9IzsrlvSIcfLeeSG2UaNvI6FlDnwq7A+PTTT/XMM8/IdV0NGjSIK5cDAAAAiFh2+1a5T9wvfb1cZtCpMn+6UMYXdj/GAQHheB3gQLiuq6eeekq33nqrpkyZokWLFmndunV1tv8ffnA0aJBPGzc6NY//+MemNY/3tu33HgfqOcEaty73vWGDonLe0TCnSN/399/Xbd5IX89fP2df6xvOcwqlff/83zUAQGix334jd8K10rdfy4y+Rs6Zf6G8QFQLq08sq1atUosWLXTIIYfI5/OpX79++vjjj+ts/w89lKQPPzSaMiWp5vGSJXE1j/e27fceB+o5wRq3LvedmRkTlfOOhjlF+r4nToyJuDmF0r73tb7hPKdQ2vfP/10DAIQOd1Gu3PtvlhxHzk2T5PQZ6HUkwHPGWmu9DrG/Fi9erE8//VRjx46VJL3//vv65ptvNHr06N983fr162u133btDtWuXaZWYwAAEOri463+858NtRojJSUlQGlCT20/T/ya3+9XUVFRQMcMNdEwRyk65skc646trJB94SnZf82T0o6V85cbZBo0DMjYoTLHYIqGOUqRP899fZ4Iq+OP9ta1GLNnsZCTk6OcnBxJUlZWlvx+f632u3JlhW6+OUavveaorMwoIcGqeXOrjRuNysuN6tWzOukkV5L0zjt7f87BvMbLcb3Y96ZNRmVl0TfvupqTMY7mz1fUrGdd7rtePatmzSJrTqG275+vb6TMKZT2Xa+e1bBhriZNqqr1v5kAgINnt22R+3iWtOpLmZNOlxlxnkxMjNexgJARVgVG06ZNtXnz5prHmzdvVuPGjfd4XkZGhjIyMmoe17aZio2VYmOTVV6eqIQEq127pISESu3aFav4eKvycik5uUzWGpWXJyo+fs/nHMxrvByXfUfeexkfX0/l5U7UrGckv5fRtu9InFMo7TshoXpbXFyZfL7tqu1/5kTyERgAEEx29VfV5UXpDpm/XC+n1/FeRwJCTszdd999t9ch9lejRo304osvqkePHoqPj9ezzz6r008/XcnJyb/5upKSklrve/bsRPXrt0uPP+5o164yffFFnP74x1Ldd982OY60aVOMSkuN+vXbVbPt1885mNd4OW5d7/ucc6zuvbco6uZdV3MqL49R79773lckrmdd7btevXpatsyJqDmF0r73tr7hPqdQ2veP/65t2hSj004rr/W/lw0aNKj1GKEqEJ8nfi4xMVGlpaUBHTPURMMcpeiYJ3MMLvf9t2WfuF9KaiDn2vFy0roEZT+8j5Ej0ue5r88TYXUNDEnKz8/XjBkz5LquBg4cqBEjRvzuawJ5zmqkn2vkJdY2uFjf4GFtg4v1Da5Ar28kH4HBNTAOXDTMUYqOeTLH4LAVFbLPPyH7wTvSUV3l/OV6mfrBK4J5HyNHpM8zIq6BIUndunVTt27dvI4BAAAAAAfNbtlcfcrIf1bK/OFPMsPPkXG43gXwW8KuwAAAAACAcGa/WVFdXuwqlzP2Jpnu/b2OBIQFCgwAAAAAqAPWWtl/vSX7wjSp6SFyrp0g07K117GAsEGBAQAAAABBZit2y/7jMdlFudIxPeSMuVYmMcnrWEBYocAAAAAAgCCyxZvkTr1P+u8qmVPOlDn1TBnH8ToWEHYoMAAAAAAgSOzKz+U+cb9UsVvOuFtluvTxOhIQtigwAAAAACDArOvKvvWS7GuzpENS5Fx2q8yhrbyOBYQ1CgwAAAAACCC7favcp6ZIKwpkeh0vM+oymYREr2MBYY8CAwAAAAACxK5cLnfaA9LOEplR42QGnCRjjNexgIhAgQEAAAAAtWTdKtl5L8m+/rzU/FA5V90lk3qY17GAiEKBAQAAItK8efOUm5sra60GDRqkoUOHSpLeeustvf3224qJiVG3bt107rnnepwUQLiz27fInf6g9OUymV4nyIy6lFNGgCCgwAAAABFn7dq1ys3NVWZmpnw+nzIzM9WtWzdt3rxZS5cu1QMPPKDY2Fht27bN66gAwpz96jO507Ol0p0y510uc9xgThkBgoQCAwAARJzCwkJ17NhR8fHxkqS0tDTl5eVp9erVGjZsmGJjYyVJycnJXsYEEMasWyX75ouyb8yWDjlUztV3y7TilBEgmCgwAABAxElNTdXs2bNVUlKiuLg4FRQUqH379tqwYYO++uorzZ49W7GxsRo1apQ6dOiw1zFycnKUk5MjScrKypLf7w9oRp/PF/AxQ000zFGKjnkyx1+q2lqs7VPGa/dnS5VwwslqcMkNcuqF/ikjvI+RI1rm+WsUGAAAIOK0atVKw4YN04QJE5SQkKA2bdrIcRy5rqsdO3Zo4sSJWr16taZMmaJHHnlkr4d7Z2RkKCMjo+ZxUVFRQDP6/f6AjxlqomGOUnTMkzn+xH65TO5TD1afMnL+FdrdP0PFO0ulnaV1kLJ2eB8jR6TPMyUlZa/bKTAAAEBESk9PV3p6uiRp1qxZatq0qQoLC9W7d28ZY9ShQwc5jqOSkhI1bNjQ47QAQp11q2T/OUf2n7OlQ1rKufoemVZtvY4FRBXH6wAAAADB8OMFOouKipSXl6f+/furZ8+eWr58uSRp/fr1qqysVIMGDbyMCSAM2G1b5E65S/aN52V6nyjntmzKC8ADHIEBAAAiUnZ2tkpKSuTz+TR69GglJSUpPT1dU6dO1XXXXSefz6dx48ZxtwAAv8l+uaz6LiPlpTIXXCnTbxB/bwAeocAAAAARafz48Xts8/l8uvLKKz1IAyDcWLdK9o0XZN98QWrRSs61E2RatvY6FhDVKDAAAAAA4Gfs1uLqoy5Wfi7TN13mnLEy8QlexwKiHgUGAAAAAPyPXfFpdXmxq0zmgqvk9B/kdSQA/0OBAQAAACDq2aoqua/9Q/bNOdWnjFw3kVNGgBBDgQEAAAAgqtmtxdry17tll+fL9B8kc9YlnDIChCAKDAAAAABRy+Z/JHfmI3IrKmQuvEpOP04ZAUIVBQYAAACAqGPLSmVfmCa7KFdq3V5Nr79XW+sleR0LwG+gwAAAAAAQVew3K+Q+9aBUXCQzZKTMqWfI1+JQqajI62gAfgMFBgAAAICoYCsrZF+fJfv2XMl/iJwb75PpkOZ1LAD7iQIDAAAAQMSzhWvlPpUtffetzICTZEZeJJOQ6HUsAAeAAgMAAABAxLKuK7vgn7Ivz5DqJcoZd6tMlz5exwJwECgwAAAAAEQku2Wz3Gf/Kq34VOrcU875l8s0bOx1LAAHiQIDAAAAQMRxP/5A9rnHpMoKmVGXyQw4WcYYr2MBqAUKDAAAAAARw5bukJ31hOyShdJhh8sZc61M8xSvYwEIAAoMAAAAABHBfvWZ3GcekrYWyww7W+YPf5aJifE6FoAAocAAAAAAENZsxW7ZV5+Tffc1qXmKnJsnyxzW0etYAAKMAgMAAABA2LLrvpU7/UGp8L8yJw6R+dOFMvHxXscCEAQUGAAAAADCjnWrZN99TfbV56T6DeRceZfMMd29jgUgiMKmwPjoo4/04osvqrCwUJmZmWrfvr3XkQAAAAB4wG7eKPfph6Svl0td+8gZdblMg4ZexwIQZGFTYKSmpur666/Xk08+6XUUAAAAAB6w1sou/pfs809I1spccJVMv3RujwpEibApMFq1auV1BAAAAAAesTu2yz73mOwni6QOneRcdLVMsxZexwJQh8KmwDgQOTk5ysnJkSRlZWXJ7/cHbGyfzxfQ8fAT1ja4WN/gYW2Di/UNLtYXQKiz1souXVR91EXpTpkR58mcfLqMw+1RgWgTUgXGvffeq61bt+6x/cwzz1TPnj33e5yMjAxlZGTUPC4qKgpIPkny+/0BHQ8/YW2Di/UNHtY2uFjf4Ar0+qakpARsLACwxUVyZz0uLcuT2nSQc814mdTDvI4FwCMhVWDccccdXkcAAAAA4DHrurIL35adO0Nyq2T+fJHMoFNlYjjqAohmIVVgAAAAAIhudsN3cv/+iLTqS6lTFznnXsa1LgBICqMCIy8vT08//bS2b9+urKwstW3bVrfddpvXsQAAAAAEgK2skH37Zdk350jx9WQuvFqm70DuMAKgRtgUGL169VKvXr28jgEAAAAgwOzqr6qPuli/VqbX8TJnjJFp2MjrWABCTNgUGAAAAAAiiy0vk331OdkF/5QaNZVz+R0yx+7/xfsBRBcKDAAAAAB1zi7/RO7MqdKWIpkTh8iMGCWTkOh1LAAhjAIDAAAAQJ2xJdtlX5gmu2ShdGiqnBuzZDqkeR0LQBigwAAAAAAQdNZa2SULZV+YLpWVypx6pswf/iwTG+t1NABhggIDAAAAQFDZzRvlPjdVWp4vtTtCznlXyLRs7XUsAGGGAgMAAABAUFi3Sva9ebKvzJQkmTMvlhn4BxknxuNkAMIRBQYAAACAgLOF/5U742/St19LR3eXc+5lMk2beR0LQBijwAAAAAAQMLaiQnbeHNm3XpbqJcqMuU6m1/EyxngdDUCYo8AAAAARad68ecrNzZW1VoMGDdLQoUM1Z84c5ebmqmHDhpKks846S926dfM4KRA57MrP5T73mPT9Opm+A2X+PFqmQUOvYwGIEBQYAAAg4qxdu1a5ubnKzMyUz+dTZmZmTVExdOhQnXbaaR4nBCKL3bxR7otPS598KDVtLuequ2WOphwEEFgUGAAAIOIUFhaqY8eOio+PlySlpaUpLy/P41RA5LG7dsm+/bLs/LmSkcyws2VOOl0mLt7raAAiEAUGAACIOKmpqZo9e7ZKSkoUFxengoICtW/fXklJSZo/f77ef/99tWvXTuedd56SkpL2OkZOTo5ycnIkSVlZWfL7/QHN6PP5Aj5mqImGOUrRMc9fz9Faq12LclUy41HZoh+UMGCwks67TDH+QzxMWTvR+D5GomiYoxQ98/w1Y621XocItvXr1wdsLL/fr6KiooCNh5+wtsHF+gYPaxtcrG9wBXp9U1JSAjZWbS1YsEDz589XQkKCWrZsqbi4OA0fPrzm+hcvvPCCtmzZossuu2y/xgvk5wkpOv5sR8McpeiY58/naNeuljt7mvTNCql1OzlnXizTsZPHCWsv2t7HSBUNc5Qif577+jzBERgAACAipaenKz09XZI0a9YsNW3aVI0aNar5/qBBgzRp0iSv4gFhx5Zsk331OdkP3pHqN5AZNU7muAwZJ8braACiBAUGAACISNu2bVNycrKKioqUl5enCRMmaMuWLWrcuLEkKS8vT6mpqR6nBEKfrazUzjdekPv8dGl3ucygU2VOPVMmce+nXwFAsFBgAACAiJSdna2SkhL5fD6NHj1aSUlJ+tvf/qY1a9bIGKNmzZrp4osv9jomENLsFwVyX5iuHRu+k47qKueMMTKHUvwB8AYFBgAAiEjjx4/fY9sVV1zhQRIg/NiNG+TOeUpalic1a6FGt96v7W2PkDHG62gAohgFBgAAAABJki0vlZ33ouy7r0kxsTIjzpfJOE3xhx4qE8EXDAQQHigwAAAAgChnXVd28b9k5/5d2lYs03dgdXnRqInX0QCgBgUGAAAAEMXst1/Lff5J6duvpcMOl3PZLTLtjvA6FgDsgQIDAAAAiEJ2a7HsKzNlP8yVkhvLXHiVTJ+BMo7jdTQA2CsKDAAAACCK2IoK2dzXZf85R6qskDl5hMzQkTL1Er2OBgC/iQIDAAAAiAK2slL2w1zZN1+Qioukzj3ljBwtc0iK19EAYL9QYAAAAAARzLpVskvel33jeWnT99XXubjgKpm0Y72OBgAHhAIDAAAAiEDWdaWCj+S+Nkva8J2UepicK+6QjukhY4zX8QDggFFgAAAAABHEWit9tlTua89J330rHZoqZ+xNUte+XKATQFijwAAAAAAigLVW+nKZ3Fefq74larMWMqOvkel1vIwT43U8AKg1CgwAAAAgzNlVK+S+8pz09XKpsV9m1DiZfoNkfHzcBxA5+BsNAAAACFN2zTdyX/uH/p+9Ow+vojrcOP6eyc1CWEJIgBA2AQFREQkgCgICIS6AYLWIuFYpxWipdalL3RGlKsWfFopWShV3WwFxAQygIKDsCrgBKoKAMQk7JCSZ8/vjYjQCGiDJuffm+3kenuTemQzvmYHk3jdnZrR6uVSrtszgYTLdM2SiY1xHA4ByR4EBAAAAhBm76Wv5r78grfhAql5T5sIrZXr2k4mNdR0NACoMBQYAAAAQJuzWb2Wnvyi7ZL4UV03m/CEy6efLVIt3HQ0AKhwFBgAAABDibM53sm+8LLtojhSIljnnQpmzL5CpXtN1NACoNBQYAAAAQIiy23Nl33xVdv4syRiZXv1kzr1Qplai62gAUOkoMAAAAIAQY7fnys6aKvvu25JfLHNmH5nzBsnUSXYdDQCcocAAAAAAQoTd9HWwuFg8T/J9mdPPkuk/WKZuiutoAOBc2BQYkydP1rJlyxQIBFS/fn1lZmaqevXqrmMBAAAAx8RaK326Uv7MqdInK6SYWJke5wQvzklxAQAlwqbAOOWUUzRkyBBFRUXpueee05QpU3TZZZe5jgUAAAAcFVtUKLt4vuw7U6VNX0sJiTIXXB4sL7g4JwAcJGwKjHbt2pV83qpVK33wwQcO0wAAAABHx+7dLTtvpuzs6dL2PCm1icxVI2RO6yETHe06HgCErLApMH5qzpw56tKly2GXZ2VlKSsrS5I0evRoJSeX38WOAoFAuW4PP2LfViz2b8Vh31Ys9m/FYv8ClcfmZstmvS47/x2pYJ/Upp28K/8onZQmY4zreAAQ8kKqwBg5cqS2b99+0PODBw9Wp06dJEmvvfaaoqKi1K1bt8NuJz09Xenp6SWPc3Jyyi1jcnJyuW4PP2LfViz2b8Vh31Ys9m/FKu/9m5qaWm7bAiKF/Xpt8MKcyxYEb4XaqZtMn4EyTZq7jgYAYSWkCoy77rrrF5e/++67WrZsme6++25aagAAAIQs6/vSqmXyZ02RvlgtVYuXSR8g07ufTJ26ruMBQFgKqQLjl6xcuVLTpk3Tfffdp9jYWNdxAAAAgIPYwv2yi+bKvjNN2rpJqpMs89urZbplyFSLdx0PAMJa2BQYEydOVFFRkUaOHClJatmypYYNG+Y4FQAAACDZXTtl33tLds6b0q4dUpPmMkNvkunQVSYQNi+5ASCkhc130yeeeMJ1BAAAAKAU+91m7fzfJPlz3pT275fadpSXMVBq3ZZTngGgnIVNgQEAAACEApu/T3b5QtmFc6TPV2lfIFrm9LNk+gyQSW3iOh4ARCwKDAAAAOBXWGultWtkF8wO3k2kIF+q10BmwKVKGjBY24qt64gAEPEoMAAAAIDDsDnfBS/KuWiO9P1WKbZa8DaoXXpLx7eRMUZRiUkSt3sGgApHgQEAAAD8hC3Il12+SHbhbOmzj4NPnnCKzPmXyLQ/QyY2zm1AAKiiKDAAAABQ5VlrpXWfyi7Ikl26QCrYJ9VNkRkwROaMXjJJ9VxHBIAqjwIDAAAAVZbN/V520ZzgbIvvt0qxcTIduwZPEWl5EncSAYAQQoEBAACAKsUWFMiu+MkpItYGb3vab7BM2hkycdVcRwQAHAIFBgAAiEhvvfWWZs+eLWutevfurb59+5Yse/311/Xcc8/p6aefVq1atRymRGWx1krrP5VdOEd2yXwpf5+UVC9YWpzRU6ZuiuuIAIBfQYEBAAAizjfffKPZs2frwQcfVCAQ0IMPPqi0tDQ1aNBAOTk5WrVqlZKTk13HRAWz1kpbNgYvyLlorpS9WYqJlenQVabrgVNEPM91TABAGVFgAACAiPPtt9+qM4l2NQAAIABJREFUZcuWio2NlSS1adNGixcv1oABA/TMM8/o0ksv1SOPPOI4JSqC9YulL7+QXfmB7IoPg6WFJLU8Uea8i2Q6dJGJi3cbEgBwVCgwAABAxGncuLFeeukl7dq1SzExMVqxYoVatGihpUuXqk6dOjruuON+dRtZWVnKysqSJI0ePbrcZ2wEAoGInwVSWWO0+wu0/+OlKlg8XwVL3pe/PU+KilJM2w6KvWCIYjt1U1RS3Qr7+zmWkYExRoaqMEap6ozz5ygwAABAxGnUqJEGDBigBx54QHFxcWratKk8z9Nrr72mO++8s0zbSE9PV3p6esnjnJyccs2YnJxc7tsMNRU5Rrt3t+zHS2VXfiCtXi4V5Eux1WTadpA5tbNM2w4qjq+hvZL2WkkVuK85lpGBMUaGqjBGKfLHmZqaesjnKTAAAEBE6tWrl3r16iVJeuGFF1S7dm29//77uuWWWyRJubm5uvXWW/XQQw+pdu3aLqOijGxejuxHi4OlxeerpOJiqVZtmc49ZE49XTrhFJnoaNcxAQAVhAIDAABEpB07dighIUE5OTlavHixHnjgAZ133nkly6+77jo99NBD3IUkhJVchHPFB7IrP5S+XhtcUC9VJn2ATPvTpWatuBAnAFQRFBgAACAijRkzRrt27VIgENA111yjGjVquI6EMjjsRTibtZK54PJgaZHSSMYYt0EBAJWOAgMAAESk+++//xeXjxs3rpKS4NfYndul9Z/Jrloq+9Fiaed2KSpKan2KTJ/zZdp1lklMch0TAOAYBQYAAAAqjfWLpc3fyK77TPryM9n1n0nZW4ILD1yEUwcuwmnimTUDAPgRBQYAAAAqjN27R/rqC9n1nwbLii8/l/L3BRfWTJBatJHpliHToo10XEsuwgkAOCwKDAAAAJQLa62UvUV2/afS+s+U+/Va+Ru/kqyVjCc1bCrTuUewtGhxglQ3hWtZAADKjAIDAAAAR8UWFEgb1squP3AqyPrPpN07gwurVZd3wskyp54eLCuatZKpFu82MAAgrFFgAAAA4FdZv1jKyZbdsF764XSQjV9KxcXBFeo3lDmlk9TihODpIA0aKbFePeXk5LgNDgCIGBQYAAAAKGGLCoMX1dyyUXbLRmnzRtktm6TvvpUK9wdXiomRjmslk3FBsKxo3lqmZi23wQEAEY8CAwAAoAqyBQXS1k3BkmLLJtkt30hbNknfb/lxVoUkJdWTUpvInNhOatBYptFxUqNmMgFeRgIAKhc/eQAAACKY3bv7QEGx8cCsik3S5m+kvO+DF9eUJM+T6qVKDRrJpHUJfmzQWEppKBMb53YAAAAcQIEBAAAQhqxfLO3ZLe3eFbxw5p6dsj98npcju3WTtHmjtCPvxy+Kjgleq6J5a+nM9GBJ0aCxVK+BTIDblwIAQhsFBgAAgGO2qPBAGbGzpJCwe378XLt3ye7eKe358bH27flxBsXPxVULnu5xUvsDsymaSA0aScn1ZLyoyh0cAADlhAIDAACgkvkL5yh3/gwVb98WLCTy9x1+5ZhYqUYtqUZNqUYtmaR6pR6rek2ZGrVKPxcTK2NM5Q0IAIBKQIEBAABQ2QIBeTVryyTV/1kZUUvmh88PPG+iY1ynBQAgJFBgAAAAVDLvtO5KPO83ysnJcR0FAICw4bkOAAAAAAAA8GsoMAAAAAAAQMijwAAAAAAAACGPAgMAAAAAAIQ8CgwAAAAAABDyKDAAAAAAAEDIC5vbqL700ktaunSpjDFKSEhQZmam6tSp4zoWAAAAAACoBGFTYJx//vkaPHiwJOmtt97Sf//7Xw0bNsxxKgAAAAAAUBnC5hSS+Pj4ks8LCgpkjHGYBgAAAAAAVKawmYEhSS+++KLmzZun+Ph43XPPPYddLysrS1lZWZKk0aNHKzk5udwyBAKBct0efsS+rVjs34rDvq1Y7N+Kxf4FAADhwlhrresQPxg5cqS2b99+0PODBw9Wp06dSh5PmTJFhYWFGjRoUJm2u3nz5nLLmJycrJycnHLbHn7Evq1Y7N+Kw76tWOzfilXe+zc1NbXcthVqyvP1hFQ1/m1XhTFKVWOcjDEyMMbIEenjPNzriZCagXHXXXeVab0zzzxTo0ePLnOBAQAAAAAAwltIzcD4JVu2bFGDBg0kSW+//bY++eQT3XTTTY5TAQAAAACAyhA2F/F8/vnnddNNN+nmm2/WRx99pN/97ndOctx2221O/t6qgH1bsdi/FYd9W7HYvxWL/etOVdj3VWGMUtUYJ2OMDIwxclSVcf5cSJ1C8ktuvvlm1xEAAAAAAIAjYTMDAwAAAAAAVF1R9957772uQ4Sb5s2bu44Qsdi3FYv9W3HYtxWL/Vux2L/uVIV9XxXGKFWNcTLGyMAYI0dVGedPhc1FPAEAAAAAQNXFKSQAAAAAACDkUWAAAAAAAICQFzZ3IXFt5cqVmjRpknzfV+/evTVw4EDXkSJGTk6Oxo0bp+3bt8sYo/T0dJ133nmuY0UU3/d12223qU6dOlX2lksVZc+ePZowYYI2btwoY4yuvfZatWrVynWsiPDGG29ozpw5MsaocePGyszMVExMjOtYYWv8+PFavny5EhISNGbMGEnS7t27NXbsWH3//feqW7eu/vznP6tGjRqOk0aeX3sNYa3VpEmTtGLFCsXGxiozMzOszmsuy8/xNWvW6OGHH1a9evUkSZ07d9ZFF13kIu5Ru+666xQXFyfP8xQVFaXRo0eXWh7ux1GSNm/erLFjx5Y8zs7O1qBBg9S3b9+S58LxWB7L979weQ9wqDFOnjxZy5YtUyAQUP369ZWZmanq1asf9LW/9m87VBxqjK+88opmz56tWrVqSZIuueQSpaWlHfS14Xwcx44dq82bN0uS9u7dq/j4eD3yyCMHfW24HMdjZvGriouL7fXXX2+3bt1qCwsL7c0332w3btzoOlbEyMvLs+vXr7fWWrt37147YsQI9m85mz59un3sscfsQw895DpKxHniiSdsVlaWtdbawsJCu3v3bseJIkNubq7NzMy0BQUF1lprx4wZY+fOnes2VJhbs2aNXb9+vb3xxhtLnps8ebKdMmWKtdbaKVOm2MmTJ7uKF7HK8hpi2bJldtSoUdb3ffv555/b22+/3VHao1OWn+OrV68O+59BmZmZdseOHYddHu7H8eeKi4vt0KFDbXZ2dqnnw/FYHu33v3B6D3CoMa5cudIWFRVZa4PjPdz3+F/7tx0qDjXGl19+2U6bNu0Xvy7cj+NPPfPMM/bVV1895LJwOY7HilNIymDdunVKSUlR/fr1FQgE1KVLFy1ZssR1rIiRmJhY8huKatWqqWHDhsrLy3OcKnLk5uZq+fLl6t27t+soEWfv3r369NNP1atXL0lSIBA45G82cHR839f+/ftVXFys/fv3KzEx0XWksHbiiSce9NvFJUuWqEePHpKkHj168LOtApTlNcTSpUvVvXt3GWPUqlUr7dmzR9u2bXOU+Mjxczwo3I/jz61atUopKSmqW7eu6yjH7Gi//4XTe4BDjbFdu3aKioqSJLVq1Srs/18eaoxlEe7H8QfWWi1atEhdu3at5FShhVNIyiAvL09JSUklj5OSkrR27VqHiSJXdna2vvrqKx1//PGuo0SM//znP7rsssu0b98+11EiTnZ2tmrVqqXx48drw4YNat68ua666irFxcW5jhb26tSpo/79++vaa69VTEyM2rVrp3bt2rmOFXF27NhRUgwlJiZq586djhNFnrK8hsjLy1NycnKpdfLy8sKytPuln+NffPGFbrnlFiUmJuryyy9X48aNHSQ8NqNGjZIk9enTR+np6aWWRdJxlKQFCxYc9o1SJBzLsnz/i6T3AHPmzFGXLl0Ou/yX/m2HupkzZ2revHlq3ry5rrjiioMKgEg5jp9++qkSEhLUoEGDw64TzsexrCgwysAe4k6zxhgHSSJbfn6+xowZo6uuukrx8fGu40SEZcuWKSEhQc2bN9eaNWtcx4k4xcXF+uqrr3T11VerZcuWmjRpkqZOnarBgwe7jhb2du/erSVLlmjcuHGKj4/X3//+d82bN0/du3d3HQ04ImV5DREprzN+6ed4s2bNNH78eMXFxWn58uV65JFH9PjjjztKenRGjhypOnXqaMeOHXrggQeUmpqqE088sWR5pBxHSSoqKtKyZcs0ZMiQg5ZFwrEsq0g5pq+99pqioqLUrVu3Qy7/tX/boSwjI6PkGiwvv/yynn32WWVmZpZaJ1KO4y+VilJ4H8cjwSkkZZCUlKTc3NySx7m5uWHbpoeqoqIijRkzRt26dVPnzp1dx4kYn3/+uZYuXarrrrtOjz32mFavXh2xLzJcSEpKUlJSklq2bClJOv300/XVV185ThUZVq1apXr16qlWrVoKBALq3LmzvvjiC9exIk5CQkLJFPdt27aVXAQN5acsryGSkpKUk5Pzi+uEul/7OR4fH18yOy0tLU3FxcVhN+OnTp06koL/bzp16qR169aVWh4Jx/EHK1asULNmzVS7du2DlkXCsZTK9v0vEt4DvPvuu1q2bJlGjBhx2Dftv/ZvO5TVrl1bnufJ8zz17t1b69evP2idSDiOxcXFWrx48S/Oognn43gkKDDKoEWLFtqyZYuys7NVVFSkhQsXqmPHjq5jRQxrrSZMmKCGDRuqX79+ruNElCFDhmjChAkaN26cbrjhBp188skaMWKE61gRo3bt2kpKSiq5MvSqVavUqFEjx6kiQ3JystauXauCggJZa7Vq1So1bNjQdayI07FjR7333nuSpPfee0+dOnVynCjylOU1RMeOHTVv3jxZa/XFF18oPj4+rF5cl+Xn+Pbt20t+C7pu3Tr5vq+aNWtWZsxjkp+fX3IqZn5+vj7++GM1adKk1Drhfhx/6pd+0xvux/IHZfn+F+7vAVauXKlp06bp1ltvVWxs7CHXKcu/7VD20+vMLF68+JCnM4X7cZSCrzFTU1NLnQrzU+F+HI+EsYeaU4ODLF++XM8884x831fPnj31m9/8xnWkiPHZZ5/p7rvvVpMmTUqa4cPdAglHb82aNZo+fTq3US1nX3/9tSZMmKCioiLVq1dPmZmZ3IaynLzyyitauHChoqKidNxxx2n48OGKjo52HStsPfbYY/rkk0+0a9cuJSQkaNCgQerUqZPGjh2rnJwcJScn68Ybb+TfbwU41GuIWbNmSQpOf7bWauLEifroo48UExOjzMxMtWjRwnHqsjvcz/EfZiNkZGRoxowZmjVrlqKiohQTE6MrrrhCrVu3dhn7iHz33Xd69NFHJQV/E3rmmWdG3HH8QUFBga699lr94x//KDkV6KfjDMdjeSTf//Ly8vTkk0/q9ttvlxQ+7wEONcYpU6aoqKio5Pt6y5YtNWzYsFJjPNy/7VB0qDGuWbNGX3/9tYwxqlu3roYNG6bExMSIOo69evXSuHHj1LJlS2VkZJSsG67H8VhRYAAAAAAAgJDHKSQAAAAAACDkUWAAAAAAAICQR4EBAAAAAABCHgUGAAAAAAAIeRQYAAAAAAAg5FFgAAAAAACAkEeBAQAAAAAAQh4FBgAAAAAACHkUGABCwtatW/W73/1OX375pSQpLy9P11xzjdasWeM4GQAAAIBQQIEBICSkpKTo0ksv1RNPPKGCggL985//VI8ePXTSSSe5jgYAAAAgBBhrrXUdAgB+8Le//U3Z2dkyxuihhx5SdHS060gAAAAAQgAzMACElN69e2vjxo0655xzKC8AAAAAlKDAABAy8vPz9cwzz6hXr1569dVXtXv3bteRAAAAAIQICgwAIWPSpElq1qyZhg8frrS0ND311FOuIwEAAAAIERQYAELCkiVLtHLlSg0bNkySdOWVV+qrr77S/PnzHScDAAAAEAq4iCcAAAAAAAh5zMAAAAAAAAAhjwIDAAAAAACEPAoMAAAAAAAQ8igwAAAAAABAyKPAAAAAAAAAIY8CAwAAAAAAhDwKDAAAAAAAEPIoMAAAAAAAQMijwAAAAAAAACGPAgMAAAAAAIQ8CgwAAAAAABDyKDAAAAAAAEDIo8AAAAAAAAAhL+A6QGXYvHlzuW4vOTlZOTk55brNUFMVxihVjXEyxsjAGCNHpI8zNTXVdYQKw+uJsovUsTGu8BOpY2Nc4SdSx1ZR4zrc6wlmYAAAAAAAgJBHgQEAAAAAAEIeBQYAAAAAAAh5VeIaGAAAAAAAoPJZa5Wfny/f92WMKfW853mKi4sr9fwvocAAAAAAAAAVIj8/X9HR0QoEDq4fioqKlJ+fr2rVqpVpW5xCAgAAAAAAKoTv+4csLyQpEAjI9/0yb4sCAwAAAAAAVIhfOz2krKePSBQYAAAAAAAgDFBgAAAAAACAkMdFPAEAQMQYP368li9froSEBI0ZM+ag5dZaTZo0SStWrFBsbKwyMzPVvHlzB0kBAKgarLXHtPynmIEBAAAixllnnaU77rjjsMtXrFihrVu36vHHH9ewYcP09NNPV2I6AACqHs/zVFRUdMhlRUVF8ryy1xLMwAAqkfV9qahQKiyUCvcH/xT98Hnpj/ZwyzxPpl0nqXHzI7rgDQBUBSeeeKKys7MPu3zp0qXq3r27jDFq1aqV9uzZo23btikxMbESU0r281Xa9dan8vftK/dtm1YnybTtWO7bBQDgaMTFxSk/P18FBQWl3r9Ya+V5nuLi4sq8LQoMoJzZlR/Kn/E/ac+uYOGwv+DHIuIwzeMRMUb29RekBo1lzugpc1oPmaS6x75dAKgC8vLylJycXPI4KSlJeXl5hywwsrKylJWVJUkaPXp0qa87Vnvmb9buN14pt+2V8ItlZ/xPNS6/VvEXXOas6A4EAuW6v0IF4wo/kTo2xhV+InVslT0uCgygnNi87+W/+JS08kMppaFM4+ZSIFqKjpGif/gY87PHwY8mOloKHHqZfrosEJD27pZd8r7sh+/Kvvas7GvPSq1Oljn9LJkOXWTia7jeFQAQsg51nu3h3uSnp6crPT295HFOTk75Bel2tupfcGn5blOSLSyUnfSYdk/+p/Zs3CBzye9lvKhy/TvKIjk5udzHFgoYV/iJ1LExrvATqWOrqHGlpqYe8nkKDOAY2eJi2dnTg7MirC/zmytl+gyQCVTQf6/qNWXOOlc661zZ77fKfvie7Afvyj77D9kXnpTadZJ3+lnSyR1kAtEVkwEAwlRSUlKpF1q5ubmVfvpIRTLR0dLQm6Q6dWVnvia7PVfe0JtlYmNdRwMA4JhRYADHwH71hfzJ46SNX0ltO8q7ZJhM3ZRK+/tN3RSZfhfL9h0kfb0uOCtj8Tz5yxYGi45OZ2r/2QNlk1K4XgYASOrYsaNmzJihrl27au3atYqPj4+oAkOSjOfJXHSV/DrJsi/9S/7f75R3/V0yNWu5jgYAwDGhwACOgt27W3bKZNn3ZkgJifKG3yqldXFWEhhjpGYtZZq1lL3od9KnH8l+MFd24Wxte/dtqW6KTOceMp3Pkklp6CQjAFSGxx57TJ988ol27dql4cOHa9CgQSVXPs/IyFD79u21fPlyjRgxQjExMcrMzHScuOJ4vfrJ1k6S//QY+aP/Iu+Geyu1ZAcAoLxRYABHwForu2S+7CsTpZ07ZHr1kxlwqUy1eNfRSphAQGrbQaZtB9n8vaqxdo12Zk2XffNV2Tdelpq1ChYZnc6UqVXbdVwAKFc33HDDLy43xmjo0KGVlMY9k3aGvBtHyv/HA/IfukXeH++WadbSdSwAAI4KBQZQRjZ7i/znJ0ifrJCaHi/vj3fJND3edaxfZOLiVa3nudrTtpPs9lzZxfODMzNeekr2laelk9KCF/9s15nzowEgQpnj28i77W/yH7tX/qN3yBt+K7dZBQCEJQoM4FfYwsLghdDeelWKipIZPEym57lOrup+LEztJJmMgVLGQNlvNwSvl/Hhe7L/elQ2tppM2hkyXXvLtG7rOioAoJyZlEbybn9E/hPB2Rjm0mvldT/bdSwAAI4IBQbwC+znq+U/N17aukmmQ1eZi4fKJCa5jnXMTMOmMr+5Unbg5dLaT4JlxtIFsovmSCe1l/fba2QaNnEdEwBQjkxCorybR8l/8m+yk8fJ35Yjc/4QLvIMAAgbFBjAIdhdO2Vf/XfwDX1SPXkj7o7I6bbG86TWJ8u0Pln2kmGy770tO/0l+fePkOl+TvCFLVetB4CIYeKqybvuTtnn/xm8LlJejnT5dRV3628AAMoRP62An7DWyi7Ikv3vf6T8vTLnXijTd3CVuD6EiY6RSR8ge3pP2ddfDJYZH74n0+9imV59ZQLRriMCAMqBCQSkK66XEpNlp78ouz1P3rW3ysSFzgWpAQA4FAoM4AC7+Zvg6SJrP5GObyPvskyZhk1dx6p0pkYtmSF/kD3rXPmvTgrORHnvbXm//Z3UrjNTjQEgAhhjZM6/RH6d5ODpJI/cEbxDSe06rqMBAHBYFBio8mxBgexbr8jOnCLFVZO54nqZrunB0yuqMJPaRFF/ukd29TL5r/xb/rgHpdZt5V08VKZxM9fxAADlwDuzj2ztOvIn/E3+6L/I+9M9Mg0au44FAMAhVe13aKjyCpZ/IP/e62XfelXmtO7yRo6X1y2jypcXP2VO7iDvnsdlhvxB+vZr+SNvkP/sP2R3bnMdDQBQDszJHeTd8qBUuF/+6Ftl137iOhIAAIfEuzRUSbaoUP6/HtX2kTdKgYC8m0fJu/oGmZoJrqOFJBMVJa9nX3kPPCmTfr7swtny/zpc/tv/lS3c7zoeAOAYmabHy7vtYalWgvy/3yW7bIHrSAAAHIQCA1WSnfq87OJ5qj7oanl3Py7Tuq3rSGHBVK8hb9A18u4bJ51wiuxrz8q/K1N26fuy1rqOBwA4BqZuirxb/yY1bSH/yYflZ01zHQkAgFIoMFDl2DUrZGe+JtP9HNW4ZKhMNHfXOFKmfqqirvurvBtHStXigy90H75ddsM619EAAMfA1KgV/N5+amfZlyfKf2WirO+7jgUAgCQKDFQxduc2+f8eK6U2kRl0jes4Yc+0aSfvrrEyl18nffet/AdulP/vx2S357qOBgA4SiYmVt7wW2V69ZN9Z5rsvx7ldEEAQEgImbuQrFy5UpMmTZLv++rdu7cGDhxYavn8+fM1bVpwKmNcXJyGDh2q4447zkFShCvr+/In/Z+0b6+8G0fKxMa6jhQRjBcl0/1s2U7dZN96VTZrmuyyBTLnXijT5wL2MwCEIeNFSYN/LyXVlX11kuzObfIy/ypTvYbraACAKiwkZmD4vq+JEyfqjjvu0NixY7VgwQJt2rSp1Dr16tXTvffeq0cffVQXXnihnnrqKUdpEa5s1uvS6uUyg66WadjUdZyIY6rFy7vwSnn3j5fadpCd9oL8u66V/8G7TD8GgDBkjJGXcYHM72+W1n8u/9knXEcCAFRxIVFgrFu3TikpKapfv74CgYC6dOmiJUuWlFqndevWqlEj2Pq3bNlSublMUUfZ2Q3rZF97Vmp/ukyPc13HiWimboqiht8m75aHpJoJshP/Ln/0X2TXf+Y6GgDgKHindZcZcKm0fJHs8oWu4wAAqrCQOIUkLy9PSUlJJY+TkpK0du3aw64/Z84ctW/f/rDLs7KylJWVJUkaPXq0kpOTyy+spEAgUO7bDDWRNEZ/3x7lTfy7vNp1lPTne+XVrFWyLJLGeTjOxpjcQ/b0bsp/d4Z2PzdB/ui/qNrZF6jG5cPlVa9Zrn8VxzEyVIUxSlVnnIgsJmOg7NL58l94Ul7rUziVBADgREgUGIe6/aIx5pDrrl69WnPnztX9999/2O2lp6crPT295HFOTs6xh/yJ5OTkct9mqImkMfr/Hiu7dbO8mx9QXsF+qeDHcUXSOA/H+RhPOU26v63M6y9o36xp2vfBu/IG/17q0PWw/8+PlPMxVgLGGDkifZypqamuI6ACmKgoeVf+Uf6om2Rf/bfMVSNcRwIAVEEhcQpJUlJSqVNCcnNzlZiYeNB6GzZs0JNPPqlbbrlFNWuW729wEZn8D+bKLpor02+QTKuTXcepskxcNXmDrpH310elhDrB267+4wHZ3O9dRwMAlJFp0kLm7AtkF2TJfvqR6zgAgCooJAqMFi1aaMuWLcrOzlZRUZEWLlyojh07llonJydHjz76qK6//np+u4MysdmbZZ+bILU8Uabvxa7jQJJpery8Ox4N3sL2s4/l33Od/HemyRYXu44GACgD02+wVC9V/uRxsgX5ruMAAKqYkDiFJCoqSldffbVGjRol3/fVs2dPNW7cWLNmzZIkZWRk6L///a92796tp59+uuRrRo8e7TI2QpgtKpT/1KNSVJS8a26SiYpyHQkHmKgomT4DZNPOkP/8BNlXJsp+8K68K66XadrCdTwAwC8wMbHyrrxe/iN3yE57PlhIAwBQSUKiwJCktLQ0paWllXouIyOj5PPhw4dr+PDhlR0LYcpOfU7asE7etbfJJNV1HQeHYJLqyfvjXbJLF8i+/C/5o26SSe8vc/4QmbhqruMBAA7DtDpZpsc5slnTZTt1l2nW0nUkAEAVERKnkADlya5eLjtzikyPc2TSuriOg19gjJHX6Ux594+T6ZYh+840+fdcL/vxkl//YgCAM+bCq6SERPnPPC5bVOg6DgCgiqDAQESxO7fJ//dYKbUJ01rDiImvIe/yTHl/GS3Fxsl/YqT8Jx+W3bHNdTQAwCGYavHyLrtW+naD7Iz/uY4DAKgiKDAQMazvy//3Y1L+PnnDbpGJiXUdCUfItDxR3t2PyQy4VHblh/LvypT/3gxZ33cdDQDwM6bdaTKdusm++Yrslo2u4wAAqgAKDEQMmzVNWrNCZtA1Mg2buo6Do2QC0fL6XSzvnselJs1lnxsv/5HbZb/9xnU0AMDPmMG/l2KryX/mCVmfO0oBACoWBQYigv16rexrk6X2p8v0OMd1HJQDk9JQ3k0PyFz1J2nLJvkjb5Dro86tAAAgAElEQVQ/9TnZwv2uowEADjC1astcPFRa/5ns3LddxwEARDgKDIQ9m79X/lOPSAm15V35RxljXEdCOTHGyOvaW97I8SXTlP17R8h+9rHraACAA8zpZ0knp8lOeVY2N9t1HABABKPAQNizzz8p5WTLu+Ymmeo1XcdBBTA1E+Rd82d5f75fsr78MXfKn/R/srt3uo4GAFWeMUbeZZmSJP+58bLWOk4EAIhUFBgIa/6iubIfzJXpd7FMq5Ncx0EFMyeeKu/eJ2TOvUj2w3eDF/lcNJcXywDgmEmqJ3PBFdLq5bIfvOs6DgAgQlFgIGzZ7zbLPj9BanWSTL9BruOgkpiYWHm/uULenWOleg1k/z1W2+8ZIbuZi3wCgEum57lSixNkX35a/vY813EAABGIAgNhyRYVyv/Xo1JUlLxrbpTxolxHQiUzjY6Td+vfZIYMV+GXX8i//0/yX54ou3eP62gAUCUZL0relX+UCvZp58THXMcBAEQgCgyEJTvlOWnDuuBFO+vUdR0HjhjPk9fzPCWPe0mmS2/Z2a/Lv+ta+Qtny/q+63gAUOWYBo1l+g5SwftZsh8tdh0HABBhKDAQduzqZbKzpsicda5M2hmu4yAEeAmJ8q64Xt4dj0pJ9WQn/Z/8h2+T3bDOdTQAqHLMORcq0KS5/Of+yaw4AEC5osBAWLE7tsn/92NSw6Yyv73adRyEGHNcS3m3PSxz1Z+k7C3yR90kf/I42V3crQQAKosJRKvWdXdIO7bJvvaM6zgAgAhCgYGwYX0/WF7k75P3+1tkYmJdR0IIMp4nr2tveQ9MkOl9vuz778i/c7j8uW/KFhe7jgcAVUJ0qxNl0vvLvjdD9ovVruMAACIEBQbChn1nmvTJCpmLh8o0bOI6DkKcia8u7+Jr5N39uNSkuewLT8p/4EbZL9a4jgYAVYIZcKmUXF/+M/+Q3V/gOg4AIAJQYCAs2K/Wyk55VkrrItP9bNdxEEZMwybybhwpb/it0t5d8h+5Xf6/xshuz3UdDQAimomNk3fF9VL2Ztk3XnIdBwAQASgwEPLsvr3y//WIdOBCjcYY15EQZowxMh26yrt/vEzfQbLLF8q/M1P+jP/JFhW6jgcAEcu0aSfTNV125hTZb9a7jgMACHMUGAh59oUJUk62vKE3y1Sv4ToOwpiJjZM38DJ59/1DOqGt7P+ekX/vCNnVy11HA4CIZX57tVQzQf4zT3AtIgDAMaHAQEjzF82V/eBdmf6DZVqe6DoOIoSp10BR198pb8Q9krXy/+9eFY8bJfv9VtfRACDimOo15A35g/TNl7KzprqOAwAIYxQYCFl2727ZF5+UWp0k0/e3ruMgApm2HeTd+4TMb66QPv1I/t3XyZ/2gmwBF5sDgPJk0rpIaWfITn9Rduu3ruMAAMIUBQZCln1vprRvr7yLh8p4Ua7jIEKZ6Gh5514kb+Q/ZdLOkH3jJfl3Z8ouWyhrret4ABAxvEv+IEVHy5/8D1nfdx0HABCGKDAQkmxhoezs6VKbdjJNWriOgyrAJCbJ+/3N8m5+UKoWL3/CaPlj75bd9LXraAAQEUztOsHrYXyxRnb+LNdxAABhiAIDIckufk/akScv4wLXUVDFmNYny7vrMZlLhkkb1sm/b4SKJ4yW3fSV62gAEPZM13SpTTvZ//1HNi/HdRwAQJihwEDIsb4vO3OK1Og46aT2ruOgCjJRUfJ69ZP34FMyfQdJn6yUf9+fVDz+QW4DCADHwBgj7/LrpOIi+S9M4FQ9AMARocBA6Fm9TNqyUSbjAhljXKdBFWaq1wzedvWhp2X6D5Y+WyV/5J9V/I8HZL9e6zoeAIQlUzdFZsBl0keLZZe+7zoOACCMUGAg5Pgzp0iJyTKdurmOAkg6cAvA84fIG/20zIAh0tpP5I+6ScWP3y/71Reu4wFA2DHp/aXjWsq++JTsnl2u4wAAwgQFBkKK/Wqt9MVqmfT+MoGA6zhAKSa+urx+g4NFxsDLpC8/l//gzSp+7B7Z9Z+5jgcAYcN4UfKuuF7avVP27f+5jgMACBO8Q0RIsTNfk6rFy3Q723UU4LBMtXiZvoNke/eTnfu27Kwp8kf/RWrTTl7/S2Ranug6IlBlrVy5UpMmTZLv++rdu7cGDhxYavnevXv1+OOPKzc3V8XFxerfv7969uzpKG3VZho3k+ncQ3buG7Lp/WVqJ7mOBAAIcczAQMiw32+VXb5Ipvs5MtXiXccBfpWJi5d37oXBGRkX/U7a9LX8h29T8aN/lf18tet4QJXj+74mTpyoO+64Q2PHjtWCBQu0adOmUuvMmDFDjRo10iOPPKJ7771Xzz77rIqKihwlhul/iVRcLPvmq66jAADCAAUGQoZ9Z5rkecHzYoEwYmLj5J19QfBin4OukbZukv/oHSp+5HbZTz/iKvtAJVm3bp1SUlJUv359BQIBdenSRUuWLCm1jjFG+fn5stYqPz9fNWrUkOfxcsgVU6+BzJl9ZOfPlP1+q+s4AIAQxykkCAl2907ZBVkynXswhRRhy8TGyvQZINvjHNn578jO+K/8v98lHX+ivP4XS21O5c46QAXKy8tTUtKPP0OSkpK0dm3pOwadc845evjhh/WHP/xB+/bt05///OfDFhhZWVnKysqSJI0ePVrJycnlmjcQCJT7NkPFkYyt+PJrlbNojmJmTVHCn+6q4GTHJlKPWaSOS4rcsTGu8BOpY6vscVFgICTYd9+S9hfIZFzgOgpwzExMrEzvfrLdM2Tff0f27f/JH3uP1OIEef0ulk5Ko8gAKsChZjv9/P/aRx99pKZNm+ruu+/Wd999p5EjR+qEE05QfPzBpy6mp6crPT295HFOTk655k1OTi73bYaKIxubkTmrr/Lfmar9Z/WVadikQrMdi0g9ZpE6Lilyx8a4wk+kjq2ixpWamnrI55kzCefs/gLZOW9KJ3cI6RctwJEy0THyevaVN+pJmUuvlbblyv+/++Q/dIvsx0s4tQQoZ0lJScrNzS15nJubq8TExFLrzJ07V507d5YxRikpKapXr542b95c2VHxM+acC6XYOPmvP+86CgAghFFgwDm7aK60a4e8s5l9gchkoqPlnXWuvFETZC6/Ttq5Xf4TI+XflSn/rVdl8yKvjQdcaNGihbZs2aLs7GwVFRVp4cKF6tixY6l1kpOTtWrVKknS9u3btXnzZtWrV89FXPyEqVlLps9Aafki2a/X/voXAACqJE4hgVPWL5adNVVqerzUuq3rOECFMoFome5ny3bpLbt4nuyCd2SnTJad+pzUpp1Ml94yp54uExvrOioQlqKionT11Vdr1KhR8n1fPXv2VOPGjTVr1ixJUkZGhi688EKNHz9eN910kyTp0ksvVa1atVzGxgGmzwDZuW/In/qcom64z3UcAEAIosCAWysXS9mbZYbdwjUBUGWYQECmSy+pS6/g7YMXzZFdOEf26TGy1eJlOp4p06W31OIE/l8ARygtLU1paWmlnsvIyCj5vE6dOrrzzjsrOxbKwFSLlzn3ItlXJ8l+vlqm9cmuIwEAQgwFBpzyZ02RkurJpHVxHQVwwtRNkTl/iGy/wdLaNbILZst++J7s/FlSvVSZLr1kzugpReBVqwHg58xZ58m+M03+1Mny/jKaEhcAUArXwIAzdt0n0vrPZPoMlImKch0HcMp4nkzrtvKuvkHemGdkrvqTVLuO7NTn5N82VNvu/ZP8D96VLShwHRUAKoyJiZXpN1ha96m0epnrOACAEMMMDDjjz5wiVa8pc2b6r68MVCEmLl6ma2+pa++SU0yKPnxPduLfZeOqyXTqFjwFpUUbfjsJIOKYrumyM1+TP2WyvJPSZDx+3wYACOInApywWzdJHy2WOetcmdg413GAkGXqpsg7f4iS//mqvJtHybQ/Q3bxPPl/u03+ncPlv/mKbO73rmMCQLkxgYDM+UOkjV/JLlvoOg4AIIQwAwNO2FlTpaiATK++rqMAYeGHU0xM67ayQ/4gu3xh8MKfU5+Tnfa8dMIpwetltO/CXUwAhD1zWjfZGf+Tnfa8bNoZnGoKAJBEgQEH7M5tsovmBt9s1Up0HQcIOyauWvAuJV1+OMVkbvBOJhPHysZNkOnQVebU06RWJ8vE13AdFwCOmPGi5A28VP64B2UXzZE5s4/rSACAEECBgUpn57wpFRfJ9BnoOgoQ9oJ3MblEtt/F0tpPZBfOll36vuyCLMl4UpPmMiecInPCKVLLEzllC0D4aNdZatZKdvqLsp3PkomOdp0IAOAYBQYqlS3Il333baldZ5mUhq7jABHDeJ7U+mSZ1ifLXpYpffm57Ocfy372sWzW67IzX5OiAlKzVj8WGs1b84YAQMgyxsi74HL5f79Ldt4Mmd79XUcCADhGgYFKZd/Pkvbsknf2Ba6jABHLREeXlBk6f4hsQb607tNgmfHZx7JvviL7xktSdIx0fJvgtTVOOEU6riXnmQMIKaZNO+mEU4Lft7qmy8RVcx0JAOAQBQYqjS0uln1nqtTiBJnj27iOA1QZJjZOOqm9zEntJUl2727pizU/FhpTn5OVpLhqUsuTfpyh0eg4bl8IwDlv4GXyR/9FdvZ0mb6DXMcBADhEgYFKY5cvlHKz5V081HUUoEoz8TWkUzvLnNpZkmR37ZA+X3Wg0Fglu2ppsNCoXlM6MDvDnHCKlNJQxhin2QFUPabFCVK702RnTpE96zyZ6lycGACqKgoMVAprrezMKVK9VKndaa7jAPgJUzNB6nimTMczJUk2L0f281XSDzM0li8MFhoJiTKt2wZnZjRoJKU0kuo24LQTABXOG3ip/PtvkJ35msxvrnAdBwDgSMgUGCtXrtSkSZPk+7569+6tgQNL36HCWqtJkyZpxYoVio2NVWZmppo3b+4oLY7Y56ukDetkLstkSjoQ4kydZJkzekpn9JS1Vsr5Tvazj4OFxhdrpMXzgoWGFLwwaL0GUoNGMimNfvyY0ohz1QGUG9OomUyn7rKzp8v27i+TwG3YAaAqCokCw/d9TZw4UXfeeaeSkpJ0++23q2PHjmrUqFHJOitWrNDWrVv1+OOPa+3atXr66af14IMPOkyNI+HPnCLVTAi+KQIQNowxUt0UmbopUrcMSZLdu0f67lvZLRulrZtkt2ySNn8ju/JDyfd/LDcSk4OnnTRoHCw0fpi1kZDIqSgAjpgZcIns0vmyb70qc8kw13EAAA6ERIGxbt06paSkqH79+pKkLl26aMmSJaUKjKVLl6p79+4yxqhVq1bas2ePtm3bpsREGvhQZ7/dIK1eJjNgiExMrOs4AI6Ria8evB1rs1alnrdFhdL3W6UtG4OlxoFywy6YLRXs+7HYqFb9kMWGTaxd6WMBED5MvVSZM/vIvjdDNmOgTFI915EAAJUsJAqMvLw8JSUllTxOSkrS2rVrD1onOTm51Dp5eXmHLDCysrKUlZUlSRo9enSprysPgUCg3LcZaspzjDtemKD82Dgl/+ZyebUSymWb5YVjGRkYYwhJaSC1bV/qKWut/NzvVbTpaxV/u0FFmzYEP//0I/kLZ5cUG9lelLxaCfJq1ZaXkCiTUFterUR5CYkHnqv9k8/ryFSvEZanpIXNsQRCkOl7sezCObLTX5S56k+u4wAAKllIFBjW2oOe+/n04rKs84P09HSlp6eXPM7JyTnGhKUlJyeX+zZDTXmN0W7LlT9vlkz3s5W3v1AKsf3GsYwMjDEceFKj5sE/wZufyEjy9u6Wtn4ru2WT4ndv197vtqho1w5p1w7puy3Bj/v2HGaTnlSjllQzIXiK2oGPqllLqllbpmYtqUaCVCsheEeVmFgpOsZ56RH+x/KXpaamuo6ACGbqJMv0PE82a7rs2RcGZ3ABAKqMkCgwkpKSlJubW/I4Nzf3oJkVSUlJpV7wHWodhB47+3XJ92X6DHAdBUAIMvE1pOatZZq3Vo3kZOUf4o29LSqUdu0Mlhm7d8juDH784Tl7oPCwG9YFnztQeBxcex8QCEjRsVJ0tBQdU1JsKCam5LGJjvnJc7E/WVb6sYmJkQLRkvGChYoxBz7+7HPPlHws2rNDdufOw69b6nMFH1eEqAAXWkVYMudeJDtvluy052WG3+o6DgCgEoVEgdGiRQtt2bJF2dnZqlOnjhYuXKgRI0aUWqdjx46aMWOGunbtqrVr1yo+Pp4CI8TZfXtl582U6dAleAFAADgKJhAtJSYF/yj4nv6X2MJCafeBwuOHgmPPbqmwQNq/Xyo88Gd/gVS4X3b/Tx4X5Eu7dsoW7i+9/v79kvUP/ruOYjy5v75KpTCn9ZD5/U2uYwBHzNRMkOkzQPaNl2Q3rJdp2sJ1JABAJQmJAiMqKkpXX321Ro0aJd/31bNnTzVu3FizZs2SJGVkZKh9+/Zavny5RowYoZiYGGVmZjpOjV9j58+U9u2VOfsC11EAVCEm+sgKj7Kw1krFRcEio2h/6WKjqDBYbvj2wEdfsvbHjz97rmaNGtq5c8eB537l6w5x+mR5MfUbVti2gYpm+gyQnfum/KnPKepP97iOAwCoJCFRYEhSWlqa0tLSSj2XkZFR8rkxRkOHDq3sWDhKtqhINmu61LqtzHEtXccBgGNijAmeKhKIllT9mLYVl5ys3RF8DQygMpj46jLnXij73//IfrFGptVJriMBACpB+F2+HWHBLpkvbcuRx+wLAABQAcxZfaWEOvKnTD7kxd4BAJGHAgPlzlorO/M1KbWJdHIH13EAAEAEMrGxMv0GSes+kdYsdx0HAFAJKDBQ/taskL7dIJNxwWFvdQsAAHCszJl9pOT6wVkY/sEX2gUARBYKDJQ7f9YUqXYdmc7dXUcBAAARzASiZc4fIn3zpbRikes4AIAKRoGBcmU3rJc+/Uimd//grQ8BAAAqkOncXWrQWP7U52WLi13HAQBUIAoMlCs7a4oUV02m+zmuowAAgCrAeFHyBl4mbd0k+8G7ruMAACoQBQbKjc3Nll36vky3DJn4Y7vNIAAAQJm1P11qerzs9BdlCwtdpwEAVBAKDJQb+840yRiZ9PNdRwEAAFWIMUbeby6XcrNl5890HQcAUEEoMFAu7J7dsu+/I9Opm0yduq7jAACAqqbNqVLrtrJvviJbkO86DQCgAlBgoFzYd9+SCvJlMi5wHQUAAFRBxpjgtTB2bped84brOACACkCBgWNmC/cHXyic2F6mcTPXcQAAQBVljm8jndJJdsb/ZPfucR0HAFDOKDBwzOwH70o7t8s7m9kXAADALW/AEGnvHtnZ011HAQCUMwoMHBNrbfAFQuNmUpt2ruMAAIAqzjRpIZ16umzWNNm9u13HAQCUIwoMHJtvv5a+3SDT7WwZY1ynAQAAkNd/cHAWRhazMAAgklBg4JjYxfMkz5Pp2NV1FAAAAEmSadJcan+6bNbrzMIAgAhCgYGjZq2VXTxfOvFUmZoJruMAAACU8PpfIu3bI5v1uusoAIByQoGBo7f+Myk3W+a0Hq6TAAAAlGIaN5PSzgjOwtjDLAwAiAQUGDhqdvF7UnSMTPvOrqMAAAAcxOs/WNq3VzZrmusoAIByQIGBo2KLi2WXLpA5pZNMXLzrOAAAAAcxjZpJHbocmIWxy3UcAMAxosDA0fn0I2nXDpnTurtOAgAAcFhev8FS/j7Zd5iFAQDhjgIDR8UunidVqy617eA6CgAAwGGZRsfJdOgqO3s6szAAIMxRYOCI2f0FsisWyaSdLhMd4zoOAADALzL9B0sF+bKzprqOAgA4BhQYOHKrlkn5+7j7CAAACAumYdMDszDekN2903UcAMBRosDAEfMXvyfVqi2d0NZ1FAAAgDIx/QdL+5mFAQDhjAIDR8Tu3SN9vFSmUzcZL8p1HAAAgDIxqU1kOp4pO+dN2V3MwgCAcESBgSNiV3wgFRXKdOrmOgoAAMARMf0uDs7CeGeK6ygAgKNAgYEjYhfPk5LrS81bu44CAABwRExqE5lO3Q7MwtjhOg4A4AgFXAdA+LA7t0mffiRz7oUyxriOAwDAQVauXKlJkybJ93317t1bAwcOPGidNWvW6D//+Y+Ki4tVs2ZN3XfffQ6SwhXTb7DskvmyM6fIXHSV6zgAgCNAgYEys0sXSNbn7iMAgJDk+74mTpyoO++8U0lJSbr99tvVsWNHNWrUqGSdPXv26Omnn9Zf//pXJScna8cOfgtf1ZgGjWQ6dZed+6ZsxkCZWrVdRwIAlBGnkKDM7OJ5UsOmMg2buI4CAMBB1q1bp5SUFNWvX1+BQEBdunTRkiVLSq3z/vvvq3PnzkpOTpb+v707j4+6uvc//j6TAUIghDBhC5tsYVFUQgBBMQIx162ItnXXIuVaixaX1la8FW0pmqpcvNzi0qs/RLu5Y+11wbgkCCphEwVFwwUVBUN2SAIkmfP7IxCJSSBAkjPzndfz8eCRme+cmbwP30xy8sk55yspLi7ORVQ4Zn5wqVRZKbuMvTAAIJxQwECT2F07pS2fyoxl9gUAIDQVFhYqEAjU3g8EAiosLKzTZseOHdqzZ4/uvvtu/eY3v1FWVlZrx0QIMD16y4w9U/btV2RLi13HAQA0EUtI0CQ2Z7kkcfURAEDIstbWO/b9PZuqq6u1detW3Xnnndq/f79++9vfavDgwUpMTKz33MzMTGVmZkqSMjIyamdtNBe/39/srxkqwqFvVVddr4JV2YrOflWx037RpOeEQ7+OhVf7JXm3b/Qr/Hi1b63dLwoYaBK7KlsaOFQmobvrKAAANCgQCKigoKD2fkFBgeLj4+u1iY2NVXR0tKKjozVs2DB98cUXDRYw0tLSlJaWVns/Pz+/WfMmJCQ0+2uGirDoW7sYmTGpKn/1ee098xyZTvFHfEpY9OsYeLVfknf7Rr/Cj1f71lL9aujnssQSEjSB3b5N+voLmTFnuo4CAECjBg4cqB07digvL09VVVVauXKlUlJS6rRJSUnRp59+qurqau3bt0+5ubnq1auXo8RwzVxwqVRZJfvaC66jAACagBkYOCK7Klvy+WRSTncdBQCARkVFRWn69OmaN2+egsGgJk6cqD59+mjZsmWSpPT0dPXu3VunnnqqfvWrX8nn82nSpEnq25fNqSOV6Z4oc1qqbNarsv92sUzckWdhAADcoYCBw7LW1hQwhp7SpKmVAAC4lJycrOTk5DrH0tPT69yfMmWKpkyZ0pqxEMLMBZfKfpAl+9oLMpf+1HUcAMBhsIQEh/d/m6WCPJmxLB8BAADeY7olypw2sWYWRnHhkZ8AAHCGAgYOy67KlvxtZEaOcx0FAACgRZjzL5Gqq2Rfe951FADAYVDAQKNsdXXN5VNPHi3TPsZ1HAAAgBZhuvWUGTdRNvt1ZmEAQAijgIHGbd4g7S6Rj+UjAADA48x5zMIAgFBHAQONsh9kS+1jpBEpR24MAAAQxmpmYUySzXpNtqjAdRwAQAMoYKBBdv8+2XXvyYwcJ9Omres4AAAALc6cf4lkg7KvPuc6CgCgARQw0KB9a96TKsplxrB8BAAARAbTtUfNLIzlrzMLAwBCEAUMNGjv8jek2Dhp6MmuowAAALSamlkYVvbVZ11HAQB8DwUM1GMryrVv9QqZlDNkoqJcxwEAAGg1JqG7zPjJssuXyRbuch0HAHAIChiox657X6rcLzM21XUUAACAVmfO+/GBWRhckQQAQonfdQCEHrsqS75uPaUBQ1xHAQBEkOLiYm3YsEHbtm1TeXm5YmJidMIJJ+jkk09W586dXcdDBDEJ3WVOT5N9d5nsuT+U6dLVdSQAgJiBge+xpcXSJx8qesLZMsa4jgMAiADbt2/X/Pnzdeuttyo7O1vV1dXq3LmzqqurlZ2drVtvvVXz58/X9u3bXUdFBKmZhSHZV9gLAwBChfMZGHv27NGCBQu0a9cude3aVbfccos6duxYp01+fr4WLVqk4uJiGWOUlpam8847z1Fib7NrVkjBoKInnK19rsMAACLCQw89pClTpmjWrFlq06ZNvcerqqqUk5Ojhx9+WPPmzXOQEJHIBLodmIWRKXvuj2UCzMIAANecFzCWLl2qESNGaOrUqVq6dKmWLl2qq666qk6bqKgoXX311RowYIAqKip0++236+STT1bv3r0dpfYuuypb6tVPbfoNlPLzXccBAESAe+6557CP+/1+jRs3TuPGjWulREANc96PZVdkyr7yrMzVM13HAYCId8QlJNXV1frggw/08MMP6/bbb9cvfvEL3X777Xr44Yf1/vvvq7q6+rgC5OTkKDW1ZrPI1NRU5eTk1GsTHx+vAQMGSJLat2+vXr16qbCw8Lg+L+qzBXlS7icyoye4jgIAiFD33Xdfg8cfeOCBVk4CSCbQVWbC2TVFjII813EAIOIddgbGG2+8oRdeeEG9e/fWsGHDNGrUKEVHR2vv3r3avn273nzzTS1ZskQXXXSR0tPTjylASUmJ4uPjJdUUKkpLSw/bPi8vT1u3btWgQYMabZOZmanMzExJUkZGhhISEo4pW2P8fn+zv2YoKMt+VXskBc6Z6tk+fl8k9JM+egN99I5I6eex2rhx41EdB1qaOfdHsu++UbMXxpC7XMcBgIh22ALGjh07dO+99za48/eYMWMkSUVFRXr55ZcP+0nmzp2r4uLiescvu+yyo8mqvXv3av78+Zo2bZpiYmIabZeWlqa0tLTa+/nNvBQiISGh2V8zFFS//ao0YIiKotoqoarKk338Pq+ey0PRR2+gj97h9X4mJiYe0/OefvppSTX7XRy8fdC3336rrl3ZfwBumC5dZc5Il13+uqqvvE7y1d+nBQDQOg5bwLjmmmuO+ALx8fFHbHfnnXc2+lhcXJyKiooUHx+voqIiderUqcF2VVVVmj9/viZMmKCxY8ceMReOjv36S2n7NpnLrnMdBQAQgQoKCiRJwWCw9vZBCQkJuuSSS1zEAiQdnIWxTHueWSwxVgIAZ5q8iee1116rxYsX1zs+Y8YMPRG864EAACAASURBVPbYY8ccICUlRVlZWZo6daqysrI0evToem2stXrkkUfUq1cvXXDBBcf8udA4uypbMj6Z0ae7jgIAiEAzZ9ZskJiUlFRnFiUQCkyXBJnUc7X37f+VL/VcmZ59XEcCgIh0xE08D2pos86qqioFg8HjCjB16lRt2LBBs2bN0oYNGzR16lRJUmFhoe69915J0ubNm5Wdna2PP/5Yt912m2677TatXbv2uD4vvmOtlc3JloadLNMp3nUcAECEKSkpqb19uOJFQ8tRgdZizr9Epl20gi885ToKAESsI87AmDNnjowxqqys1F131d24qKCgQElJSccVIDY2VnPmzKl3vEuXLpo9e7YkaejQoXrmmWeO6/PgMLZ+Ju3aKXM+03MBAK3vd7/7nYYPH64zzzxTgwYNks/33d9XgsGgcnNzlZ2drU8++UTz5893mBSRzMTGqf1FV6rsb/8jm7tJZtBw15EAIOIcsYAxadIkSVJubq4mTpxYe9wYo7i4OJ100kktlw6twq7KlvxtZEaOcx0FABCB7rvvPmVmZurRRx9VXl6eunXrpvbt26uiokJ5eXnq0aOHzj77bE2bNs11VES4Dj+4TGX/+5yCzy+R79cZMsa4jgQAEeWIBYyzzjpLkjR48GD16tWrpfOgldlgtWzOcmnEKJmYDq7jAAAikN/v1znnnKNzzjlH+fn5+vLLL1VeXq4OHTqoX79+6tKli+uIgCTJRLeX+cHlsn95SPpwlXQqG8sDQGs67B4Yq1evrr19uOLFoe0QZj79SCotlm9squskAAAoISFBycnJOuOMMzRy5EiKFwg55vQ0qXsvBV94UraBPeIAAC3nsDMwVqxYob///e8644wzNHz4cCUmJtZO6dyxY4c2bdqk5cuXq1+/fkpJSWmtzGhGdlW2FN1eGsH5AwC4V1lZqeeee04rVqzQ7t27tWTJEn344YfasWOHzjnnHNfxABm/X76LrlbwkQzZ996SOeNs15EAIGIctoBx00036csvv9Qbb7yhP/3pT8rLy6t9rEePHho5cqRuvvlm9enDpaTCka2slF37nszI02TatnMdBwAALVmyRIWFhZo1a5buueceSVKfPn20ZMkSChgIHcnjpP5Jsi/9TXb0mTLtGEcBQGs44h4Yffv21U9/+lNt27ZNPXv2VFlZmTp06KB2fKMOfx+vkSrKZMawfAQAEBpWrVqlhQsXKjo6unaDxC5duqiwsNBxMuA7xhj5fjhNwQfukH3rXzLn/tB1JACICEcsYBz0xz/+Ufv27dPQoUM1fPhwDR8+XP3792f35TBmP8iSYuOkYae4jgIAgKSaDT2DwWCdY6WlpYqNjXWUCGiYGXKSNCJF9tXnZM9Ml+nA1ygAtLTDbuJ5qIcfflj33nuvxowZoy+//FILFizQtddeq4yMjJbMhxZi95bLbsiRSTldJirKdRwAACRJp512Wp1lq0VFRXr88cc1fvx4x8mA+nwXXyPtLZd95TnXUQAgIjS5gCFJ3bt3V1JSkpKSkjR48GD5fD6VlJS0VDa0ILvuA6lyv8yYM11HAQCg1hVXXKFu3brpl7/8pcrLyzVr1izFx8frRz/6ketoQD2m9wkyp02UfetfsgW7XMcBAM9r8hKSBx98UJs3b1aXLl00fPhwnXHGGfr3f/93tW/fviXzoYXYVdlSoJs0YKjrKAAA1PL7/Zo2bZqmTZtWu3SE5aoIZebCK2Vzlsu+9FeZ6Te7jgMAntbkGRhbtmyRz+dTv3791K9fP51wwgkUL8KU3V0ibVonM3qCjO+oJuEAANCirr322trbnTp1qi1ezJgxw1Uk4LBMoKvMpAtk339bdvs213EAwNOaPAPjv//7v1VcXKxNmzZp06ZNeumll7R//34NGzZM119/fUtmRDOza1ZIwaDMWJaPAABCS3V1db1jVVVV9Tb2BEKJOe9HssuXKfjCk4qaNcd1HADwrCYXMCSpc+fOSkxMVGFhoQoLC7Vx40atW7eupbKhhdgPsqWefaReJ7iOAgCAJGnOnDkyxqiyslJ33XVXnccKCgqUlJTkKBlwZKZDrMy5P5J9YYns5o9rrlACAGh2R3UZ1U8//VTt27fX8OHDNWrUKF199dXq2bNnS+ZDM7MFu6TcTTJTr2JNMQAgZEyaNEmSlJubq4kTJ9YeN8YoLi5OI0aMcBUNaBIz+QLZt/6l4PNPyDf7fsZZANACmlzAGDt2rK699lp169atJfOghdmcbEmSGT3BcRIAAL5z1llnSZKWL1+unj17asiQIbWPbd68WU899ZSmTZvmJhzQBKZtO5kLr5Bd8t/S2vekUVz6FwCaW5N3cDzrrLMoXniAXZUt9U+S6cbMGQBA6Nm2bZsGDhxY59iAAQP07rvvOkoENJ0ZN0nq2UfBF5+SrapyHQcAPIdLUEQQu+Mr6autMmPYvBMAEJqMMfU27AwGg7LWOkoENJ2JipLv4mukb7+WffcN13EAwHMoYEQQuypbMj6ZlDNcRwEAoEFDhw7VP/7xj9oiRjAY1LPPPquhQ4c6TgY00SljpEHDZV/+u+zeCtdpAMBTKGBECGut7AdZ0tARMp27uI4DAECDrr32Wn300Uf62c9+ptmzZ+tnP/uZNmzYoOnTp7uOBjSJMUa+H/5EKi2Wzfyn6zgA4ClHdRlVhLFtudKunTLn/dh1EgAAGhUIBPTHP/5Rubm5KigoUCAQ0KBBg+Tz8TcXhA8zaJh06mmyr78gm3qOTGyc60gA4AmMBiKEXZUl+f0yyeNcRwEA4LB8Pp+SkpI0btw4JSUlUbxAWPJdfLW0b5/s/z7jOgoAeAYjgghgg0HZNSulE5NlYjq6jgMAAOB5pmcfmTPSZN95VXbXTtdxAMATKGBEgq2fSUX5Mimnu04CAAAQMcwPLpeifLJL/+o6CgB4AgWMCGDXrpSi/DInj3YdBQAAIGKY+IDM5Cmyq7Jkv9ziOg4AhD0KGB5nra1ZPjL8VJaPAAAAtDJzzsVSh1gFn3/SdRQACHsUMLzuyy1SQZ7MqPGukwAAAEQcE9NR5vxLpE3rZDetdx0HAMIaBQyPs2tWSFFRMqeOdR0FAAAgIpmzzpMC3RR8folsMOg6DgCELQoYHla7fGTIyTIdYl3HAQAAiEimTRuZC6+Uvtwiu/pd13EAIGxRwPCy7dukvB0yo8a5TgIAQKtYv369brrpJv3iF7/Q0qVLG22Xm5urSy+9VO+//34rpkMkM2PPlHqfILv0L7JVla7jAEBYooDhYXbNCsn4ZE49zXUUAABaXDAY1OOPP6477rhDCxYs0IoVK7R9+/YG2/31r3/Vqaee6iAlIpXxRcn3w59Iu3bKZr3uOg4AhCUKGB5m174nJZ0o06mz6ygAALS43Nxc9ejRQ927d5ff79f48eOVk5NTr92rr76qsWPHqlOnTg5SIqKdmCwNGSH7r3/IVpS7TgMAYcfvOgBahv3mS2nHVzITz3cdBQCAVlFYWKhAIFB7PxAI6PPPP6/XZtWqVbrrrrv08MMPH/b1MjMzlZmZKUnKyMhQQkJCs+b1+/3N/pqhwqt9a45+Vf70JhX+eobav7tMHS+f0UzJjo9Xz5fk3b7Rr/Dj1b61dr8oYHiUXbNSMkZmJMtHAACRwVpb75gxps79J554QldeeaV8viNPQk1LS1NaWlrt/fz8/OMPeYiEhIRmf81Q4dW+NUu/4rvJjDpdZS/9TRVjUmXi4psn3HHw6vmSvNs3+hV+vNq3lupXYmJig8cpYHiUXbNCGjhMpnMX11EAAGgVgUBABQUFtfcLCgoUH1/3l8MtW7bov/7rvyRJpaWlWrdunXw+n8aMGdOqWRHZzEVXy65/X/Zf/5C58ueu4wBA2KCA4UF259fS11/IXBoa0xIBAGgNAwcO1I4dO5SXl6cuXbpo5cqVmjVrVp02ixYtqnN71KhRFC/Q6kz3RJkJ/yab/Zrs5CkyPXq5jgQAYYFNPD3Irl0pSTLJXD4VABA5oqKiNH36dM2bN0+33HKLxo0bpz59+mjZsmVatmyZ63hAHeaCS6U2bWWX/sV1FAAIG8zA8CC7ZqU0YIhMl66uowAA0KqSk5OVnJxc51h6enqDbW+44YbWiAQ0yMTFy5w9teaKJP+3WWbAENeRACDkMQPDY+yundKXW2RGjXcdBQAAAIdh/m2qFNdFwb88JFtd7ToOAIQ8ChgeU7t8ZCTLRwAAAEKZiY6R7/LrpK+2ymb+03UcAAh5FDA8xq5ZKfUbJNO1h+soAAAAOJLkcdIpY2T/+deambQAgEZRwPAQW7BL2voZy0cAAADChDFGviuul0yUgn95WNZa15EAIGRRwPAQu+7g1UcoYAAAAIQL0yVB5uKrpU3rZD/Ich0HAEIWBQwPsWtWSr37y3RPdB0FAAAAR8Gcda7UP0n26cdk95S6jgMAIYkChkfYogIp9xOZUWzeCQAAEG6ML0q+a26QKspkn13sOg4AhCQKGB5h170nSTKjTnecBAAAAMfC9O4vk36R7Mo3ZT/50HUcAAg5FDA8wq59T+rZR6ZnH9dRAAAAcIzMBZdK3Xoq+NQi2f37XMcBgJBCAcMDbGmR9NlGZl8AAACEOdO2nXxXzZR27ZT919Ou4wBASKGA4QF23QeSDXL5VAAAAA8ww06RGT9ZdtmLstu3uo4DACHDeQFjz549mjt3rmbNmqW5c+dqz549jbYNBoP69a9/rYyMjFZMGPrsmhVS915Sr36uowAAAKAZmB9fK8V0VPDJRbLBatdxACAkOC9gLF26VCNGjNDChQs1YsQILV26tNG2r7zyinr16tWK6UKf3VMqbf5IJnmcjDGu4wAAAKAZmI6dZC6dIW39TPadV13HAYCQ4LyAkZOTo9TUVElSamqqcnJyGmxXUFCgtWvXavLkya0ZL+TZ9R9IwSD7XwAAAHiMGXOmdOJI2Reeki3c5ToOADjndx2gpKRE8fHxkqT4+HiVlpY22O6JJ57QVVddpYqKiiO+ZmZmpjIzMyVJGRkZSkhIaL7Akvx+f7O/5rEq+mi1qrsnKpA8pllnYIRSH1tSJPSTPnoDffSOSOkngONnjJHvyp8rePeNCv7tUflu+A9m3AKIaK1SwJg7d66Ki4vrHb/sssua9Pw1a9YoLi5OAwYM0MaNG4/YPi0tTWlpabX38/Pzmx62CRISEpr9NY+FLduj4Ic5Mmk/UEFBQbO+dqj0saVFQj/pozfQR+/wej8TExNdRwA8xXTtITPlStnnFktr35PYtB1ABGuVAsadd97Z6GNxcXEqKipSfHy8ioqK1KlTp3ptNm/erNWrV2vdunXav3+/KioqtHDhQs2aNaslY4c8++EqqbqK5SMAAAAeZtKmyK7KUvDvf5Zv2MkyMR1dRwIAJ5zvgZGSkqKsrCxJUlZWlkaPHl2vzRVXXKFHHnlEixYt0s0336yTTjop4osXkmTXrpS6JEgnDHYdBQAAAC3EREXJd82NUmmx7PNPuo4DAM44L2BMnTpVGzZs0KxZs7RhwwZNnTpVklRYWKh7773XcbrQZSvKpY3rZJLHsxYSAADA40y/QTJpP5DNfk32802u4wCAE8438YyNjdWcOXPqHe/SpYtmz55d7/iJJ56oE088sTWihTS7IUeqqpRhHSQAAEBEMFOukF37noJPLZLvzgdl2rRxHQkAWpXzGRg4NnbtSimuizRgqOsoAAAAaAUmur18V/5c2vGV7GvPu44DAK2OAkYYsnsrpI/WyCSPk/FxCgEAACKFGTFKZsyZsq88I7tju+s4ANCq+O03HH28Rqrcz/IRAACACGQu/anUNlrBp/4kGwy6jgMArYYCRhiya9+TYuOkwcNdRwEAAEArM53iZX58rfT5Jtl333AdBwBaDQWMMGP375PdkCMzcpyML8p1HAAAADhgTk+ThoyQfe4J2eJC13EAoFVQwAg3G9dJ+/ayfAQAACCCGWPku2qmVLlf9unHXMcBgFZBASPM2DUrpI6xUtJJrqMAAADAIdOjl8wFl8quflf2wxzXcQCgxVHACCO2srJm+cgpY2X8ftdxAAAA4Jj5t4ukxL4K/u1h2b3lruMAQIuigBFOPlkvVZTLjDrddRIAAACEAONvI981N0pFBbJL/+o6DgC0KAoYYcSuWSm17yANO9l1FAAAAIQIM3CoTOq5sm/9S3brZ67jAECLoYARJmxVpez692VOHSPjb+M6DgAAAEKIufgaKa6Lgk8ukq2qch0HAFoEBYxw8elHUnkZy0cAAABQj2kfI98VP5O2b5XNfMl1HABoERQwwoRdu1Jq114afqrrKAAAAAhBZuRp0sjTZP/5d9m8Ha7jAECzo4ARBmx1tey692VOGS3Tpq3rOAAAAAhRvst/Jvn9Cv7lIVlrXccBgGZFASMcfPaxtKdUZtR410kAAAAQwkx8QObin0iffCj7+guu4wBAs6KAEQbs2pVS23bSiaNcRwEAAECIM6nnyIyeIPvCk7Ifr3EdBwCaDQWMEGeD1bJr35MZkSLTrp3rOAAAAAhxxhiZn/xC6nWCgv/zgGzeN64jAUCzoIAR6nI/kUqLJZaPAAAAoIlMu2j5brhD8vkUXHSP7N5y15EA4LhRwAhxdu17Upu2MiNYPgIAAICmMwnd5bvu19LO7Qr+vwdlg0HXkQDguFDACGE2GJRds1I6MVkmOsZ1HAAAAIQZM+wUmR9fK617X/aVZ13HAYDjQgEjlG39TCou4OojAAAAOGZm8hSZ0ybK/vNvsh+uch0HAI4ZBYwQZteskPx+mZNHu44CAACAMGWMkbl6ptR3oIKP/6fsju2uIwHAMaGAEaKstTX7XwwfKRPTwXUcAAAAhDHTtp18M2dL/jYKPjRPtrzMdSQAOGoUMELVF7lSQZ5MMstHAAAAcPxMl67yXf8badfOmpkYbOoJIMxQwAhRds1KKSpK5tQxrqMAAADAI0zSSTKXzpA25Mi+/HfXcQDgqFDACEHW2pr9L4aeLNMh1nUcAAAAeIg56zyZ09Nk//W07NqVruMAQJNRwAhFX22Vdu2UGXW66yQAAADwGGOMzJXXS/2TFPx/D6rqiy2uIwFAk1DACEF2zUrJ55M59TTXUQAAAOBBpk1b+X4+W4pur+KM22XL9riOBABH5HcdAHXVXH1khZR0kkxsJ9dxAAAIK+vXr9fixYsVDAY1efJkTZ06tc7jy5cv10svvSRJio6O1owZM3TCCSc4SAq4Z+ID8l1/u6rn/4f0P/fLN2uOjC/KdSwAaBQzMELNN19JO7+WGcXVRwAAOBrBYFCPP/647rjjDi1YsEArVqzQ9u3b67Tp1q2b7r77bj3wwAP64Q9/qD//+c+O0gKhwQwapth//6W0cZ3si39xHQcADosCRoixa1ZIxsiMHOc6CgAAYSU3N1c9evRQ9+7d5ff7NX78eOXk5NRpM2TIEHXs2FGSNHjwYBUUFLiICoSUmPQLZVLPkX3teQVzlruOAwCNYglJiLFrV0qDh8vExbuOAgBAWCksLFQgEKi9HwgE9Pnnnzfa/q233tLIkSMbfTwzM1OZmZmSpIyMDCUkJDRfWEl+v7/ZXzNUeLVvXu5X1xtmq+jbb1T5xELFDT1JbfoPdh2rWXj5nNGv8OLVvrV2vyhghBC7c7v09Rcyl13nOgoAAGHHWlvvmDGmwbYff/yx3n77bf3+979v9PXS0tKUlpZWez8/P//4Qx4iISGh2V8zVHi1b17uV0FJieyMX0p/uFWF826T7z/+0xP7sXn5nNGv8OLVvrVUvxITExs8zhKSEGJXr5AkmWSWjwAAcLQCgUCdJSEFBQWKj68/o/GLL77Qo48+qttuu02xsbGtGREIaSYuXr6Zd0glRQr++T7Z6mrXkQCgDgoYIcJWV8suf10aMkImPnDkJwAAgDoGDhyoHTt2KC8vT1VVVVq5cqVSUlLqtMnPz9cDDzygG2+8sdG/7gCRzPQfLHPVTOnTDbLPPeE6DgDUwRKSULHuPakwX77LWT4CAMCxiIqK0vTp0zVv3jwFg0FNnDhRffr00bJlyyRJ6enpeu6557Rnzx499thjtc/JyMhwGRsIOb7TJyv41f/JZr6kYN8B8o2b6DoSAEiigBEygm++LHXtIZ082nUUAADCVnJyspKTk+scS09Pr719/fXX6/rrr2/tWEDYMT+6Vnb7Ntkn/yTbs7fMCd7Y1BNAeGMJSQiw2z6Xcj+RmXS+jC/KdRwAAABEOOP3y/ezX0udOiv40L2ypUWuIwEABYxQYN98WWrXXmZ82pEbAwAAAK3AxMbJd8MdUlmpgo/8UbaqynUkABGOAoZjtrhQNuddmdMny8R0cB0HAAAAqGX6DpS55hfS55tkn3nMdRwAEY49MByzWa9JwWqZSRe4jgIAAADU4xubquCX/ye77EUF+wyQb0L6kZ8EAC2AAoZDtrJSNutV6aRRMt25lBsAAABCk7n4mppNPZ96SMFgUL7Uc1xHAhCBWELikM3JlnaXyJc2xXUUAAAAoFEmKkq+mbOlk5Jl//KQgi//Q9Za17EARBgKGI5Ya2Uz/ykl9pWGneI6DgAAAHBYpl20fDPvkBk3Sfaff5P92yOywWrXsQBEEJaQuPL5RumrrTJXz5QxxnUaAAAA4IiM3y9de5PUOV721edlS0vkm3GrTJu2rqMBiADMwHAk+ObLUodYmbETXUcBAAAAmswYI9/FP5G59KfS2pUKPni3bHmZ61gAIgAFDAds/rfSug9kJqTLtGvnOg4AAABw1HxpF8rM+KW05VMF779DtrjQdSQAHkcBwwH79iuSkczE81xHAQAAAI6Zb2yqfLPulHbtUDDj17I7v3YdCYCHOd8DY8+ePVqwYIF27dqlrl276pZbblHHjh3rtSsrK9Mjjzyir776SsYY/fznP1dSUpKDxMfH7q2QXb5MJnm8TJeuruMAAAAAx8UMHynfr+YpuPD3Cv7xN/LNukum/2DXsQB4kPMZGEuXLtWIESO0cOFCjRgxQkuXLm2w3eLFi3XqqafqwQcf1P33369evXq1ctLmYd97W6ook5n8A9dRAAAAgGZhThgs32/+KEW3V3D+f8h+vNZ1JAAe5LyAkZOTo9TUVElSamqqcnJy6rUpLy/XJ598okmTJkmS/H6/OnTo0Ko5m4MNBmXfelnqN0gaONR1HAAAAKDZmO6J8t1+n9S1p4J/mqvg+++4jgTAY5wvISkpKVF8fLwkKT4+XqWlpfXa5OXlqVOnTnrooYf0xRdfaMCAAZo2bZqio6MbfM3MzExlZmZKkjIyMpSQkNCsmf1+/zG95r6176t459fqdNMcte8a2stHjrWP4SYS+kkfvYE+ekek9BNAZDJx8fLddo+CD90j+/h/KlhaLF/6VNexAHhEqxQw5s6dq+Li4nrHL7vssiY9v7q6Wlu3btX06dM1ePBgLV68WEuXLm30+WlpaUpLS6u9n5+ff2zBG5GQkHBMr1n94l+kuHjtGXqKypo5U3M71j6Gm0joJ330BvroHV7vZ2JiousIABwzMR3ku+luBR+fL/vs/1OwtEjm4p/I+JxP/gYQ5lqlgHHnnXc2+lhcXJyKiooUHx+voqIiderUqV6bQCCgQCCgwYNrNgM67bTTGt0rI1TZHdulj9fKTLlCxt/GdRwAAACgxZg2beS77jbZf/yP7OsvSiXF0k9+IeN3PgEcQBhzXgZNSUlRVlaWJCkrK0ujR4+u16Zz584KBAL65ptvJEkfffSRevfu3ao5j5d962XJ75dJPcd1FAAAAKDFGV+UzOU/k7nwStn331Zw0TzZfXtdxwIQxpwXMKZOnaoNGzZo1qxZ2rBhg6ZOrVkjV1hYqHvvvbe23fTp07Vw4UL96le/0rZt23TRRRe5inzUbNke2ZVvyYxJlenU2XUcAAAAoFUYY+S74FKZa26UNq5TcP5vZXfX3/MOAJrC+Ryu2NhYzZkzp97xLl26aPbs2bX3TzjhBGVkZLRmtGZj331D2r+PS6cCAAAgIvkmpMvGdlLwzw8oeN9v5Lv5dzKBbq5jAQgzzmdgeJ2trpZ9+3+lpBNl+g5wHQcAAABwwpx6mny3/F4qLVYw49ey27e5jgQgzFDAaGkffiAV5MnH7AsAAABEODN4uHy/zpBkFLxvtuxnG11HAhBGKGC0sGDmP6VAN+nUsa6jAAAAAM6ZXv3ku/0+KS5ewQVzZNe97zoSgDBBAaMF2S+3SJ9vkpl0vowvynUcAAAAICSYQFf5fpMh9R2g4MMZCr7yrGxVpetYAEIcBYwWZDNfltpFy5xxtusoAAAAQEgxHTvJd+tcKfk02RefUvD3N8t+8qHrWABCGAWMFmJLi2RzsmXGTZKJ6eg6DgAAABByTLtoRV1/u3w33ilV7lfwP+9U8M/3yxYVuI4GIAQ5v4yqV9ms16WqKpnJF7iOAgAAAIQ0c8po+YadLPvaC7KvPie7YbXMlMtkJv1Axs+vLABqMAOjBdjKStmsV6WTkmV69HYdBwAAAAh5pm07+aZcLt/vF0lJJ8o+u1jB398ku/kj19EAhAgKGC3Arn5XKimSb/IU11EAAACAsGK69lDUrDny3fhbaf8+BR/4DwUfmy9bXOg6GgDHmI/VzKy1sm++LPXoLZ040nUcAAAAICyZU8bIN/QU2deek33tedkPV8lceIXMxAtkorjCHxCJmIHR3LZ8In2RKzP5AhljXKcBAAAAwpZp106+C6+U73d/kgYNk336cQXn3iz72UbX0QA4QAGjmdnMl6WYDjLjJrmOAgAAAHiC6ZYo36y75Jt5h1RRruD9sxV8fIFsSZHraABaEUtImpEt3CW77j2ZtAtl2kW7jgMAAAB4hjFGGnmafMNPlX3lWdnXX5T98AOZC6+UOes8lpUAEYAZGM3Ivv2KZCUz6XzXUQAAAABPMu2i5bvoavnu/m+pf5LsP/5HwT/cKpu7yXU0AC2MAkYzs/KFGwAAEbdJREFUsfv2yma/Lo08TSbQzXUcAAAAwNNMj17y3fw7+a6/XSrbreAfb1dw8X/Jlha7jgaghbCEpJnY99+RyvfIN/kHrqMAAAAAEcEYI40aL9+JI2VfeUZ22Uuy69+XmXqVTOo5ruMBaGbMwGgGtZdO7TtAGjzcdRwAAAAgopjo9vJd/BP57loo9Rsk+7dHFZz3S1W886rs3grX8QA0E2ZgNIdP1ks7vpK59iYunQoAAAA4Ynr2lu+W38uuXiH7whKV/tdcqW1bmVPGyow9SzpxpIyfX4GAcMW7txkEM1+WYuNkRp/pOgoAAAAQ0YwxMqPPkE05XXH5O1S87CXZ1e/K5iyXOsbKpEyQGZsqDRzKHx+BMEMB4zjZnV9LH62WueAymTZtXMcBAAAAoJpCRtthJ8vXNVH20hnSxvWyH7wjuzJT9p1XpITuMmNSZU5LlenZx3VcoNXZqkpp394D//ZJ+ypqP9p9+6T9e6W9e+t+PNDe7tsr7d+nspTx0pnntlpmChjHyb71LynKL3NW6500AAAAAE1n/G2kU0bLnDJadm+57Nr3ZT/Ikn31OdlXnpH6DpAZmyoz5kyZzgHXcYFGWWul/fukijKpvEyqKJcqymQPfFRFuVT+3W178NjeikOKFQeKEdXVTf/Exkjtomv+tW0ntWsvtWsnWdtynW0ABYzjYMvLZFe+JTN6gkxcvOs4AAAAAI7ARMfIjJ8kjZ8kW1Ikm7Nc9v13ZJ9dLPvcE9LQk2uKGSPHycR0cB0XHmSrq6Wy3VLZngMfd8uW7Zb2HDj2/eJD7ccDt4PBw38C45Paxxz410GKiZHi4mWi23+vCBFd5585eDy6vdQ2uqZAcbBQ0aZtg0uuOiQkqCI/v4X+p+qjgHEc7IpMaV+FTBqXTgUAAADCjYmLl0mbIqVNkd35dc2sjA/ekX1ioexfHpZOGS3f2LOkk0axXBz12GB1zSyIPbsPKUTskcpKvytO7Kk5VrCvQtUlRTXHKsobf9GGig9dusoceuyQj+Z79xXToaYY4dH9XShgHCMbrK5ZPjJomEy/Qa7jAAAAADgOpkcvmQuvkJ1yubT1s5piRs5yBdeslGI6yowaX3Mlk8HDZXw+13HRAmxlpbS7RNpTIu0ulT3ktnaXyO4urXNfFWWNL6EwRorpKHXoKHWIlS8+INO1h9Qh9sC/muOmQ6zUMfa749Ht+fo6DAoYx2pDjpT/rXw//InrJAAAAACaiTFGGjBEZsAQ2Ut+Kn2yvqaYsSpbdvkyqVPnmj0zEvtJvfrK9Oon9egj066d6+j4HrtvX03BobSmEGF3H1J82HOgILG7RNpz4OPeioZfyOeTOnaSYuOkjp1k+vSXYjtJHTodKD50lOnQqaYocbAY0b5DnUJEfEKC8ltxqYVXUcA4RsHMl6UuCdLIca6jAAAAAGgBJiqqZvnISaNk9+2VXf+B9PFa2W++kP30I6mqUlaq+Wt71x5SYj+ZXn2lXv1qChzde9ZsIIpmYffvqyk07D44Q6L4QEGi+LsZE4f+27+v4Rfy+6WOcTVFiNg4ma49a28rtpNMx7ja24qNq1eMgDsUMI5B5bZcafNHMj/8Sc03NQAAAACeZtpFy4xNlcamSjqw/0HeTumbL2S//lL6+gvZb76U3bBKCgZrChtRfqlHL5nEvlLigdkavfrWXMLVF9m/R9jqaql8T53NLCuMFNyx/bsZE6WHzI7YXVJz9YyG+NtIneJqixKmR+8DxYfONfcPzJyoKUrE1SzT8OgeEV5HAeMYlP/rGaltW5kJ6a6jAAAAAHDA+KKkHr1qChTJ42uP28pK6dvtdYsaWz+TcpardreEtm2lnn1rChu9DszaCHSvuRpEdLTUNlrGH/q/qtVc0nN/TRGifLdUVvbdFTVqixMHjn2vWNHQco3SgzcOzpA4UJQw3RPrzpg4WIiIPdCmHQWJSBH674oQY3eXaG/2Mplxk2o2XAEAACFj/fr1Wrx4sYLBoCZPnqypU6fWedxaq8WLF2vdunVq166dZs6cqQEDBjhKC8CLTJs2Uu/+Mr371zlu91ZIO76S/foL6esva5ahbFovvfeWGtwG0u8/cAnLA5e5POQSmCVxnRW0qnk8+uBlMGseN9HR3136sm20JCtVVkqV+2s+VlXKHrxduV+qqqx/u2r/gfZVslUNtN2/r+bqG2W7a441JirqwEaWBzat7ByoWVrToeP3NrLsKMV0VHyffiqqrK65ugYFCTSAAsZRstmvS5X7ZSZf4DoKAAA4RDAY1OOPP67f/va3CgQCmj17tlJSUtS7d+/aNuvWrdPOnTu1cOFCff7553rsscd0zz33OEwNIFKY6PZS/ySZ/kl1jts9pTUFjeKCmsLAvgpp796a5RIHbtt9e6X9e2uOl+1SZd43suVlNff3761zJYxGronRNFF+qU2bmiUZbdrW3G7T9sD9A7fbd5DatK0tOtQUITrW/HG3tlgRK3XocNQzI/wJCTJsdInDoIBxlMyEdMX266+yxL6uowAAgEPk5uaqR48e6t69uyRp/PjxysnJqVPAWL16tc4880wZY5SUlKSysjIVFRUpPj7eVWwAEc507CQNOUlHM98g4ZArWtQu49hXUafoUXvb55P8bQ8UIvwHChPfu32gaMFGlQh1FDCOkunUWe3POldlVAYBAAgphYWFCgQCtfcDgYA+//zzem0SEhLqtCksLGywgJGZmanMzExJUkZGRp3nNQe/39/srxkqvNo3+hV+vNo3+hV+vNq31u4XBQwAAOAJ1tafOP39qctNaXNQWlqa0tLSau/nN/MfLw79C6rXeLVv9Cv8eLVv9Cv8eLVvLdWvxMTEBo8zRwgAAHhCIBBQQUFB7f2CgoJ6MysCgUCdgVZDbQAAQGiigAEAADxh4MCB2rFjh/Ly8lRVVaWVK1cqJSWlTpuUlBRlZ2fLWqvPPvtMMTExFDAAAAgTLCEBAACeEBUVpenTp2vevHkKBoOaOHGi+vTpo2XLlkmS0tPTNXLkSK1du1azZs1S27ZtNXPmTMepAQBAU1HAAAAAnpGcnKzk5OQ6x9LT02tvG2M0Y8aM1o4FAACaAUtIAAAAAABAyKOAAQAAAAAAQh4FDAAAAAAAEPIoYAAAAAAAgJBHAQMAAAAAAIQ8ChgAAAAAACDkUcAAAAAAAAAhz1hrresQAAAAAAAAh8MMjGNw++23u47Q4iKhj1Jk9JM+egN99I5I6SeOzMtfC17tG/0KP17tG/0KP17tW2v3iwIGAAAAAAAIeRQwAAAAAABAyIu6++6773YdIhwNGDDAdYQWFwl9lCKjn/TRG+ijd0RKP3FkXv5a8Grf6Ff48Wrf6Ff48WrfWrNfbOIJAAAAAABCHktIAAAAAABAyKOAAQAAAAAAQp7fdYBQtn79ei1evFjBYFCTJ0/W1KlT6zxurdXixYu1bt06tWvXTjNnzgyrdU35+flatGiRiouLZYxRWlqazjvvvDptNm7cqPvuu0/dunWTJI0dO1Y/+tGPXMQ9ZjfccIOio6Pl8/kUFRWljIyMOo+H+3mUpG+++UYLFiyovZ+Xl6dLLrlE559/fu2xcDyXDz30kNauXau4uDjNnz9fkrRnzx4tWLBAu3btUteuXXXLLbeoY8eO9Z57pPdvqGioj0899ZTWrFkjv9+v7t27a+bMmerQoUO95x7paztUNNTHZ555Rm+++aY6deokSbr88suVnJxc77nhch6lhvu5YMECffPNN5Kk8vJyxcTE6P7776/33HA5lzg2XhxPeH0M4cWxg9fGCl4dI3h1XODVsYBXf/Y39j0+JN5jFg2qrq62N954o925c6etrKy0v/rVr+xXX31Vp82aNWvsvHnzbDAYtJs3b7azZ892lPbYFBYW2i1btlhrrS0vL7ezZs2q18ePP/7Y3nvvvS7iNZuZM2fakpKSRh8P9/P4fdXV1XbGjBk2Ly+vzvFwPJcbN260W7Zssbfeemvtsaeeesq++OKL1lprX3zxRfvUU0/Ve15T3r+hoqE+rl+/3lZVVVlra/rbUB+tPfLXdqhoqI9PP/20femllw77vHA6j9Y23M9DLVmyxD777LMNPhYu5xJHz6vjCa+PIbw+dvDCWMGrYwSvjgu8Ohbw6s/+xr7Hh8J7jCUkjcjNzVWPHj3UvXt3+f1+jR8/Xjk5OXXarF69WmeeeaaMMUpKSlJZWZmKioocJT568fHxtX8taN++vXr16qXCwkLHqVpfuJ/H7/voo4/Uo0cPde3a1XWU4zZ8+PB6Vd2cnBylpqZKklJTU+u9L6WmvX9DRUN9POWUUxQVFSVJSkpKCvv3ZUN9bIpwOo/S4ftprdV7772n008/vZVTwTWvjicifQwRjufsUF4YK3h1jODVcYFXxwJe/dnf2Pf4UHiPsYSkEYWFhQoEArX3A4GAPv/883ptEhIS6rQpLCxUfHx8q+VsLnl5edq6dasGDRpU77HPPvtMt912m+Lj43X11VerT58+DhIen3nz5kmSzj77bKWlpdV5zEvnUZJWrFjR6DdKL5zLkpKS2nMTHx+v0tLSem2a8v4NF2+99ZbGjx/f6OOH+9oOda+//rqys7M1YMAAXXPNNfUGAF46j5988oni4uLUs2fPRtuE87lE4yJhPOHVMYSXxw5eHStEwhjBa+MCL48FvPKz/9Dv8aHwHqOA0QjbwNVljTFH3SYc7N27V/Pnz9e0adMUExNT57H+/fvroYceUnR0tNauXav7779fCxcudJT02MydO1ddunRRSUmJ/vCHPygxMVHDhw+vfdwr51GSqqqqtGbNGl1xxRX1HvPCuWwqr5zTF154QVFRUZowYUKDjx/pazuUpaen166rfvrpp/Xkk09q5syZddp45TxKh/9lQQrvc4nD8/p4wqtjCC+PHSJ9rBDO585r4wKvjwW88LP/cN/jG9PS54wlJI0IBAIqKCiovV9QUFCvqh4IBJSfn3/YNqGuqqpK8+fP14QJEzR27Nh6j8fExCg6OlqSlJycrOrq6gYrbaGsS5cukqS4uDiNHj1aubm5dR73wnk8aN26derfv786d+5c7zEvnEup5jwenKZbVFRUu/HToZry/g1177zzjtasWaNZs2Y1+k3/SF/boaxz587y+Xzy+XyaPHmytmzZUq+NF86jJFVXV2vVqlWH/YtZOJ9LHJ6XxxNeHkN4eezg5bGCl8cIXhwXeHks4IWf/Q19jw+F9xgFjEYMHDhQO3bsUF5enqqqqrRy5UqlpKTUaZOSkqLs7GxZa/XZZ58pJiYmLN5QB1lr9cgjj6hXr1664IILGmxTXFxcW0XLzc1VMBhUbGxsa8Y8Lnv37lVFRUXt7Q0bNqhv37512oT7eTzU4Sq94X4uD0pJSVFWVpYkKSsrS6NHj67Xpinv31C2fv16vfTSS/rNb36jdu3aNdimKV/boezQteKrVq1qcIpyuJ/Hgz766CMlJibWmU55qHA/lzg8r44nvDyG8PrYwctjBa+OEbw6LvDyWCDcf/Y39j0+FN5jxjY0xwOSpLVr12rJkiUKBoOaOHGiLr74Yi1btkxSzZQna60ef/xxffjhh2rbtq1mzpypgQMHOk7ddJ9++qnmzJmjvn371lZyL7/88tq/KKSnp+u1117TsmXLFBUVpbZt2+qaa67RkCFDXMY+Kt9++60eeOABSTWV0DPOOMNz5/Ggffv26ec//7n+9Kc/1U7xOrSf4XguH3zwQW3atEm7d+9WXFycLrnkEo0ePVoLFixQfn6+EhISdOutt6pjx44qLCzUo48+qtmzZ0tq+P0bihrq44svvqiqqqradaCDBw/WddddV6ePjX1th6KG+rhx40Zt27ZNxhh17dpV1113neLj48P2PEoN93PSpElatGiRBg8erPT09Nq24XoucWy8OJ7w8hjCy2MHL40VvDpG8Oq4wKtjAa/+7G/se/zgwYOdv8coYAAAAAAAgJDHEhIAAAAAABDyKGAAAAAAAICQRwEDAAAAAACEPAoYAAAAAAAg5FHAAAAAAAAAIY8CBgAAAAAACHkUMAAAAAAAQMj7/2T7K/rhK+OvAAAAAElFTkSuQmCC\n",
"text/plain": [
"<Figure size 1080x720 with 4 Axes>"
]
},
"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",
"psi_mpc = np.array(x.value[3, :]).flatten()\n",
"cte_mpc = np.array(x.value[4, :]).flatten()\n",
"v_mpc = np.array(u.value[0, :]).flatten()\n",
"w_mpc = np.array(u.value[1, :]).flatten()\n",
"\n",
"# simulate robot state trajectory for optimized U\n",
"x_traj = predict(x0, np.vstack((v_mpc, w_mpc)))\n",
"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_traj[0, :], x_traj[1, :])\n",
"plt.axis(\"equal\")\n",
"plt.ylabel(\"y\")\n",
"plt.xlabel(\"x\")\n",
"\n",
"# plot v(t)\n",
"plt.subplot(2, 2, 2)\n",
"plt.plot(v_mpc)\n",
"plt.ylabel(\"v(t)\")\n",
"# plt.xlabel('time')\n",
"\n",
"# plot w(t)\n",
"plt.subplot(2, 2, 3)\n",
"plt.plot(w_mpc)\n",
"plt.ylabel(\"w(t)\")\n",
"# plt.xlabel('time')\n",
"\n",
"plt.subplot(2, 2, 4)\n",
"plt.plot(cte_mpc)\n",
"plt.ylabel(\"cte(t)\")\n",
"plt.legend(loc=\"best\")\n",
"\n",
"plt.tight_layout()\n",
"plt.show()"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"full track demo"
]
},
{
"cell_type": "code",
"execution_count": 19,
"metadata": {},
"outputs": [
{
"name": "stderr",
"output_type": "stream",
"text": [
"<ipython-input-9-004252095cfc>:18: 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.1228s Max: 0.2149s Min: 0.1088s\n"
]
}
],
"source": [
"track = compute_path_from_wp(\n",
" [0, 5, 7.5, 10, 12, 13, 13, 10], [0, 0, 2.5, 2.5, 0, 0, 5, 10]\n",
")\n",
"\n",
"sim_duration = 100\n",
"opt_time = []\n",
"\n",
"x_sim = np.zeros((N, sim_duration))\n",
"u_sim = np.zeros((M, sim_duration - 1))\n",
"\n",
"MAX_SPEED = 1.25\n",
"MIN_SPEED = 0.75\n",
"MAX_STEER_SPEED = 1.57 / 2\n",
"\n",
"# Starting Condition\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0\n",
"x0[1] = -0.5\n",
"x0[2] = np.radians(-0)\n",
"_, psi, cte = calc_err(x0, track)\n",
"x0[3] = psi\n",
"x0[4] = cte\n",
"\n",
"x_sim[:, 0] = x0\n",
"\n",
"# starting guess\n",
"u_bar = np.zeros((M, T))\n",
"u_bar[0, :] = 0.5 * (MAX_SPEED + MIN_SPEED)\n",
"u_bar[1, :] = 0.01\n",
"\n",
"for sim_time in range(sim_duration - 1):\n",
"\n",
" iter_start = time.time()\n",
"\n",
" # Prediction\n",
" x_bar = np.zeros((N, T + 1))\n",
" x_bar[:, 0] = x_sim[:, sim_time]\n",
"\n",
" for t in range(1, T + 1):\n",
" xt = x_bar[:, t - 1].reshape(5, 1)\n",
" ut = u_bar[:, t - 1].reshape(2, 1)\n",
"\n",
" A, B, C = get_linear_model(xt, ut)\n",
"\n",
" xt_plus_one = np.squeeze(np.dot(A, xt) + np.dot(B, ut) + C)\n",
"\n",
" _, psi, cte = calc_err(xt_plus_one, track)\n",
" xt_plus_one[3] = psi\n",
" xt_plus_one[4] = cte\n",
"\n",
" x_bar[:, t] = xt_plus_one\n",
"\n",
" # CVXPY Linear MPC problem statement\n",
" cost = 0\n",
" constr = []\n",
"\n",
" for t in range(T):\n",
"\n",
" # Tracking\n",
" if t > 0:\n",
" idx, _, _ = calc_err(x_bar[:, t], track)\n",
" delta_x = track[:, idx] - x[0:3, t]\n",
" cost += cp.quad_form(delta_x, 10 * np.eye(3))\n",
"\n",
" # Tracking last time step\n",
" if t == T:\n",
" idx, _, _ = calc_err(x_bar[:, t], track)\n",
" delta_x = track[:, idx] - x[0:3, t]\n",
" cost += cp.quad_form(delta_x, 100 * np.eye(3))\n",
"\n",
" # Actuation rate of change\n",
" if t < (T - 1):\n",
" cost += cp.quad_form(u[:, t + 1] - u[:, t], 25 * np.eye(M))\n",
"\n",
" # Actuation effort\n",
" cost += cp.quad_form(u[:, t], 1 * np.eye(M))\n",
"\n",
" # Constrains\n",
" A, B, C = get_linear_model(x_bar[:, t], u_bar[:, t])\n",
" constr += [x[:, t + 1] == A @ x[:, t] + B @ u[:, t] + C.flatten()]\n",
"\n",
" # sums problem objectives and concatenates constraints.\n",
" constr += [x[:, 0] == x_sim[:, sim_time]] # starting condition\n",
" constr += [u[0, :] <= MAX_SPEED]\n",
" constr += [u[0, :] >= MIN_SPEED]\n",
" constr += [cp.abs(u[1, :]) <= MAX_STEER_SPEED]\n",
"\n",
" # Solve\n",
" prob = cp.Problem(cp.Minimize(cost), constr)\n",
" solution = prob.solve(solver=cp.OSQP, verbose=False)\n",
"\n",
" # retrieved optimized U and assign to u_bar to linearize in next step\n",
" u_bar = np.vstack(\n",
" (np.array(u.value[0, :]).flatten(), (np.array(u.value[1, :]).flatten()))\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",
" # move simulation to t+1\n",
" tspan = [0, dt]\n",
" x_sim[:, sim_time + 1] = odeint(\n",
" kinematics_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": 20,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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\n",
"text/plain": [
"<Figure size 1080x720 with 3 Axes>"
]
},
"metadata": {},
"output_type": "display_data"
}
],
"source": [
"# plot trajectory\n",
"grid = plt.GridSpec(2, 3)\n",
"\n",
"plt.figure(figsize=(15, 10))\n",
"\n",
"plt.subplot(grid[0:2, 0:2])\n",
"plt.plot(track[0, :], track[1, :], \"b+\")\n",
"plt.plot(x_sim[0, :], x_sim[1, :])\n",
"plt.axis(\"equal\")\n",
"plt.ylabel(\"y\")\n",
"plt.xlabel(\"x\")\n",
"\n",
"plt.subplot(grid[0, 2])\n",
"plt.plot(u_sim[0, :])\n",
"plt.ylabel(\"v(t) [m/s]\")\n",
"\n",
"plt.subplot(grid[1, 2])\n",
"plt.plot(np.degrees(u_sim[1, :]))\n",
"plt.ylabel(\"w(t) [deg/s]\")\n",
"\n",
"plt.tight_layout()\n",
"plt.show()"
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": []
}
],
"metadata": {
"kernelspec": {
"display_name": "Python 3",
"language": "python",
"name": "python3"
},
"language_info": {
"codemirror_mode": {
"name": "ipython",
"version": 3
},
"file_extension": ".py",
"mimetype": "text/x-python",
"name": "python",
"nbconvert_exporter": "python",
"pygments_lexer": "ipython3",
"version": "3.8.3"
}
},
"nbformat": 4,
"nbformat_minor": 4
}