{
"cells": [
{
"cell_type": "markdown",
"metadata": {
"colab_type": "text",
"id": "view-in-github",
"tags": [
"no-tex"
]
},
"source": [
"
"
]
},
{
"cell_type": "code",
"execution_count": 1,
"metadata": {
"id": "JoW4C_OkOMhe",
"tags": [
"remove-cell"
]
},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"Note: you may need to restart the kernel to use updated packages.\n"
]
}
],
"source": [
"%pip install -q -U gtbook\n"
]
},
{
"cell_type": "code",
"execution_count": 2,
"metadata": {
"id": "10-snNDwOSuC",
"tags": [
"remove-cell"
]
},
"outputs": [],
"source": [
"import math\n",
"import numpy as np\n",
"import plotly.express as px\n",
"try:\n",
" import google.colab\n",
" # Load LIDAR scans from Github:\n",
" !wget -q https://github.com/gtbook/robotics/raw/main/Figures6/lidar/PC_315967795019746000.ply\n",
" !wget -q https://github.com/gtbook/robotics/raw/main/Figures6/lidar/PC_315967795520065000.ply\n",
" !wget -q https://github.com/gtbook/robotics/raw/main/Figures6/lidar/PC_315967795919523000.ply\n",
" !mkdir -p Figures6/lidar\n",
" !mv *.ply Figures6/lidar/\n",
"except:\n",
" import plotly.io as pio\n",
" pio.renderers.default = \"png\"\n",
"\n",
"import gtsam\n",
"from gtbook import driving\n"
]
},
{
"attachments": {},
"cell_type": "markdown",
"metadata": {
"id": "nAvx4-UCNzt2"
},
"source": [
"# Sensing for Autonomous Vehicles\n",
"\n",
"> LIDAR, a sensor found in most autonomous cars, can be used to construct a 3D representation of the robot's environment in real time.\n",
"\n",
"
"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"## LIDAR\n",
"\n",
"LIDAR (LIght raDAR) is a technology that measures distance to an object by using laser light and the \"Time of Flight\" or **ToF** principle. There are several variants in use, and the simplest to explain is the **direct ToF** sensor, which sends out a short pulse and measures the elapsed time $\\Delta t$ for the light to bounce off an object and return to a detector collocated with the laser pulse emitter. If the object is situated at a distance $d$ from the emitter-detector pair, we have\n",
"\n",
"$$\n",
"\\Delta t = \\frac{2 d}{c} \n",
"$$\n",
"\n",
"where $c\\approx300,000km/s$ is the speed of light. For example, for an object at 15m, we have \n",
"\n",
"$$\n",
"\\Delta t \\approx \\frac{2 \\times 0.015}{300,000} = 0.1\\mu s\n",
"$$\n",
"\n",
"Assuming we can measure $\\Delta t$ accurately, we can then easily compute the distance:\n",
"\n",
"$$\n",
"d= c\\frac{\\Delta t}{2}\n",
"$$\n",
"\n",
"In a *scanning LIDAR*, there is typically one detector, whereas in a *flash LIDAR* a single pulse is emitted in a wide field of view, and an *array* of detectors, akin to a CCD sensor, is used to detect the returning light pulses in multiple directions at once.\n",
"\n",
"In practice, *indirect* time of flight sensors are more prevalent in robotics and autonomous driving applications than direct ToF sensors. There are multiple reasons for this: measuring elapsed times at the nano-second scale is difficult and expensive, and the amount of light energy that needs to be emitted for direct ToF can also be a problem from an eye-safety perspective.\n",
"**Indirect ToF** is an attractive alternative, where the light is emitted with a waveform, e.g., a sine wave, and the returned light is correlated with the amplitude of the emitted light to calculate a phase shift. The elapsed time $\\Delta t$ and distance $d$ can then be calculated from the phase shift.\n",
"\n",
"Two common scanning LIDAR technologies are in use for robotics: **2D LIDAR**, which consists of a single laser beam that is rotated around a fixed axis, and **3D LIDAR**, which has multiple laser/detector pairs rotated at different inclinations. 2D LIDARs are also often deployed on aircraft to create highly detailed digital elevation maps, where the third dimension is provided by the aircraft's forward motion. LIDAR altimeters are even deployed from satellites in orbit around Earth or [other planets](https://pgda.gsfc.nasa.gov/products/62)."
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"## Ray Intersection\n",
"\n",
"> Intersecting rays is as easy as computing a dot product.\n",
"\n",
"To perform inference about the environment with LIDAR, we have to model how LIDAR beams interact with it, which in the case of polygonal objects comes down to line-line or line-plane intersections.\n",
"\n",
"We examine the 2D line-line intersection case first. Assume we have a line in 2D with equation $\\hat{n} \\cdot p = d$, where $\\hat{n}$ is a normal vector and $d>0$ is the distance of the line to the origin. The hat notation signifies that the normal vector $\\hat{n}$ is normalized to length 1. Then if we have a ray of points $p = \\hat{r} s$ where $\\hat{r}$ is the **ray direction** and $s>0$ is a scalar, we can find the intersection by plugging the ray equation into the line equation\n",
"\n",
"$$\n",
"\\hat{n} \\cdot (\\hat{r} s) = d,\n",
"$$\n",
"\n",
"where $a \\cdot b \\doteq a^T b = b^T a$ is the standard vector dot product. We find the range $s$ to the object as:\n",
"\n",
"$$\n",
"s = \\frac{d}{\\hat{n} \\cdot \\hat{r}}.\n",
"$$\n",
"\n",
"We can ensure that $s>0$ and avoid a division by zero by checking the dot product before doing the division:\n",
"\n",
"$$\n",
"\\hat{n} \\cdot \\hat{r} > 0\n",
"$$\n",
"\n",
"The following code implements this:"
]
},
{
"cell_type": "code",
"execution_count": 3,
"metadata": {},
"outputs": [],
"source": [
"def intersect(n, d, r):\n",
" \"\"\"Intersect line/plane (n,d) with ray given by direction r.\"\"\"\n",
" cos = np.dot(n,r)\n",
" return d / cos if cos>0 else float('nan')\n",
"\n",
"assert intersect(n=gtsam.Point2(1,0), d=5, r=gtsam.Point2(1,0)) == 5\n"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"The story above generalizes *completely* to 3D, where with $\\hat{n}\\in\\mathbb{R}^3$ and $p\\in\\mathbb{R}^3$.\n",
"In this case, the equation $\\hat{n} \\cdot p = d$ defines a *plane* in 3D:"
]
},
{
"cell_type": "code",
"execution_count": 4,
"metadata": {},
"outputs": [],
"source": [
"assert intersect(n=gtsam.Point3(1,0,0), d=5, r=gtsam.Point3(1,0,0)) == 5\n"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"## Simulating a 2D LIDAR\n",
"\n",
"> Computing line intersections is the main computation when simulating 2D LIDAR.\n",
"\n",
"We now put the above to work to simulate a 2D LIDAR sensor situated at the origin. The *SICK Tim1xx* is a relatively low-cost 2D LIDAR sensor, which has a field of view of 200 degrees and a resolution of one beam per degree. Hence, we expect to simulate 200 measurements.\n",
"\n",
"In our simple simulation code below, we create an environment from infinite lines. A more powerful simulator would allow for line *segments*, but infinite lines are enough to illustrate the principle. We create a corridor-like environment with three sides:"
]
},
{
"cell_type": "code",
"execution_count": 5,
"metadata": {},
"outputs": [],
"source": [
"north = gtsam.Point2(0,1), 2.5\n",
"east = gtsam.Point2(1,0), 8\n",
"south = gtsam.Point2(0,-1), 2.5\n"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"Then we simply create 200 rays, ranging from -100 degrees to 100 degrees, with 0 facing due east:"
]
},
{
"cell_type": "code",
"execution_count": 6,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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"
},
"metadata": {},
"output_type": "display_data"
}
],
"source": [
"#| caption: 200 \"LIDAR\" rays at different angles\n",
"#| label: fig:lidar_rays_200\n",
"angles = np.linspace(-100, 100, 200)\n",
"rays = np.array([gtsam.Rot2(math.radians(angle)).matrix()[0,:] for angle in angles])\n",
"fig = px.scatter(x=rays[:,0],y=rays[:,1])\n",
"fig.update_yaxes(scaleanchor = \"x\", scaleratio = 1); fig.show()\n"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"Finally, we do the intersection:"
]
},
{
"cell_type": "code",
"execution_count": 7,
"metadata": {},
"outputs": [],
"source": [
"scan = []\n",
"for r in rays:\n",
" ranges = [intersect(n,d,r) for n, d in [north, east, south]]\n",
" _range = np.nanmin(ranges)\n",
" intersection = _range * r\n",
" scan.append(intersection)\n"
]
},
{
"cell_type": "code",
"execution_count": 8,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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"
},
"metadata": {},
"output_type": "display_data"
}
],
"source": [
"#| caption: A simulated scan by intersecting 200 rays with the environment.\n",
"#| label: fig:lidar_scan_200\n",
"scan_x, scan_y = zip(*scan)\n",
"fig = px.scatter(x=scan_x, y=scan_y)\n",
"fig.update_yaxes(scaleanchor = \"x\", scaleratio = 1); fig.show()\n"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"As you can see, the resulting scan of this corridor-like environment does not produce a uniform sampling on the walls. Because the rays are distributed uniformly in *angle* space, they graze the walls at increasingly shallow angles, and the distance between successive intersection points increases. Of course, this depends on the angle that the wall makes with the rays: the end of the corridor is far away and hence is sampled fairly uniformly. This is a typical pattern when working with LIDAR scanners."
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"## Geometry of a Moving LIDAR\n",
"\n",
"Above we assumed that the ray is situated at the *world* origin, but we can also generalize to the case where the rays are defined in a *body coordinate frame* $(R^w_b,t^w_b)$. In this case, it is convenient to transform the plane to the body frame. We can do this by expressing a point $p^w$ in world coordinates as a function of a point in body coordinates: $p^w = R^w_b p^b + t^w_b$ and plugging that into the plane equation:\n",
"\n",
"$$\n",
"\\begin{aligned}\n",
"\\hat{n}^w \\cdot p^w &= d^w \\\\\n",
"\\hat{n}^w \\cdot \\{ R^w_b p^b + t^w_b \\} &= d^w \\\\\n",
"(R^w_b)^T \\hat{n}^w \\cdot p^b &= d^w - \\hat{n}^w \\cdot t^w_b.\n",
"\\end{aligned}\n",
"$$\n",
"\n",
"Hence, we obtain a new plane equation in the body frame as\n",
"\n",
"$$\n",
"\\hat{n}^b \\cdot p^b = d^b\n",
"$$\n",
"\n",
"with transformed plane parameters $\\hat{n}^b \\doteq (R^w_b)^T \\hat{n}^w$ and $d^b \\doteq d^w - \\hat{n}^w \\cdot t^w_b$.\n",
"\n",
"We can use a `gtsam.Pose2` or `gtsam.Pose3` object to specify the body frame, respectively in 2D or 3D, and then use it to transform plane coordinates:"
]
},
{
"cell_type": "code",
"execution_count": 9,
"metadata": {},
"outputs": [],
"source": [
"def transform_to(n, d, wTb):\n",
" \"\"\"Transform line/plane (n,d) to body coordinate frame\"\"\"\n",
" wRb = wTb.rotation()\n",
" wtb = wTb.translation()\n",
" return wRb.matrix().T @ n, d - np.dot(n, wtb)\n"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"We can do this for lines in 2D"
]
},
{
"cell_type": "code",
"execution_count": 10,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"(array([ 0.93969262, -0.34202014]), 3.0)\n"
]
}
],
"source": [
"wTb = gtsam.Pose2(r=gtsam.Rot2(math.radians(20)), t=[2,1])\n",
"print(transform_to(gtsam.Point2(1,0), 5, wTb))\n"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"and for planes in 3D:"
]
},
{
"cell_type": "code",
"execution_count": 11,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"(array([ 0.70710678, -0.70710678, 0. ]), 4.0)\n"
]
}
],
"source": [
"wTb3 = gtsam.Pose3(r=gtsam.Rot3.Yaw(math.radians(45)), t=[1,2,3])\n",
"print(transform_to(gtsam.Point3(1,0,0), 5, wTb3))\n"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"With this new functionality we can transform the world model and predict what the scan will look like, in body coordinates."
]
},
{
"cell_type": "code",
"execution_count": 12,
"metadata": {},
"outputs": [],
"source": [
"scan2 = []\n",
"transformed = [transform_to(n, d, wTb) for n, d in [north, east, south]]\n",
"for r in rays:\n",
" ranges = [intersect(n,d,r) for n, d in transformed]\n",
" _range = np.nanmin(ranges)\n",
" intersection = _range * r\n",
" scan2.append(intersection)\n"
]
},
{
"cell_type": "code",
"execution_count": 13,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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"
},
"metadata": {},
"output_type": "display_data"
}
],
"source": [
"#| caption: Simulated scan from a different location in the same environment.\n",
"#| label: fig:lidar_scan_200_2\n",
"scan2_x, scan2_y = zip(*scan2)\n",
"fig = px.scatter(x=scan2_x, y=scan2_y)\n",
"fig.update_yaxes(scaleanchor = \"x\", scaleratio = 1); fig.show()\n"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"As you can see above, when the robot rotates 20 degrees *counter-clockwise*, the resulting scan in body coordinates seems to be rotated 20 degrees in the *opposite* direction. This makes sense! The forward direction for the robot is along the horizontal X-axis, and as you can see in the scan, the robot seems to be \"looking\" at the correct (upper-right) corner of our little hallway example. This perhaps counter-intuitive behavior is something to always keep in mind when looking at animations of LIDAR scans."
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"## Real LIDAR Scans\n",
"\n",
"> From theory to practice.\n",
"\n",
"3D LIDAR sensors have been used in many autonomous driving efforts, e.g., by Waymo, Cruise, Argo, etc. Below we explore some real scans from the [Argoverse 2 Lidar Dataset](https://www.argoverse.org/av2.html).\n",
"\n",
"First, let us look at a single scan, which was acquired using a [Velodyne](https://velodynelidar.com/products/ultra-puck/) VLP-32C LIDAR sensor. \n",
"The `32` in the model name reflects the fact that, for this particular sensor, there are 32 separate laser beams at different inclinations, that spin around for a full 360 degree field of view. In this case, the inclination angles are uniformly sampled between -25 and +15 degrees with respect to horizontal, but of course this depends on the application/sensor model.\n",
"\n",
"Several things worth noting when looking at the single scan below, taken when the Argo test car is turning at an intersection:\n",
"- The location of the car (at the origin) is marked by concentric circles formed by the lowest beams.\n",
"- The range is approximately 200m, so we can see fairly far down the cross streets.\n",
"- Occlusion is significant: objects close to the car throw \"occlusion shadows.\"\n",
"- Everything is in *body coordinates*, and the streets appear rotated because the car is actually turning."
]
},
{
"cell_type": "code",
"execution_count": 14,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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"
},
"metadata": {},
"output_type": "display_data"
}
],
"source": [
"#| caption: An actual 3D Velodyne LIDAR scan from an autonomous vehicle\n",
"#| label: fig:lidar_scan_real\n",
"real_scans = {0:driving.read_lidar_points('Figures6/lidar/PC_315967795019746000.ply')}\n",
"driving.visualize_cloud(real_scans[0], show_grid_lines=True)\n"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"We can also learn some things from looking at two successive scans below. \n",
"The scans are slightly rotated and translated from each other, and this will be exactly how we can infer the ego-motion of the car in the next section."
]
},
{
"cell_type": "code",
"execution_count": 15,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "iVBORw0KGgoAAAANSUhEUgAAArwAAAH0CAYAAADfWf7fAAAgAElEQVR4Xuy9CZhV1Zk1/NZEUQVFAVUgM4oWKKhANEwCKmWMqIgZNF/Ml8FO/qS70+k2nc73fXbb8beTTrr/TKbTiR2/TpvENnY0eSLRiJ2AAyCjyqAiUKhAMUMVcxVFTf+zdvFed506994z3Vvn3lr7eXwE7jn77L32vves8571rrdg3LhxncJGBIgAESACRIAIEAEiQATyFIECEt48XVlOiwgQASJABIgAESACRMAgQMLLjUAEiAARIAJEgAgQASKQ1wiQ8Ob18nJyRIAIEAEiQASIABEgAiS83ANEgAgQASJABIgAESACeY0ACW9eLy8nRwSIABEgAkSACBABIkDCyz1ABIgAESACRIAIEAEikNcIkPDm9fJyckSACBABIkAEiAARIAIkvNwDRIAIEAEiQASIABEgAnmNAAlvXi8vJ0cEiAARIAJEgAgQASJAwss9QASIABEgAkSACBABIpDXCJDw5vXycnJEgAgQASJABIgAESACJLzcA0SACBABIkAEiAARIAJ5jQAJb14vLydHBIgAESACRIAIEAEiQMLLPUAEiAARIAJEgAgQASKQ1wiQ8Ob18nJyRIAIEAEiQASIABEgAiS83ANEgAgQASJABIgAESACeY0ACW9eLy8nRwSIABEgAkSACBABIkDCyz1ABIgAESACRIAIEAEikNcIkPDm9fJyckSACBABIkAEiAARIAIkvNwDRIAIEAEiQASIABEgAnmNAAlvXi8vJ0cEiAARIAJEgAgQgdxDYOzYsXLxxRfLzp07Ze/evaEnQMIbGkJ2QASIABEgAkSACBCBeCMwdepUeeedd+TUqVPxHqiITJkyRQoLC2X79u1y7bXXyiuvvCLHjh0LNW4S3lDw8WQiQASIABEgAkSACESDQHl5iVwze4y8vGavNDW1RtPp+V6mT58u7777rhw/fjzSfjPR2eLFi+V3v/uddHZ2yvDhwwXR3ldffTXUpUh4Q8HHk4kAESACRIAIEAEiEA0Cty+aKItvnSQ//fkmWbW6PppORWTixIlyxRVXyIkTJ+Ts2bOGSG7YsEHOnTtn/nzNNddIeXm5bNu2TSZPnmz+bf369eb4q666SoYMGSIdHR3S2toqK1euTIxr4MCBct1110l7e7s0NTVJSUmJicaCVOOzefPmmb5KS0sN2d6yZYunOd18883y7LPPmmOLiopk/vz58sILL3g6N9lBJLyh4OPJRIAIEAEiQASIABGIBgFEeOfOHiur1tRnPcL74Q9/2GhlQYS1gaxqKy4ulgkTJkhzc7PU13eRcRBaRF5BdtFmzpwpdXV10tjYaIgw+jpz5kzis7feektOnjyZFqwFCxbI888/nzjO+fe0HbgcQMIbBDWeQwSIABEgAkSACBCBHEIgnaTh+uuv7xFFLSgokLlz55ooK4hudXW1gLRCC4zPamtrZdmyZT1QgP72rrvukl27dnUjzCDKb7/9dlrUbrzxRvnDH/5gjisrK5Np06bJmjVr0p6X6gAS3lDw8WQiQASIABEgAkSACMQfAZBGEM6GhgbXwboR3pqaGiNlUJKKxDckvYHwot1www3y4osvSltbW4KcgqAiwnv77bcbMnz69GnzmUobIKNI1z74wQ/KSy+9ZOQXkyZNMhKJQ4cOpTst5eckvKHg48lEgAgQASJABIgAEYg/Aqq3PXDggFRUVBgCClJZWVkpiP6OHDlSDh48aCayadMm44owYMAA45Jw9OhRo+OFrAH/geRC31tVVWXOhaQB/fXv31/WrVtn/j5o0CAja4CEAX+/4IIL5PXXX+8W9U2GGvqdM2eOHD58WPr16ycrVqwwEeUwjYQ3DHo8lwgQASJABIgAESACOYQACC50tRqVTTd0EFmcg0gtor1uDQlviMa6fQ6ijX9XnW+66+nnkEUg2Q1SiigaCW8UKLIPIkAEiAARIAJEgAgQgdgiQMIb26XhwIgAESACRIAIEAEiQASiQICENwoU2QcRIAJEgAgQASJABIhAbBEg4Y3t0nBgRIAIEAEiQASIABEgAlEgQMIbBYrsgwgQASJABIgAESACRCC2CJDwxnZpODAiQASIABEgAkSACBCBKBAg4Y0CRfZBBIgAESACRIAIEAEiEFsESHhjuzQcGBEgAkSACBABIkAEiEAUCJDwRoEi+yACRIAIEAEiQASIABGILQIkvLFdGg6MCBABIkAEiAARIAJEIAoESHijQJF9EAEiQASIABEgAkSACESCQEFBgYwaNUr69+8vb7/9djR9jhs3rjOSntgJESACRIAIEAEiQASIQCwRmDp1qrzzzjty6tSpWI7PHtR1110nDQ0NMnz4cFm+fHkk42WENxIY2QkRIAJEgAgQASJABMIhUFBWIgNnjZfTa3dLZ3NruM4cZ0+fPl3effddOX78eKT9ZrKz66+/Xl544YVILkHCGwmM7IQIEAEiQASIABEgAuEQqLzlMqm8ebI0PPqKnFm7O1xn1tkTJ06UK664Qk6cOCFnz56Vzs5O2bBhg5w7d878+ZprrpHy8nLZtm2bTJ482fzb+vXrzfFXXXWVDBkyRDo6OqS1tVVWrlyZ6HngwIGCaGx7e7s0NTVJSUmJvPLKK4ZU47N58+aZvkpLSw3Z3rJli685kfD6gosHEwEiQASIABEgAkQg/giYCO/s8XJ6TfYjvB/+8Idl7969hghrA1nVVlxcLBMmTJDm5mapr683/wxC++qrrxqyizZz5kypq6uTxsZGQ4TR15kzZxKfvfXWW3Ly5EnPC0HC6xkqHkgEiAARIAJEgAgQASKQTtLgRi6RPDZ37lwpKioyRLe6ulpAWqEFxme1tbWybNmyHuAWFhbKXXfdJbt27epGmEGU/SShkfBy3xIBIkAEiAARIAJEgAh4RmDatGkmMotkMLfmRi5ramqMlEFJKhLfkPQGwot2ww03yIsvvihtbW3m72VlZeY/RHhvv/12Q4ZPnz5tPlNpA2QUXhsJr1ekeBwRIAJEgAgQASJABIiA0dRCZnDgwAGpqKgwBPSll16SyspKQfR35MiRcvDgQYPUpk2b5NixYzJgwAC59tpr5ejRo0bHC1kD/gPJhb63qqrKnAtJA/qDjdi6devM3wcNGmSuBwkD/n7BBRfI66+/3i3qm2xZEFWGHhhjwnjxH/TFYRqT1sKgx3OJABEgAkSACBABIpBDCIDgQlerUdl0QweRxTmI1CLa69aQ8IZkOLfPQbTx76rzTXe9TH1OwpspZNkvESACRIAIEAEiQASIQCwQIOGNxTJwEESACBABIkAEiAARIAKZQoCEN1PIsl8iQASIABEgAkSACBCBWCBAwhuLZeAgiAARIAJEgAgQASJABDKFAAlvppBlv0SACBABIkAEiAARIAKxQICENxbLwEEQASJABIgAESACRIAIZAoBEt5MIct+iQARIAJEgAgQASJABGKBAAlvLJaBgyACRIAIEAEiQASIABHIFAIkvJlClv0SASJABIgAESACRIAIxAIBEt5YLAMHQQSIABEgAkSACBABIpApBEh4M4Us+yUCRIAIEAEiQASIABGIBQIkvLFYBg6CCBABIkAEiAARIAJEIFMIkPBmCln2SwSIABEgAkSACBABIhALBEh4Y7EMHAQRIAJEgAgQASJABIhAphAg4c0UsuyXCBABIkAEiAARIAJEIBYIkPDGYhk4CCJABIgAESACRIAIEIFMIUDCmylk2S8RIAJEgAgQASJABIhALBAg4Y3FMnAQRIAIEAEiQASIABEgAplCgIQ3U8iyXyJABIgAESACRIAIEIFYIEDCG4tl4CCIABEgAkSACBABIkAEMoUACW+mkGW/RIAIEAEiQASIABEgArFAgIQ3FsvAQRCB/ESgs7PTTKygoCA/J8hZEQEiQASIQE4gQMKbE8vEQRKB3EEAJDcZwU31We7MkCMlAkSACBCBXEOAhDfXVozjJQIxRCAIkQ1yTgynziERASJABIhADiBAwpsDi8QhEoE4IhAlYY2yrzhixTERASJABIhA7yJAwtu7+PPqRCDnEMg0Oc10/zkHOAdMBIgAESACoREg4Q0NITsgAkTARqBfv34yYsQI819NTY3g73V1dXLw4EHZuXOnL7BIfn3BxYOJABEgAkQgCQIkvNwaRIAIhEYApPaSSy6RkSNHytChQ6WxsVEOHDhgCO65c+fMZ0qASX5Dw80OiAARIAJEwCcCJLw+AePhRCAfEQgSSVWSO378eENylcgikguSm6w5ye+ePXsE/3lp06dPl927d0tDQwOtzrwAxmOIABEgAkTAIEDCy41ABPooAlGRXJBVkNwgDeQXhBnRXxDZdOR33rx5icixXi/IPIKMlecQASJABIhA7iJAwpu7a8eREwHfCAQhh26RXK8kF0QWLR0hxjXGjRtnyC+ixSqHcJ7nRnhtEILMzzeIPIEIEAEiQARyDgES3pxbMg6YCPhDIAgJDEtyQV6RsAYtL9rAgQOTkljnbHCs6n2d56UjvCS//vYGjyYCRIAI9BUESHj7ykpznn0OAb9EF5FVEFVNPIMm108k1ya5kCdowpoSXieJ3bp1a4IQJ1scJ/kFEX/zzTdl06ZNvtbTLxa+OufBRIAIEAEiEHsESHhjv0QcIBHIHAIgoSolQKIZpARRkdx0JHbKlCkJyzKQ49OnT6ecKMjvzJkzjeQBLZnsIR1aJL/pEOLnRIAIEIH8Q4CEN//WlDMiAikRUJKrkgNEY6GVVflBqpPdzrUjuX6hB4lF4hrGgoaociryC0kDjgE5tiPGGlH2Mgd7jCS/fleMxxMBIkAEchMBEt7cXDeOuo8iEJSghSGqQc9VHTBIrZeosU1+EW2GdAFE3I78KuG1k9lwnsoptMiFl4ixcwsFxbaPbkVOmwgQASKQUwiQ8ObUcnGwfRGBoEQsKFEFxkHPdUt2A2GF+wKIaboIrq4vZAuTJ082emKcrx6/8OHVP7vtBb8R42T7KSjmfXF/cs5EgAgQgVxAgIQ3F1aJY+xzCAQlXEGJatQk1y2iq5FYaHfREMHFcem0u5iTVnHzk7RG8tvnvjacMBEgAkQgKQIkvNwcRCCHEQABVC0r/g8Nq9MhIdX0ghLkMLZlGI9NRu0IbjryW1tbaxLdMG4/JYpJfnN4k3PoRIAIEIEIECDhjQBEdkEEsomAk2xCz6pVylKV9NUx9hbJTYaRHcG1Cbvb8baGN2iJYif59Rppdo4naBQ+m3uF1yICRIAIEIEuBEh4uROIQA4gkCyiCoIYR5Jrj9dP0Qkkn2kCmvoAQ/agzS1pDZ9pieJUVdrclhljg1YYGmPgqNdMF2km+c2BLw2HSASIABGwECDh5XYgAjFFIKxsINuR3GTjdVqIeU1c0wguEtfUcxf2ZemS1pJVaUu3zCDLSpz9yCzsfhH1NZGEgoJ0l+PnRIAIEAEikEUESHizCDYv1XcQQOQQBNCvL2y+kFzbNsxedaecYOPGjT2sx5y7xK62BjIL+cb69evTJrs5q7ThPFR38xK9tWUWJL9953vLmRIBIpC/CJDw5u/acmZZRsDWdCJSiIghiFm6lmskF/MBIYTbAuao+uFkJDfZ/EFIp02b1s16DP65qRqS1k6dOmUkCGheo8VOhwiv5+lc1SWC5DfdbubnRIAIEIF4IkDCG8914ahyBIFkiUtarnflypWuMwFR1GPUn9ZLcQbtLNtyBSV+qq9F5FoLQ3jREKdbTo2oqmQBWNjaXT1/4cKFolHhoE4PYZLW3CK/GKcfDCh7SLcb+DkRIAJEIHoESHijx5Q9EgET+Zw5c6YsXbo0gYZNUhEp1MioV9lDGJKrulaMC9dTHWw6ohb0mmG2gDMBDTIExcgmvPY17EIV6Zwe7PPspDW/0Vslv4g2+3XK0DGQ/IbZKTyXCBABIuAdARJe71jxSCLgGQEQKZAzRHjtqKgfj9ywHrt6XfXn9RqR7Q2S6wasanAhndCSwSCX69atMwQzWXNGi3FsOqmERrCd0gWv0Vt1l8D4sMZer2nPgeTX89eLBxIBIkAEfCNAwusbMp5ABFIjoIQRRE0jfyBc6aKp6NUmuYhaaiTY6/lByWrQ87K1F1SGAEyBiZL3dAlo6vSgRBQ4etEa29FbvwTW6Q9M8putXcLrEAEiQASSI0DCy91BBCJAwI0wQtLwyCOPpO3dSXL9SA40Mhkkiqw6YpBIvxXa0k4qQwcgag4CirGrXZkXQgmMFSP1Bd60aZMnx4YwBDbMuQohI78Z2kzslggQgT6FAAlvn1puTtaJQNBqWSBQShiRaOVGGO+44w5ZsmSJa2TXrVqaV11tGJJrXxd/VqsuL9HnOOwep4bXSSi9RHDdpBI4L120GPMPWt3N7VwvRN1tv+Lf6PMbh93IMRABIpBLCJDw5tJqcayRIBCG5KqzgupiU2lyFy9eLMuXL08QKSfJhT5UX5d7IZxBZQdhbc8iAT2iTpIlrSmhxMOHnwiu7diANfAqlXCLGHsh2wpDGOLMyG9Em4ndEAEi0KcQIOHtU8vddycbhuTargGIynmNxMIzFseCVEFDioiwlq71oiONKpIb5Lpx3SmpCK+OWSO406dPN/8EEouHi3QR3CC+wOjfWeACVeFsZ4l0WOr+0qIafogzyW86dPk5ESACRKALARJe7oS8RiAI0Q0bEdXzbXeBuHvsxnkTaGS7oqIiUWLYS0RcyejkyZPNA4fajnlxXgiatBZGLhE2akzyG+ddzLERASLQ2wiQ8Pb2CvD6sUAgKpJrR3JBfhDJRbQvXaNcoTtCWA8lqloVzSvJTYZ1UBIb1OnBWeDCT3U3t6gxI7/pvkX8nAgQASKQHAESXu6OPotAJkiuHclF2Vw0uAG4taAkF31FUdo3bguv6wH3BZQP9hMV9zsXJbHq9OCVTOI8WyfsVboQVCusUWotHKL6ZK/jtXHBAwRId2trq1+4eDwRIAJEIOcRIOHN+SXsexMIIlNQlKBnBXkIqqn1Q5JBjnC99evXJxYpLMnNVGnf3txFtmRBk8ayNR5nJNVrFDaMdMGuCue3ulsYvbCdREmrs2ztMF6HCBCBuCBAwhuXleA4UiIQhuQqoUI0D4TBb+KYH5JrT0IdHXC9ID65GskNem6ctxRIHx4IguhyMzUvpwRh48aNRpLiJdlNI78Ym9fzdH2DVndzkm51DElWqvoTn/iEPPbYYz3gC/PdytRasF8iQASIQNQIkPBGjSj7iwyBMDdiO5Kq1crwijwZGXAOOijJ1X7s8rZ+q62FiQJHBn4GOsqmZCHs8MM4NgRJksN4tTwxJBPqBOKlJDLOxXj1wUjLMDu9he++++60hVDCfOfCYs7ziQARIAKZRICEN5Posm/fCIS54YYlilGQXDsaC3sqkJcnn3wyLQ5hx572Ar14gOqNM63LzdQU7YcXfTuAh6d0Tc/zUxFO+wxToc0tWQ7jhaWbW4Q32TzCfBfTYcPPiQARIALZRoCEN9uI83quCAS9uYYlimFJrl2e1y2SnOw1MkDIxdK+XrdvGCsxr9fojeNsT2Y/frthCk2E8em1yS/2OjTSXqvK2fgG/X72xhrxmkSACBABNwRIeLkvcg6BuJBcJL6BUGhhAze5hPM1cq6X9k21WXRuiGrnWsliv1+CMElrTtLs1XEhjFUZvjMzZ84064L1QfOaoOfEhuTX727h8USACMQBARLeOKwCx5ASARAp3LDVmgnEMlVJX7fOwkZyg55/xx13yNKlS42+MqgzRJy3Ry7pcjOFox1F9eO6ENQhAvNwnqsPGMkS7HT/rVy50sDgtElTqUa6BD2S30ztIvZLBIhAphEg4c00wn24/zCRIJtIgejmEsnFkuv4tbytX2eIuG+bfJUshMU9qG7Xqbv1Wg5ZySsILSr7JYvcIpEOe9LNE1odM/BAhuIeag1H8ht2N/B8IkAE4oQACW+cViMPxhIFydVIKNwNNFvda5WtoJFYhT7M+W7nImFp3bp1xt4q15tWP6uqqvJd4jfX5x5k/E7drh/pgtPpwYs9mjNyi78rccZY0JIVQdH5hfEItjEK8zsQBGueQwSIABFIhwAJbzqE+HlaBMLc3MIQzChIKvoIM4Z0586bNy9BDtMCGcMDKFmIZlGcFdpAPL1EUINGjJX8KnHG39PJHpwzta/tR6rh7CfM70M06LMXIkAEiIAICS93QdYRSEcSvQwobB9hz/da2hflhRGdRgnaXGqYn8oxtJBCLo0/rmNV7a1i60e64PTphdWYF3s0YAFLMiXBQcgryW9cdxTHRQSIgFcESHi9IsXjDAJBozVhCWbYSGwU5zvdIVTrmEpuAcKLlu5Vchy2F3W52V0FkN+gRSpULqEev+nkEiC8+uCi5BXSIbsoitfZu5FfEG+vsiO9TtDfEq/j5HFEgAgQARsBEl7uh4whoD6zuCnjz0ESt7QPtQDz20dYoh3WAg3jhx2UWkBlDOyAHTslC4hEe3nVHvByPC0JAjYJhfQARNRLlTWvbg1wC1myZEkPUhqmwAWmEpY8k/zyK0EEiEC2ECDhzRbSfeQ6ShBBULXEKaI/fpK2cp3kui21ajhRbcyrfjNTW4a63EwhG02/SkLxHVL7PS/fHy0v7ObW4KWscJjiGJh5mNLINnKM/Eazj9gLESAC3REg4eWOCCxTUOicUVBUoALJdSvEkAxu7QPRYDTtw8uNHsf3diTX6zYCKVGZQ7rX0F779HocJQtekYrHcWF9evUhCxF7rD1KXHuJ3uO7pCWyMQZ8F/3u1bCRY0Z+47EHOQoikE8IkPDm02r6mEvYKErYV/0Yqt2HW1nedNMJS3J7s7SvEt+KioqMyh3USgzVtSCrgGTBr9Yy3Trw88wj4PTpVT2uFwIL8lpbW2vIru1n7WXUbtXdsIf8PMyS/HpBmscQASKQaQRIeDONcIz6jzPJPVXeLoOur5GiqnI5/OCKpKiFJblxLO2rkTiNpHkhMam2FSULMfrSZWAo+rCEtyHquJBK76s6clT8U82tPgB51QpjGmHKKSsMJL8Z2BDskggQAU8IkPB6gim3D0ImOCIyXuUB9myjjuRqhAlj0ShRYVmJjPnObdLR1Cpn1u2WY7/enBhC2ZWjjFxhdFN54NK8YUlytlZfyQiuF0Tnq+dnOmqcLTx4nfQIeNHNqoXe8uXLu3Xo1+nBPtkZcdakTD8Pa06tsh+bNXssYR/k06PMI4gAEcgHBEh482EV08xhxowZJhLkxQsW5BA3SESAgpb0xXD8EuWK6y+Rs3VHpHXvCRkwa7xUffJqafvFG9LvQ5dKcbvI+OdP+6q6lisk123p/MgdqMvtA19gj1MEgdQqhXhboNID/DuivOvXr3ftyU2z6+eBK0xZZAxIr4+xYz/7SdRzTojk1+Nm4WFEoA8iQMLbBxYdEV7clFLd8Oybpa3z86P39EtyndAr2b5kzpVy4vIBUrHhuGzd+qYc3XtIOppb065ULpPcZMRXHz5sWzNKFtJuhT59gFN6AGcQvFHx4gXtLIzhN3IbtjRxFAlzuvgkv336a8DJE4EeCJDw9oFNgZsQStzCh1ObGznETRH/ZZPkJosGN0wbIGePn5amLftN1DdZyzeSm2yeeCCBn6++Ml63bl0giUof2O6cooUACOzcuXMFel88yGqxFC/SAztyi98EP+fq9xr71tYa+ylQ4ZYw59ctguSXXwciQAQUARLeHNoLYSIW8OF87LHHxI7k+i3ioFCFjeQmI7m4meHGCk3vqH9YKIXlJXJm7W5pePSVHqukukT8P+g8cmHpnZIFPJAgYo8W9OafC/PmGKNDAA+7kAngu6UEFJIHPwlrbpFbL4UxdBZetMapZkzyG91+YE9EoK8iQMIb85UPQ3IxNY2ATp8+3cw0KDn0S3LHjRkk06eNkHFjK+WHD20w1/bbR8mYShl57w1y6oU6OfbrLT3O17n4iUjHfLnN8LxYifnR+ebCnDnGzCFglxXWqzjdEvw8PAWtCpfs2n6IN/pwqy6H8fuxStOxhP19zdyqsWciQASiRoCEN2pEI+gv7I+w22v+qqoq336vfgkqpl5eViJNza3ywH3zDdk921Ioj/znAZMEF0QbfNlffFCq9nfK+LJhgc6PYDmy0kUYXW7UtmZZmTAvkjUEQHghgUlGCHX/aJEJPwlrQavC2eQ3TLKaVpfD7wu+Q4hkBy2PHfZ3N2sLygsRASIQCAES3kCwxe+kdOV4Ud0LN4RkiWs6oyAkV8+9ZvZY+dxnpslD/75DqqtHysSJY2T7joZE1rXXSGyYMcRvZVKPKEqXBSUfuKIf0pJrmHG8/hD4xCc+Yaqspfv+pSpN7OWKTuLsp0BFFJKFsOO350jy62XFeQwRyC0ESHhza726jdZZqSxVOV4tFer04kSHURBM9PG+6ZfKnJnD5JVNJ+TaawbK6jU7ZMbVF8hrmw7K40+8mRLpKMYQdilLa4ZJW8MZaW9sCtuVp7kispWJ6meUO2R0+XKic5XF2HvMz8Cxh6AVx/la3MJrwlnYAhVRVHeLwidY8VLySxLsZwfxWCIQPwRIeOO3Jp7Iki0RsIs4JDsZN8A77rjDJK5FSXKVSDvlCpA0bNvRYCQOe/aelD8uf6fH0BCV1qhQELmD16UbcW+tSYTb/7XnepwCz194AKP1GzNYmjbvl6MPr/HatefjwkgWPF/EcaBNHGxbs6D98bz4I6BEFxImdVUIO+owmt0wJZEx7iiitlGSXycJDostzycCRCB7CJDwZhjrKKICUUU/8WoTxCeonjYKomzri3Ej8uvzGWS5lNQe+cmaHtHbcT/6SKJLVHo79IOXUtqg+b0+1k4TBjdu3NhrVmJ4sMA48BaAcge/qxj/4/XhEUQ3k/ssjGbXrSSy16ixkl99QMbfg/x2kPzGfy9zhEQgUwiQ8GYA2TiRXJssY6pI6oCON52ez4YlLOGOg1cuiC3cHgrK+kn/mmo59FbPh88AACAASURBVOAKQ35BhhHZhZShZMxg85lbJNjPNolSl+vnul6OVdKBY/1k5nvpm8dkHwF9oGpoaDDrGcSpIMio3ZwS/CSLhYkaK/lVyUUQj2AngUYf6vrixaM4GWZR/PYHWQ+eQwSIQHoESHjTY+TpiLA/dCCFmngWJgKLwSYjqEhc81piOE4kd/g9803U9divNyddCyTMwR1i46aDPY4pu3JUV6nixjPG13fIR6e69gM5Q/+aYbL3q7/ztOb2QUrqsXaptNS+O87QCdT5ZgjYLHWrUiIQXRBNPw+wUQ8xrGwhjEWa/t45C1xA5uWHuGqE3NYs++3DiWvYe0LU68T+iEBfR4CEN8QOCPuD5qwhH0bH6oWg6k1h5cqVrrP20kcquFJFcqurymTxokny+K/eNMTUTwNZRWnhVIT3R9+/SY42NMn931jRo2tEcStvnizFVeVSUHdEjq7dLZU3XybFVQMEMgYUuNCGSK/XCK89X5RvzdWIqb4mRvQfr5j9EAU/68hjwyOAqCYeqtR+qzeJrtts3GQLfgpU2IVx8ODo9ztlR45BWIGTn+tHRaBJfsPvdfZABKJGgIQ3AKJhiK6TFOJHWX/Y/d68/BJUtxLDfvtwwuVVrqCWZfd/4yXZU38yAOqpTwGhbmpq60am8W+47pJndsjiWyfKqKmjZMa4CpNM9+7Fw2VtZ1G3TkF+939tqSHXqVqcJQthgKWtWRj0MneuJqKhRK8S3cxdLbqew1RXc0omguh1nZFjvwUuSH6j2wvsiQjEAQES3iysghspxI8v/vNDctEPyBb+Cyp7QInhpUuXir4SRTRPI3t+9H92aV+NomA+cWogubcvmpQgvKtW18vcOWPNENd0FMpvVu8zGl5tZ3cckcM/6Bkhxue2TVMmrMTihBvlDvFYDXzfIUOqqKiIzHGht2YWJnLrlEzAfcLvmwgn+cX5+M9P0+gxHjzUqi2I7AG/vZpcGCZ44mfsPJYIEAEREt4M7QKvkc90l1eSC4KLH9ygsgfVByNTX5M88IPvl+QmsyFLN4/e+Pzb36w1tmiIKr9v2kjpFJG77pwi//LQBqmfcZGROCBhDQ1yiVMv7Ow2zN6wEusNnJJdk7ZmvbMa+J5DuoAGfW7cHiTDoBKFR6/TH9gP6VQZGX5PtbKcX9kE5m+TX/1N9uo4gYcYNLil2I3kN8zO4rlEID0CJLznMYrixyZuJNc2n1cLMPwfNwjcSL20sJIHL9fI1DGQM6Ahke1HD95k/gyd71f/drlUf362lE8dlbj0gW8tS9iR2VZiGr32E4nP1Hx6s1/V+UKrTFuzzKyE7bjgx/EgM6PJfK925DaI04JNOiEL8ytZiKK6G1BS6QYS3rzohmtraxOOEMlQjuJ+lPkV5BWIQG4h0KcJbxQ/Koic4ocXP3b4s1rb+I3K2NHEMJHcdKQb0RH80KcqMZzLJDfZ129e7QTZvf2oHG1olpayEhn99YU9Dh3x83rB60rVC/Z1kuuGpZIMfBYkMpZbP4/ZGa2+7o+D40J2ZtzzKm4RUz/JZk69sF/JgjPyrFppvwmcXnTLXks9K0pR3Kd6a115XSIQJwT6HOGN4sdDCSHIkUZO8QMblOQqWdbogNdXY7qR0pFce8NpFAk6Xue/55Jcwc+XCFXWxnzntoRswRnd7Xe8Tdq3NUjrawdk75tvJ+0aEoi2hsyWHfYzr948ljrfcOjrd3bKlClGnwtyxwesLkzD2pTp+fh9DuL0EFVxCrekOfy22xUv/e6iKO5ffq/J44lAviDQJwhvFD8SdtQTT/1BvVbdXBoQUQySwGYngniNLNslhrNV2re3vyywIKu8ZbJAtlBwuFkunTnVlBPeV35GOipKBBXYKm+5TIqHDkjqwQsv32FfmC0Nj75ivHzZ3kNA5Q66j/1GxfoSlnbpX/3O9qX5+52r7i3V2/qR04QtjoGxRpEw5yTx+H6gGp6fCLYbblHc1/yuB48nArmMQF4T3rA/CG6v9kFM/SR6YXP0Nsm1NyjGgldqmAcIr2Y8+51TFJv+0olVRlMLmUEmG8gtik0UH2iWi9a0JKI+bUVIYxNjQ1ZaUy2FZf2kect+16EgSgxSfPL5nT3KE2dy7LnUN3W+yVcrW6V/c2m/+BkriCfeQCEijubXpizs+bgm1hCSsDAuDUhYw30FpBeJc/rQ49cxwold2Hudn7XgsUQgVxHIa8IbZFGi0q8mkxmAWPp5delHrpBsvs4+NEHEa+JaEBy9nJOqWISX89Mdo9E03FjWDtgvx3cf6uHEkK4Pfu4fAcod3sNMJUQtLS1557jgf2dEc4ZtERjEHsyO2gY5H7NwsyjzIkVzJqzpWzr0p/aQJL/R7BP2QgScCJDwpijF64eYAtgoyGlU/aQaSzJbnGx/PaZPGyENR5tkz97oClGksxJDtPds3REpaWgSXP/SSVUybswg+efvrklZAQ7ljZs3748FYS4aWi5Vn7paioeWy8FvLU9bKCPb66rXU2JhJwL21liyfV31qVZXC7+/Jdkeb65ez66sBsLo16khbLIccPOSqKb4Qr+L/Amn7MeuuolIchDtsdsaMvKbqzub484EAjlHeKP4AkdRwEEXI1dIrr150pUYzsRGi6rP900bIdu2N/Qgp+msxEprhpkhXHDPfEH54FsONMicaSMSw/rhQxvktU3dC2dABgGpA0jlqH+4SZq3HEhZ3jiqOabrB/KKEffWSltjkxz9yZrYEl7nnkOkPd9tzdQjFoQFb1BIdNPt5ug+1yQxJAEHKYbjh7gmG3Wq6m52/kSqWUdll+a8RhT3zuhWiz0RgewjkBOEN4ovalS2X1iiXCS59tbCD+rChQvlySefzP6OC3HFcWMHyQP3XStPPb3dVE9T+QlucKmqn6lLA0oHF5aXmBF8qLBNphV2SFNTVxlhePM2nS8pjAjqwFnjTRU26HtBeNmiQSAfbc1sv2vdh9GgxV6CIBBFslpYpweMW+UKINLYF4jq4m2H0yGH5DfIKvMcIuAfgdgS3ihJrm37pa+K/EZe4kRyscx2aV+8xkPymR9bNCSuPfbYY/53TC+fMWvGOGnrGCKVldUmWujVDg7kFf/1Px/pxTRaX6iTA7/e0mNG6uqAD9wqsPUyBHlxedX5ggBEkbHeG6DYpX/puNAbK5D+mk6XBey1MJXZgvjzKgFHlUu0oHIFRn7TrzePIAKpEIgt4Q26bG7EFD9wfm2/cP04ktyovHJtK6mw9jhB18p5HrS018wZK48/8WaPLnW8+CBI9bOSMZUy8t4bEv0i2nvoBy9JZXOrcYqwGyK8KDkMG7JTL9TJsV9vMTZmiBSj/DCivlE2jK29oSnyfqMcYyb7yjVbM41SV1RUGLLu50Ezkziy79QI2A9Zmqzm57fPSVz9OkXMnTvXRHnVoUGt1iB98euS4xbFxlz89uNELIpAE/chEYgrAnlBeKMipvlOct02ITSH0FauW7eu12/cH79zitxYO0G+eM9zRl6gkgUQC7fIfHlZiUk6c2pvk33Z7MgtCG/zbzbLd+6+0pwP0vvy6vpuCXRKRIuqyhNk+dCDK6Sl7khk32cl4id+v1VOPPtWZP3mYkdxtzWzS/9GQS5ycY3yZcxh9bpByiIjYW358uUJUhqFVRrWQ/vB7zjuhX6JeLI1JfnNl93OeSgCOUt4c4HkIvITpKhEVNZoXre5Rj5wvB9jd6/9+zlu8OABcuGFNYaEq02PWwQNZPezn5kmSGJDRBiOuvjzD3+8wdVtARFaSBoQuT2397jR5c6dPdb0oe2XT7whf1z+rutwkfTW0XxOWvee8DMdT8dibE2b99Pf9zxacbM107cqfbn0r6eNnKMH2QV8gsgN3Px53SLHd999tzzyyCOuKEVV3S2qfhj5zdHNzGGnRCCnCC9+WHDzge4Pf/ZaXcwNgagIszo+gKCBqOKVkupp/eiEs01y3TDBj+W8efMEN3YQXz/jD/M9s9cC/Xh5TazRYByPxLPy8hI53inylS8/5yoN0OITiOyiWpoWmABJ/sCCi+TSSdVy/zdekj310VmkhcGE575X5ao3bM3s0r+pEiK5TvmDgMoEUNwiaKRU5S5aVEJt0pKVdE/2O6xuH+qZ7kd3rH2S/ObP3uRMokEgY4Q3qtchdia+/gh5TVRyQhQVyUW/dtIYSG4QXWlcS/tmS9+bTrKQaotD74vo7Lixleaws50iD+xuksMPrkiqhYUGt/oLs3v46aLi2+JFk+Sfv7s66SVRWhiV1lCGuL2xu+Y3mq8ie0mFQLbkDuq4AJKtCUpcmb6HQBDJghMl2yZNtbuQNPhpbgUuSH79IMhjicB7CERKeKMmuXhKxg+FGooHSQ6JmuSGTRrT8WBu+FHtzdK+6b4I+MFGtCNKfa/9AOM34/mB++abId//jRVyzeyxRsKA/9BWra6Xn/58U7opufrpLr51oty+aFLKCC8kDcM+P1sOfGtZWsL7v78yR7ZtP2qs09iiRSBTtmZavauqqsrTG4ZoZ8Xe4oxA2OIU+M1HhTX8H/+pR7PfBDO7yAbuhRpk8YudM/Kr9yBnMQy//UZ1//d7XR5PBLwiEJrwRrXJ3V7pI5Ib5EsYV5Kr9mhhpBheFzaq46LQ96arfuZ1rB+onSA31l4k9399hXz7m7VGxoCGhDP46KKhIhoqkO3/2nNeuxXogauryyKTM4Dw7qk/4eo24XlQPDAlAlHZmuF3B6+P0ZAtH+ShmkvVdxBwFpaAVtfLnlm8eLGsXLnSyMT07WBQ2QTQTlXgws9q2GWaMTa9NwW579rXjYoX+JkLjyUC6RAITXjTXSDV51HqVklyw6xE+nPxwzhjxgzzg71+/XpP+t501c/SX7X7EZAegEyi8ERDQ3Mi4Qx/B/lF8hoS09Q+zG//PD73ENCSrLZm0svN2nZcANH1ck7uocMRZxIBldmovViqhF+3hLWwHsE6t6jIr0rsEJhR27Yg8gkn5iS/mdyF7NsPAlknvCS5fpYnfsem0/d6rX4WdGaQMMBGDFHZxYsmGhszTVrr7aQz6Hz7T6w2vr1s2UfAi86XpX+zvy75fsV09mJeEtbcPILxhtNP4rD98AfyGqS8sq5VVNphkt983/25Nb+ME143F4MgCV4KK77I+DJGIQ+IgnxHGVnOpa2j+l51VFA/31RWYlHOr7qqzER7q6vKjaQB/0fS2bYdDT0ug4gvXBpOr92dVn8bZIzTp40wBPyNIQOl4voa2f+1pbEpIlH9+dlSXFVuClsceXhNkOnl3DlOWzMQB92f0CviNbQfIpFzAHDAvYaALRHQKCnuWWh4M+al2VpdzV/xUyAD14iyKhvJr5dV4zG5gEBGCK9NAvFlsQX2QW40akcGkosvchgNbBQkFwuryWs6P7+lfXNhc6Qao5ZVRVIbGogvXulF3WA/5iwIgWuAYD7w9/MN0f3q3y6Tow3NSS+txR1gR3Zm7W7fQwRhdlZXUxKNymtfPO8H/L/+6y058sJO3/1n8oRR/3CTGXtL3VFTJrkvNfxuLFy40EwZv0F+M+T7Elaca/QI2MQVVo8grX6Ja1DNsD0bp92a32Rhuy838us3Eu2GNGUP0e8/9tgTgcgIrzPSGbTogg4xjiQ3KrKcyxvRzUpMyS/mFWXhCpDaHz14kyQrCDFpYlWi8EQ6TEF6gxSNALEd853bZETdIWl9cads3HTQXAryBZQehk3Z3GGlctedl8uX/na5nD5fpjgsyU43H36eHAHVItqOC17kDsSUCGQCASSswZkBv5MI2gSVGjg1w0FLEttl2sNUZXNzjSD5zcQOYp9RIRCK8Eb9Oj9Kz92oyGlU/US1YL3Rj/2aLpVkIZ2+N8jYQXpRZrg325CPXil/MWe0nNt3optXr02i7XEq2UVFt0z69o4bOygyZ4nexDeqa6tWsqWlJanjgpaUxTWDEIaoxsp++g4CdsKaU2oQJNrq7CMoaY3Snky/V0roteBG2FVm5DcsgjzfRsA34c0UyUWWNVoc5AokuWKiEVpyE+vipfqZbqxMEN/e/tpCM9zU1JaSfEN+AYnFvz29Q0bee4Mhu1rRLerxq2NFqnLIUV8zrv2pvOjUqVOeKwRGZWsWV0w4rngggLcNqF65ZMmSHgOKgnBG0QcG5lYeOahDQ1SuEU7ASH7jsadzeRSeCa9mN4ct6QuwbEKphSXwKsSvEbezr6AVz6LsJ5c3g+Iwffp0M40wyYVR+PfmCpaQPaAtqu0qUfy9X73Zg/BqaeO9f/O7SBLaEFH+QO1F8vKa+pT65VzB0O847QIuGiULkh9gR8vwsB30Ju93/Dy+byCg5G/VqlUpJ+zm0uBX7+uWMBdkP0eZpEby2zf2ea7M0jPhhQdr0JK+cSW5cS3tm+3Nk0krsXwlvipbaGs4I8VVAwTyhYPfSl42VAkvEseQ6BbHBjeHtvMa5DiOD2PS0r94dQqCCllCVA03ZzzsQW8ZpRY9qvGxn9xDYMGCBeYhys8+VXmA7S3tl/zapBX7OajEwB4L7v9Bq7th5Uh+c2//5tuIPRPeIBPPVCQ3TFQ4l0r7BsHc6zk2DvhBDPMw4+WauSpzQEU3OEDA8sxuiOpW3nKZFA0dIOVTR5mPUkVv9fiTz+/MiDWalzVwHqMJeSd+v9VEnYd8dKpxcogjIdfEyIqKioTsKcicvZxjP6QFJQpersNj8hcB1ZPrw1PQmaqsDMEZ9OW1spt9PSfRxG89/vPboiSsUY3JOQfKHvyuat86PnLCG6X+VZ0a8KSLG57W/PYrfYhad5yrW8Spyw0jWQiKQa4RX+hyQXj/uPwd1ynD9gsRXrRTL9SZohOI/oI89q8ZJoceXCEtdUeCwpXR80B4R9xbK+f2npB+YyqlsKyfHPjWstgQckwevyeQU5WWlvrSkUcBnNPP12+ULYoxsI/cQgC/sXPnzjWDhowhiMzGbcZOa7GgiWpREGiMT/tBBFjzboKQaLsvfNeDOli4YUbym1vfnWyMNhLCGyXJVRF+WM9dktz3tk8mJQtBNmkuyxxAcBEBbdq8Xy64Z36C7AIHREpPPPuWjPn2bVJYXiJn645Iwy9ecSWQRUPLZfAtk01E1enxGwTToOeAmKOdfL5OCgokNpIGjZCpf6nfh9ygeCQ7j7ZmUSOaf/1pcZN169YZCUGmmp2oBkKtHvB+ymNH4RaB+UVZ4MKuFKflmoNEtEl+M7Xzcr/fwIQ3SpIbFTmNqp/cX9b3tI6Ijmer+plf3OJKfFE57XOfnmYcGVC2+P5vrEhMDZXL2hubTOW2jqZWQ2zR8GdERzubW6XylslydscRaWs8YyqcuRHaAbPGS9Unr05EgOHrC4lE8+b9hjRH2T5QO0HKy4plyTM7knar8gZokTFeeBaDlLfuPR75eFLNTYklXt9C9xhVhCwqPPVVLPqjzjcqVHO7n6jkC0FQsLW6dtK2n76cpZH1TaofAp2M/Aa1/ouSSDuxYOTXz+7Ir2N9EV6S3Hgvfhgrsd6cmZYp1rKvvTkWXPua2WPlrjunSPl5MvuH83IGlDBedaTFEFUQXUgYUEpYGyq5gchCyoDoLv6vMgccAysxt9LH+AznDfnIVDmzbnfSimgajfVbMQ0lmHHtXz7xZlJpBsYAeUO/MYMTBB5zRDnmxkdfyeiS6L5F1T5NRIsb0XUCQFuzjG6JnOgc+xbJ3Pg/ygb7JYhRTzIKXawdPdbSyEGcHpwkOqgEIxmRZuQ36t3TN/rzTHg/8YlPGNuwMLrPKCOwfb20r709NcKAfwuzPr295Xtb3ztuzCAZO7bSWH0hKgrS62x/88gWGfDJq80/I4rbf+KwxCEgonA5QAU2EEVEe6Hnxb9fUV0mX/qz9yetGucFexDSICWClcD/+883JSrF2YUyEMlF4l3Z1FHSb/RgKS8vlrNSkHH9sToujBw50uxbP5nsXvDKxjG0NcsGyvG7hj6kw588qHY1k7NyVmUL8jYiiuixEtaoqru5RX6DRpFt/BH1RSuArostbxHwTHhxcwoSdYmS5EYZYc71FbV1uXGVLATBWCNnvRE1ASF937QRxpEBUVFtkDU8tf2YzJo4VEYUdMrm/qXyXEdxj+lBDoDEL9h72XKHD7Y0y+EX3hbp7JQ/Ln/XU+U4EOWBs8bLid+/ZSQGpTXDjGY4qIsCIrwg8XvqT5gkvM99Zpo88N01smvHURl+z3wTjUbrL50yZOcR2brpQMbcGtxK/wbZK3E7h7ZmcVuR6MejhSTCeD9HP6rkPbpFWo8f2y+Lbh4vS57eLnv2nvQ0nCis0pT8qqd/UP2xDtiZyKfBnrB6f5JfT1siJw/yTHj9zI4k1w9a3o+1cUVVqahe63gfQfaO7A19L6qpoVIanvVBCPFnt/ZWR6E811FkiCN0uiCLILtoKgmwz/vsgSOyas3elHIC53XUt7dk7S65eWChuTmduHK0iRxDQ+ynIcKL+dgEfnv/Unmqo9jojitvnmwkGtDtgvAeXbvb/Dnq5qX0b9TX7I3+aGvWG6hn9ppqi1dVVSUrV67sdflCkNlqYYorrxgl18xol98/d1Ce++Nbvuei0gm8mQlqlYbxR1ngQom9OjqFkVAEwZbn5AYCkRFektzMLbg+EeMKuSxZCIKQvjqMusiAcyywHxs3ttIQS0RCEem1CSJ0vKeHDpRb54yRwQWdsqP+pOxvapM1F19gIrCwHyuedaEMmDnenKbJbOrc4Db3cWMHyZ765BEWOEJcUl0mdxe1yb88tEF2XTLcaIb9VGuDdOGzn5mWmA90yNu2N8jaHQ2yf/SQRAQ5yNp4Pcd2XMDrx97WOnodd9jjaGsWFsF4nI/o5syZMwXuC0HkCyqV2rjpoCxeNNF8F7/6t8mL1GRj1ko24YaEe0oQv+monB5s8ovxIEKrVmdB3io7yy2T/GZjR+XGNUIRXpLczC1y3KzEMjdTbz1nWt/7o+/flEhS27b9qCG/mrRmE1/nv33xnucMoQR5xU0MelhoeOG927T5QFIPXhDRHz14k7y26aD88KENriCojEG9fMf96COCym77v/acN9BE5IH75pu5aINcI1ninOdOPR6oNk258vrX47QCHUZbs0Cw9epJkC+A6IZ1DFGpFKRReODEm6Mvftn7dzjTIDiT3YK8OYwySS3KAhckv5nePbnVv2/CGyXJZWnf7ptFk3jibCXWm9tbs6JRbSuq14qQMTxw37WG3OKGtHHzQePSoDemVPPFMSC5sDEbMbFaNp6P9kLicOQna6R5y/6UcL3nnvCG0famarAtA5GGE8SZtbs9LwPGBnI9d85Yc46zYpznjjweaO9hdd0IEqXxeLmcO4zEN/5LZidTIqobVhM6d/ZY81CM3xf9nYFjCpJj49TSRWzxG5TuNw3zicInWHEh+Y3TDsn9sXgmvPpaHSRVXzcEMddmad+eJFer1uCTviZZCPIVilLfCzL4wN/PN6QQDTcklTXgz4j2oiIDkr6cDZFSJZBIMoNdGRp0vKmkDDhGiTb+fP83XjJ64HTN6w0nXT+Z+DybpX8zMf5s90lbs2wj7u16Kl+A+0JUlfUW3zpRbl80KUF4MRKQX/x+4P9Lntne7fsPT+zeLEbjJK34+5az9dJ802hPD/I20uAL4A7Q+6rNWRBc7aIU6DNsRTYnKVdO01fkVt6+Dfl3lGfCC79B6JfCkFzoc8IS5nxZAluwz0hYsFXFzWn69OkJ79ZgvXT54yLaump1vYnsItr6pT9/vyGlP/zxBnMzAim2k9g0uuu8plZZSxfhVaKN8xElxt8vnVRlJA651Hqz9G8u4ZRsrLQ1i8cqYh3mzZsnqOwHC6+o3kqodMntYVmTZFVXD+Lb2NQmY75zm5EuNTz6qin8MuofFho/b7eCNPhNwvmZbPpwVnxZtZTtbQmsr9V7Ht5ggmAG0Q0rGUdf6CeKimz6phn8JKxzRCbXgX2HR8Az4fV7qSilD36vHdfj89VKrLfxzrS+F/PTKA3+vGpNvTz+qzdd7cVUdwvZAeQHXtsHai+Su+683Oh53UjvkI9eabo69ustXrvM6HF9xXEhChARsYPHMazqUr0Spq1ZFGj760PlCyA7kEmFlS/o1W2fazs/QD/H9xyJsk4nmH97uk6aF06W49LlB4sS5vDzPr12l/Hgtptqg2E1+NOfbzLRYi9vivwh1P3oqOzJVKqgSXNBdMM2+UXRGqyl5gsEjdTaEeknn3wyDFQ8N4YIeCa8uMGli+6S5PZc4VytfhbDvZpySKrvhW3Q8uXLI3cCwA0MiWnQ4oGQPv7EmwkZBEoQ2w2WYqi05sfaC/0jextk2tm07C/+PV3kONPrpgVfYIsXZSQs0+PORP82qdH+sVZ46FFiO/STVxs/ZTRY1x38VvrsfI2E4ZygUbBMzDff+ozqDZETF43qwtkFvxP2w7JXDDd2FMrajiI5eJ74wo4QMinbklBzALRPEF+7DLrXawU9TqV4IIlB7clsqYJGa4MUyVDyG1WBi6CY8Lx4I+CZ8ELSgPKJzkaS677A+VL9LN7bt+footT3OntXP9t//9kmk3ACBwS0KG4ykFVcM2es0Q+7RWmgEa75wmw59Xyd1KOIRRZbLpb+zSQ8eDCBdR3WDBruqqpyue7WSfKvL++ToqoBhuBqaWmMA6+nT72w0yQb+tFmZkvn60bcM4lfb/cNXHE/w+tr3NOiki/Y88Ibm+3bGxKFHR75ySLzMUgporpOtxc3TN7tLJCn2osT0V4cA+I7ZX+j3FZ7kTz19A7zEI6+sBexjr3h/uAsABHUBiyqfkh+e/sbFt/reya8KC382GOPJWaikR78H9peFX3Hd6qZHxklC5nH2OsVsBbQ5EEfHVXJ2s9+eppxO/in766W7TsajJsDWphsa+j4PvuZ6YmkONwQkcyy5OkdPSQTuGni84eX7ZJ9a/d4hSLwcfbr3jA+yHFIwgkMgnUiSAwy7m2bffDeEwAAIABJREFUN+gnkXF/+Sevkpf6908cDZKLKK9Wygt7/Uy6O3z7m7WJJCpEJPO5TZs2zSRQISkt3RvLKHGYNLFKbqydkCCn2vfxroq2MjhJRdttHYXyuEtVxxlnz8r6B1cah5mnnt4uS57ZkXa4pTXVpkgOHr78PHil7dg6wGkDpjj7lRhE6fRgyxSo0fWzmvl3rGfCu3jxYkNqsREhFofWiY4CYnRDtt9o0MS+/Nta8ZhRlPpeRPXKy4rT3lzgxTvy3hvkyMNrkvrwAh2Q3W9/84YeQEGLh0Q2p1Ti1u/eIh8ZWCgHOwvk3j/9XcYA1opMkIfggSGI2b4ODtpjv8UyMjaxAB1jjbDuILoalTvbKbKts1AuLeiQjZ2F8rs9p3tU2EMFOz+SFq9DC0p8IcVBUiYe1JwND26IWncVRFiWcR2o17kCe+hUf/qzTZ5L4CbrGw/A8NTFPQuvzHurIQoL7S6wxn66v62f2UcfL2rrMSSQ4cfbSxKyBucB0IRftb9BXv7FaynXDA+cSHzTYjjoJ2iJcj+42YnZNl/w0weOdXN6wG9SkMh8lNXd/M6Dx/c+Ap4JLyK8+nQEgXmQzdb7041mBE5dLol/NLhmqhe1zEJkJxP6Xue41aIMSWupSA9ufqi8BE0wCBWix4jWwCXCSXZBum6+Y4rsbDgrV1f3FxS8cB4TFr9MOC6gWhyan2IZYecRxfl4VfzxOy83kXc8YCB2u62zQKYVdMjZ8xE5kJVkzU81vCDj9SN3wD5DFBea0lSRwLhJG2z3FCRlBWn47s+dO9ecumrVqozft0DSFy+aJKiqlspxxRx36yQZMGu8jCzolBEF50O91iQfaktOdvUwJLUdfXhNUmjw8D1oQY0gr8DZ/CbWBsFfz3H66YKwBnmQjqJCnI7JTsDDWPQ+HmaePDfeCHgmvNgceEVsyxriPbXoR8fqZ9Fjms0eM6nvteeBm9iQj0w1EZV9f7+0W6JJsvniBogiEckKUGhGNvTDn/vMNPMa/Y/L34kEPtWbIxEN8o8oMtW7brSXmAQu3FjxGjUXGmQL75s2Ui6sqTLRW0Ry0VDe+YWOInmxo0gGS6cpL73r/Gc6L+h2Tz2/U9oaz2QkuuuGn776xcOcWj35fX0c53XRSoG257VzvMPvmS/Nm/f32GO9IV9Qko4xQu4CiUg64gtZAppT17v6TLv8d2lZt+mC4JZPHdXt35AMmezhuvrzs83xiAbjjVPlzZdJcVW5nK07atwfEOnNdtO3FJqkFvQ3J4oKcckIOZNFs70rsnM9z4QXw0GUd+nSpZHcELMzvfBXoS43PIZx60H1vSAIfl9vquYWr4eTaXdRAhgtXfTFxkWz+ytvuUxmjB1kbmB2/8j0vnRStTnl2CXDpGjvCXnoH18MBa0WkwlbOtVtEIgoDfnoVF8YhJpMgJPxKv/G2osShAQay3NlJbKmo0g2dRbK2fMZ8ugar53XPPm6IfA24QCRwFqBRIQh9fqaGw80TtmB0/kh2VTz0dZs3JhBJpkTiZx4wNO/I4KKtqP+pIDw2g9V+H5fOe/9smt2f6n/2cueqoMF2D5JT9HorVY3RGGZPfUnTVKZ862MHcXGZ9iDkDQhov32mTYpub7G6G5VjgByWzx0QDd5AgaCfbj3qz1lTnjwrLxlsvHzDbM/o8RH+4q6HLHtyxuURGNs6j6Bt4Fs+YWAL8Krma1+SUKuQUbJQq6tWLDxBtH3asEIZFonkxVA0oDmVcOJm9Lory/sNomBjWek7idruvVRMaZSZv/tAhN1hBF9EE9eW3OuiWjp5EkgryVjBguIF8ie1/LGqAzXUnckYwkywVZdBFHc22+d1C2iBr3k0o7iRETX2Teit7CFGvb5OeYj4N+0Zb/nNU43VkhW7rpzijlM7az0HETlQFqQod/owds5X23NIMtQ31ot/f3Xf9wjBWUlZp+1vnZArrvuGhk0ZbSsH9QgbUVdWlUv5XDTrU+Qz0Fmx44dZN7agATDRgzEFx68aPhetTU0yWWFHbJte4MhwziuqamtGzG2re1w3tkdR6T/xGGJIWmRCmCQruG3Bg+iIMBuhSzSnZ+pzzVvAL68WpENUVa/byuidHrI1FzZb+8h4Ivw6qtPRHnzsdFKLB9XNfWcVN+LH1rsay8/sOmKRPhFEURyxL21Ulw1oNupTmIJqYSWL97/taXmZum1KdHFq281Z3eei5shLLWcWdyIoCHKZG62dUek4ReveJJp4PiuiOhIKbtytCGJCwYUmgQkjdB5HX+Ux6lFlPaJiNoTe07Lu5dc0OMyGDPwUKyBEV4Fp8tyx7xBRGzf1HRzQCY/5CpaPQuWZ4hs4prDvjDbJMalen3t7N+Pzjfd2DLxuX6P3B4cgQV07ZAEaFQUUXAQRrz50IS234ysTth2TdjULrWjmuTIiDJ5qqPYkF2/VnCZmCf6tKUOkDjgv90fnm4uBwkM3DxAWG0PZx2LJn4mG5ufBDT74frQgytSJtVmCot0/Ual03U6RmgCrpff+HRj5Oe5iYAvwospQtawZMkST8QgFyChZCEXVinzY/Sj70WU95o5Y5LqbVONVgtYIEJl++1qSWL7XLcoLqLHai3kBRXNcK6oqEhrxaQyBLfiFhpl8lL4ApHd/hOrZcDMC7u9egVZu398ubyypt68ss12g4Th9kUTe1S3QrGP37YXJwpE2OMKmnwGWYsfSYt9TRA7vNpGs7XaGunFv+NhCA9KaF5eVQd1d4hqjUD4yspLzGt9leqoVZdGPO1raRTeza1Ej9OoOJIKH/z123Jo2ZtGB49rvLtwihSW9TP7z+sbiajmmqofrK06fkDqcGTIQPMwg+8GdMiI5KvDB75HkDgdfnCFSW5DZDZZ8+sKgt8Rr2+gsoFLsmtEpdONKoLcm1jw2uER8E14cQNF8hr89YJkWYYfcvgebCN9PO1l25Mx/AzYQ6YQCKPvTTUm3ORwM4YdERqiirjRIxkHTV812vpQvzcx+/r22wov+xvaSFhXdYwZLMt/vjFpxTdnZBPkorq6TBpGD+mK5l45qoe+0B6XF8KcqbW1S7zC1P94Z4GJAD676ZAUfGRqtwh7l4ShK+rm1rCWIKU//PEGV7cMEBSQmKCkAv3ffutEWbVmb7fkRJAgRPx0HRD1hdTC6+vp3iC+WmkMex6JWU7fWLy1OPlCXQ+skHBV0XhGRu071kMvj9/w+fOulqobR8k77+yVDT9Za/S9iAbjQVLfSkDbem7fcZNMqNIGrA3IZboofab2oT702t99vDWANEOr8kG+grUFyT304EuJNwW2vAEPVJhTvzGVgeRNmZpfJvpVqYKt0w1akc22JkP+AhPUMrFi8ezTN+HFNLD5amtre93T0A+k1OX6QYvHBtH3JkNNK7S5fX73F542/wwig0iPNtyoIVvwe1OGmwrqyjc0NMjbrUekbWR/T2QIZHfAzPHmVXDrw6vlwOYDKTcBbLuKZl4oV88eK5v7l3ZL8Ep2YqZskPB6Gxi7WW4B16s+9T5Tne7/ve09a6bH27v0uoOaz8nJsi57MWCOiKCXBw1EF5Hwdv/XV0RuD5fu26eRXewNkF8Qn5a6o+lO6/Z5NuUOKj+AHAFvNpCUp284EGmEZzWaXT4X58A7FsmCC4vaRb8nIM94aDxxephsqGyXQ8MLjea1ZN0u+fP3DTPRXURO+/3VteYBBg8DiJpqUhceyi64Z76vhwRfwIY82MYj2YMM1r+oqjzww1TIIfb66VFKFaKyS+t1UDgATwgEIrzaM5LY0NxKDnu6ehYOckoWkL1JDU8WgM+TS2CP+9H3uk0bkacv/fn7e7xKt5OTtFgF9HzQiyKy6OVVNa7nVvp3yuSh8pcw7T/VKav+5pm0qwGicP2dl8uGIRXmFapbw40Wsod5tRPM6/RNnUXSXzo9kV30l6norkYQ3YomzLxlkvzpbRPNdN7qKJT+BZ2ytqPIkF2MB+4KmAtsmqC59aLPTQtmhg5Qsoc3A87y01pc4My63b6spnrD1kwlG0pir711kpTePDmRMAgZycSxXW8cNEkN0eEf/PgN+fKXrpL+pR0G4W+1lZgHQuzdWYXtMruw698RQV7RvyxR0hkRXRBeREOBE6K/iN5HkcyGvoeWFcv/ua3G6HKjkOrYWn3syYPfWu77wTdDWzB23doPbprsFrQohboz4C02Ir/wbWbLLwRCEV5AoVXGsmHo7xV6Vj/zihSP84KAH31vsv5w4/7Sn13drSztlvqT8ujhc77Ird2/vc+RkGEXhIGEAoTBrewoCHhVdXmPxDG8WsbNds8Xf5O4DMjE6NnjjFQB0bGDllWXF+z0GEgEkhFpP/0kOxYRZ+ns8jLVV8U4Vn1cQZj+ud8AQ4Kg7QRRsl8Vg8hjjEElCFHMIV0fqZwc7MTHoCQprK0ZHh7SJVJiPfBdgDZZtbzYY//7K7NlT/9SeWr7MaO5tRMLVQqxa885IwMqLGiW2k+/T1YOrpCBVeUyq7DDPHihgMOFBZ0Ca7eto4cYDTmi9UgcBMnF2BA19ZNImG5NoL0vLy+We4tbzaFK4tOdl+5z9bEuGjrAPMBEOeZ0187Vz+1CEupJjd9Ev03lE0HO9XstHp9dBEITXgxXyzauXLmy1zx6KVnI7sbpi1fDk79Kefy+1bAtlRQ7vNb9fluJtDU2+XI+UGcJJKKlqg6EV7+wO+qsGWaSXxDRxI1Ti1g4b864ycLuqHPzfgGBPFRWKvO+MMNEctG8RHOhW4VdGkgX9IiInHqxS4piP9nzUmeDi/cdM5G8TdsbzKttrTgFUo85gkw1NrXJmO/c5mr1BiIJbWVcCAeSvzTyif0DDTFcL6D5Rdt1yQWJOfrJ3rfxD2Jrptn/kK20PLtVTp93EAHGkDJoQ3RXPXXta0LC0D5miFkPPHhN2d8od00fbg5Z2t4VkV/49gETQT3WWSAXf/0mI2XAGxFoXXV/Xrb0DXlm9V4jW4CkAU4E0Lhqwhf2Jd6ceH17km5fYt7jFlwiX/vAeHNoJiogphsDP++JgDNaC/IKrS5b30YgEsILCPFUtHDhQkGkCbKBbDVNzgEZ0Wun8xXN1th4nfxEIIi+FxpTEFBNWgMyW8+0y2OnO81rdUSfoNl1a8jOR0SybOoouXBnoVS1l/lKtISOFSTixLNbzY0e5AJRNo2EIjkIpHT0vmNGC/v6jAkyoqBDRhSIvNjxXgEGVBg7Liiz6y5jGLnzsLzz5BY5svdE1hceRHb42EpTBW3777dJc6cYTbS+ukaJYxAgTUbDAwDI46TX98pvTneaV92QMyC6iChkU3ObwBZMLaGgk41LpM0ubLCn/oTc/40VpnSw2pl945HNUvH5OUaPDF3s8V9vDvRK3I/O17bOuq6w3URS6/eeNA9Xv3ziDU+OJnC2wPoYjeraQ/KxqZMMSRl4bbX5rny2osC8sUCSIXS/IK+IyON7oQ0PMqrTxXphzd3K6rq5b4C8Bnmw0Qg1iPzjT7zRQ26CscXtwSnrX9BeuiB9eXsJ+JheNjLCi/lp3XJoafxGwPzgQysxP2jx2EwhoPpeyHm8lOOFlADm83jt/p+r90ndjIuMtrCj+Zy5MSezwFLLMhw7feth+fCsYd2KE4AQ46YPrV+ypoTPzb/38w8tlukFHdK/QGRXZ4E80l5iSC3K6T7U3mV9lapNPXtWitftlv9+envWE7h0XFrdblZBu0lygp4Sr8zx/3vvu1Z+M7IqoTX+4Bt7ZN3lYw15n/Lidnn7ui6Nb38R+cK5JkNOfnq6U3add9BQ54ygNmPp8Av6OYgvyBYivJq4B+cIWHm1lJUkvHtRqAAuDkEj7XaG/NXTmmX//uOy5Jnt3Ygdkq2GTh0lC6ZdIPPHVpi9BI06IrZYh8rzchg3dwS1WwNB7dx9Ui4ZNMro5vWNIeaItnjRxIRjBRLa4MiA/tW/GgR4/9eeE4zlgr+6Vg794CVj4YfvRvHQ8sRxeAvh/K7oGDIlvdEHAj+OGkH3Bc9zR8CZ7KbuNczp6Ts7JlLCq7ChhjlI6fPPPy9RRVudkgVodKix6TsbNa4zDaPvBbFSFwb7zzpXjSTvml0qZ6qKTDb+oDGV0lY1oFsBAkSwcFN308jiVW7ZlSPl3N4Tpkqarc/FdfDK+YH7rk3Au62jUF7oKJK7i1qNXhf+tCCGzgbyfWbdLhNB7G3dqxbMwBw/Ome0LJje9XofDRn7n/30NHmnqV1Ka6oNqZ1+PrnJbU+h4trGziJ5saNLxqENZAxR+CgSnTK9l9Uy7fFfvSENY4YkipUgeg3yGySKqWNWbe2OnaeNntYmC1pIQqug4WEDpBeuDDf++EOJpDTsmTNrdyWcJbAuFdfXSPlz+2T69OmC/f7Of79m3kaoVML20lULPVz/RFk/I53B+WgglJDRuDkxaKTXTc4AkjzEWNOVG9IcdUNhGZVeeHEBifr67K87ArY1mSa7kU/k/y7JCOE1N9Jx42TmzJmeq1e5QU1dbv5vwHyZoUp6oKmFP6T9oIcb9OJFk4yE4I/L30k6ZUSy2toLEomgeKjb9m6dDP/mTeYcEAW8dod9GF5Xa9Uz3EgrFlxivEX1Zo6+Lp1UJXVDBhoyjOpo0OdCY2k3u8gB/h1k92ynmHKncDXY1FkoIwo6Beb+0EyiGEY2dbluYGl55z8sf9fgieguontHHu4qxQxZBhKJQGBWn+kwY77p0qEm8vjP31st48ZUyqRJVca3ddzYrjLQmPOuzkL5LeYvBUbvjIeRuDs3uOFjJ7dBAgBNa9Wnrk5UywtTiAHYQgry7q5Tcq59pKByHyJlIAsX3HKZ3LOoRo7XHTXHoIHwQsN7DlHamuFSP3SAIX76wAS9N0jtmI/NkDGdlfLq48tk6FfmmX2KqDQeBOE9izVMZb2GPjBHjSBDwhNmnlH/LmkRCcwnE4Q66vH2pf5oTdZ3VjtjhBcQBi1SQclC39mA+TZTjcoeOviufGDBUPOqedXqerl90SRz8wdBc1pKAQNoe6F3XLmmVdau35NwXFCLIn2djhu7JuQYolZ3RPqNHmwIsO3dq1ZdiHC6uRfgXCfZda4Fop2QNJTVHZF3fr1FTrlocxE1y3bkE4QXNm/Ac/P2BuPXqq4Lpc2tUrPgYmmddaHcWl0qT50nsDcVthnbKkQdlzy93bhUgPAi+giJyfEPTzORc2CIRCg0EKbejl4H/X44k9v+41dvyqErxyQKG+C1viYxBr0G3g40HusQvNGrHD5UXq/tkh6M37JX/uR9XQlnsIr7k2/cKCvqT8n2HUeNphoEVmUi1Y/Vy/BLxsjWmV1vEaKIfqqndVxL5wbFm+dlHgH9/UYA48knn8z8BXmFrCKQUcKLmXgtUqEWSzDNhx7SS3WorCLFixEBHwhcN3+KfPoTE2Tv/hb5+wf+YM5EpS/oLX/6s40J0ouHQvzIfvyOMTJ4UKshZHhVq9WYUI4VGerqelBw/hWuDkWLJejf9SaP82f/7QLZ3r9UFha1ydCyEvnnP1vSbQYo7fp/vjKn279t6iiUwQWd0q+5VXb37ydLn3xT6p9Pbu0DfTEqWWXScswusQpiCzIHLfQO2LpVVproH6KBmA+qk106qVoeaS+Ws50FRpYB7KDzRJGJLw4UefjfNpjyrnjIuO+RzabIBhKdkM1fOnGYiYQCV7W08rHssTsUco65c8aaceHBa9nRFmm/ribxgHTsN5t7RP29TEIfqGABpvZiY6ZMkIn/o0bmDSozbwW2vrXf7GU7oQ1vIFRacPnrxbJrxesmydlvyWwvY0x1DB52xo6t7FHBLWy/PD8/EABvobY3P9bSnkXGCa9eDAk+2ETQ9WqjZCH/NhRn9B4CTn3v1CuGyO2LJhoyCxP9iy+5whyMh7uv/OWUhMk+pA/6Shjlb79/PnHswoIOmV3QYWQH6ocLbalaLqEvELUTP3hJzookKljpiNwSZmy/U8gWNEkNr5QRXU6XZGNX/crE2oPYnh46QJb0K0sQUJCVj3/scnnjaLNsvHiEcU8Y1njaRH2BLTSkw8dUmsSpXyx7V1548g1Z9KczpODKUXLFsdPy4jPbDQnsXwNiXGL00HgV3rRlv8EsiuhnJrAI2qdqXiHfADZrtzeaAiNSM8x0GcTJwThFLJokf1z2jnmI0wbHj/Flw6Ts1UbzT3BZaJhWbjS2eIAoPd4u1ffVSltRZ1YfKCDFwJhBzvGGBfsK3zE4SGzcdND1rUtQvHkeESAC8UQga4QX00eRCkRw161bZzS+yMSllVg8NwZHFR0Ctr73wnH9ZOEHhsjho51SX39CttftMzIHEE+QEegd8apYK0xBVgBSBscERF4NiegskKUdRfLqL14zf4de0W637G8wr+X/+/Jx5p9B4KCbdPNltWUN6tCAcxAphnUXtL9IckIErjde78MiDJIDOA84G8iVJuJpwtT9X38p4YQBy65njrSYhL17butKatKEKvz5P147LHVDByaSiUDy4bkbF/ux6HZgV08alcWfoe1FYh68idFUA93e0BTIwkzHqm4gSm4hdxgz5WLZ3nFYOjccMJrf169oFRlWLnu/+ruop5i0P7xdwT5ataZefvqzTeZtC/6Opm9VsjYYXogIEIFeQSBrhNfW5WKm2fbr7RV0eVEicB4BfdjDXweUHZX3Ty9N3HDxWhjRJ0R2Gxqa5ON3Xp7w6wXh/W1HsXy8sM1ELLWt3nRQ/u9DG0zClrON+8/1pjjB00daZNXRs4lkJRyH1/9IFIJeGBGuL375uYSWF9f6fns/k8l/+AfvlRdGFBeFGdJFezO52CAoICuPP/Fm4jJ4NV5582TjLzz+lsvkgy3N8sbRszJ1YpVcVNBhPI4/MbCgG244GTj/YvdpKZp5oXm1bzcQP5D9ME4GmcQhbN/q4QssoV/Gg8ywz89OWHah/2T2eHptJMWhH3st9DNozPFwZbtZaAU3HIOSrUjqbGpvMY4ZSC5007SHnSfOR7Qf1mX4/48e7Er8xEMQHiZBdvFnzAEPQc4xwK0BVc6CWrlFMX72QQSIQLQIZJTwJpMs4N97o0hFtNCxNyKQGgG79C8cF6BVhHsDol43LJgsQypPyagRYrxEcWO+/+srTIlVdQ7Q3lFpanZhuwx2uIMhIWjcPfPl6NCBiYEMqTssmx9caQjz7v6lMsCK/nYVXdgqV1eXyec+My3h5auaWHTyv/7rLWlYu7tHlA/kEolzvUEE1TpNyyTjFf2wsZXyzuih3YoK3F7YJk91FHcrjHFv0bkehBfuE//VUZxy8ZDQlQsWZFF9ByGLgfsHrObwQJSs2VFiu9KbHm8XWFBfdnwGX/ahgwvl1ltmSVvHEJl9NUhmkyGfmahOpuPUNwMozIEkx4aGZvOAh2bKTX93tZFk2GWRbc1xFEl0Ua0R+yECRCAcAhkhvJrpmKr6WbaKVISDh2cTAf8IaOnfqqoqU/rXrfIgZA633TLVODloww1YX7PaVwXRAzHQ5CN8BrIAgvzFf7xBflVabkjehQWdsril2URt0dTSCa/97aIJSNhCBBivdhHpQ1MtL0iBW+TOPwrBz0D0EBpLlEVGKVktGYweoWnGwwE0vf0LOs3f3XyCcSw0z5CCoCEZb2Nnofk7LMigi4b9WLKGSC8S4Zw2bsFnlbtngjxi72G/jR07yDxMYa/CecROWht+z3zjGIJW9toxmdw01MjXtKQr9hz2Hhqiq/ieDB48QL77L29KxcDT8rlPTzMEFCWtg0RWsW8++5npZmzbdhw13xndy5gDItoYAz7Xh0qMH9Z7kAVByoKkSCQwdjafM+4jUZUgzt3V58iJQP4gEBnhDWolhmgXtLyoVsWsyPzZWH1xJvgOQLpQWlrqyWXEjpY58TIkt7rc3Jz/uPxdo7+0Ca8SUxBVSBHwelglDzhHSS/6RRUpJGSpBhfEAK+lbYs0zeYHAf7la4c9RzeVnKonbhTrXjVrvFz1qffJ9LcPSXlZceIVNPpGwh60p39W1GqcANDub+vX7bKotjakQOTSgu5R8Xc7C+Si8+c83l6cKISQaswgvLAn68tNy2LDccHZEPnvKgfcz0gjVCLS8vIeOfTLruMRkb9mzlizl0GWNXkOhPTkqTZ59thguaKkXaaMbJYlJzrltQGlgezJbD2624Mb3mTg4QlWffYDlVZZs+em0p++vO6cOxHINwRCEd6orMSQwIYKOyS9+ba9+sZ8QHSxf9H82OlppridSIU+lLCq1MB2bVBEEZlas+mgzJ42QjrGDJYPTx+eSHRzJuGAWOAaqZpGUf+w55S8PKrKJDElM8hXn1O87v3onDGCcrb/8tAGk+2OBhKERLlUhQLssYDMQ0OJDHq8Wsf50wra5UNF7T2GvKaj0BSIQPQW5ZDhVoGkvhHSKcfhSywFMlg65eNFbQlCjE4Q1dUHAvwZbhSIDCMy/qHCdhMtxkPDfzzxppyaeWEikQ3nupWidQ4M2tXBt0xORAlzfefbUV1E1LXhrcHIqSPlgrPnZEv9SeOBjLcHeIswsKnQBC3OnjjTzaYOhBkSGrRfPvGmzJ09pptsBw8xqPB3y4GjsqxoqDRXtMuuby2TxqY2E20FicaeSFU6G32rPhkFV/AAhu+PVnrTfYkIrlr5aVQXhB1/xsMNrgMLO9vTOtfXkuMnAkSgCwHfhDdTVmLq1wvCsGfPHq4PEYg9AirdaWhoMLIFv28o4BsLMgqiuHgRSF+T3H7rJCNrAMkFcUWEE0QQ5X9V7qBaVmTE4wYOIoDEHOh/V63ZK8tX10vJmMGGtI4eUGzOBUFeX39SBl1fY+zGtAoVbvAgMTcPLDTEFVW5NsyYkJLkIdEJBKHqxTr5m89MNeNWraQmuPmJkEFfCXcKRBAn/ujDhqiqFMFtE6DcMRwlbFL7rbYuiQIILIgryCzKI8OLF/3Bpk0jwugTBOtxS8cL/a+WHIazg7HtslqfvJ9UAAAgAElEQVRxwxnZbSWzgfRdUlUmK5/vqpynBUJypdgByg+DECaTr+ANAKKxkBjYDdHQjy2aaIp4QHvbUlYik0ZcKEPn18ihEw3SMvcC1wpnuBaIM9YZrfZT0wWRfKwJcMdDyPr6U7J8VJV5mLl88xlZ17+/HJlYYmQFKI/ttUIZvld4GwL5hC25sBM8IV/A3m/ecsAkaQ77wmzzsALyDucKlCvuazru2P/gcoBEICQCnglvUMmCn/GB9M6dO9dovpDJy0YE4oaAPvDBXs9ORItqnPraFeR2155z8t0fvGyItNoogQSjPbvpkLT+z/ebP+//2lITkQL5RdOkGxDeM4++IjdPv0Ce33RISv6fOd1cCUDOULUNDTf7K8+2GPJdestlxpvVzYYMETf0i4ZSrlP2Ncrba/Z082Id/lfzTXJbOimAXQIX84Ku87pbJ5m+9o0aYq6BqCxI7KaOIhPBvbSg05BdtC8Xd80Xf4dEARrmD513s/hte5GRLKhOF32AIB/rLJCy89II9TJGH4gQX1/YLpcWdpg+N3YUmgQ4tOsK281nr51pl51r9sh/P7Nd/uf3bpG1HYWm3PKZdbsNfsmaugVEtUei6AcRXDzg4EFFI7hOT2VETCdNrO5WnAHH/MX3bjYR3oe++5pcddWshE59wG2XGRJp68WRcIg+7rpziom24kEOe6zmC7Ok5crRZirXnj0rcwYUJqL1+Dc8MEEmgQeJUVvbZO+Lr8vZgwfMw5vTrQPH47gJ5cWmuAi+QyDrtqzHrPG9tSZyb48P/66SBjuq21s2fFGsLfsgAkTAHQHPhBdEFPXSNQEhk4BqkYpVq1aZrHY2ItDbCNiOC7DUw3chU3sTESrctJe/uF/+z98sNKWGL5lQIihcgSgo5AeabIOqYLjZo6nPbmlNtXzsr+eaf1t25KzR40KGgFe1dtv390sN4R1YVS7XtpyV//vXz6aFGVEyEAZE3ZQsa7RYT0b1NbwmPvrwmpT92YTXeSCcFEBw1xqi2zO5DBpeaHKfO+/KgFQpRHRVtoDX5EhUU9lCqgQ1vfalBR2GFGtTD2REHG15xdYzbfJSaVmi+AewSEV4EcFGQ9KXLQ9IC3aWD1BCqOupGnOniwLmgzcTS5a2yIoVr5jKmGh444CmyX7qruGcBmQNqIi3tandFAYp3bLPrBN8lUFI7abyg1mtnbKw7D1pBWQ/INAqhcG+1CTFv3hki3kDYUfbu2Q2J4wbA6QLILQg1EiOQ7Jd8dBy8/3oTeu9LC83L0cE+hwCnglvtpFR39KlS5f6flWc7bHyevmLAN46YC/CcQERXRDdbDX1Dz3bUijHj5+R3z5dL+s3bO92+XkLJpjomboOQFdb0tBkfEfxmvitzkJ5rqPI1ZFA/VbxehvXgnQCekuQMhBu/IdI8w9/vCERwQW5hqYV0V9E+xDpLKs7LD/53nuvvkF4obv0YumEayM7382dAhPVJDWdNPS5kCdAtoCmhPb2wna57Hx0Vo9F5Bfnj5ROWdNZlHbZbFcH+2DYwuG1uy2JQPEPoz3tLDTR8PaGM6YsMQgTtMvABtFwPGyAOCJRC64YcSG8iN4CeyREasNDEdYX0VXMAcd0+dW+V0kNMp6ST10up8o6uhWOgIYZVeqw7iD/swo7TJRVKwbaeDY2tcp3Xt4vJdfXSOsLdXJy7wlDQrseysoNdpAVYJ8N/s0mOTNmiHy+drycbmyWlS8fkflzL5FJNcXS1lYgxcWdRnaxb/QQ84ajc/N+aa0qN/7MWkAEZBfacPSHhxNcC+S+eOiAbnPA9UGA9U1J2g3DA4gAEcgpBGJLeIEibM3mzZvXzdomp9DlYHMWgaCJaFFP2HZy+M3vjkhZ+ViTGKfEG6QFhLdt6ABTfa3u+bdlwr5jiSQh2Hbh30HMnA0RXqevLqQTaCA66g8MQuFWHMA29NcoIIjP6K8vNH249W+TK5AjkA+NGLphhyguktTUiQLV5hDVtRuIqhbmgDYXf7eLdOBY9POz8yWak63RNBPJfS/Cax+H6zt9kBFBRlEQuyGy3bLjyPlEq65yur1RoS7dPtR9ZVvTqcwBLgbO9cZv8cyZMwV6dVRNayvu7GbZptptXBekcv7ZZmNb5tagwYYVGPC+rKDD7M/De0+YQw8/uMIQTvQHrTBkF2rXh7cb06eOMEQa+/PAQZGRI0Te2Nooj1cNMmQZEeFjv9ncbWxIrMNnaJqMiX2KiG4Q+7N02PJzIkAE4olArAkvINNkNtVLxhNGjipfEFCi29LSYhLRsiHhSYWdJqNB+4gEI3wfYOWHBp07ZA6aAY9/g/YUDZFPaEyTvcoHMXArMoCoHnSpeB2NyJ5GJGEtNXZsZULPCcKAqNm14yrk9SEDZd+jrxqSAaKC6Jkm0yWbW9fr60qTiATS/r6pI7rZriU7D8QTDgtu87KjvwstPa7B43wVuVRYQxIBHXCyhogxNMCwNtMkOPzbmo4ioyPGmPQVvEocMunjqk4KtiWc1wIhWM8v/fn7u8ks/vKhxUa33PLsVjn0+7cMDJDyDPrMVXJp4QWy9YkVCfmCG0aIkFZXl8mN4ypMZFfLY9vHPtRWYqQg0EXPLoA7RlcUHxprkF9T6a/uiInO/n/3zZdj0vWggqTCSWdbjH4XhFf7hvb79bf6ycDRI2TrjAIjMzry8GpDZiFTgLxCo8+ItqvXbr78XnEeRIAIeEcg9oRXp7JgwQIjbUDFHjYiEDUCkC3ADxoRLBDJTOlzoxq3PggOKG+T6+cWmVe7aHjV/kh7ccqiCiBlqus1CW+W7VSy8alt2d1feNocAmKLyBlK9/62o0gaHn3VVGhD0wIEe7/6u6TTBQnpbG6Voqou4jxuTKV8sbsxQtJzITFA1NdOOnMeDAJ17/mkNnwGUmU/AIBUte49bl6jm1Kz+47LRTsPdSNTzj5BmkFqEaGEvhgSB+BtPJCBvRScT/Y7blwy0H+mCK8dXVfXDrV0S2Upp3NSz1pbnwvniYKPTDWH4EEEdpFT571fNs95ryQ1rvuB2ovMg49b1N+2IEM/tuWe7YyhhVLw5gEJg9NAgC1JyndPiZwrKzEPIDgGDzPXv31QfvC91TLyo1caOQTOO/LCTtnz/E7pP3GY0e2OPdRP4AHcMLVc2i8eZNaj8dFXzH71ss+j+n6yHyJABOKHQM4QXkDHIhXx20C5PKJkpX9zaU7QVN668FKZenlXYhdes08r7BCQwrVJdKuppAbJ5o7IL4ghIs120wptkD3gM7XnwjGaRGcfD+Jx8exxJgJ44cRqOVHWzxSSQEPBiIVF7bK/qc28enaWWMYx6qer5EkjhYbQnp8vks9ARjWCCNKl5AwSjyeWvyPHNh9IDAtFNxA5RCUuNLuAgRseILkgYbimNryex2t6uzndAKLeVyCeqg1G34iaww/XS+KV8wEG52sktOCFerm8c4ScOnXKBBgG3HapSVSErlcT0Wy7L5xrE0q7opo9Z2APH2VghzcQILGqwYb7BuQk328rEawfIug4Dh7JkKOsPtMhrQ+vlkN1R82D1leHF8vSjq7iIV1vK3YLkjWR9FayuVEm1veXk+8fLMd3H5Y3f748aujZHxEgAjmIQE4RXuCrRSpWrlyZ8vVaDq4Fh5wlBLT0LyK6mXZcyMaUEHX7k0/PkqumD04QQucrfHVWQNSxq3xqtUkM0gbCAt9Rp6ZXP0eRDLw+fnl1vcDYHxZiIJFKnKCvxOdalALn2V68uN5ld1wp88dWJPxucQxIECLS6sSAYhKXHzslo8qLXRPZ4LeLaCp0uiA7hvC6EHxEEK/Z3yiNm/cbGyxYnXltWvAjWalnux+QX0gscD2VWYCAnXh2q6/oLtYQzU9S2wP3zTcPIbb9llc7Lbdzde0GvHXaPKwkk/MAH+eDDxIVO5ohJ1gj100aKnfdeXk3uOG6geRJtZLDuqPUMx7Q8HAC8qtE2LlOwBaJbVp4AnP8kzunyNKLRyYOVV9d/AOOwx5X+c/IkSO76d697gMeRwSIQH4hkHOEF/Djh2zhwoUmmY1FKvJrQ2ZyNki8gXShoqLCEN1c3zvQMqr+1elygEgoIpAgsCv+bZ1MHDtI6utPyLGa4ecz4bs8Tu3mtBezPwNBAqFFRBHXBRlE5FSjsHbET10a0N/Esy3GhQGEGgleJlHJ4abw1LZGWVF/SmaMHST/49Iu/1235qbDRTRwVmG7PGWRZj3XS6TT7Tr2636Qe5D6VGMC0YUPsJJ2PFzgNbqfV+huBDTddwEaXqx7suIROB+R+W9/84ZuBRjw784ILwIJkEQ0jCyQg/+0TNrSVOZzjg3aYewnPDSVNrcKorzYJ9oQ2UUkHw8rWjAEpBdkFpXyhhR0GkcRu128r9H8m/oDQ4+LIhGww4OlGFpb4xkT1cV1kQSpch27H9wvMD884CJqDcmS3yIx6daCnxMBIhB/BHKS8AJWROmg62WRivhvst4eYVwcF6LGQeUEScnYyRL5wb+ukl27D8udP7498co9WSIbCCI0p6a4ROMZV3cB9QhGJSs7KQmeqCBeiL7BngoR2Iv3HZOrq/snIrV4XQ25hSnicL6ABkjRL594w9hjIZFq8aJJCTs0t3lpRTX9DDKI2YXtrolsblpWXE+j06nWQ5P2EHl1kje38zTSq5/BAitVxNzZh20N53WfwFEDDx33f2OFOQXaaZBDRDhBdD9+5+XmIQeYOstNj541Ti6pLpNXX9xnnHCQpPnOjQOlo6Ir0g+Nd6qG8WK9ljyzw1jauUWmoee9fdFEs0+Aj/omq98xEv3e7Sw0pBd+y5A0LG0vTmiz4aMLiQYaHiLU99nGGHP1GtXGeZAAoQz4gQMHSHy9bjQeRwTyBIGcJbyKP3S9iNyxSEWe7MgIp4GoDiqiIaoDxwU1yI/wEr3aVTI7L5AgZO6/u7vQzB/R7L/76mXnE6y6Xr27JbYhOqYRMyUZqYpHgOhgDIgyauIUzkOk71/vvrIbNogIQ/Zgl5fFAU6yBHKkhRrcwAVp1kgqXoOjAAUy/fHvmDeIGubR5Se7s4esAA8Jy093yIr+/Y2rBIhUOnKHcUDnCxLspivWcSIC/Xh7lwsBGgg3XvFnypYMkWjINVReAA0vCpF8uficDC3vkkiYdWxqlX99eZ+RdSBCqn65AxraZeKrnQnbx6GfvNqMPF2FPPSJCDEkEE91FJk1aGt8r7y0vW76EAPssLaogLfJoS1H8hkq3OFByF5fJ7HF9ZCYpnZ2YRwX8BAM8ku5Q6/+hMX24gioxT1xObbgxXhgOU94gS2LVMR4h2V5aHbp3927d+eE40JQiDTCB3Lb3NxqyCMieRpt0yjfqTMDZebVg6R/aVfZXDS8gnfz5rXH4kUSgFfxIIEa4cX5iDL+3T/eIBMGFMv3frVVXn/+bV9T1DLKbidpWeEDnQXGxgpECx7E0NGmGi+wQMSxoaFZdpf1k4KPdFm7oXmJaGoy3i37G2TGuNR2EniYgIuEtj1f/I2v+Xs5WH10bdxBWFEAA7pmeODiAWDb9gZDdF+fcVG3KmZV+zulednbsm1dz5LIbhFbtTFDlTSQbLQL7601Tgq1BxqlX9M5+enPe5aDB9E9erRZPv6xKTJ39liTtOb0Udb5ahKbc/528h9IL+zsIG+Iojl1vnhjSLlDFMjmbh8qmXzyySdzdxIcuSsCeUF4MTMtUgFT/lzXZnKv+kcgHxwX/M46XaKTXbTC2bdtEYXPYNOF6KDdYOmEJDcQDk1mM3KHhjPGBgrRwj//2JSEVtN+bW67OuCc/jXVXRXJGpvSTlMj11r4AicY/fCYQXLppOrE+WqphcjhmdGDU1bJUixWra6XX6/ZK5V/da2ZB/xa7eS6ZIPDa3NU74JH7ejyYuNJjIIfbs1JeN3cKtKCkOYA4ItEQkTN4ZesUhJEt2EHp37K+vCjCWn9Wwqk9bUDsufZja5robZiwGnJM9sT7haqa8aD0qYdDaZABLTaTVu69MpoWJ9Jk6qkvv6kiTor5mpNBskL/vzJP32/PHrknBwdOjAxy2RkFwek0paHxdE+n3KHKNHMzb5Y7Co3183rqPOG8GLC6k2qkT2vIPC43EXALv2LdYd0ga0LAbyGh9bWrSFhCOWI0aA3hRZy1D/cZAigs2nkVH1etbgC/n1GS8v5IgNdtmVKsJ56eofxarUrrymp9mKLBuK1fcfRBOGCy8NHPz1dbhimRYVFUBHMLnuryU1uyWI2+YeG959+t9MQZJDxoOVk1ZMW1cDspEGnJRykE15kAjbublFWfdjAQ4POR6UkSnh1LZ1rCOnX6AnjjHzh6L5DSb8iSqRVnw3iq6WmEclXl4yGtXukaNZ4Kd97TD5bUWAeSOyCEM+s3iutMy9MFOiAXEEfUHRukCc4EyfxEAWJidqcATs/yX9RfPdBfGtqaowUCsETBlCiQDX+fUDmgmqCdICK/1oFHWFeEV4FYcaMGeaPLFIRdFvE/zz8OEHKUlpaaiyHersiWhwRS1WyFxXZUFULDUlDqEzmLJOLzxDdReJQ8683yxULLpa9QwcYDTD0sSC8SkbUDQDJSei77uG1smXPSRn2BVRUG2yOPbf3hCE4iHh6ifTamF6K6m1jKhPFJPAq/5kjLabvky/UGZ0sCDuuYeuOK2++TMqmjjIFMmB/hYbX/G6v3/EZiOOg62s8a3txjpJE/BkEEWRv4KzxCdu3M4++kijKgf7xwOA2fxBB47px/j94A+PBZNmRs4lSxXhoQHRVXRaU8GoEVz9X7PQm7icIALI5e9oIubH2IkPk7eRE9XnWssqj9h2ThYVtXcU7zmu58ZClMhPMFRZznz7XpfFtrSpPaJqRZIcGRwjgpfvNr8NFpr57tDXLFLLx61ej+0uXLqWkJX7LE9mI8pLwAh0WqYhsj8Sqo3x1XIgSZJvoIprpTLRCchWsoGDnNfK8B6qWcHWOAxFDkMqbCtuM3+0Ty96V5zcdMlFRtzbko1dKxfU1htSCLI/++kIjHUDlLiWUbklczkpYeF2PV+QgSYgwIlJ8199dLwekwJBXEN6XLh9rItIagQaZHoMCGY1nTHRZo564Lohg5+b9pjKX3f7s766TQWMq5af3/cFooBHFhnVbskhpqnW65DuLpHHzgcQrfkRkKxpPG1swrAPkB8Wfn2PwdHNxUD00roEHB+hdnQleSmj1WCW8sAXD2FXvConP3LlzzQMhIlZ+dKnqqQuXhEELauSbN4wziYF2g+UdbMaG7jtmCoXcPmmITD3bYuYJ2Qmi3Kv+f/beBLyu6jr7X5qsyaMkD7LlCVsSHmUzeWA0NimOcQIfQ0Iapn9aCOFrgZK0JUAoIYHmSVJoU5KGf2kgSUMgoSEMMQXbTI4HQrBsDMaSwZM8a/Aga7KG7/mtq3V9dLhXd5aupLOfhwf53nP22Xudc+9999rvet/qJuVY08jUAspZPAUy5OC5ScvL1ffD4VTH8/MSqi+ArxW4ebJmoaLV9943rADY9QrV+t79i2TE/RbwEgTPpCKSRyG5jyWbyzYjckLbt2/vd4oL8Yy+EzjBmQTIObfcAbw/PJ4idw3pkOEOIINs1K8dtsRIi5FhRBXBKumx521oaJVglsRj7l6sgI7MHtv4TgUEK/ziPYAbmbzhV5Upv9cJXM02F/BkklvEZ9l3PiPvjxgiN6WdlJVPbZR15Qc+RUkAKGOMoLJnxSPl95nZXULb8K0/qFwX73P+9AcvlWPZgxSALstNlQlNzfKdJzdJW02DZq8B4inZGWFlpCkac9sJA7qvvWeRyrSNbmyRN7bVyrZZRRpTFgJDNuyUy0/PU6DIwmRScb4aMgAmTT6O48ioA2hPvl4ps+rq1Q2O9o1vrpS6jhRVL4BXDfifvC9TNWed9Qy4slFsFsgO2P3scZ3iRVNUNWGFwyzCjiODT/GgE4zDwTVTie5c/rj3tGC20+n5ORFrAMfzsxOqL4/nGypCfet9doNZ0HgqT33rvkU72n4NeAmKVVwizeTxO6N9THrnvIFYiBaPSLMtfnmnKQHADstct3kCW++B+L04YiE1Bdh6IL0laFU9WbqOxpNdtv4BtCOuLNPtdxpAzVyv+DfgEYCbM3usXDw4VbOw8DydzTKf80vzlcMLUH/g3gvVOGFsWaFsmOXjJDsLzUyH1QqunP25C8hQMADI0daeaJP/dQHijt+Wy6GqowrayUoWQMkYNzwoQLNrkc0dVTRUPjNxiEiHqBvd/Q++JTnXnaVZS7NN5ngWHOva0/zOYowJxQmUJ3AjI/YASOx13ZrJc1J84x/UeFJ+/VKFvL3qE7HsblZzqpTsyZSq17fod51lq8wOGFBNMRnFgDwTbrc04scCifeuvGGuXLawyO/cZ/P8Sesp2TX3s1pQWy8plYfl8LzJXd4yzjdZf+gLgFoAfF9uJmuGiU1lZaUuwr3WtyLADggNsOu1gRGBfg94uY22vYcOKy47XkvuCDiBbn+w/u3taDszvuGMxUwUrk1t1Qyf6d4GOhdQCL/38nsukndHDPkUQMNid8hFxV2q+c26d/22Gs3AAi6dDYCEfi20CdP65X3A+5MvVkj+9WfJ8dXbNXts3NVxb1SoyYXT3YtzbOvd+mdOaL5acxtGAKQzioarYoUBNNN9tXPMjEKtltft0ZcnPHalmKHCJydaJb32hFIYyL5y/qN3LfiUVTJZUqglzua0KHb+7TwG3mx25SGpPOc01U0+9uSfZf6F50nm0TYtSgukN22Zb/oxA5D8vXWyZd1uaWxoFTLAZJgBvGSBc7LTP0WFMbc0+ghmXmKA1jleFjF1v90clAYTzjOZrMd4smbJemeCj4vfF5xaI+G1971ZeiMOFIEBAXht4nB1WJmvXr3a4+ok4ecBSRjjyhnQTcJh9rkhXbL4NAWC1dUNQVUb3JNi23puartyMde7jALcx2IXjEsW2WEylABkKAuNm3zV9sOWTddThj1Xrhq2BXnZyvMEjAL6JqXgtJX6KRBlclSWsYZr+6NDJ+WTTj4wfcLtnbRsmtx7ns+Ry90AtIBOrGt/15au46R4jSwrdA7ef+y4+LPSUAIAqPCQg3FJrUCPa5F5vuiyUhmcn+MvigOUfzA2T0EzfSHHNnTDDrn/roVdhueWhgs0fqgkZmRh78Onxr53Q2aWHBGRkQczFeR+LvO4VFU3yH8/VS5wYpsqqrtQSlhojB8/VD64sFQpJPQ9J7VN425Zb7uGFTVCHyHb7DTUCPcDQBa3vaElbDm6cPtN1uM8ukOy3plT4zIlJ7Ly3o5v8t+veI9wQAFegudVY8b7EYq9P68QLfYYhtuDM9MXzjmBAO8VnZnfUxzTBlk2OEUW5qZpl7h6/fnn72nR2OjbL/SDyfPrjnWRFQPwspUPAA3kwEWmt6iuXkZvrlILW6r6p+Sky7qHVncZOmDeTdmwAwCVltE1EAeflkZGFoMIpwEHhVrwcM2pLVCMLENt7zV1+DLJAH2yspWrP5ajs8cpqHRKuP3dGSM/lTV1WyU7r3d5aqsuOty0DK4BDYIiwvrWFPn+oZMio3J0Psxl8b4a1SV+r6FN9v78z11AL4sH9IMH5+X4C9FMeQHwD62Ca1rmGwoF83IaaQTLPDvHDuUlGjWOcJ7JZD/GKWsG1cFTkEmOO0ZCZfHixboL4knNJcc96elRDDjAS4A9k4qefswCX8+sf5ubm3W17f0wJP6+OO2Aw7kahWxPurbdAWIUVTmpDmQCydTSfr7rhGzac0zOW1Ck/15fUes3tcCG1uTBnNfH0GBXRbVcWprnB4+8/4XmBhnV1KJqDdAGyBw3VxzukjVkTn+xvETePdwkf3vJJKVBwE81egN/w189cVGJlHekCuMHaKM8gOLE9upG2TWrSLmlTkWJYPGh/wfuu6CLXBfAel0HxVw+hzVTtyhpalajClQlOpTnO0yB6dK0Ns04Mx53M0Bpyhhu3izvX5rapsCU9qNDXU0ceJ84Q5fgHpG1nrKvTqqqG+V79/mkwKzB54Un7VzYGKcY97pIGplsChGNUx3Juf3xWE/WLHnuqoHdVatWeQXPyXNbenwkAxLwEmXPpKLHnzW9oFn/muICnGpPCqZn7wVZvr+99eyILhqIb+rsAIDlK7TyyWlRcHVFmq847L5jPh6rUR8CXRiKAVX/mQK94RSYXvTxATktJ01+uXavtBcNlynzJ8i1aa3yzy9UyraXP/J3BXWC4q32zftUYQEpM3MHg5cKYCZri0lECY5tDh4vnTy89Yg0FY/SoqqDj74ZUpXBnSkHsGOJ4Qaw0AZYDBCPR9oGhYw5GVUWDmgkE1P6dS4syBjnbj0ujWfmKXDO2LBTVq6tktF+TVufexz34lQmu0OmpbbrQsIy6twjssFwmuk/UnDrngjjCqbcEXLS/fwAA74UuHmyZj1/s71d3Z6PebJeccACXrshJksCr9driYuAp7iQuNhG2nNpSb4CP3eBV3f9uIu7nMcCrOamtCvA2tjh02e17XiOg67w+m+2yNDGFpXPQv+X7Xi26unXtufZWkeSy7KkZCrvTvfJWNHIRv7byp1y4/ISqapplMfuec3/nsmhWZaRNwzYw7O14jKOu31ibpcsM8VllSMGK2+XLC/b8biHUbj1xJPlCp7hQf/+xQppzs5QM43rJwxWEGkN/jJg10mPsPcAn3BkncYexGJySrtsyjrlHMfxgFgoI2SfA3F8oQkgl0YcaQY0kU4D6ELHQAmjqHNh4Mymk63XzHyn1Bznd2fpG877HGN87b6uvBDp5yia4z2ebzRRi/4ck7MksxuJFnX0V/TOTOYIDHjAy83xPhSJe0QBuibs7SkuJC7OkfQM3xWpKlQGAL7hNsApmUq24p1ZRzK3c1N9mcl3dh+TZ3efkIW5qTI9N101cTFHeHHVDin6wef0UmyxXz9xsGyYOV7BrgHHteUH5Nld9Vrk5ga7nA0q/mIAACAASURBVEeW+YnOAjOA4Yjth+TV3cdVAQBHNQArmeTdtz2n1zG+Kn8jEQZwzZ8/Ub5z42wFlMxf/zvRJsOWTZOjL2/V86E13PG5EjW+wL4Yua7Ll5fqPF7ZVqfZVAArmdu8Tgk2aBF/GjFEAW/b+l2yeGGRzE1p8y8A3DFWBzvOLR6poPWSI8dkZ0W1jJs/URYPTtWiOndGmDlzHJJyW2qapHHpdAW5jPfoH7YKtrw4uJmOsV3T3O8oPgyHfxvu8wDAhbqBUofXIouAJ2sWWbyiOdozlIgmav37HA/wdt5fz0c7vg+60/oXoOsVCcQ3vrH0hsoADfkpH5gr6cJHDdU3YIwtcLc0Fdv37/90vWZJUVS4Y9pwNYr4uLpRDlRWy9GsQYJMGU5rZXecr6YRtzoyuPBc361ukslXzZZhjS3y2cE+fiuAjUwkIPX+1lO0AMCb0wSj4OYFem20f6195YY5qkyBQQPzRb3g5sWTldIA2H3syXI/EE/5w4cK1MnkAo5pqECUXDxF/r8zRsmvnv1AzRswZoA+gRTaqMZmPfa1VTuUu4o28X23nuUvTnMXnNm4DHhCKSCrDVAGPBau+EDpJlZg17a1Wuo/OaSnLRmZJRfPGe2XN+M+kFGnr8kpHZoxb6qslmnbD8oXl5foOcbNNbUHsvC+hYvLOi3UTe983wCul80NM2AhDvNkzeITR3cvnsZuYuLa13v1AK/jDnomFbE/zp7iQuwx7MkeApk1hHN9syd2a/RObeuQgnSf8gK2xej4AlZp67fVqhZrdtlY+cyEIbqlv+Zwk0wpyFZKBM1tYWtjMRkxZ3EVmc2Ozfs0M2sA1T12syi+7U6ftfH4WxZIyuyxSr8AbL5RUSvrpozRLOvE/9kof3XjHM3qji8aJiwM3snKkoxFxeoa58xkAm4vKs3XY+AIb5wyRvufVZAlY3PSJT8/R3m4wTKqvP755iaZnpsmb+0+LqvG5is1oOE/35P77r5IRhWk+DWE1bFu0z5dIAA4yyYMVYoF2XNng+8LmKXhegaF4XlXNj6cexvoGLLy0EXIIHst/hHgt8e+O3GTpLbB24KPPM7sKF588cVamPbOO+9E3oF3Rr+OgAd4XbfXTCr4svE+MOE/+3DTZsyYITU1Naq4EEj8PvzevCN7KgIYDnzpmplRXc4AldMRjG33v2hulJy0TNmYIZp5BIQ5+atO1zEKqdDgxXoCvVmKtpamQgVgWz9F1Qw437iozowpIBVdXeyA7/3ZJqVCAAyd2cef/XS5zg2eLhldssCnlRX6qRR/2HhQ/jg2T6kB6O7iFAZP9y+/+xlZkNImP999QvaOG9FFkxfKwLkLx6u8l89m18ffjbhVHpZ/mJijGVtoIu9WN8rc8kFS+f578tc3lUp6Xs6nMukA9Yo9x+SGlkY/4IU/vN7BfSabOzylIyCfOOIxdlJQoEx4rWci4OT5erJm4cfc09gNP1YD9UgP8Aa588b/8cjuwT8aprgA0DXXGk9xoW99lcBT/Zuvna0FYThtRdrcmVfAlpOmQH+/aM6Q7Wm+zCNSW5RpmaQWhVlPvlQhmZ/1mVPQyAjflIZ6gKgubHl7mr9PADIA2IrDsD+ubTipwLAl20d3gB+LY1pzZbU89silCijJ2u7ec0wu+eo8+dLcUQqm33jpI3lpbZUCZagIM+uOq0RZxs0+gwg4ui/Xt8uh7Eztb8j6nbLgmlkyrLjAP4ZQ1ADL8ALyAaGvtKd3CfENzQ1yWq7vNYr7oHSgBWxc3KXXzJR940bIrPFDtNCPRiaXwjay604VB65FbLtzxgv3/hJDnOxYQFAk57Wej4AnaxZ+zG13duPGjZ7Nc/hhG3BHeoC3m1uOTuy8efNkxYoV3vaSI06e4kL/+Z4w6S4AIeoNZC8p0Iq0mYECoKvs/SrdeodmcPBgkwwdPkWySkbKxLki5w1q1a36QulQHi1A+++f2epXHTBQbOAOQL2/I7WLIgLHAJTrAM6derpkOT8CHHe6wgFQKWYzygb84Kef/UCmXH+mvjZlb608/1KF9oPqwuebG+WMXJ/zG/q1JqFmGWUyqwBx6z+c+BCLK1SdIU37I1sNgIYmYY1jAPdksDGwMD5vfU2DGlhMravXTHIB3GQy5dAWOg0uQoHtcMboPAYFCBrUDQ/kRhq9xB3vyZp1H1tPYzdxz15/69kDvCHuqG2TsHIc6IVXTutfz5qxf3wVwHGFh4pOLc1JcTBTAkAggNIA1piUdn+20aLg5NZCNZj0PxslPz9bCgpyVO1g1KgRkpXZLseOt8pb7x+Qyxb6TCk4j8wnAJe/oQc4lRvcUQYUBuP5Al7hDJu1Mdze9sYW+ftbz5aKrEw1f8jafliyPjtd+aiYQECHWHuiTb51yUQFlQbcg7mchXPXAcZzUttVAuyLmokVzVLf0NKg2WY0cJ2ZXkDv/FSk3cgC+64A0GceKF84VRacQDkegJd7xeKAYjf41V5L7gh4smZd7w9Jqblz58rbb7/t0eiS+9FNitF5gDeM2zDQTSq8QrQwHpI+eggZXZqz6ItiKP694OpZsmPKaM0ouhuAcEQK5gYdCs7M1cuOuzutJSAw3XdAZKyvvkvWb6tRHqqBPIB1U4evWAvdWrc5BOc4+byBQo4rGQATTrCZLTiPK9x+SPZPHaUvQa+AGgHIxuQB4IkUGIAV0A3tAspAIG1d97U5F/6yZYDpzwr2MOAAzG+qqJWvFeXK0CHpGjPm6cwYc03m7WwsNH7tokHE41ED5AL6UczwWt+LAMCX72XMLEg+wPUdaM0zlBhodzz2+XqAN4IYmknFmjVrBoQ7mAd0I3g44nQoerKpOYPEtpfj1G3E3aBCUHj3Ej3PVBbIOBonFa4u2/xs07s1Y808gW1x1ZoN0A4cbJSs7KEyfOgpfihgFoBJQ2XAmtkbc805naYVZHMDAWIywLSH2wZpAZwBSgB6TU2jUgbq83J1HiNrT8i5BVkKkMkwW+bV5ggAxQyDDLSZYdiYoChAoaAB+gHFgNwPT7TJm1lZnTzkk/J6e7rSJHCHgx4xuCFN5h05LOdMGKLnErt1OKCltiv/FhBMXywYaHCT48HJpS8ziPAoCxF/HJL2hIEqa+Zp7CbtI5nUA/MAb4S3B5MKirT6M6/XjDiQxyFz4CkuRPiQxHD4qDsuEGxynVqyMXQX9akXIHt11axOUAY39hSlwUAwCgmAPQWYrV11eY2/ynvG1UW+i8I4qBI0wPDO3S3SfDJP8ic2yGspPj1a+LR5OenKV7VmoG/u9oMKWJeMzOziluaeqPFhjToA4MVWl0w0GWujLJB5BbTTnHxdAC5zMO4twJeMbSAawZ2dFsCoVVDoZm5zLBQAugBp+jM1C8ss+ww72pW7u67ToY5x2GICo4hYG1bJJ9bvlJaqo1qE5rX+GYGBJGvmuaP2z2e4J2blAd4oogyXlWI2eL0HDhyIoofkO8UrREu+e9IbI0Lf9fLLSuR/M7M1M2lA07dl3yHwd61QzMYHYCOjGqyNr62XLw1O+VS296OKGnniyY0ye/Z0ue6LY6W+NUWe3FAl//fccdqV8YK5Ng1wDUhkXGRkyQjzDmCcv51ZYedYnLxflBA0g+rIIHMsmVU4tzSuByWCdm2aD5w7jTbQ731md720F/mOAqAuTWv1A3RA746OVH9/jBvNYTK5lhW3bDZcX2TZDEiHsvoN95kwlQXPBS3ciPWf4/qrrJknGdp/ntHemokHeKOMfH8xqfCsf6N8AKI8DecuWrIK+N90z0XqGEZm1DKNbLdbJjfQtAPZ4LqP+0Jzo6TuPSLvle+XbRU1KhFGM4BNtvf1t2rk/IUFkp7uA7g/fu+wjCgr1Cwp4HdNdZPq5UIdQL4rNz9HVRZQOABAAjSDFbTZeNSNrPNYBbcpPl6wzy5ZFHgCOi9NbZPn23ExOyXzZVQH3l9+5Jj89nCLNBaP9INeMt70QyYXOgQg9+nOjDJAnQwz9AwAOmNGwYGscTgc4XAeNwrQcLKDuuBxc8OJWP8+pj/JmvE7tXTpUr/8Zf++c97sEhUBD/DGENm+vOI0L/f8/HzB+ncgFj3EcOujPnXM3YslPS9XDv7rm0kBSnDvwo43q3ikZM8eK6mdnFvAHaAMyaxQLVSGl/NNJoy/oWzkzp+o1y1eNFW+0NIgK9dVyfySPL8WcOUn6fLz/14rt39tpgzuNGBwZpsBpgByirz2d3KLMbkwC2LnmN3KDmSIV3QCXDO54P/MlwwwvF/6mZ/aJuvb0xT8UqBHhlY6pckM9G7IylIFCJoVuzFOssVwiBnfgY5UzUQDoBm3ZZABxrHycwG3zRWHPZWFUA/pAH6/r8uaeRq7A/jhjfPUPcAbh4D2JZMKrxAtDjc8hi4AevnXnaVap1jG9nQjewu4HVQ0XEGnuwHaKDoDiAEM3Vv/gcZLhpQt/0AN+1/mivsZ1wNg55SN7XIoPFPAL1lQ2rDNVfK7X26Vh7+9RAbntsnaHfXyv+PzupwDaCTTi8KDAVqflFeqNHb4XNvcigduEAz4pIjNKQfmlDbj+NKmZjma5aNrZKkiRYpKjsHpJUZkcmlGh+BvgC7gGbBMUwWIlFMUjVjuObFUkFt5WO2QPb3cWKI58M7ta7Jm0AfPP/98pQ8OdFnQgfe0xn/GHuCNU0yTXQ+Q8VFs19zcrNa//YV7HKfb12PdQGkY9+BSBbs9ya8EaKIAgQGEu8ErhbLgBH4mx4WTWagGCHzEBXgBYwboAfg0yx6H6o/zAJpLbpmnoDuvvF3KzuhQcErxl1EATMYLwAvFYVd2pizLTVEQTBEdxWQAzd17jqrmLs0yrLzuzvyaSgPxOPjyVjk+b5JSKPg34BmeL3MFzBq9gbFotrejTV5M8WkAm0kF1yPrTHbXnOUCSbiFiodp5SIjlqxUmFBz8N5Prgj0BVkzkjOAXdxOvcLp5Hp++upoPMAb4s6N/falCkzC8ZK3rZcNGzYkxWrUs/5Nro8lmrdDLp6qNrpkPHtSeqzo+5/rAjjJQk4DuHVq6RIpA2NkJNlup/DKgFp3kXQDXrK6zC+7bKxmkw2wAXizZ4/TbC6N41KzB/nHxXGHH1+nZhGAZLLQtOuOHNVzjEdMRhkuLmYNBkQtw4rCQ9X63SoPNrRomBzOy5VBRcMU6AJE3fJigFVeb9y8X9aWH9BFASCXNnpzlQLYBXPG6HXI6iro7eyLY8x9jf/f0tKg9sbEDlBsqg8UuTV2BtDiiV5wIH1jZ5yNk0ssveZFIBERcPN8yaImgz28p7GbiLvt9ekB3hDPQN51Z6mffLiSPnyBnHfeeZpBLS8v75UnzFNc6JWwh7zoA/deIIPzc+Sng3IUgPVUlhcQN2zZdOW8UlgFGAvUDISFk9V1ng8N4GmHOQKqDMfzcv2OZzU/f1dB7cibFyiYxHa4ubJasmcXSpEC2XZBgmvvfSsU5AJ2OR6lAbbuhyyaKteNzOyiuwvo3dqRqhbF5q7GwnTC+1WSM3usZmed/FhoEyNr65XvC4caHrE741xQWy/Nf/hQQfGIK8v0fUDnV4b4FCIeac3QIjbj3hJPGlxfCtJ00SApsr8jRQvWkCcjEwy1wcYCXYT5AtCDOaV5erkhP0reAXGOQDLJmvUlimCcb4PXXYIj4AHeBAW4N0wq+NIyDV04TxSiJcNqPUEh7nPdokjwpWtmaCb1h8dTZP/DKxO+RQ2VYfQdF2isyNwGA7u8j6sXDVWGcBuUA4q5nEoDmCZU1TTKD57cpIB1xFVlcvXiSVKY0iGPvlApn5s4RMbOLlSQfEndMTlvZJYqJfx3fYccy/bxZVkMAEo5lwZI9OnznuIKG3eYecFlfeOlbZJ9ZZmqINAolJPKahlVNFS1ezOKhmsGFhBaX9sg1T9dp6/BLQYkGwDOWL9TDr2+XTPxC+eM0ePJAG+a5bNDNqBLhta0di2uAFniGCp72118D/90XdgL7HDvk3ecF4FwI9Cbsma98bsZbly84/p+BDzAG8Y95Ic3muKQnjKpgOvEtTIzM1VxwSP3h3FTe+GQr9wwR85bOF55qRggAHgTLR81rWyMXHPrOVLXkRKUngB31ax4IwkLwC67kxLh1LHFWAEO7O9fqtBs7bKFRUoJwHCiYs8xmVOaL5hQfPPH70pGTYN85cY5csacMX5Kxa6XtypdQTnHKSJrDjfJnsfXyVeXl+hx1iyz/NcdrVKU0e7X7YUqATWC7PG4686U3dk+FQVnI3PrXnAArskmA3Dz9x6Rvb/4s5CVt7lxTsveI0rTAOgCcgH6cInJ8JpLWiQxdB4LxcVzQYs2et558Y6AKfkUFhZq0ViilXzYGaXhZOo1LwKJiIAHeENE1arqowUniawy9RQXEvGRiG+fZtFLxvLLC4tkfmmearVaFjLa5yqcURbkZ8s/3LVQCjo5s8HOocCLLXv0bsNtgDsyrFektvq1b42zSh/Ma/D8SXLJxZPVyQyAi/5tUUG2vLP7uDz1L3+UhsaTQhHfHXctlJkF2Xrpx453yKHsTJmf0qbUAca1al2Vnv9Py6d20dmlsG5LdaMM/VWlXPvlafLECB+whRqBo1vGzQuUNgA1Ah7syaojIReuSLNNuf5M+cvBKfLJpv2yY9sJaTtzmnw8SZTeMO2V92X/0pn+TDTFdbuy4O36bIYjafTXWutTsfCAbiSR847tyQg4Zc3MfbO+vj5uQ/A0duMWSq+jEBHwAG+IAPGDPHj+RImlQpovjMWLF8dNNNtoCzU1Naq44FWwJu/nnN2BYcum6fMzqaRAvnbNdOWB3vvH/Vq0FU4xZLSz+/xlJXL58tKQp7vVCpwnPP9RnWydOkrHTIM+AMcVAwWz5LXjn6vvkM1ZmTqvg4++JTMevFTdz8jsri4/KJctLFLFhPu/85aewmKg7I4LpCU7Q2bV1ct/3/uqUhjGL5qi0mjDUzr8qgoASsZ58A9b1bTi+lvPlsaOFHnsqXIFi4/8x+e0SCx3Z6ocqtwjJy/x0Q9y36iQxk375dCeowqwAzWKCafNGSPYKf/rD9fqAuF7912gGefqExnyXutJeWfLfpmxYLzqEgP23zvRppSLaHR0AbonNuyUY6u3J5zSEvLmewd4EYggAvGWNbPfxsrKSv0t85oXgURGwAO8IaJLhpcfcIpsYm0XX3yxsDJ+5513Iu7KWYi2a9cuLYjz+LkRh7FXT/jLG+bIkoXjNTP60DMfatYxke3cBePlr26cE/UlvrezQRo6lRKsEzKv85qbFOwh/+Vsxqk9+vKHqtBww4TBWmj2yrZaNZXg+G98c6VU1zTq+ad/c7FcPXKQbGxPVbMH4kFG2PRz3a5pANDfHG6R7dWNcue04TKosUXuuvMVHQKAFxD+X99YJVMXzZRBl46VEdsPKZj+eJxPwze16ogMa2yRL48aJO+VH5Cnn/1AUGG5bGSmFNfVS2tervz4mQ8k5eOTcuOX58rkiT4u876GVvm3n/xJ/v7Ws5RDDJVCM9xRZHXpj8UA3GaveRHoqxEA+BYXF+vwAavR0B2STdWor94Lb9zhR8ADvCFihZwT244HHl4VflS7OTLSClRPcSEuYU+KTn720+X+cfznk+Xyx3V7FPhFww8PZ0LwXf/m1rPDOdR/DBlYGpQAOLazbpmvnFayumQzgxW+AUZxFHuxullqG06q2gJqD4DgP55okysHp8qatXvkiafKdc44zv31qEF+qTFA7/Pt6XJ5aqufa/z8i9uUf1u8aEqXbDLHMhZ0g+/86os63vv/43NaTAYAhgox8wfLZXlHu/xp/UnZWF8lHaNyVNrs7IIsdU5bs26PAt6Cmxeo5m/u3iMy7apZ8s4nGZL951p5770N8sj3LtYCtP/47huabb77ngtVCxhtXR9IT42IyoD6gtEXIrop3sFeBJI0AtHaF0P1Y9fT09hN0hvbT4flAd4QNxZKQ0djfB2NwjGp4AsB6gLWv952T/c3iXvEVvjRP3yY8CKwaL8HjF4AMIQeQPbyez9cK8e+7AOkcHzjsYvgHF+kGd6PKmrk6We2aBEZgPfV3cflMxOGaJeM+4l6kdsG+8ZOe3XVJ7KtokYVGc66ZZ5cPTJTvntcVAkBnd8r0toEqbNrOx3R/umF7dLx2enSVHFYucyAaICk2ReToX2lLV1uSjupKgrf+OYqzcAuGZmlWd/fv7hNSksL5PSSfKU3kGH99yc3Sc36XXLhnedJaUm+ZokBsqPuuEDGFBfI2U0p0ryxQ9av3xw0CwXX+Ya/O1deHD5UDj/zvtS9VanzY4FCgSGgFyrFFy8rkd+1p2vBGoDbqUwR7LkwTWKPoxvtJ8c7ry9EAOBrWV94vuxABuP58vs3b948WbFiRdBj+sKcvTH2vQh4gLeX7plt56Cq4OQu9YdCNDJ4tERlLumbCn7jVVNoNPKWBcJWeiI5sdE8KowNDefvP7RYuaGWCWWrn0KsH793WNoWFatdLDJZ8YzZJYsny5eumRlw2FwbagFZ15ycdAWucGNpV9yzSDLGDVOQ6aQV/PuT5bKroloL4YwSwPEoMfzlwnG6wQ8gpCEh1pydoaDwitQ22bJutzy7u94vM4aSg5lFUCxnphKqdNCeKseqjkhtY6sqItDIMret3yXVneCWsUGRQGECgNtSdVTl10wh4sVVOxT0kmkGoE6uyZC2/U1yYEO57Nx1WOc8pGi4NIwbLsUXT9FxAsQP/auPX2yAl/8Drt/a0xX8P90W3DgCjq5lc9UCOAh3OJrnyTvHi0CyR6A7WTOrPyGzG8/Ct2SPiTe+5IiAB3i7uQ9kDrFiTZQFLHQFeL2YVFB4hvUvDQmYZLT+RdMVMBvKhIPtalowGsiIq2ZL7rxJUvWNF6L6FJi2rAFc97+j6jQBJzHPIYuKVSWAbfO/OnecXgWw+eqqHarJy9//tqtBUmaP1ePaak/I0Ze3xgUkAbAB2u4GJ3VVfbu88dDqT12H7CmANlAh249+8icFus5mUl53prWo1JoVcQFQFSxKilIN6jbvk6+ePlw2ZWWdArqpAN12pSA4+cAsCjCV4FyMJcgC0x96v6+t3qHSYYBYDB+QU/vhPa9p8ZeNhexyxoZd8uZLH0nbohI9PlRzOt+R8b3yhrlaZIj0GA5rTntgfbY7UtRm+HcOAwnPGS1UlL33B1IE3LJmJHkmTpyomV2v/mQgPQnJM9e4AV4qrrEJ7U/FGOZQFcgRi63W1toGOfToqYxQpLfVrH/Z3qHxRZCMQNfmNfbbSxXw7vvWim4BGVlNRPxZKAB+yXChN5uSnaFmAE7HrXC40UZZoD/AtknFGeA16a94Znjhe+LOFUvjGTGb2jkp7epyRoPjeu/PNst1t54tC1LbVZv2qUHZ/mPRYwX8umkaxJIYhFvs5ga8gFgyqLia0ciQ1/7i3S5TvPaaGfKZxaf5X1vRlqacWoDf/d95058F5gADmCgq8D79A04xmEAyDMDKe2RwAbE4j6FXy3tWmDYnApMLrvm7Np/JBTq9gM6lndljuMHOMfG3Ad8dm/bLtqxMtRjGaKJwjE/LN6s5VXa/+5EcXPmB/3kG8C+4epb8eWyeMDazFOZ45uIG58xl855jEd2XWJ4p71wvAn0tAgDdz3/+88Lvnen5etndvnYX+8d44wZ4Kf7IKRsru297rn9Ehqru7AwpuGWBYI1KBsnZ+LE3fl6kEw5UiMY2EBneZOY12QKg6usvhJWBBKiOe3Bpt+FBM9UdW/cJAD22ps2BygAu28YsOACngPFAAC7Se8PxRpEAeIYLLt3XsTHZ6wb82IJfebhZeafY/VqRlioMHBddKPBcsXjkb+dia8JjV+pWeXeLLGJjZhYsDP79ptl+kFizfrcuFuj/3H21klc2Vn794rYuNBCyu4A+pMSw7N2cleUfI5xjeL40noXRy6b5i7bI1BoXl/cp6jLKAtJk1gC+NMvoMm+KwNwNMEsW163UwHFQHigeW5DapqdBh/hoW7UWxEHT4P6RXbfFBv0wvoOVNXJabr6ktKTKnu3bpXTCBAWwH+zdpQoNQ4qGSXVers6JbO0NLQ0ytSBbFwlkmqGh0Bgz/7ZsNvd03W+2yOEEq25E8yx753gR6M0I2C4mO5ioE8Vb1qw35+Zdu+9FIG6ANxFZtmQIZ6zGE8458OE3lQa4u27r30SaVMQjlpEualgwaFY4J0P5kfwf4OpswUAq29BkOQEtZo1LdhMASEM9g8wx2WYDqLwezYKLewzAMaqGUSQAhmSgI+VgKnd03HC/Va0PlPkAIeAJwNu4ea/87ZJJsr8T8JEhNaUCi48TcBPLoh98TlqqjgSlinBdOK+W6WZeNy4vUXMGWuv6XXLZDXMFhYhpV8+SQ1mZkvn+Xnn7Pzb4bwnb+Vggfzg2T+qKRyk4vsdXtya3dUqAcW9Y8EFjALiifzs3pV0zotaYJwVfNCcQtvcBvm5Zs0ifUbK9KENAbSALTUPZAfULgC/z59lgIR5JY1HBIvfrN81R8M9cJqe0+3nGzAuQbaB8XUea0h72rt+tXOb8vXV+reFIrusd60WgP0WgO/35eMia9adYeXPpmQjEBfCaOUNafq4WrvAjU/eczyazr7fM4gLlYbL1Gynwsbmb9e+QIUPU+rc7zcJ4m1TEM/6ALmgJoTKyzmsaSAa8Ej9MPNzNnUl1L54swwsoNd4v4I5GttMAGP+OJisLKKcBnmkAJTKYZFnd9rPhxBMwPjYnXTOQQE2AEcAMtQK4qb9ZtVMXAP/ytTM1gwkAPqsgUwEgFAKjHLjBLf2yaAgG6g3wOm1z584ZI391wxzJyfEVEtJePNws744Y4pcYM7kwe58iNGLA9Tue2yT/fNcCv6SYM2tv2WkynNAMnMDWR2kQudbhxOaMnYFFwCRg3wCr8xgoEmRyoUhYUZs7/gBnCuXg02Lxa/3AjYZv3NycJmPGni4vbi6XY8PSEIyV7wAAIABJREFUNH5pebn+xQixgjcNfWVKxigZ3JCqFeZfuHKq2kDTGCPNaBg2hkdaM3TOAGCOIePLGFhwYKvsNS8CAzUCVpQdypI4WlmzgRpXb96xRSAugNcybGw580NJRgWuZryKb2KbYu+dHYviwjnnnCN8Gaxevbr3JhCHK/NsAKAAgC17j8iePcf0GekCbCoPa2bSKciPcQFgBE444JOV1OCaE3LzkklalW9b6/RjAJm/ee7qfrs5opEzRppleKEOAPZ4niMB93ZRJLJuPH1ElzGYWcGsuuPyxL2vaUHU2OvOlGWDUzU2P1+5Q65aWKTA9InjHao/S7Ns7e1/t1D2Tx0lK9dVfYp3axeyzyEFXpO3H5Ki2no/aIOi8PxL2+S0skJZMaVQM7dtv3xXnd+QIDN+ri0umD+LidtunCPo+Tp1g3GO41pnFWT7eclkOMliA9qt4M2ZxVVN3apjMmfZ6fJH+LEp7aqty7EAVqTaFqW2fqp4DRAJ4SEQ7cEZYOdCwTjFZGWhM1gmGY1hMr+AYeJhrabGlwHHia1o3GhZuKBYRo9s9r//cn27/Gn1J/JPn5uqXGR1fYOW0dk31A3TBib2TZXVsjsGbn9ED693sBeBJIuAaey+/fbbYdekRCJrlmTT9YbThyIQF8DLfAElgJTqx9fJqNsv0K1osnr8e6A14+MeP35cJceiLUQLZlIRj4KqnrgnxmMFuCID1fyHD+VARY2fouAeg/N5scxwzr++oVq1yE5NeGeHGikAntwZNLLPZHpjsYC28USrvcwY+AwA8NGSdWYlyYK+0p6u7mD77ntFHnv0Us0MrmhLl3P318gvfvKOjB8/TP721rN1e/w3h5v9PF6k1v5p+RQd3te/uSogCIeKcO01M2Xr1NFyKGuQmitM69zmB9z96tkPdKs/77qzNMtu3GDTBzYFBuJ+suqI8nrtPYrq4O/6+MUN+lmfuGyaztFNSwDAPtw2SMEgJhXGwQUwY9RAbPT7YvNe+drckf73oUU0daTIrQ6+r/v5oG9aIF4vr5u6A9l0rtVdY3zWKLRzZ5DJGANqablvVMqSBUWyKStT7yGqE/B5jdcL4EWr90inKgWgd9qKLV6Wtye+ZLxrJFUEwtGYDzXg7mTNQp3rve9FoLsIxA3w2nYqW8pW0EWmLZSEVX+5Paa4QOEZ1r8A3XhUorq/QIzLGU0mszdiDQidsmCCXDh+iBb7vFvd5C8mSifLuGGXNM8eK+mObWYK2ZCDW3b9XM0C/vMLlconlec2yffuvUAND8jy0gB6DQ2tmp2Ltbldzxg7fE6KwMhoAuCDFbEBkuEaOwulnIAPEEsmE2veGftqVZP3w4Y2NTtwFqJhdgBAxXSh4Aef80+JrXK21N30AzuAOHz/oSX6T7KdOyuqVZqLbXl4qDTscQ/+n7ki0iH7vvWK5GRnyAP3XaBjMctf6w8Th3+8a6GwbW/FWbwHxQP3teq8wZ8C9bxvgJe/yfiix4sdL4uUP5QflCnXnSVL01rlD89u0f6tmcED97u7ZvxZ9zFOGTXoElAqnOOO9tmwYkMMNDC64B6g/uAG+kbr4NrcK/6/vqJWsp4r76JsEe04vPO8CCR7BAyoxqvw2i1rFo19cbLHzBtfz0YgLoDXCrsYOtvSVEhHux3cs9OP/Wo9Yf3rNqlwArHYZxC6B5y3AFqYE9C4v2RSTQ0gUA+YHuzOylTeLpatuG7R4DqSEdPsYOeW8E23vKhFaGQQaaaJapqwFCeVd6RphvhbSyYqnYGMJA2AyL/JQEbTuIbRI5ARg0+KAcS+xlYtuLNCOcZHC6YdbIVuzjFYUZe9RhZzUONJ+cvBvmIui4UBXsuoAngpEDMdX44lM0zxWHdznVA0VC69Z5FKnbFtf/+Db+lCAB4vmWNA56u769Uqm3tnEmSBQDSZ9LFlhfKTtlPcX8YB1QH3NeTF3CoKjBvXNeS/aIDOoY0tynOFqkGWd1tFtTxw74U6PjLHSzp5shajQPq/3d1Xng3AJ8/U0tRWpUpYBviXh1qURgNlJC87XV9nzKOKhikYtgyus3+yzLWNJ+VY1VGl1HDunNJ8XUS8ezJdpma0qcwaCwEAvT3XRlmxLC99kglW3m/lIV2gQemwz09TRfWASQZE87n0zulbEbDdyERo7Dp5vriOAnzjkUzqWxH2RhuPCMQF8JL9AvTGUtgVj8n0RB9k8gBmQxrS/FaKRsxPpJg2wPq8887TDzryLj3VDISRVSUTSJbu5JfPDlgcZsWLw97fq6AG8EKW66LSvKDDBfiYhaxlRzmYhdOlpSPk8uWluvX/xHFfdvFrX5ihIO6JJ326q489cqmCqV89u0VeW7UjorDY3OCvsoU9/O4lqrV64hfvyrryA6ohDPjmP55vQC10AMbhBvvMvfDuJV2UGcjmOjOWq8sPKnUBPi4gCt7nUy9WaP9wWKE5EI8f/fhPCo7+4rJS+fiiErXqpdFf2huV/ux2oMkWXjVbvn7uWM2qGi/X9HjXrNvjjxsZXEAwsWPB4W5kjCdfNVspGjQylir/RfFdaqtu6ZPVBGientIhZ+5j0bFOCssK5f/eWKYg1DKtnH/1kWPyP7/ZIhvLD8jokgIZtWiqzKw73kXzN6KbJ6LUj7rOrKvxhXlWuJeMFVMIBeUiWkBoWVnGxW4D1sa852wAVmvoiQCKOYb/M3dT2wAAA6ABtNAZTJHCCg6tD+gN0EsqV38sK36zRV+2xV2g5yjSGHjHexHo7QhYvcmaNWsSaijBb6DteIayL+7tmHjXT84IxAXwJufUEjMqo27MeKlBFRd2796dmAsF6ZWVNFs9fLn0xCoXXVba089uURBLcdXHF5V2sfE1+TGOYzFw/PF18p0bZ3dRBgg0HcAd7fs/fley7vZtx1ujqKr4nR0qqwWY+dYzWwPSCQzwUpEPCI6E2gCoI/sJUCYjzXZ/fU2DfPKtV7qMhaK4tpoGScvPUboO84UD6wS9U+ZPkDOvP0MVFgBZVrHvrOw3qsLiG+bK/5k7WqkL3/7Ju3Isy6e5e874IbJv3Aj55Leb5ZzxQ+WvbpzjzwKTWUXSLfO5cgVP3TUy8uctGO8HvBPGD9V758wOm+2wU1vX3SfzfOLRS+V3benKiYWisXJtlRyeN0kubG5STiugkUYx3sv3vqpZ6fGLpopp77Loebo9Xd5f/Ym0N7QISi6m1GE0jVAfIO7/I23wkls1e22Nvnd0pPq5yvY6481sbNH3WrJ9lAzN7Da1KL85FqqD0lQ6dybI6lLu9nx7umaDZ+SmKTPYwK+5zEGFoM3YW6v39pOGVo1Bd8WVX7lhji56Xlv1SajweO97Eei1COAU2tNJGCbryZr12i3v0xf2AK/r9jm3uJ1vmeJCdVmOHBzvk7CigAcAlD27UDmRPdVY5eLOFg1Xim3sP67d499ejWbMgP7mymotXiITC8XCqXUKB/fCO8+Xq0cOClpgZFXyttUNoEKqy5klnd3UJFcOTtVM8YOHTipAsO1457jNLIHXbrvjlYhAr7MftroB4dAweA5OFI2QlCvL9BAATXtji86bbK/bfc/GYFvygC622J0FVqgEAMzJWgPi9nf4MoOWFYTagFoFDQoD2+kf/Pw9BW2Xn54nb84cH5YKhVFBLKNrgNeUFsK55ywEzigbI6eX5kvliME+CoMPt6nuLvbExbX18pkJgxVAYiuct7dOaseN0Cz5+Hd2KKA31zYDzSxkoI2ckZsma0+0yxeaG3RhRBaaxk6C0+kNkP728CEyOD/HT6Fwy4O55wPdgIwu8f2oI0WvZ8CcLHlj40ktniRLvbBstN4jssK0A5XV+n8WQ2TWmcPuqqNybM9RfZ17R2bZ1COaO0TeLT8qs48clvGLpsgrnRJmgF1b+DjHN762XoZu3uvP9jrfs12CrJQOpa8E42uHc/+8Y7wIJDICZFuXLl2q9SrI+PVW82TNeivyffO6HuB13DfnFvfuPT6+3fTp09UBjS0UuEM16Y0KSqx4yTRge1qRIhqTCn+mz+FKFc1ja7JdAH7T1oXrShbS4mLZQWf/AD4ksGgASySiAGdGa+D1cfMnSNp1Z+sxAAYyhe+daNMsIy2YDi2AMyc7PajgPyC1sVMLONScKeaCXkCBHUVlKjXVmaWzc52FZgYwnf2S/WP7O5CiAPOFolEyfohuiZO9tGZFn85/E1OuARXirdWnCva6mwcZ3G3barpd2BCTEVeWBdQats8CvF8K3wyQck3T0OVvmx/0jPXtaVrYBeCd+/FBefKjOvnH5VP9UmUv7K6X/31kjSxeWCRfumamv1AOegVAkkbGGS7ytKtnq+IEXHEA8YNnFOj7wTRxndxfFhNwvs0RbXSKj9YAGAWocj+xJjbgbHq/7nvsVGrwgWbOVYU8naOZhpgDG/cVt7wTLnMV932C2ztvyx4F98aL12c7O0NYTKJIcn4d2d0dUS/eQj3j3vteBKKNQLgau9H2H815TuDr0R2iieDAOCdiwHvugvFaeAJY6W+NrA7zW/HqTgW6xcXF/hVsd/zcWGyGY4lhNCYVBs4CSXuFOxbnFj8ZWdOKdZ9PPCl+AixBNTCAa8cBEACXABpTXgDspN+8UFrzc/Wwu9Na5FDVUQWyZMBQbwjX0IRxQgMgOzvylgX+Yjj3OOGg33tTmRyoqJbHniz382nJLj6+64RmsJ2NLCWyXTYO48i6+w1UgGXUi1mLT5OvLi/RDOJD7x2WtPmT/NbIFM8Zn5lrDf3lnzR+Fkvj5oZ7vzgOqoG7UMquY/bOZHUvv6xEubhc7/sPLdZLMEYWKtj3FhTk+MHv+vZU5e8CIDHUAFDaNn7hii2auf7CZSWfMpVAESKUsgaGL0iYEQfu3z1DTtkMB3Jpg08MEAfEkokmC8uYaFacdkVqa+c4fYsnFlSXp7WqVbGbe9tdbL+Y2qoSZE56Bc/KruMjZU1xh0rwucGzuz/oHPOampR20h+/SyN5Nr1j+04Eokm09PTsPFmzno5437lexICXqngaup79jV/mtP6lGhRpsUQWosXrMYm0aCAYbSPYeNxyXc7jKOTCHCJQA/B+fnmpbo07nb441oDfuZ3ZPl4z0Os0kkDNoXxbrfz+kTURh8u0fKu+/oIWoNECUU+Ywz/etUABENlWsqxfO2OUjCnO75J95XyAyluPvC07OxUrbFDGJQ42SAARYN7APcVbZKXZtt646YDMW3a6zCzI0mw3SgebZvpcvvau3yXfOW+s3ywB4BkpbcOk7Ny7EBRPNWze5zeyYLH3pWtm+EGYqTjYnOz+ALwxowDQQ2XwgcwOVWXg/9AH0Nk9p6lJs8MAZgA0CwPuO3zwcEAeP64zb1gsO6e2q/rCFWmt/vA6dwucMQfokn3F7hcgS8aZe0ZxHZlV+iBzC6+YZrxgQDSKFGRyOc4AK2DestgAfF4HOGOjDMCu60hRDvHaE23ycn2HStcVftgqjeMzRYa0KtgOBn7ZAThzX6389IdrNT7mZFhckO3fAYn4ofdO8CKQoAhA6zv//PNl1apVUltbm6CrxK9bqH/8V1hYKKEc3+J3Va+nZI5ARICXHzpftmdoF3emZJ5gOGMz69/8/HwtRAPo9rVm1ItoeL3B5kpmk+wnWdWmh1fK/Xct8BsYdBcfgA3ADQBF4RWN5wYpMQDf+KKhaoIA6HGqBXCcZZ6Lb5kvC+aM8fMlnS5sHGeuYmx5H/ntJqVWMF7+O/DwKv23KWpQXMbfZAuzigs0O0vjOYa6YpJiZFM5hox19vbDMvT2C+SK1DbdGmcrHF4o1f+ALTLO7maLQV7nGECu8VFZIPIa8dCMt5pxdJX84jzixvuWHf7wRKtMz/WBM8Di71/aFlTX1eQB3ZbEwbSbu1vI2NwAtuZMZllZFjJfuXGu0ix8tsmnrHV9urvpSj0ApGL1a8oTGGtw3wM1p9QeQPvEiXRJSZ8kGzZsUOOWIUXD5Nv3XqDZW+LAs2S0C2d/jIXM7tyUNtnYkaY0BOPSGo+XcZnqgrmyLUhpC8o3t/5RZqCZ8gb3iD6N0gBl43fffV3jctGFM2XeWUPl/tZTdJVA8wZcj1jxgRzLHiR7zpms2eE70076dzX62veQN97+GYF4a+z2ZJQ8WbOejHZyXytswGsi9WSk+NGy6vbknl73o4vF+jdQzwAntWyt9akP9HRjPhSzYekYzQrcxo+BQuPm/VqMB3Bk675t/S75m6/5tFydvEMFjkVDdavbKsv5wbcCKcsSBstKBgItGCQAquB5mvGBOzsJWCu4ZYHyqW1LXgF62Vi1xHU3ssZDFhVrdTyc2Ol7axV8msOYbe+zfU6re26TjLvuTAUfvqIm6WI24J6P8aPtuvQLsIebasVHfIagCbiBLgVgFKjRnNxm64vXPtpWIxShuWPvnKe5qPEMujPZi66eKTs27dfMNDEHiCMHF4mqhTum9AMgJutsmsKnrdgiNywvUcD+81U7ZdNLH3V7DZ45igGhxlBQhqTdwjlj/LEwiTbu94MPLdE4IUG3euNBLRhlcTBqPDxrn0QYGVrjT5vWLhldxufMtprTGsfbeVyURQpFne7GPWAxxALtsoVF+jZzfPLFCpWYY1xr1lXpAu3vvjBdx0H78foaOXhWob87A9iWLeYNQC+FagbIS9+vkpTKw7rj4TUvAr0dgWCOn709rkivD/C133yP5xtp9PrH8WEDXud0ASPWyPoiB2Wi6n0hLGxzUIhGY6sjWutfm6ttRY57cGmP2SkD4ABnbnDtNqkI935YFhBwy081BV5QFQC8wZrZ2QL2nEVNHO907gLoBQNWlyw+TTNiZO2c2WCKl3gvbf5EKW9Pk49/8WepWb9Lh0K2FrBz9A8fqlxYoDFyTegSFP64XdDoA0MElAL+595XVYqM7f0TG3ZJw6a9CqLZ6scV7AsTcz9lO2vyYu458VkgFq+u2iE1NQ3KuXUaQDAmFg1wYZ2FYGQOAV0A6/XbauTXH9XJty6ZqFq6tHA5u0bhcCpIsAgBxBFbkyUzSbJotIvdz4L1ZQAQUH6o6phSI0IZgqDyMWzZdF0kIhl2+8RcBZFQAFCpMAUPFtjOBcWPn/lAdkwdrcYYSzVuvqI0BY+dQNPGaZbOgZ5h6Apke+HiHqg4rFbAZkJiBX1mhuI8//LUVs1cA6S5N5hU0Nh1GH/LfFmUCgWjTeprG1QzmYUYQBlbYpNi4547ecPQG8hOM3fr3xZj4X6GveO8CMQ7AtDloBatXr26T9D7wp2/ZayRVDMzi3DP9Y7ruxGIGPACQj6zeLIWG/HjRoYHwGs/FMkaCrP+nTt3rv8BjyYLGmh+TkesnrL8RSnBsp7ureloTSr4kUcarLsMNT/cAFTAAZndB+67UENiW/Q+GadjUTmfOTmjbP9zDWgRPGPOH3+jIODmByBhC99tBGGZY4DzrqxMeehrZ+oWN1xOQD1z5TyywVA1kL26686u0nJkQRmTuwUyanAeYxJl9rkArAHonY3FAplRssBvbKuVz14zUx3M/mvjISmcXejfNudzBefVVEO6+3w5KRx2HNxiGsCb6zF2syEmkw6XONbGbg+6v7bwIXPM1nx1dWPQhQ4LtsHzJwn/Z4FBxhWNW7KwK9p9smdbvn7KEIPvm3+4a4EurP7+ma1a0MY5uJ65QS7zATza6257ZPd8rXgNfeMXV+2QjEXF/kLFVHWWGyynlvi+s+EqQ2/hvvIfoJxdgqkF2cohRsYNEL6xI9Vf3HbfsRQ5LReXwVZ1bjPAC9i17C5949CHI1+sGfhY76t3/sCOAEZHNDTf+2vzZM36650NPK+IAa9T85QuQ/3493Y442H9Sxbrj2urgv54UxCFGgCNrOvhx9cFLeSKJh6AgtTsQV36JCOJNFb14+s0O2l/O/uP11YUADc/P0cXOg2NrQp4jbJgVBd+9AFPtiUfzTw5x1n8ZVxNK7Iz1QWnSgPAP9Aig3EVFGQrUBxRVigP3XqWDunhtkHK0SWzaOcZ99atU+vk5Np8nBJqweZIZpcxk/0DsENrCJVNBcBxD8l6/s2oQX6wZgsJKxiLNK72eWUs44uCc2gj7TfQ8bZg6c7MgvOcVuTprSky+K1Dgr41lAFALwB0RXuarC0/qM+3s9luAff0X77mu6fuBv3kd+3pyr8GmD7cmhFSNYE+yMpOS0FxIkXe2XNcOp7bJF+/0Ueb6K7ZM8GuQ+68iboIM94wdIVbkdYrPyBvZWbJsJICBcpOSgOAl+MMAFOoyTHQZlLKxuozYbz0eNwnrw8vAt1FIFk0dnvyLnmyZj0Z7d67VsSA1zQzye7xw5asVAYeYJMWs0K0aBQXTMarO8BhgNdpHEClv2nSxnp76R/Ai9mFNX5c2SrlOmR4uTamCO5mVozR8nrJrgLgLIPPPTcQlYjFjjNrbNxVtoWhD1gm3VnAZhJpoagXd997oVIEPjnRKt+9Z6WkZGdoJtupoWtb8IF4xRZXA+Hd3VMyqFbgBUD7/PISVTQxZQKjZHDvGINTlYJ+h2zYKW3rd+o2OFlZxui0AGZ8LDzCUUlxZuRjfQ5Dnc+9Ky3N91s8A2xpbhm54RNHSdmXl8jgES1yMqdNtlQ3+jnjZNrJgJKdRXt5LYsoF+i1cZBZ/uzVMzVjbaYYvLfycLO8PWKIZkpRkSDTam5nweYAjYCsLEoNWAHn7q1ToEvc4a1DjYGnbkV89KPqE52c72NfPls/7+wakLmG3gDwhcKwur5d/zaqArQNFl7Opu5tgO7UNs0Is8PBrsbcq2dLzbjhsumRt3utNiDUfffe7z8RMKlLUynqPzMLfyZGd/jNb34T/knekX0iAmEDXn44rWDGrGTJkFnFezgV3z0RESOls0oF6GIWEUuzrdTnX6rosv0LSBm6qFjQCwWAoWTAVntadoYWTvEjD5cyHs0UBpzyX1a0dXz1dmncvK/byxivl4r37qyQ2ZLmBxwbWlQF2KZl/mS4nSL4AAxeT9Rih/6hzgCgTi8t8Bd9EQd40sF0fz8F9ouGSuGcQtk/dbQ8MG2Yzg0aDgDammUlARiWveYY5gfgBuAAfOw1QEiszbirUDLs3hnohc965f4ave79D76psm6Mg0w1oB+dXNM1vv/Bt2IqOot1HqHOZ+cBoGeuhBxvuw6XfaZD0tN9hV00ispQoBj22eldqArbqxvlke+8GXSeZ198mvKFDfACTldWNyvlgUwpgBeeLple6CzBmmnrwrOlAVRRbthZWaMLe55JFnqD83Lko45U7a9JObc+nV9oGGZGUrrsdJm4bJret+tGZsojbafUOJBBm5vSLve9V93FndDGRbYXwI/ZCo2FGXzhUDsEoe6F974XgVARSEZDiVBj9t73IhBJBMIGvAZ6rHMqwils4gfbCp54zy0fFclgYjk23ooL3Y3FOV+TgLKCIbJ2/Gg79U1jmVd35wKS0vNyQwJe+ujOpIJtd8DU3956tgI7MooA3njwO2OZu7MgivGs3nhAAa9bdivYNUwv9keHWoTKdwA8wNGK7cjoUlzG/J2Fd06+MMcCMKPlqJPlJBN/9OWtep+cwNappAC4H3/xVC3eQtYLTixzBuBa8RaFZ06zjljMQ2K5L6HO5fOhRV9XlWlx4Kx3PpEN7x6TWbPOUCMXZP+uu3a6PnMsQqyAj7n9fOVOOXrlHMncvFcu6NTx5X5s2n1M+8OueWxuhjzx5EaNC4sza7i9AXaPZQ1SoE3WlAaApKETjHKDu9lxZFjnp7b5DTTg4sIRNlm2oUXDFEDTBxQEN3dYbYz/p1wWLyjSzDxAGS7y8LuX+C85s+64zKqrl+//+E/Cd6jTkpuDhuxvlKPD0nX8NChSf/HBbvn9i9vC0i4OdW+8970IBIoAhWmLFy/uMxq73l30IhBNBMIGvIE6d8pwmazT/odXfqqAKJqBhXuO0RaOHz+uP6SxKi6Ee92x316qIvMUjpHNxcnLfqAOP742IL0g3L7DPc6oFLtvey7cU8RpUnHl5cV6HuCKbO175fsV3FGsFa4yQNgXjuJAt2Xv3722S6XFaJhJdEdj4BgrpiJ7C4/W1BUAt2TraGZgAHgEQDH/cI0RwpmS0TBMOcEWRs7sLv0YOOdvxvm9f1mnYzPAzfuMj0Iz7hcZ4GQDvAA4PhMUoVkzVYJtla3y+H9tCCiXx/Y/usvYSAMu/+PFStlRvl/vr2klm+4ypg+ZIjKsqUXeeGmbxqqx8aQsvXqm/GL4MM0OA1ppWB0DSgGtphVMdpYWyC7agC9KCfY+/TEHsqwmvZZVeUjuPH24X7cXtQaOp/BsjGaTfbNn8UjhonGW+a6o/cW7Oi8WPhRaOvnMgGgyvMbl5dqLPj4g//3URqXIsAA0pzvk2mKRlAvn2fWOGRgRgPaGnGVfMZQYGHfFm2UiIhAT4HUqBdgPuwFeqxhn0O4K+lgn4ixEs4wR8iI91WxrneuxjQmtAMDLDxoZG9vaTMR4jGJAVuzbP35XWlzFbOFc819/sFRq69p1S/nQoToFeE5TAegETs5pOH0m6hjmC+2A+d7xg3WS22k3GwnIf+DeCzTjRjOQCOCtrm6Q11Z/4ncAi2YOlrF1SoE5+yG7S2YSgwzAjtFThtTWy/cfWuLfqlZXustKdZ7WDDCZRTM6r9wXy3wnE+A1mpNlJtWhrJMaEGpL3ug5/zAxR3nWZlRhlBkW002V1WrFe82SyaqJDIWAjPkfn3pPAaQBYiv4IoZOpQYnbxa93/IOn2tasOYEvxxDtpfscn1No+oGv1xY0IUX7ATIjAHQa/eH+fEc8AzA2XYanZDlt+8TrmGA3MaFDvRz9e2SUXtCMoqGq3wdWXPPkjiaT6t3jjsCljAC7Pbkb6h3J7wI9EYEYgK8Ju2EFmrRDz6n228AXr7UncoFkYCT7oKQLNa//IAxP6rKx71RoT/QzVf6HMWsWQYvHKmvSG68FVSxxc62bjijYkItAAAgAElEQVQWre7+AZAtqVnSkV0ia1e83mNZ8Ujm6T7WqvON/xpOhtf6sJiRDTRucrhjgbtONtXJ+7VzTd+XgkJ77t39GuDldefnAH1cwK1TGQJTCqcLm1s1wtk3c3LyqsOdTyKPYwFMc8qFYcSADa+Bd2KGokkg3nlhWaF8du5ozWA71TDsuwRtXnR30U+mAWL//8MtUv7QaknD0vfuJaryYFQDDCjMBc0AL8D07vST0p0+L+PHgnhHR2oX3i/novxAn4DpZ3bXS1V1o3Q0nlQQ3FrToPQuACnHcH8CNQO8vGcJgsllhTLy5gV+EM0YmCsNG2QD1OfXHZP6DbtFOjrUkppnOprvgEQ+B17ffSMCxqfHnTOagu6+MUtvlF4ETkUgasBrxgdkdEySiywL2/v8mFHMNfqOC7s1Ygi30A1+ESvRiRMn+j2xk+EDSgwevWuBbjXz4/r4qp2qmmA//PCZcS0Lt8gqnAfTsntOY4dwznMfQ9YsJy1T5pYPUl3i8vLyaLrplXPCfW6cgzOliXCUDZznqTNadoZqolKcNGzZNGmqqO7Cxw11f3ke0HOtf3ytH5yYKYUBaa7x2KOX+gv0eiWwMV501B0XyPySPD9QczrUYZH8n2v3Slperu6CUPBKxjPQ7g9UFBocchY4qTmDpL2hReksfN+UNDVLaVOznFXgs5tQreJntkjTVXOUahBMlxcFBhoZ2P0dKQpm4e0uTWtVuoJp4VrhGLbEcHZpTgrE3WktSmcAbKLeEs3Cw74jAMkn1u+U6ycOlm2zirpkeB9Ib5GVa/fIxqljpD4vV7PMJ37xrsy/rFS5+0afSIRaSoyPgnd6kkdgIGjsJvkt8IbXCxGIGvBqhrOzYIosJpkKMixOTVSyOb7sx0kt0MgqLlDLU7JeFHbRqr7xQtBpOwvRUFzoTmGgF2Knl7RMHZlDA1NOOSabd7x0NOG1ApZi3dJkcUJjcXLxxRfrdtY777zTW2GM+3XJlJIljLWRDSeDxr21TKPzGQ8HfC+4epbcvGRSSOex7hzpYp1Hos9nQZp3QYmMKmqQ5SMzBbBIQ8mAbKcTPPI6mVi+F+6585TUXqAxAqInFRfI1UePypbqJnm5vl05wgDfk69XymdzUzVTbhnkv7xhjixx0EJwtQMQv15+UIbefqEaYpDhNaton7ObjyJhdAL0eK9IO8UDJhtMoZrxg5ENc7YXdtfL5lUfy7jrz1RpsoLaeqmpaVRQDSQ/XHVUAbMzE2uygvRDEWbr42t14Xx01jhprW1Q44mzCjKVh8yxNKgYEypPyisF6XJseLpeJ/+NSrVC9vi8iX7C+0f/0ZoS9Y/Ze7MY6BGIGvACZsnUqBbsc5vVHhTAS7aLL313QREgMD0vR2XM+BHjR8scr9z8x3hb/ybqJjuLqoJlXI3bvPe+FXHT0STrSHbp/u+8FbepxcukItoB8RyR7epOYs0HPhs044riQrCtXNMO7o4SEOk43bzLSM638XDPbnO4ucGVhp8biC4RSf+9eSy7L+eff77U1NTogmnG9Dy5+atnawaUbX8KugC8W9tT5fn2NDVUQJaLLCrH0EJxkd3Fi9gvr5syRkEoNBHi+9G2GgV9PBtkiC9fXqKKHBSN8bpRYQCt6OweEfE7oP2sLV2zu4BSyw4vSGlXA4ryjjRVZEDH13i9t6a1dsqSie+8Tte17u4DBYjOzysLJb4H+X/dbzcrgOf7kUzvoKJh8pvhwxQIA67/PDZPuyZm13W0SX1ah6ypHySv/+cGuf2q05SfHsrGuTefEe/ayRGB7pR6kmOE3ii8CCQ2AlEDXvvCJstLdpdMbsEtC5THCxDuTp7MCndOVh3Rc2p+/q6eM3TkCLkoo0Sli9DP7SnFhUhCbJX//JCyBW0NQwKkg9zatAA5/nNKUEVyvUDHWkU/TkzxzOzEalIR6bycINcKkyjsCtRsy9/es4xesGPdZg+Rjs19PM87dIZjq7eHXLiYHbGbrmAqEdd+YYa8tpLis9Pk9NJ8pUv0tWZ8+sLCQkHf2flZveKamfK5xZOVYwsgBPD+pDVDQSPb9O4WroscvOWLLivVgjD0eXkG3nxpW1ihg340+vYL5eLBqVr45WzwjHFmA9BentqmGd/nO/V4Oe7a1FZZ15GqAN4K3VCLAHCj8cvxThpF+bYa+XDTfpVH43U+oyzO3DJ/vu+GYt0V429qAgpXbFGaxY6lM7oU1UGVyt9bJzd1Wl0Dcvfuz5K09A4ZlN4gr7z2UVhGJGEFyzuo30XA09jtd7fUm1AUEYgI8PKljBKB0x3KnZ21TJhbdsnGhmwRmTyaHTtsywlpLh4sDQeOyKFH30paAj16rWih0gCbgF9kk5DxogXKVAHu868/S7m98VKrICtIhX8oC9congfV6126dKmadiDzlsgWzBI52DWdoNedLU3kOCPp28bozuiZUoQ51SXr+MOZqzkRdfeMmKEHoNe4vFs7Uv1ZVbsOcfreD9f5F24A08HzJ6pucSDZOT5PF3x1nowfP0yBq2+n482wCreQhBtbVqgcXqczm5urC+AEnJPZJRMMBeJ3bWma7XU2K87j/5at5v1//uFaNelhLjmzx0pafq7OiZ0vvgfczeekmNG54zVJ/8/iyppbd9rpBPj6WzWSV3CavPHmlj7Fww/nOfOOiU8ETGMXt81kTCLFZ5ZeL14EQkcgbMALUEV71slfZJuQZm5rdjnTmHRf3inhlLKlRgvR0i6cIHVvVcrBzAY5tmVvyOxZ6Ckl7giqx7/SCXid5gRsqfIjRNbFnXU1nc1QhU2RjNrsd7vLckbSn/tYsnfwevlyTGQxGz/ytFB6us7xkRXFWYuWrMU6gD14lc5sP4ujM8rGyBNPlQvglxZPSkos9zvcc/nhRK+zublZ1qxZE3JhWrbsdPni8pKARWR2TXSFLfPJ98OIK8vUtZCdIuP387ljB8V2MzhuzLLpck5Tk1y2sCgkJcKuZdJln29u9Cs98N4jrT4zCWeDPkBmF24vig3uYwC5nONUbuB8KDcsasjoGnXr7LrjUjlisGaCh/zyT1IyfqgqUZDZ/v1LFSpLRoPW4KuD2K4ZX/1sOJRvbHx83/CMrVm7R/ZUHVNO/5FjGYLW8crVH8bsLhnu8+Adl/wR6Oldu+SPiDfCgRyBsAEvQQLg4iA2rLFF3amoHm7Nywl7ux6AU/qVi2X8wUEyTLL8WcRAYDoZb4ob8Obn5yh/EI4hLdDWLHMeflWZdDS2KFfP+eMbyhK4uxgQ/20V1WFltqKNpdOkIhlUMWwe/NgT975IBWAO9rxE694W7v00i+ZYNZVN9xqVFDd9IdRY5nzzYrllQq4/A1rbcFJeUcOI1i67JYBZ7IBZIF6e6nM3e/67byjlA0DHApPXqqsb/cCXbDrvG3831FjsfeME+yS9GuTfVu5SfWdr2P/CnSU7jUoDmeQV7WkBXdr0fmI2gUlEalsX9QaK4NDJ/vq5Y6W2oVXWVDfJ1qmjxfo3iouTlmSaxNQ4kNlFAYdst9J/ak9ohvg7N5WpfB0LPmIAfYddpmPHW+U3zx8XaCaeiUC4T0P/Pc52YpAd8zR2++999mYWfgTCBrx/fevZWkGMUP+XR2Yq4OBHCL5aOBm6UIoLZF+aKw+H1Vf404vvkfy4/M2tZ8nppQWacSIG5tTFlYJRDEyL1XjNlmkKZlYQ31HH1htZ+BkzZoj3pRlbHHvjbAN2zt2ISMdhLkyxSNctvv4M+fK54/yXfmHVDvnds1uEnYrS0ny/Xq1RnEz2iwwmYB2TEDKhxo12zsGpjhLO3CybmomtceNJ/ylO1QRzh4N3DKUB84d1HWl+TV6yukZ7cF4T0ItbnDV2YMheA9h/9ewWeWNbrWrtTi3Ilrb1uxQok/Fn14JmKi9QfQC3gF8MN6A44ER3LHuQTGhslisHp8gWXNyeKheTzUPhwdozv90uKemTBPdJdmg8sBPOk9G/jvE0dvvX/fRmE58IhA14+WIlS8GP548eWqxXdwv5B5KCYpUJYCJDuHHjxj7PIXLKkH1m8WSNxwP3Xui/G4GyvJa5MrMEy2jzQwboTfZmlfjcv2SUhgMY4ELFgslrXSMQrdSZk76A+kIsoIn7c+09i2TJSEyBfQ0FDbKdbTUnulCiWBx+dXmxTM9N1+PIggPc+ZyZRFxOdrq+7rNXrlDFjnAbxZEtVUel+vF1XU6xRSgvUogGjcEK7cg448xmOr2m9IDqhNOtDdmwpWltmjX2FbFWKAWKcRrVCX3ykTcv1J0yK9AE0DMno7gQL8C/uTcyVigxeWVjpfKcyZpNnrxii2Z5kWRDeg0XPiyWAc9oEkOnsQwfRcD9SXIw3Hs9UI9L1p25gXo/vHknTwTCBrymDEBGxTiUfLHb1ppJL/HDtOXDWuXnAnTJDKG4UFtbmzyzjmEk/PAwZ6eBAXOfWzbG9+NTUaO944J27TUztZJ88+5jWoF9dkGWn4toLnXxKmSLYUphnZrMkjbGlQxWKBnOBAEKPM/uSvpwzu1Pxzhtu+NZ5EJmlc/HjctLNFxkb/935gTlrZrbmMWRz5fRVqAV8J3z9upP4hJmPndIKDZXVnfpD5CJWySNzOu1aa2yoi1N1rsK1XjfgK3JmVlHdp7923Z/eK5+eBy93aMKcn2KH9Mld95EdWhj4euug6APwHnj5v1dCt0mXzVbrl48WTb+9n39Hqbv+x98K6haC3FsPpkvbe0jlELGd7HX+m8EqL0guQTH3mteBLwIdI1A2IAXPiCV0XzJ8oPkA3Xl+oULyOP9RRdOkbpjQ2XEiHEKdKnyTybuZ6JvvoF+rmMxsQyUbS8nqtAs0XOz/nHoARStXr26py4Z8joAAxYU7mr2kCc6DvjZT5cPeC3TeNAXQsUc7jnfId/+ybuSebtvZwTABwilWGvxQt/7UABa502SveNGSP7eI5L6emXCOeuoOCCPCKCFj/tIW0aXDK5zbla05nzNbIvtNUsI/GHjQdkwa7w6y1lWl0w24Bs6WOOmfTr3SBqZe3bdyORCpQrUUJBh9wng/f1H3xO2ueH3xnMhE8mYvWMTFwG+k1HXIZufyELjxM3A69mLQOIjEDbgJQNGVtMtos8Xb1b2EN0+Ky4u9heiuYFutFuriQ9B/K7gLGqjV+SSzOvefnz4EeyrxVYWqd42qXDfMbKHZArbahqi4oDbMx3KACF+T0py9UT2nm3QzMxMBUOx0BcimZktVOycv2hulIW5PumvX79YIRunjpYxxQXqVoaWLyA0nmYi7rGi/oADJAD8BzfNlpbsDPnhxmpJ7XQltOOdNsPOPizza6/x2Ydb+18bD8muWUV+i3G+C3F8C2acEm4MC8sK5WhFddDsrtOwA4oFu2/ca4xCPH5vuFFO/uN6Ukoy+aPhjdCLQPAIhA14kd2ywhHTnSVbCch77Y12Kd+0QzO68NFo7qxDX5ViivThcYNefvT+86ly3So3/m+8DSMiHWM8ju9PcjdW6R6rmkE84trTfbB4YaGK+kJP87PN/Yw5k+Fd9PEBtQV22xDzPiATh7S5qe1hy5DFEkt2rODnNnaIDId+MH+idsc45qe2qwmFWRHzurtgza7NAvfV3fVycNY42fbo28oz57sQIBzLwtfkDkPReJyFts7vndPnlWnG95ONWzUjOJB24mJ5LpLtXNPY7Y3Pb7LFwhuPF4FQEQgb8FpHpSX58vXbz5W9B7JlYpHPQAJqw0edElnOSmqndBQZ4ssvK1EgzDYcW5tUSfdHzqQZQ1jMnFqjyZzptgp2jEXCaV5mIZwoJecxqKaQ6etN6hFqBDSy8+h7p71eKX9xWam82cntNYBJERnFYM7G7gnWwYlqln1GBxeqzKSSArUTBuiixGCSZRhU0Nz8XV57ui1ducA0znvkO2/Koaqj8tgjl+p3H4CXnZ9o5gEPGFpEIBv3QDFxX8dndjFIcn5eqbUWOZnbldLTH7+PE/WM9Ha/BnY9CbrevhPe9ftKBCICvBSikd0tm5kiP/vFVln+2YmqgUkxim2Z2cQBuABewDBSXvB+yWrYliScSbcbVV8JWjjjNAtiZ4W287xkBL78yLfWNqjbXbgN7hi8XrbBvUrwcKPWe8c56QtkhXqzmJQFFpbkNLis5kZ3pEPU6ndH+QH5uzMAmp+O1ze+uTJmSkB3d8H4vDhLool72xCfffDL9e2ybHCqnoo6wq/qRVLKxnYBveYu97u2dAXC01Lb/Zeyol/AJedfvrxUqU+Rgt4RV82WpopqiVbLG1UKGufzTHzvwfOkum6Q/OTxd/q8kk7vfbp67sqexm7Pxdq7Uv+JQNiA95v/cIWUb66Td/+8ScpmDfdrZxIKaAxs3cMRczbjRlrxBuAXGoSdwxc+NIn+3AJlcMyiOJofukTGyn7k9963ImLHO7ZHyRpSHZxoDqhl0Clsem3VjkSGpF/13Zv0he4CyfY8Dmvj3qyQ03LSdFFtfOrlXz1HTisr1IXYWQWweYPrXcfzZgHGxz24VGUDmyoOS9GCCZJSeVgQVuN7je80nj2nnBnXR8LslXYfDxmt3rmpbX4KBHQI9HNJEHA+ShUAXqMakLXFzRLlBubbXTEb2XGOc6s4xBIDWwxBb/D0e2OJZGLPJfEEDYnMbqK/axM7E693LwI9G4GwAS8ZWXcW17KUAF6ytU8/+4GqNVgxhhVqAUzwlrcsBq87HZN6dsq9fzUE989dOF6LAGMtXInnbIwXGK0hRk+ZVBjn1m3fG89Y9Ke+WIhgCbx///6k5GsaaDTbcufuB7sO7A7dmnZSXcwAiRguJLKZAoJZ/3Z3LUAq9ABUQmjugrab0k5KXUeKPN+eru8t3lcr50wY0qVLrkPT78+bFwg63Tisdac6wnXzrjtLBhUNC9vpsrt5OL+Tnfq9Hr83kU9a5H1TXAqVAZUcj3cdefy8MwZ2BMIGvE5QS8j4UXjs0Uu72OlS2ObcouOYB+67QHU0AXls4+3Zc0zPG6gV8cn+uCF4H4uBQ7KbVCR7/OM5PqOboL7Q2/SFUPMyeoPbtREAOLykQK7c7zOgCGTsEqrvSN8P9N3WXR9nLRgvx758tha5jZEOaRLx2xBPSvEVuJlBBXxksr40Ct2cdA2SBt/74Tq/6gKgNhwXy0jn5z4+2HzNNMjT7401wvE5H+oYzdPYjU88vV4GXgTCBryBQkOBGllfsrc0QC3c1UA0BSvUoGittKQg4ZqaA+9Wxj5jE98/+vKHAYXww71CMptUhDuHvn6cZdtxx+svZgMsugG9FHtBCUhkC4djbxQEiu6skYmmUbB2pLOgLdg43YVu0MKgOdmuD0VptKbKwxIvgxrmRTbXDHLo3yhWgShCfJZNv9dTAkjkExe8b09jt3fi7l21/0UgasAL2OXHx+ww+dK8fHmJbjkGArymCenxLnv3IeJHtLsfUKSiEMgPV6mhu9l4Fpc9f6+NvlBTU6NFhP1p2xO6FIvlSKyEE30HRt1+gWSVjNTLkM29qVOVgcI12k/aMvzAd05KmxzoSFVNYdq0lHYthLOmEmardijVCU3gwruX+N/bfdtzcZmK7cI5Fw0YWEAb6c4Ux4Avg/D4vXG5FWF1YskDU1MJ6yTvIC8CXgQCRiBiwOt074GTa3y6SxZPli9dM1Mv4ixOs6vaeR6VofeeRMvgGleyJ0ZihVIrVqzo0QILNI8BEP29KNLuIVkgFhj5+flKXzhw4EBP3N4Bfw0oQKPvuEB1hAfn58jd6b4M709aMwTJMmTNUvceESkeqYB4UkqHSpotSG1TOgOaw25qgyUF6BuOLrQGzDDi0Vg0fP6yUr8EGYkLiuho4bhAGr8XPnh/W1DFI77x7MNkH/vTLk084+P15UUg0ghEDHj5wvzKjXPliSc36tYbNIbS0nz549oq+cqNc7SC2b6wbavM9CbJLjz/UoWn9RjpXYrj8cG4knG8xKe6sqwjLl49JYNlWaubbnkxkVNLir4NhMC1xPzFaz0bASfv/a9vPVtpXnVLZ0hrfq7U/XaTzC/Nl22zivyDoniNTDDZ3Y/aU2W/pKiLnDmzkRRAAYLvUlO1iXVGfO4Hz5+oVCW+pzHIYTHId7Jd9/4H31SN9HCaOWuSeewvlJlw5t1Tx3gauz0Vae86AykCEQNed3DIECAjhLQOjSK151+s0G1HTCrMlY0v74EAPvr6wwNQDEZLiWVuPW1SwcIM3edI9U1jmWNPn8uPIuoLzc3NWsjSn+gLPR3LeF2PIjuyspg6wO0dUXlIvnr6cKU2YEIB2F3RfsqQYl17qhzpSJG6xlaB8pCXkyFbO1Ilu/KQAmXAMzsVE8YPk6ef2RI2IHXPx1ztqr7+guTlpMsD916ofUGfyM/P1t056iuc3N5QMXHye70sZKhohf8+LpZ8rj1DifBj5h3pRSCcCMQMeLlIMLcg3T5bXqoZ3ezsjKTi3oUTnFiOcVZYW3alqbI6JgWEWMYT7rkm/p8IYX/PpCLcu9D9ccTRWUjk0RfiE9d49ILE2rBl01RWzBogFwVhHNpoUBrKO9KkrkNkfYdPsxewu7MjVRUeUHRAzxcbZWcz055wxplZXCDDlk2X6p+u8ys9wAu24jezOTct8Ggd3xiLx+8N546Ed0xPSTuGNxrvKC8C/SsCcQG8wUJihWqRfFH39fACdFVI/6oyOfjoWwpwnQUoFIxF4mTW0/GwopZAPOx4jQWwNnHiRE84PYqAWvaHrWSKh7yWfBEAbOZfd5Zfm5cRAnrh9wJ2AbZPt6d3Gbhbv/eLqa1dHNqgHdx2p28Xje8XNHrhBwcrLjUzj/0Prwx4jGmBo/3rbLEAXye/1ytsi/y5tO9F6h283ZrI4+ed4UUgVAQSCni5eDjyPqEG2ZfexwGptfaEDhm+HG5JNHMx4+9ojR16Ig78ECL/9J9PlSeUa23AraeL2Xoihom4hkdfSERUE9cnuzo5ZWOltaZBRt6yQAEvnF3ALm1paqtSGzCmoJCN9nBrhl+v96LUNuX1WnMW+0547Er/6/FSb6BDc8aMVUnH4/dG/lyhscvODYYSXvMi4EUgMRFIOOBNzLCTt1cyK2xr8mNHo2jl+OvbuwBeXrfsb/LOJPEjs8IMT98zeKz5ETQrUYr+PPpC4p/LeF+B3R7T1HX2jUnFrZ00BzfgvTPtpAx3SJbBrYVjS2PHKD0vVznCkag3wOPNLBnZ7Q5TIEdNrknigtbQ6KNlhGoevzdUhHzvezSv8OLkHeVFIB4R8ABvPKLo6MNkiuwlM3FwUh14L97SYGSU4A02bvZllPtK80wqgt8psuDnn3++oL7g0Rf6yhP96XFij2zWw853AbxXpLWqLBm2yUc6RLO+8HinbT8oUwuyVR+XFg85R0A3C/IDD68KGkyUdSiSMzMhOxBuP2MxWkW4d8Pj9waPlGcoEe5T5B3nRSA+EfAAb3zi6O/FPO4tw8sbUBjS83J8mV62N4tHyt77VsTF3MEubFXYcPbi5coU59B0251nUnEqPIAEgC7qC2id1tfX9+St8K4V5wjYZ9PZLS5rH3XSG7AbBvgGaqg0fFRRrTJlNAqBUWzg9e4aPGIyy0df3hqXRTAOmgBeVB2iaR6/t2vUPI3daJ4i7xwvArFFwAO8EcYvPT9HeXmhGlxethybK6uFHx/a4Z+u02ITnJki2YoMdS3eB2hnFA1PehWI7uYy0CuUnfQFj+YRzlPfN44xwxc1oXDYEDtHT5bXVBycr1Pk9n+/uUoXx4Bd+PXmivbayk+CypQZzzdYvQDFqXB2zSkz0kgyhmjsnT1+r4hH5Yr0afOO9yIQnwh4gDeCONoPl9EUus+w+ByY+MHhPLItDZv2SfXj6yK44sA71EwqBppbmFN9AfMIr0q7fz37UI5Y6KLegCsbzU1zMIqD0274QEeKbN5zTM7ITfPTGywy3anfQF/ozqHtsUcuVZ1qkyWLJNpmKBSt+s5A5vd6GruRPGnesV4E4hsBD/BGGM+8686SjsaTWow24qrZCmLJ4gZqTi3eMXcv1kKTfd9a4dfFjPDSA+bwnjap6M3AMlfoHJmZmWoJ3FNOdL0554F6bb4vhiwq1kUw2V7UG9zt9pYTaj7hbmR64flaw7Hy9y9uizqU6PDSzBo+ko6gN/xtp6Pcj37yp0hO7XKsAV92NgYCdcdoHZ4yTdSPjHeiF4GYIuAB3gjDZ3y8Aw+vlFG3XyjtjS0KYPkRc3JnAbsp2Rl+ni7KDRSMeBne8AI+EKqX0d0sLi5WoLt79+7wAuMd1acj4FwEGwB2Tsj0et2T/F1bukxOaZc5DjOKaDOs8QggWd49e45G7fzmHMNA4Pd6GrvxeOq8PrwIxBYBD/AGiB9V1bii1f7i3U+9C2hlW9Ia25MAXvi5ThH4UXdcIIPGDZeqb7wQ2x2K8uz+on/cH00qoG1QlIZ5hEdfiPIB7wenuRVdmBKAd0JTi4zeXCX58yfKG+1psiC1TfY2tMqVg30avs7WW3btqDbQouUAB7p9AN8ZM2aoKsn27dv7wR32TcEryO03t9KbSB+PgAd4A9xAaAs4pAUqLCNDo/SE/Fw9kyK0QDI/FKpxjLMP477d/+CbccmMBHv2rr1mhnxm8WnyjW+uiqqwJNmeaXhvc+fOFXRo+/KWv2WtPfpCsj1hvTcedoxaqo4qPSo1e5C/qI3vFZpZFDuNKD7aVi0FBTnK6UWujIZ9++6qYz02ke8/tFi1eSOVKQs1QD4jAMTCwkLZuHFjnwe+F198sfLx16xZE2rq3vteBLwIJDgCHuCNIsBkb5EWQ2aM4hCyu4H0b/lBwKqztCRf/rhuj+Tn58hf3TgnIT8UzmlQfQ1Hj4KU6prGKGaYfKf0dV6v0Rf6w4948j0d/WdETkdGmxV836yUDhmbky5XpLbKGy9tk/MWju9SxAYIfnX1joS6IzqjDI+X7ze+1xLRjN87ZMgQXej2NWk+T7MRhSYAACAASURBVGM3EU+F16cXgdgiMOABr5trG0444eMiL4RtMIAXC2FnI/vR0HBSf5CohKbhWf/qqk+EH4ovXTNDcE6i6CQRgPT0knyVL0KrM5aiknBi0ZPH9EWTClOd2L9/v5pHeOoLPfnE9L1r4aKGogsL6kBtUkq73NSp2YuCw5GOFDm9k9frdGMLd+Z8/0GtiNS1Ldz+Yz3OVA3s89MXgG9fX5zHes+8870IJGsEBjzgNfWEeHJtya6SgbGGWPsli08TikzQ0rx8eam+BRgNJSAf7YODziY/gG7HpGj7S6bz+gInzugLlqHqy1SMZLr3A2UsweyI4fjSsB5GtaF8W43MKc3X1wzwXrJ4svxxbdWnbID5DmKxjUUxx9KchXO7b3suacNr/F7jvSfrQD2N3WS9M964vAiI9EnACz8WJ7O6326O+h6S1aDgDG1MsrSHHn0rbnJhX7lxjpy3YLzs3nNUM7v80EAz+MY3V+p4yfKac1LUExjgJyazSYWNjeIbitK85kUgmggEKpC12oFLU1tlQWq7fsewk9TQeFJ3lXBhoz12XOTj9btl+t5ayclJlzPmFAo7PzQW2U8/u0V3l9AHRh6NWgMoWsnckp3fa2B31apVfbrWIJmfAW9sXgRiiUCfBLzmTV/19ReiAqlmIMGXPMUhZFMOPvpW3FzKyOICcikcI6u7raLaT29IVEY3loegr57LDwxqB/Bik0HWy+gLNTU1qivq0Rf66pOVHON2WhKzOOc7iu8qvr9YqF+e2ipzO+kMv3p2i1x+Wam0ZA+Sde2psqa6WcbX1cv1E3L9tCrnrNas2yNPPFmeHBONcBTJyO/1NHYjvIne4V4EeiECfQ7wOlUS9j+8sov2bSTxI3vSVHFYpcTgzTk1dLvrByA7oWhoWILtFKzt3uOrnDaFBn6YvOxuJHeq+2ONL8dWJxzZ3miWecrPz1dN3QMHDvTGMLxr9sMIsBNFG7Zsmr9Q9vjrlTLmH5dIXk6634547Yk22ZWVKR91nJIuuzOtRYY7zCqc4fnVsx8IVKu+3Ezer7f5vezooKdNZrcvcIz78j33xu5FIJYI9DnAy2TZhhu+bLrO+9jrlWGBVSsGqf7pui5ZYfoafceFahyBFFmoZpJfZGrZToSrC6jl79+/VOE/neN8NIZVXQAvtIZEFKqFGnd/f7+35H8ss9ObgLu/31tvfqK0q2Gfne6XLSMmqDdQxHYse5Acka7INpiBhcXytjte+RTHN5FxZsHPzheqDvH+/rPPYG9QiExCDfc0b0cnkU+Q17cXgdgj0CcBLyoJZsuJxW843DPjw+29b0UXgwiAMEYSR1/eGlBaLFCIKQhD8xJ7zeqaBv8hBm55gUwwnLn+pJIQ++OW2B560qQCOsW8efOkublZNTa9H7vE3luvd1GnRjO9+X/tnX9wldW5759AQkgwBNmhkjQh6iEEjQXSSyuxAY8Ee0kV8Z4q59i5nuq0U28v0zl4rOPoeHREr56O7ZQ5HY9X5zjV60w5pXKuiCIjBFu0gtYrwWNASIY2ISVpSQIxYceQEO58F6zdnd/v3u96f3/XPyi873rX+qyVnWev9/t8n7kXk9faRwS6mtNEp7u4xu2A95mfrlbSCqeqw+Eti/75d8v6r7q6WuGmxy5/OkkgGAQCGfBC1jDrtsVyybJSo9rbVJZMOzEg4xmnF0hOQ+JIcsMpL5JIcA2bOwScLlKR/IsV/qCUL7izrlF9Cr6Q65Pd7jcOqbdRaHdPHZC28xmycyhzTDRLMs6pMsRXZFxwdUhuKFah30bBSxeuDgvLC9RbKnxJf3dfq3G5A053EfBqiZdT66n1vZAXOSUx0B67kFJAq89GAiQQDAKeBLypaGbHwggZAoLd3v3Nw05r3UIOqcIPvv+VC9/u9x1Xjgyw+dn8y0+GVTvS7gwMeN1amQvPccoHU3uCUr7g7npG9Wk6uTZ5/pAq3DrlnFx1MVnt/56bKvXnp46JqPw/W+Xr8y4ZVqACb6SS30Qhz+Cxhy8E0bql4+frtzVySt8bRC9wv60Nx0MCXhFwPeDVH+JIvEjXVgwBc+GDq5Tudqzyv07D1Kci0KPh1OKOddeokxEmpDlN3nr/OIWBrhf+t3ZPYZLlC+iLiSnW14FXpkdAlxzW0i3dC052L884n7Aje3/6dPn10NgBL3x1H3t4RcKq7NiZQXn5f38gf7jowYs+8cUdX+BHtuRT4PRm4I+7TOp79RdptyQT/iDIUZBAeAi4HvACHRIwPm88aSnZbDzUmbFcGUzSz3qxJPC/RFU1/HKA88JISYMXY+IzhxNAUgkC1j179qSss0XQrDOw4b7gB+szrm/4CegcBXxG4gv9tOJ8+WxPk0pYuzI3U33JPlDfLsgliPcNyt6WHrlsw4oEmL+eck5+faRLWjbtVdeU33SVvDo0VT6XDJXodmrrQfUnyqHjLVR1VXEiKE6m+y/P/s61UsVOrqoJfS89dp1cIfZNAu4Q8CTgdWdq7jwF+l347JrOPHZn9NF4SjpFKpLlCygewaS0aOyVkbOEfGpa8SzLCa2mKCHohWvM0Ii8gLH6h3WZDngXZgzJ2v4+efSJ36jPpMsWFEj2PwyXLOg+4O178vl9UijnBcVyEEjjS7xuYXtjpfW9hYWFAlcFq29q9GcBC0qY2t3shwS8IeDbgNct2QLkCah8BnkCW3gJWC1SgV+KKGaBhqQ0q78Uw0su2jPTxR9OPPKm52+UxlsJyMSKNtYmLMtOPrcvEaBrF5q/n3eJvLGvVXquvXxYNzhBzthxoRrktu1H1Wfhd+9aoqqxoTBFGN9apaLvTefLcrR/Yjh7EvAvAd8GvPgQR1Wh028ccjQxDa/8bl1TPqy+vH+XiyOzQ2CyhBPYGlVUVKhAl/IFO6TDc69XJ7ypEsQ4Y3+/VBWnGC+3AafG+EwVOS+6RHGyX6/2CEciW0dHXyiD3WSuk3loa5szeuymuht5PQn4k4BvA163cOGEF0kbn1KW4BZyz58D/0zo+rR/LuULni8JB2CIwFi5DRVVJZJ1Q5m0dvRJ7uIi5VuOk1/IF6oLsqVqypBym0EFyR/9ZF/oA92RqKHzLy0tVSXKm5qa1D/rzwho/9lIgATCQSCQAa8u0wudmglfR2Qyoz36xN5wrCpnMSkBnN6gHGhnZ6dkZ2erksBwdGAjgbARKNq4OnGie7b1tEDygJLqyQ4Or75+VCWvPfr43nEDXviK44Bg155jRj53/cQ5Wd+Lz4SllbPk33+5e5jNpJ/Gy7GQAAmkTiCtgFdX/Gl7arctp4XUh3vhDu2Da8o6B5Zi8fgAP9zSXZAA3qcDXgydySgBXEAOeRQBXXI9udy6zoXAxXBmwGc2gl00OMzoJLXJPkuVtvfbFxLb0PB5iSB5V92x0KyELiiBIhnV156Rt+qOqYJCbCRAAuEgkFbAiw/ROd+rkrOt3dLx/D5FApnCyPrVH6ZO4tFm6WHLInaSGfu+QAAJKygJjCpJ9fX1StpQW1srDQ0NAjcGNhIIKoGRib4IgOHjC5cJNJzutj9Vl5geAjsUnUAQi2IUXfEBycjJUslvCI71ZzlOdR+4r2qUdVmYAsKRHrsLF/6VfOlLXxYWmQnqTwPHTQKjCaQV8KIbZC/jpPfEIztVr/Oe+aby1v3zJndkAfgQtptBDM3a164rUdnJdvvi5vI3AQS20OXl5eWppLRk+YL+Nzgy2C1S4W8KHF3YCSDZV1uZJduV6XmjPHH3jsMJDPqU92fP/k7a/2aJDHbFVeJb8md5cmXJZH5wckA54pbWzwLt1zuRg8tY+t6w7yHOjwTCSiDtgBdAEPBqA/OC71WphIhkSxynoSHozc3NTNsDFzXkv7XuGtHZyU6Pl/17Q0DLFyY7xdVZ2ZA40I7Mm7XiU80SyC4rUJ/LIhmSs6hQ+e4OtHYPO+WdV5Kv/v/38y9TRYF0O/XKQYkfPKFOelE+HV69uiHY1RXaEPQGNf/Bisdusr6X8iez+5O9kYCbBGwFvMVP36JOAiBr0H6Vbpb7RdKFfh2XLjQTJ8XpPpv3OUtAyxeQhIKTWyvFI+i76eyasHdvCOANHNrIvAstDzswNEVeHcocNTgEvPh8T5Y/4KJPj3TIttePJpLXgviGTNuSWS1CoWUPWg7FL8Xe7GU+lQTSJWAr4MXrMzS8QoNeDB6PqA4E2xu7zUogaspdAdIGBM6fJtWYtzt+3u8dAUgU8CoyFosp94X29vaUBqPLiLKccErYeLGPCeiT25GfzficXbtmgTRdeon8aVHxqBn07m+WgdbT8oWSfPkfC2clktyQtAbdbxADXUzSztscHSg3NzdTAuXjPc+hkcBIArYC3pGdaVlDy/qttkjjQ/iZTasnzZLFqUM8Pmj7QxeBM7KV1997QY/MFlwC+oTWbrLJZEUqgkuIIyeB0QRQlOKq278kqwqmy+sd/dI7e8awiyBd+/yfd8nTT65Sf2/KEtLkWuD3BmRqB6Atbv1s3K7xZRhfauGxa+Wtz3gdaalUsn+vyfmwLxIgAbMEjAa8GFpy0oSdocLzETqxIy6cuiJwxoflRB+SdubCe50noBNPenp6EgUlTDwVvxwR/OoiFSb6ZB8k4AUB/RbuXNcZOfXKx6OGgM9B2I8d+Ku5Mq04Xzpf/n/KjefM+81y5R+75O/WLEic8P7oJ+8NeyOGe9E6Ovu8mJp6ppZn/NuL9eOWil+5cqUKcvHzbKIl63uRDJvq2yQTY2AfJEAC1ggYD3itPZZXkYAZApAv4KSlsLAwLfmClVFQ12uFEq/xOwEcRhRtrFXDPPHImwk3Bz1u/DtsybQdGfzJOzrjKoi9seZK+XrNFUrGgLdh+PvkBrcHFAGC24OXbTwpnLYfhAwBdoSmG/W9pomyPxIwT8CzgBcfTGhB1YCZXwr2mCoBraWzK1+w8lwkwC1fvlxZmvEUxwoxXhM0AnMfrJHM2TNUIjJyMf7l765Sb9msBLGofokg2I03cqly1cHoZC4tqfY71vXJ+l4E1nYkEybGwz5IgAT+QsB2wIvAdWF5TH0wptIgWfh6zZWyfsPORNCrSwbTJiwVktG7FvIFFI/o7+9XSSNuZUu7+YszeqvKGXtNADpeFKpQBxEHT0j5f7bK8Ys+u/i3/JuuUj7r2ufX6/Faeb5OQHVbZ0t9r5XV4TUk4C4B2wHv2psXyK1rytWrrpGvuSaaSvmCmNJc7ar7feIy/B2CYCsnCu5i4tP8QACvJSEvKCsrU/KFlpYW14fFIhWuI+cDXSQw+86lkiEisJdMbvBch9MDfNbdqKZpYso62PXKO5f6XhOryD5IwBwB2wEvkhVgXJ7qCa+5KbCnKBCAQTwkBXgt6YQGL1WGdmyNUn0WrycBpwlkxnJlcIQu1+lnOtl/qh67To6F+l4n6bJvErBOwHbAm/woJDnQy9Y6fF45OQEtX8CV0M+6JV+YfGQiVqo0WemH15CAlwRwehu7c6n8adNepd0NetNvgfxWMVEH4ShcYbUQTtDXguMnAT8RSCvg1bXVk61p9N/9Yssnw2QKfposxxIcAlq+UFFRoQJdL+QLVmh5pRG0MjZeQwJWCMCubObK+fLZnqbAyBXGm5d+84LqaX5NGKO+18qu5DUkYJ5AWgEvKpM9cN918urrR2VX3TE1Kl28ATXVU9Hymp8Seww6AX1yCveFQ4cO+fYXl+bMIhVB33EcfxgIVFdXq2mY8th1kkmyvterfAQn58e+ScCPBNIKeDER+C7CnxGnvPr/4c+I5scqPH6EzzENJ4BfAtDpouGXQFdXV6AQsUhFoJaLgw0JAbwNQkEJfF5AKhCkRn1vkFaLYw06gbQDXkw82eQbxuTfWlehygHj1NfLijtBX5Qojh+v+fwuX7CyLixSYYUSrwkbAXz+480eyvq62cLydiVZ34ukXD/lKri5nnwWCThJwFbAmzwwBL/PbFqtAt7NWxqcHDP7DhEBXdBBV0Dyq+4uFeS6zDG8P/2qPU5lPryWBCYikP+Nq+Sfb5kvhw5aK1JhiqY+HXXbY9fU+MfqR39hDtOcnOTFvkkgFQK2A97qqhJlSYaKaTfWXCFHjnRKS+tnqYyB10aQAH5ZQQKQnZ0dSPnCZEumfxm7UQVusrHw30kgXQJIaLtkWal07zg8bhdf2LBCpotIx3P7HKucOdL+UieLhrHyYbK+l4FvujuX95HAaAK2Al4Ujnjs4evl3feOywsvma9PzgULJ4GoZCnrIhU4tQ5CIk04dxtnZYcATm/zb7pa2p7aLQOt3Xa6snUvckaQI3L3PdsjYweo5RqdnZ3Ke5wyB1tbiDeTgNgKeMEPbg1wbVh/707iJIEJCUC+gJLA+ACPkg8li1TwByPIBLKK81MKduHr23fwRMoliPGGMB4flN/uOz4Mly5DD4/37W+eVlp/2I5FJQCkvjfIPz0cu58I2A54MZnk5DU/TY5j8QcBfdKZl5en5Avt7e4mtviBAqzWKisrladw0Nwn/MCPYwgGgZxFRTLnnio59cpB6Xm7adSgcThSXh4b5dWufdzbz2fIww/tTvgBf62qRCVD5+ZmSe+ZqbL7N+dVsBsGrX+qK0p9b6rEeD0JDCdgJOAlVBIYj4CWL6AkMDx1o9y0rpcsorwLwj93BL2o2DbUNzBssghev3vXEvV36zfsVHpfaIQRIPfvOCxLC7LlyN98WeIHT0jH8/vUdc/8dLUKdtE2b+2VX//6t5EMdjVI6nvD//PDGTpHgAGvc2wj3bOWL/T09Cj9ahRPZMbaAFqXp8uLRnqTcPKRIoDT3bVrymXb9iOJxOa5D9bItOJZiRNhyCHOtp5OSCgWXVMo9/5gqeJ0/0O7aXd5ccdoz3J8vlLfG6kfI07WBgEGvDbg8dbRBCBfgPtCLBaLrHzByr4AI2Sa79mzh18GrADjNaEjMCUnSxDwft7YId1vHBpV1hgnwv/9ji/Lb975o8wpyJDNWz5hwDtiF1DfG7ofC07IQQIMeB2EG7Wu9YcvrbisrTyLVFjjxKuCQQDyhMIHV8mprQflzP7mSQeN66cvmDPsWvzdzJXzZdq0bPlvlxRK4RdOy7ySfPm3F+tHJbNN+gCHLqhcMlf17HaRjYmmg8+SsrIygVyqqWm0dtohFOyWBAJFgAFvoJbLn4PVhRbweg3uC1HJnjaxGixSYYIi+/ADAZzYFtxTpU5r+xs7JhwSrs2/6SrJu6FsmOVZ3g3z5dLbFsuUngEZ+td6ueP2Ylm4IKasL1tau1WQ6WUVzx98/yuCBLuW493y6BN7/YA9MQbqe321HByMDwkw4PXhogRlSJAvaMutMBrAu7UOYSmP6hYvPif4BIo2rlZJbdDv9rzdKKde+VhNCtr/r9781/Luf7wl/6VylnJoSG5eBppwI3rsn1aoQkvbth91rMiG3dXV+t7+/n4eQNiFyftDRYABb6iW073JQL4AT128QkPSBJt9AitXrlSdQNfLRgJhJYDT3eIf3yJD8QEZ6jsrnS9/qE6EtSQKtmOzZ01RHu9wcnj08b2Sm5sp0PTihJeVPK3tDOp7rXHiVdEhwIA3OmttZKZ4BY9AFw2nupQvGMGa6ETbuEXJWN8sQfYWBAKQLUC+0Lu/Wbpe/jDxpqiurk59puhiE37S7gaB61hjpH9vUFeO4zZNgAGvaaIh7Q/yBZ0YgeIRLS0tIZ2p99NikQrv14AjcJYAqrfF7lwqJ5/bpyqnDd5yufTmDin9b/eOw6qY0QP3Vcmrrx/1VXKYs1Sc6536XufYsufgEGDAG5y18mykCMCWL1+u5AsoHkFPXeeXgkUqnGfMJ3hDACe72WVzlH532rQsmftRn5y4fqZ83nhS+o+eVAFvKg3ODpdtuP6iNOJkKrdG7lp8rsASMTs7m2/oIrf6nDADXu6BcQno5AdcgFNdlsR1d7PgVB26XnCH+wUbCYSBABLWMmMz1FRQZKL9qTpb00o+LT7XFbfVV1Rupr43KivNeSYTYMDL/TCKgJYv4FUjdLqUL3i7SXAiU1hYKFrf6O1o+HQSsEcAX6SXrbtR6jPbpXvHoURVNXu98u50COjAl+XO06HHe4JGgAFv0FbM4fFCvoCktObmZuW+QPmCw8Atds8iFRZB8TJfE0DSa01NjRw4cIAFEnyyUtT3+mQhOAzHCTDgdRxxMB6QrO2ifMGfa8YiFf5cF47KGgEd7OJNBeVR1pi5eRX1vW7S5rO8IMCA1wvqPnumtsLiqYvPFmaM4bBIhf/XiCMcTUC/Orcb7N5Yc4W0HP9MjhztJGaHCFDf6xBYdus5AQa8ni+BdwNAVSO4L7S1tamkKMoXvFuLVJ8MXS+C33fffZfrlio8Xu8qAZNynJ8/t0beqjsmm7c0uDqHKD5MFxfCQQjcedhIIOgEGPAGfQXTGD+S0qqrqyUvL0+5L7S3t6fRC2/xmgCLVHi9Anz+ZAR06XEUUjHxhbogliPx+KBvy/pOxiNo/059b9BWjOOdiAAD3ojtDx0kMSs3HAuvkwzhpsEvLuFY07DMAl+q8eWapbKDv6I68I3FYnSLCf5yRnYGDHgjsvSQL8B9oaenh6/BQ7bmLFIRsgUN+HTc9I9+4L7rFK0f/eS9gFMLxvCp7w3GOnGUYxNgwBvynUH5QsgX+OL09Dr39vaySEU0ltyXs3Q7qfKOdRWKAzW97m4HHfg2NjYq+0o2EggCAQa8QVilNMeok0X4oZQmwADepjWTLFIRwMUL+JD1mwa6vQR8IS0On/pei6B4mW8IMOD1zVKYG0iyfAHuCzj1Y4sOAVMWUNEhxpnaJaA9dqklt0syePcnB75ITuTvm+CtYVRGzIA3RCuN19q6DC1/8YRoYdOYCitapQGNt6RFAImTlZWVqgw5C0qkhTAUN1HfG4plDPUkGPCGZHm1ZyLcF6ipCsmi2pyG23pKm8Pl7QEkYNJjN4DTNzbkG2uulI7OuByoD75FJPW9xrYFOzJMgAGvYaBud4eTPLgv9Pf3q2Qlvk5yewX8/zwWqfD/GgVxhKY9doPIwNSYn36yRj490ikvvBSOBDDqe03tDPZjkgADXpM0XewL8gX9CwfFI1paWlx8Oh8VNAI8iQvaivl7vNpjl5X+/L1OXo+O+l6vV4DPTybAgDeA+wGaOZQE1sUjTFQwCiAGDjlFArqUNL8gpQiOlycIaPs7fOYg2HWrTcnJkoycLDnXFXfrkXyOQQLU9xqEya7SJsCAN2107t+o5Qt4MoIWJoi4vwZBf6K2jqJVXdBX0v3xI9itra2V5uZm1/MELr1tkeTdUCatP3xNhvoG3J88n2iEAPW9RjCykzQJMOBNE5ybt+EXjX4ljUxoyhfcpB++Z7FIRfjW1OkZeV3NL6s4X6aXzZGet5ucnir7d5gA9b0OA2b34xJgwOvzzUH5gs8XKMDDY5GKAC+ei0PXFneUwrgIPQKPSg58USiHbywjsOgeT5EBr8cLMN7j8WEAnS4a5Qs+XaQQDAtfqODywV84IVhMB6agdd/cHw7AZZeKgP4MamtrU1IZOg1xYzhFgAGvU2TT7DdZvoBAt6mJr/DSRMnbLBLw+nW1xWHyMpcJaL0lq2dNDh6Si2nFs+TM/ubJL+YVYxLQ+w0acVhsspGAaQIMeE0TtdFf8jdd/MDTfcEGTN6aEgFdpAKnLPxlkxK6UF5MuYv1ZZ2xrFRidy5VN7Ss3ypFG1fLYFdc/rxpr/VOeKUikFwt9MCBAzzw4b4wSoABr1Gc6XWGYAPFAfLy8lieMz2EvMsQAexDaDb37NnDL1yGmAatG12eHCe7/NI9+erhdDf/G1erhLr+xpOy9t5qmZ2bKT//X7+e/GZeMSaBZH0vErXb24NfgY5L7T0BBrwerwFOUsrKyhKeuh4Ph48ngYQjCF9lR28zoKAEmpseu2Gj/MB910luTqY8+gRPeO2uLfW9dgny/mQCDHg92g86GaSzs1P9cuFJikcLwceOSQCnvEiaxGtF2uCFf5Noj11KWsK/1kGcYbK+F4lt/H0ZxFX0fswMeF1eA+2BCvkCktL4qsblBeDjLBNgkQrLqAJ9odZvoxjJoUOHAj0XDj68BPC7U2vLqe8N7zo7OTMGvE7SHdG3li+wypWL0PkoWwT0FzR0Al0vW7gIaI9dBhDpr2v5gphUV5VIS+tnsqvuWPod8U5LBKjvtYSJF41BgAGvC9sC8gV4nfb09FC+4AJvPsI8Af1ljbpe82y96lEHu/TYtbYCcF9AYlpytbfvfHuJVF9Xojp4q+6YbN7SYK0zXmWbgJYF0r/XNsrIdMCA18GlTrZYYaapg6DZtSsEkEBSWVlJJxFXaDv7EK2JZLBrnXPB96qUC0NywFu5ZK4sXBCTI0c75WtVJTKvZKY8+vheifcNWO+YV9oioPey1p9T32sLZ6hvZsDr0PJeffXVUlFRIZQvOASY3XpCgEUqPMFu9KH6s4mn9faxPvbwCmk5/pl0dMbl1jXlEo8PyPp7d9rvmD2kRID63pRwRfZiBryGl15nt0O+AAN/lkk0DJjdeU4AQS/sq7q6ulikwvPVSG0AOumHHrupcRvvakgaoN3FKe+Xl8xVl63fsNN3J7zzimdKSUm+/HbfcTMT92kvyfpeJIXTYcanC+XRsBjwGgKfLF/gD5ohqOzG1wR0gQK8FucXO18vlRocvqTgc4rJh+bX6o51Fep098DBdnXi67f2nbuWqMQ6PwbjTrCivtcJqsHvkwGvgTWEhghJaQ0NDcrWhxoiA1DZRSAI8PW4/5cJQe7KlSt5Iu/gUqHYBE55f/ST95S8QSTj4p8OPjSFrgtiOZKbm+XLYDyFaaR8abK+F/69/GKeMsJQ3cCA18ZyQr6AQBcNSWn8YbIBk7cGlgCLVPh36bTHbnNzs+AXPtvkBKbkZEnRxlrpebtRunccnvQGSBl+8P2vjLruF1s+kYJYrpI63P9QndxYc6VAWoCAb+6wnQAAHDtJREFUeGF5gfzsX3/nO+nDpJMN4AXU9wZw0RwaMgPeNMDiB0ifbCHQpU4oDYi8JVQEGFj5bzl1giE9dsdfG5x84nT2F1sa5EB9u7owdudSyS4rkFOvfCx9H5+YcGHh0vCtdRUqsNUNAS1kDehbt589+zsVFM8ryU/83f0P7ZaOzj7/bZyQjihZ38ufiZAu8iTTYsCb4rrDmgklVylfSBEcL48EAbw6R2O5bG+XW3vsMp9g4nXIzcmSB+6rkldfP6oCXpzuFv/4Fjn1ysFh9mPj9fLAP1ap09qRDdIGBLiQESS3T492qkAYAXJU9LTe/iSMfrr+2aB/r99WxvnxMOC1yDhZvoBfIshQZyMBEhhNgEUqvN0V+FIOqRU9dideBx14IghNtUGacOOqK1Ui2Fjt7nu2q7+GnCEnJ0udAicHvzhRZlW2VKmbvZ76XrM8g9AbA95JVilZvoBAt6mpKQjryjGSgKcEdJEK/My0t194VczmPAH9S5weu5OzxgksAlIdnOo7vrBhhfQdPDHhCe+NNVfIt9ZdI69uP6L8d9Hg0vBRfbuqvIbT29zcTPX3kC3oZ+lnjHzm5KPlFU4RgNtMaWmpUObgFGH/9MuAd4K10CclOuGD7gv+2bgcif8JsEiFu2ukPXZpE2eNO1wV1q4pV84KukHSMPfBGhnsikv/0ZMyJTdLut84LNllc2So76z0N3YkroUe947brx4maXjhxXqBBRgS1nD6i1NdJKwlJ7YhMMYz4d/L5g8C1Pf6Yx2cHgUD3jEIY/NDp4vTXSSlUb7g9DZk/2ElQEssd1ZWe+xSO22d99qbF6jTWa2lLdq4Ws62dqsgd3rZnERH0PPmf+NqGew6I+1P1Ym+buWSy6RdMqR2yjmZm3FeEOyeF5Hv3rVEkKSG/7715gUS7xuUjo64OvlFsIsgGCfD214/an2wvNIVAsn6XvwssYWLAAPeEeuJUxKUBMbrDXjqspEACdgnwNNH+wzH6gFfKBDs4u1TmH5BI5ks3jfgDLSLveIZBQU5ylFh6uxc+eLjtWM+L37whAqAYVPW83aTFNxTJTOL8+VszjR1/d1TB+TyDIS3ogLZr9dcqazHEPTCASLZwaHleLf87NkPfeXR6yjkgHYOaRDliwFdvAmGzYD3IpzkyiwoCUz5Qvg2O2fkLQFt5cdkKjPrgGC3trZWwuaxi6plCBrdcjGAjCGreJZctmHFmAuDQBeSBkgbZiwrldzFRYnr5sp5+X7mhcAcp7dIgEMyGv4bwe5IlwZcBzlDOolyZnYNeyGB6BKIfMAL+QJE63l5ecIEm+j+IHDm7hCgXZYZzmHWR8MBAf62br3yn/fMN+Vs62mZVjwrsTj6//Hnyef2ybkuVE8TuWxBgXzpnmVydHq2XJ4xJNNFpP18hnzlg2Oya88xVVxi2/Yjcse6a1TQ++6+4zInlitIcoPm9933jssLL7EAiJmfAvZCAqkRiHTAq+2TGhsbWYUotX3Dq0kgbQIsUpE2OnUjvzSM5odCETh5RbGIVFveDfMlZ1GRTF8wXLd76W2LE368kD/052TJf/3HalleMF2ePZcls+S8nJYMFfjePXVQSRjgxgAtL06pYT3W1zcwqgrbZCfX3/n2EpXQRtuyVFeS15PAxAQiGfBCvgCfyp6eHhrk8yeEBDwigDcrCH6ZaGV9AbT0irKQ4cwQtCJAbf3hazKUovY3qzhfLv3m4kTA27u/Wc73DciMa0ul7andsm7VFUpi8UbvkHwwfboszBiST89PUQNYknFOlp/uUUHueDIFSBvgCPHWRanDZCfXTz9Zo+zNNm9psL4xeCUJkMCkBCIV8OoEj1gsptwX6A866f7gBSTgKAEWqbCOlx67E7OCFjfVYBc9wnc32ZVByxmQrBZ/+UN1WguHhWcHs+S0iHJk+MP5KTJdzkv+1npp2Hd8wgQ7BLxoyfZn1ledV5IACZgiEJmAl/IFU1uG/ZCAWQLa75plcMfnSpcLs3suuTfIIWJ3LpXM2IzEXw/FB9Tp7s3XFScKS3w6NEU2D10oJoGGk+Culz90bmDsmQRIwCiB0Ae8yfIFuC/09vYaBcjOSIAE7BPQSVjU049mCelHYWGhoHoa3WPs7zX0ABlD5uwZMn1BgWTkTJPM2bnDNLwt67eqk99/KJ0hRRcrpn1+XuQnvZKwI0MyW9/HJ4YNCMEzTou7dxw2M9CkXuAb/Nt9x1XlNjYSIIHUCYQ24IV8Qf+i4MlR6huDd5CA2wS05AhfSvHllE2Uxy5amDx2/bCuqKaW7Mqgx4RAFZIGlBa++vHVcv8XshLD/elglgo2M2O5ypM3OUEOxShQnW2g9bTMuPZyab3/NaPTnFcyUx57+HoWrDBKlZ1FjUAoA174fVZWVkpDQ4MqHsFTkahta843yAT4+l5UlUd47La1tTH4N7yZ4aWLJDVUVBurdb78oZzZ36wKRjxwX5W81tIr9Uc6lQevDpKTA15oh4s21sqZ95uVq0O6WuLxpolgt6OjT57ZtFolvjGZzfCGYHeRIRCqgBd2PSgJjAAXSWmUL0RmH3OiISOgE7Si6EZA2zZnNjNkDLmLiqT0pqtUOeB956eo5LPkhkpq3W8cUslvSDabVVagLMiSG4Lh3v1/kP7GDvXX6LfwwVUy2HlGTjyy0+jgYYeGQBcV3CBniMcHHa9AZ3QC7IwEfEQgFAEvTkN0UhoC3ZaWFh8h5lBIgATSIaD9ZvWbmnT6CNo9WsuM0uYsbWpu9XDqOvvOpcqrF+4K904dkDeHpqqSwJ+LyH8c+LN6GE5odZEJFL9AwPnRmXNK34vywyOv0SOELRqqtTmRxIaiFUeOdCpvXjYSIIH0CQQ+4MVJEDx1KV9IfxPwThLwK4EonXbqAJ+WidZ3IwLZjJysRJA63p0Idi9ZVqr+GQEvAt0bppxTFmP//ukp2f3SR/I//7ZC+d/iJJWNBEggfAQCG/DilwMCXTQkpXV1dYVvdTgjEiABRQAJqPiZ37NnTyg1+VGWcNjZ4nBSmPbFWZMmicE9YdnNC2XxgpiqjtbfeFJWlORJbm6WCnLxZ0EsR17dfpQBr50F4b0k4GMCgQt4IV9AUlpFRYXS6VK+4OPdxaGRgEEC+uce9lxh0ueHdV4Gl37crhDIwj8XutrJGmy9UEDi/ofq1KUo4Yv/R0OVNBaGmIwg/50Egk0gUAEvDOqRlKa9Oum+EOzNx9GTQKoEdGndsFgNakcKeuymuhPsXY/qaSgX/OmRDhXsTlbu197T/nI3dMBIcIMTxEgP37GegZLESJ5DMD5e6WJTY2M/JBB2AoEIeLV8Aae7ONWlfCHs25LzI4HxCYSlSAU8dvGZBo9dfnk3s+N1YhmS02Aj1v7UhdPcke3pJ2uk5fhn8sKL9a66HmB8c+6pku43DlsKeH/+3BqJxwfk0Sd+w4ITZrYIe4kwAV8HvMnyBZzoMGs5wjuVUyeBJAK6SAX+CrreIDWMfeXKleqLOwts2F85Xd0MhR9QIhgNZX9RIOLPm/baf4AHPeiAHPri48e7J3Vo+FpViXz3riU8CfZgrfjI4BDwbcAL+QKS0rTxOk9AgrOpOFIScItA0IpURMl1wo09oCUCeNbZP55WZX3RYC8GT92gNuiNUdXNimMErNOgRS4pmSnbth/hSXBQF53jdpyA7wJe/EJARnZeXp5yX2hvb3ccAh9AAiQQXAL6y7Hfi1TQY9f8HstZVKQkAij6gOQ1lAVG0YiePU2WJAPmR+Ruj9D3QueLhmS8js64+m84TuDUd1fd712VbLg7ez6NBFIj4KuAF6c1cF+Ap259fX1qM+HVJEACkSWgg0m/FqnQHrthSbbzy0ZDwYdLb1ssQ/EBVSoYbg1ICItKw0kwWrxvQAW3aPOKZ8rXritRSXnQ/kID/J27KmXzLz+ZVBoRFW6cZzQJ+CLg1ZnXnZ2dTOCI5j7krEnANgEtF9AyKNsdGuogKCfQhqbrejc45YXjAf6Evy5OeKPcHnt4hRTEcuWFl+qVxzAqxn3320uY+BblTcG5KwKeBryUL3AXkgAJmCYASVRhYaFA4uC1X68uKBE272DTaxb2/lARzq1AHFIGaHpfePEA9bxh31icX0oEPAt4IV8oKytLeOqmNGpeTAIkQAITEPBDMYegJdRxQzlDAJILSC9af/jahEEvgmI0BMaoIDfQ2q2S7+w0SB6Q+IYEON3mlcyUjo4+KSjIUdZsbCQQFQKuB7yQL8B9oaenR1nyeH0CE5WF5jxJIGoEoJtFoZoDBw64XpEx7KWQo7aX7Mx39p1LZXpZgZx4ZOeE3RR8r0qmFeer6xAko9kJeBHYPvbw9fKLLZ8k9L1wdHhm0+rEOO6+Z7udqfFeEggUAdcCXu2bGYvFVPEIui8Eap9wsCQQSAJeFKmAxy5sFFFQgo0ErBJAoYxpxbNsBbkjn4WgF6e4+POOddcoTa/Ieens7JOcnCxLtmdWx8/rSMDvBFwJePF6sbKyku4Lft8NHB8JhJBAcpEKJ6ua4Tm1tbXS3NxMl5kQ7iOnp1T89C3yeeNJ6Xh+n9FHwaLs6SdXqT7fqjumAmBYmX10sF0OqACYjQSiQcDRgFfLF3DagVNdyheisak4SxLwIwGdN+BEApnfbdH8uB4c03ACOOGFn3B/Y0fiH7KK85WW1067seYK+da6a+Rnz/5OneqiIhvaq9uPyLbXj6r//s63l8jC8pjy8mUjgbAScCTgxUmHzpSm72RYtw7nRQLBIwCLMLxtMlnURnvsQivM8ufB2xN+G7EOcpHEVvzjW6T7jUPSveOwrWFC0rD25vJEH5u3fDIskQ3ODrm5WbKr7pit5/BmEvAzAeMBL2x4kJSmDeBZEtjPy8+xkUD0CJg8jdUe4n6v8ha9VfZ2xtllBZJ/09XS8dy+lOzI8r9xlbpPB7lwd4gfPCHnui5UULPTnn6yRt5973jiVNdOX7yXBIJIwFjAi1MOBLpoOD3p6uoKIg+OmQRIIAIE8BYKyWX4nIJbTDpNe+wy2E2HXrjvgTzh0m8ulrandqcUrELHi/LIqBang9yxPHzh6IBiG6gsZ6ehKAX0vJu3NNjphveSQCAI2A548YtDa+Og021paQnExDlIEiABEki3SAU9drl3nCAwVnBbtHG1nG3tltNbD8pgZ1xwTdHGWlVKGbZlSHRLV+d7x7oKqa4qkfX3TmyZ5sRc2ScJuE3AVsALPRx8LhsbG1VWMuULbi8fn0cCJGCXgC5SYfWkVgfJSH7jZ55d+rx/MgKQNWTGZqjiFTj9RcA72HUh8M2cPUMFvjgRtnvaO9k4+O8kEHQCaQW8lC8Efdk5fhIggWQCOvFssiTb6upqdRs9drl/3CSQGctVp7pD8QEV4KLB0UG3vo/bjPr3ujk3PosE3CKQUsAL+YI+DcEvBmYku7VMfA4JkIDTBJDMVlNTM6aPrvbYbWtrS1vz6/T42X+4CeigV89SJ7YlV2gzRWBe8UxZu6ZcXnixXuJ9A6a6ZT8k4CkBywGvli/AVB1JHnyV5+m68eEkQAIOEUAymz7FxefcRIGwQ0NgtyQwJgGUKb5kWan6t563mxKnumNpf+0ghE0Z/Hrvf2j3MPsyO33yXhLwmoDlgHft2rVGvSu9njifTwIkQALjEUhOxEWeAj12uVe8IDAykMVpbu7iIvnTpr3S33jSiyHxmSQQWAKWA97AzpADJwESIIE0CCDoRZEKBLtIymUjATcJTJ2dK198vFa5MHT+nws2ZShKUfjgKiPFKEbOBY4NaLQoc3OV+Sw3CTDgdZM2n0UCJBAIApBwwVccuQr4UzvRBGLwHGQoCOB0d9Zti5WEIdmFAW4NVqzIEBxPL5ujpA8TtdycLMnNzZTHHr5ePqpvlxde4pe7UGwgTmIUAcsBL34B0GOXO4gESCDsBHRiLmzHent7BQlrcGfAf6dbpCLszDg//xG49LZFkndDmbT+8DXJKp6lXB3GqtiGCmzx+IAqLfyLLQ1yoL7d8mQQLC8sj6lAmY0E/E7AcsB7++23i/4F4PdJcXwkQAIkkA4BXVBiLI9dFptIhyjv8ZIATnlRlGLeM99Up8J/3rR31HDW3rxA4n2DsqvuWMpDxb23rimX+x+qk45O++WPUx4AbyCBFAhYDnhx6lFaWqqCXjYSIAESCBsBnOLiNBceu+O50KRapCJsjDif4BHQzg5//Kc3UypzPN5MyxfE5MtL5iqtb0EsR+aV5EtOTpb6722vHw0eII44MgQsB7wgArue9vZ2OXToUGQAcaIkQALhJoAgF59tkCxYKSihi1Q0NDTwszDcWyMUs9OV2lCG2E5DQPv0k6sS8of1G3YmPHp/8P2vyLySmeqkl40E/EogpYAXvxi0tKGrq8uvc+K4SIAESMASgXQ9dtO9z9KgeBEJ2CSAIHewMy59H5+w2dNfbode946/rZBdu48pb14WpDCGlh25RCClgBdjQvIarHq2bdvm0hD5GBIgARIwTwBBa21trdg5qf3qV7+qClNMJIMwP3L2SAITEyh++hYZ6jsrJx7ZSVQkQAIXCaQc8OI+fMijMWOZ+4gESCCIBCBLQLD7zjvv2Haf0UUqmNQbxJ0QzjHnf+MqyV4wZ8wktXDOmLMigckJpBXwQtqAymv4ZQFNLxsJkAAJBIWA9titq6sTU9KsZN9e2jcGZSeEa5woVIGiFKe2HpQz+5vDNTnOhgQMEEgr4MVzdeIGpA3jZTQbGB+7IAESIAFjBObPn68kWU6cxmqJBItUGFsudpQCARSqKLinSnr2NFnS7uYsKpLMWK6lIhYpDIOXkoBvCaQd8GJGeJWHwHfPnj2+nSAHRgIkQAL68wrWijjZhSODE00XqUDf/Fx0gjD7NEEgu2yOoDDFtOJZqruW9VtNdMs+SMDXBGwFvJgZpA2oNc/XeL5eZw6OBCJNAHkH+su5G2+kWKQi0tvN15Mv2rhaMmMzEmOMHzwhHc/vc2zMsCz79GhnWoUtHBsUO44kAdsBr5Y2OPGKMJIrwkmTAAkYJQCPXQS5Vjx2TT7YCa2wyfGxr2gSuPS2xQLbMgS604rzpe/jNrHr0TsRSZQuRulhFKpgIwEvCdgOeDF4VmHzcgn5bBIggbEIQF4AJ4bm5mapr6/3BBKLVHiCnQ+dgAC0vsU/vkUFuT1vN5EVCUSGgJGAF7T0LxZWYYvM3uFEScC3BEx47JqanC5S0dbWRitHU1DZjxECThSoMDIwdkICDhAwFvDqXzCUNjiwSuySBEjAMgF9qorcgqYm/5xgaR0xpBVOJc1ZhsQLSUBEUKDi88aT42p4s4rzZaC1W2YsK5XM2bnSveMwuZFAYAkYC3hBgFXYArsPOHASCAUBHeya9Ng1CQbyr4qKCkds0UyOk32RAJwcLtuwQrrfOCRZxbOU3peV27gvgkzAaMALEEgQgZm7V5q5IC8Gx04CJJA+Ae2x69dgV89s7ty5cu2119LdJv2l5p0uEYCjw+eNHdL18ocC7e9Q34BLT+ZjSMA8AeMBr67C5vdfOuZRskcSIAGvCAStvC+LVHi1U/hcEiCBqBIwHvACJE4wli9fLqzCFtVtxXmTgHsEoI0tLCxUMgE3PHZNzSy5SAV0vUEauykG7IcESIAE3CLgSMCLweOXENoHH3zg1lz4HBIggYgRqK6uFgSOQa5qFrTT6YhtMU6XBEggJAQcC3jBh1XYQrJLOA0S8BkB7bEbFqsvnfD7zjvvqBwINhIgARIgAbMEHA14kTENf95f/epXfF1ndt3YGwlEloD2tfWyoIQT8P3kHezE/NgnCZAACXhJwNGAFxODDQ80vUF+5ejlAvHZJEACfyGgg0K/eeyaWiMWqTBFkv2QAAmQwHACjge8eByrsHHbkQAJ2CWgPXbff/99aWlpsdudr+/XiXhwu2GRCl8vFQcnIqjYBt/ejuf3kQcJ+JaAKwEvq7D5dv05MBIIBAFoXOH8AieGqGhcdZEKWjwGYotGepDw652SM01a738t0hw4eX8TcCXgBQJWYfP3RuDoSMCvBKJcnSxKp9p+3X8c18QEUH648MFV6qKW9VuJiwR8S8C1gBcEWIXNt/uAAyMBXxKAZVdpaWngPHZNwmSRCpM02ZcTBOY+WCN9B09I947DTnTPPknACAFXA15YCd1+++2Rei1pZJXYCQlEkID22GVRhguLjwMDNPKI4A+Dj6eMksNFG2vl1NaDcmZ/s6WRTp2dKzNXzpfe/c2Su6hIet5uYtliS+R4kR0Crga8GCilDXaWi/eSQPgJ6ApkqDyG4I7tLwRYpIK7IQwEZiwrldidS1WAjP8++dw+6fv4hEp+QwDNk+IwrLL/5uB6wAsErMLmv43AEZGAHwjoghJh89g1yRaHBtdee62gSEV7e7vJrtkXCbhGIDOWK0PxAZl122K5ZFmptD21W+Z8r0rOtnan7PaQm5MlC8tj8lE9fx5cW8AAPsiTgBe/1FCFjR/YAdwxHDIJOESAhResg6Wu1zorXulPAjjJnX3nUsldXKQGGD94QhAEZ86ekbLbw9qbF8ita8rl0Sd+Iy3HP/PnhDkqzwl4EvBi1jr7eNu2bazC5vk24ABIwFsCuiojvgSH3WPXFGkcHOhE4A8++MBUt+yHBBwnAA3vZRtWSGZshnoWTnq7dxySs62nRSRD+htPpjSGgliOzCvJ5wlvStSid7FnAS9QQ4+GX3Sswha9jccZk4AmoF/R0282vT3BIhXpceNd3hHAyS5kDAhw+xs7ZCh+lrpd75YjMk/2NOAFZUgbUCaUpzqR2XOcKAkkCMyfP18qKyuVcwsriqW/MVikIn12vNNdApAyFNxTpR4KKzM4NLCRgBsEPA94WYXNjWXmM0jAfwS0xy7L55pZGy0Ta2hokEOHDpnplL2QgGECl962SPJuKJMTj7wpg51xw72zOxIYn4DnAS+GhtMJbS7PxSIBEgg/Af0aHie7sB9jM0MABwg1NTVClwszPNmLeQLQ705fMMeyZ6/5EbDHqBLwRcAL+Ei+gMUOTyaiuhU576gQwM86PXadXW0W7XCWL3snARIIHgHfBLyswha8zcMRk0AqBLTHbltbm9BVIBVy6V3LIhXpceNdJEAC4STgm4AXeFmFLZybjLMiAfrGerMHtAPG+++/z8Rgb5aATyUBEvAJAV8FvFragGxtngD5ZIdwGCRgk4BOpoIbS1MTM7Jt4kz5dn7ZSBkZbyABEgghAd8FvKzCFsJdxilFloAOdumx6+0WwOcqdL1o9D33di34dBIgAW8I+C7gBYa5c+fK8uXLhVXYvNkUfCoJmCCgPXYZ7JqgaaYPWsGZ4cheSIAEgkfAlwEvMMK2CI3ShuBtKo6YBHQhBBaU8N9eYJEK/61JlEaUXVYg08vmsLJalBbdJ3P1bcDrEz4cBgmQAAmQAAmQAAmQQMAJMOAN+AJy+CRAAiRAAiRAAiRAAhMTYMDLHUICJEACJEACJEACJBBqAgx4Q728nBwJkAAJkAAJkAAJkAADXu4BEiABEiABEiABEiCBUBNgwBvq5eXkSIAESIAESIAESIAEGPByD5AACZAACZAACZAACYSaAAPeUC8vJ0cCJEACJEACJEACJMCAl3uABEiABEiABEiABEgg1AQY8IZ6eTk5EiABEiABEiABEiCB/w9TaEi/3O7VVQAAAABJRU5ErkJggg=="
},
"metadata": {},
"output_type": "display_data"
}
],
"source": [
"#| caption: Two successive LIDAR scans from an autonomous vehicle.\n",
"#| label: fig:lidar_scan_real_2\n",
"real_scans[1] = driving.read_lidar_points('Figures6/lidar/PC_315967795520065000.ply')\n",
"driving.visualize_clouds([real_scans[0],real_scans[1]], show_grid_lines=True)\n"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"Finally, let us look at scans that are taken a bit further apart, in this case there are 8 scans that we skipped:"
]
},
{
"cell_type": "code",
"execution_count": 16,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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"
},
"metadata": {},
"output_type": "display_data"
}
],
"source": [
"#| caption: Two LIDAR scans from an autonomous vehicle that are eight frames apart.\n",
"#| label: fig:lidar_scan_real_8\n",
"real_scans[9] = driving.read_lidar_points('Figures6/lidar/PC_315967795919523000.ply')\n",
"driving.visualize_clouds([real_scans[0],real_scans[9]], show_grid_lines=True)\n"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"By inspecting (you can do this interactively using the [gtbook website](https://gtbook.github.io/gtbook/driving.html)) you can see that the car is *still* turning, but as the two scans are further apart the \"mis-alginment\" is more pronounced."
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"## Creating 3D Maps\n",
"\n",
"> Point clouds can be used to represent the 3D world.\n",
"\n",
"If we know the exact pose at which a LIDAR scan was taken, we can transform the points in the scan into absolute coordinates, and create an extended **point cloud map** of the environment. In math, suppose we *know* that a scan was taken at $T^w_b$, then we can transform all LIDAR points $P^b$, which are given in body coordinates, to world coordinates:\n",
"\n",
"$$\n",
"P^w = \\phi(T^w_b, P^b)\n",
"$$\n",
"\n",
"where $\\phi$ the the action of $SE(3)$ on points in $\\mathbb{R}^3$. Earlier in this chapter we saw this can be done by matrix multiplication, but GTSAM actually implements $\\phi$ directly as `Pose3::transformFrom`. This method can be applied to a single `Point3` (just a $3\\times 1$ vector, really) or on many points simultaneously, by passing in a $3\\times N$ matrix:\n"
]
},
{
"cell_type": "code",
"execution_count": 17,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"(3, 86651)\n"
]
}
],
"source": [
"scan_in_world = wTb3.transformFrom(real_scans[0])\n",
"print(scan_in_world.shape)\n"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"We will use this capability in the next section to produce large scale sparse point cloud maps of the environment around an autonomous vehicle."
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"## GTSAM 101\n",
"\n",
"> A deeper dive in the GTSAM concepts used above.\n",
"\n",
"### 2D and 3D Points\n",
"\n",
"In GTSAM `Point2` and `Point3` are simply functions that return 2D and 3D numpy vectors, respectively:"
]
},
{
"cell_type": "code",
"execution_count": 18,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
" [3. 4.]\n",
" [5. 6. 7.]\n"
]
}
],
"source": [
"p = gtsam.Point2(3,4)\n",
"P = gtsam.Point3(5,6,7)\n",
"print(type(p), p)\n",
"print(type(P), P)\n"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"### 2D and 3D Rotations\n",
"\n",
"2D and 3D rotations are represented internally by $2 \\times 2$ matrices and $3 \\times 3$ matrices, respectively, but these are wrapped into the classes `Rot2` and `Rot3`. We can print them, and get the rotation matrix via the `matrix()` method:"
]
},
{
"cell_type": "code",
"execution_count": 19,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"theta: 0.349066\n",
" [[ 0.93969262 -0.34202014]\n",
" [ 0.34202014 0.93969262]]\n"
]
}
],
"source": [
"R1 = gtsam.Rot2(20 * math.pi / 180) # 20 degrees rotation\n",
"print(R1, R1.matrix())\n"
]
},
{
"cell_type": "code",
"execution_count": 20,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"R: [\n",
"\t1, 0, 0;\n",
"\t0, 1, 0;\n",
"\t0, 0, 1\n",
"]\n",
" [[1. 0. 0.]\n",
" [0. 1. 0.]\n",
" [0. 0. 1.]]\n"
]
}
],
"source": [
"R2 = gtsam.Rot3()\n",
"print(R2, R2.matrix())\n"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"While there are various methods to create 3D rotation matrices (use help!), above we only use the named constructor `Yaw` , which is a rotation around the Z-axis. Below is an example, which you can compare with the 2D rotation example above..."
]
},
{
"cell_type": "code",
"execution_count": 21,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"R: [\n",
"\t0.939693, -0.34202, 0;\n",
"\t0.34202, 0.939693, 0;\n",
"\t0, 0, 1\n",
"]\n",
" [[ 0.93969262 -0.34202014 0. ]\n",
" [ 0.34202014 0.93969262 0. ]\n",
" [ 0. 0. 1. ]]\n"
]
}
],
"source": [
"R3 = gtsam.Rot3.Yaw(20 * math.pi / 180) # 20 degrees rotation around Z\n",
"print(R3, R3.matrix())\n"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"We will look at 3D rotations in much more detail in Chapter 7, when we look at drones."
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"### Reading and Visualizing LIDAR clouds\n",
"\n",
"The utility functions `read_lidar_points` and `visualize_clouds` are not part of GTSAM, but are part of the gtbook library that accompanies this book. On the [gtbook website](https://gtbook.github.io/gtbook/driving.html) you can find much more detailed documentation as well as the source code, but `help` is very comprehensive for those functions:"
]
},
{
"cell_type": "code",
"execution_count": 22,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"Help on function read_lidar_points in module gtbook.driving:\n",
"\n",
"read_lidar_points(filename: str)\n",
" Read 3D points in LIDAR scan stored as a binary_little_endian .ply file.\n",
" \n",
" Parameters:\n",
" filename: of ply file\n",
" \n",
" Returns:\n",
" A tuple (3,N) numpy array.\n",
"\n"
]
}
],
"source": [
"help(driving.read_lidar_points)\n"
]
},
{
"cell_type": "code",
"execution_count": 23,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"Help on function visualize_clouds in module gtbook.driving:\n",
"\n",
"visualize_clouds(clouds: list, show_grid_lines: bool = False, cloud_colors=None, marker_size: int = 1, do_subsampling: bool = True)\n",
" Visualizes cloud(s) in a iterative 3D plot.\n",
" Adapted from code by 3630 TAs Binit Shah and Jerred Chen\n",
" \n",
" Due to browser limitations, rendering above 5 frames requires\n",
" subsampling of the point clouds, which is done automatically.\n",
" \n",
" Example input of arg:\n",
" clouds = [clouda, cloudb, cloudc]\n",
" where each cloud is a numpy array of shape (3, num_points).\n",
" cloud[0] are the x coordinates, cloud[1] is y, and cloud[2] is z.\n",
" \n",
" Args:\n",
" clouds (list): ordered series of point clouds\n",
" show_grid_lines (bool): plots gridlines\n",
" cloud_colors (list): colors for each cloud in the visualization\n",
" marker_size (int): size of each marker\n",
" do_subsampling (bool): whether or not subsampling occurs\n",
"\n"
]
}
],
"source": [
"help(driving.visualize_clouds)\n"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"While the visualization code is statically rendered in the book, when you open the Colab things should be rendered as interactive plotly scatter plots. Try it!"
]
}
],
"metadata": {
"colab": {
"collapsed_sections": [],
"include_colab_link": true,
"name": "S63_driving_sensing.ipynb",
"provenance": []
},
"kernelspec": {
"display_name": "Python 3.8.12 ('gtbook')",
"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.9.18"
},
"latex_metadata": {
"affiliation": "Georgia Institute of Technology",
"author": "Frank Dellaert and Seth Hutchinson",
"title": "Introduction to Robotics"
},
"vscode": {
"interpreter": {
"hash": "9f7376ced4243bb13dfcffa8a3ba834e0602aa8334cd3a1d8ba8d285f4628083"
}
}
},
"nbformat": 4,
"nbformat_minor": 2
}