diff --git a/.github/FUNDING.yml b/.github/FUNDING.yml new file mode 100644 index 00000000..80f4984c --- /dev/null +++ b/.github/FUNDING.yml @@ -0,0 +1,3 @@ +# These are supported funding model platforms +patreon: myenigma +custom: https://www.paypal.me/myenigmapay/ diff --git a/.gitignore b/.gitignore index e04b28e1..62e48c67 100644 --- a/.gitignore +++ b/.gitignore @@ -1,5 +1,6 @@ *.csv *.gif +*.g2o # Byte-compiled / optimized / DLL files __pycache__/ diff --git a/Localization/extended_kalman_filter/extended_kalman_filter.py b/Localization/extended_kalman_filter/extended_kalman_filter.py index 11760f03..3f0589b8 100644 --- a/Localization/extended_kalman_filter/extended_kalman_filter.py +++ b/Localization/extended_kalman_filter/extended_kalman_filter.py @@ -6,17 +6,22 @@ author: Atsushi Sakai (@Atsushi_twi) """ -import numpy as np import math +import numpy as np import matplotlib.pyplot as plt -# Estimation parameter of EKF -Q = np.diag([0.1, 0.1, np.deg2rad(1.0), 1.0])**2 # predict state covariance +# Covariance for EKF simulation +Q = np.diag([ + 0.1, # variance of location on x-axis + 0.1, # variance of location on y-axis + np.deg2rad(1.0), # variance of yaw angle + 1.0 # variance of velocity + ])**2 # predict state covariance R = np.diag([1.0, 1.0])**2 # Observation x,y position covariance # Simulation parameter -Qsim = np.diag([1.0, np.deg2rad(30.0)])**2 -Rsim = np.diag([0.5, 0.5])**2 +INPUT_NOISE = np.diag([1.0, np.deg2rad(30.0)])**2 +GPS_NOISE = np.diag([0.5, 0.5])**2 DT = 0.1 # time tick [s] SIM_TIME = 50.0 # simulation time [s] @@ -27,7 +32,7 @@ show_animation = True def calc_input(): v = 1.0 # [m/s] yawrate = 0.1 # [rad/s] - u = np.array([[v, yawrate]]).T + u = np.array([[v], [yawrate]]) return u @@ -36,14 +41,10 @@ def observation(xTrue, xd, u): xTrue = motion_model(xTrue, u) # add noise to gps x-y - zx = xTrue[0, 0] + np.random.randn() * Rsim[0, 0] - zy = xTrue[1, 0] + np.random.randn() * Rsim[1, 1] - z = np.array([[zx, zy]]).T + z = observation_model(xTrue) + GPS_NOISE @ np.random.randn(2, 1) # add noise to input - ud1 = u[0, 0] + np.random.randn() * Qsim[0, 0] - ud2 = u[1, 0] + np.random.randn() * Qsim[1, 1] - ud = np.array([[ud1, ud2]]).T + ud = u + INPUT_NOISE @ np.random.randn(2, 1) xd = motion_model(xd, ud) @@ -62,19 +63,18 @@ def motion_model(x, u): [0.0, DT], [1.0, 0.0]]) - x = F@x + B@u + x = F @ x + B @ u return x def observation_model(x): - # Observation Model H = np.array([ [1, 0, 0, 0], [0, 1, 0, 0] ]) - z = H@x + z = H @ x return z diff --git a/Localization/unscented_kalman_filter/unscented_kalman_filter.py b/Localization/unscented_kalman_filter/unscented_kalman_filter.py index cb59a57e..78b44754 100644 --- a/Localization/unscented_kalman_filter/unscented_kalman_filter.py +++ b/Localization/unscented_kalman_filter/unscented_kalman_filter.py @@ -11,13 +11,18 @@ import scipy.linalg import math import matplotlib.pyplot as plt -# Estimation parameter of UKF -Q = np.diag([0.1, 0.1, np.deg2rad(1.0), 1.0])**2 -R = np.diag([1.0, np.deg2rad(40.0)])**2 +# Covariance for UKF simulation +Q = np.diag([ + 0.1, # variance of location on x-axis + 0.1, # variance of location on y-axis + np.deg2rad(1.0), # variance of yaw angle + 1.0 # variance of velocity + ])**2 # predict state covariance +R = np.diag([1.0, 1.0])**2 # Observation x,y position covariance # Simulation parameter -Qsim = np.diag([0.5, 0.5])**2 -Rsim = np.diag([1.0, np.deg2rad(30.0)])**2 +INPUT_NOISE = np.diag([1.0, np.deg2rad(30.0)])**2 +GPS_NOISE = np.diag([0.5, 0.5])**2 DT = 0.1 # time tick [s] SIM_TIME = 50.0 # simulation time [s] @@ -42,14 +47,10 @@ def observation(xTrue, xd, u): xTrue = motion_model(xTrue, u) # add noise to gps x-y - zx = xTrue[0, 0] + np.random.randn() * Qsim[0, 0] - zy = xTrue[1, 0] + np.random.randn() * Qsim[1, 1] - z = np.array([[zx, zy]]).T + z = observation_model(xTrue) + GPS_NOISE @ np.random.randn(2, 1) # add noise to input - ud1 = u[0] + np.random.randn() * Rsim[0, 0] - ud2 = u[1] + np.random.randn() * Rsim[1, 1] - ud = np.array([ud1, ud2]) + ud = u + INPUT_NOISE @ np.random.randn(2, 1) xd = motion_model(xd, ud) @@ -100,7 +101,9 @@ def generate_sigma_points(xEst, PEst, gamma): def predict_sigma_motion(sigma, u): - # Sigma Points prediction with motion model + """ + Sigma Points prediction with motion model + """ for i in range(sigma.shape[1]): sigma[:, i:i + 1] = motion_model(sigma[:, i:i + 1], u) @@ -108,7 +111,9 @@ def predict_sigma_motion(sigma, u): def predict_sigma_observation(sigma): - # Sigma Points prediction with observation model + """ + Sigma Points prediction with observation model + """ for i in range(sigma.shape[1]): sigma[0:2, i] = observation_model(sigma[:, i]) diff --git a/Mapping/kmeans_clustering/kmeans_clustering.py b/Mapping/kmeans_clustering/kmeans_clustering.py index 984b5565..8edfa11e 100644 --- a/Mapping/kmeans_clustering/kmeans_clustering.py +++ b/Mapping/kmeans_clustering/kmeans_clustering.py @@ -73,7 +73,7 @@ def update_clusters(clusters): mind = min(dlist) min_id = dlist.index(mind) clusters.labels[ip] = min_id - cost += min_id + cost += mind return clusters, cost diff --git a/Mapping/lidar_to_grid_map/animation.gif b/Mapping/lidar_to_grid_map/animation.gif new file mode 100644 index 00000000..210ff581 Binary files /dev/null and b/Mapping/lidar_to_grid_map/animation.gif differ diff --git a/Mapping/lidar_to_grid_map/grid_map_example.png b/Mapping/lidar_to_grid_map/grid_map_example.png new file mode 100644 index 00000000..7a91f7c9 Binary files /dev/null and b/Mapping/lidar_to_grid_map/grid_map_example.png differ diff --git a/Mapping/lidar_to_grid_map/lidar01.csv b/Mapping/lidar_to_grid_map/lidar01.csv new file mode 100644 index 00000000..1f6b3f5c --- /dev/null +++ b/Mapping/lidar_to_grid_map/lidar01.csv @@ -0,0 +1,154 @@ +0.008450416037156572,0.5335 +0.046902201120156306,0.5345 +0.08508127850753233,0.537 +0.1979822644959155,0.2605 +0.21189035697274505,0.2625 +0.2587960806200922,0.26475 +0.3043382657893199,0.2675 +0.34660795861105775,0.27075 +0.43632879047139106,0.59 +0.4739624524675188,0.60025 +0.5137777760286397,0.611 +0.5492297764597742,0.6265 +0.5895905154121426,0.64 +0.6253152235389017,0.6565 +0.6645851317087743,0.676 +0.6997644244442851,0.6975 +0.7785769484796541,0.3345 +0.7772134100015329,0.74575 +0.8652979956881222,0.3315 +0.8996591653367609,0.31775 +0.9397471965935056,0.31275 +0.9847439663714841,0.31125 +1.0283771976713423,0.31325 +1.0641019057981014,0.31975 +1.1009174447073562,0.3335 +1.2012738766970301,0.92275 +1.2397256617800307,0.95325 +1.2779047391674068,0.9865 +1.316629231946031,1.01775 +1.3561718478115274,1.011 +1.3948963405901518,1.0055 +1.4330754179775278,1.00225 +1.4731634492342724,0.99975 +1.5113425266216485,0.9975 +1.5517032655740168,1.001 +1.5896096352657691,1.00275 +1.6288795434356418,1.008 +1.6684221593011381,1.0135 +1.7066012366885142,1.022 +1.7453257294671385,1.02875 +1.7862318838107551,0.9935 +1.8257744996762515,1.0025 +1.8661352386286207,0.96075 +1.9045870237116205,0.92125 +1.9465840088377355,0.8855 +1.986944747790103,0.85725 +2.025669240568728,0.832 +2.065757271825472,0.80675 +2.1066634261690886,0.78875 +2.1464787497302105,0.7705 +2.1865667809869542,0.75625 +2.2261093968524506,0.74475 +2.2683790896741876,0.68275 +2.3090125363221823,0.6375 +2.3510095214482956,0.59925 +2.3916429680962885,0.5665 +2.4330945378311526,0.538 +2.4783640153047557,0.50825 +2.5203610004308707,0.4875 +2.562903400948233,0.46825 +2.599173524466238,0.45 +2.642806755766097,0.4355 +2.685076448587836,0.42275 +2.722437402888339,0.4125 +2.766888757275069,0.40125 +2.8007045115324587,0.39525 +2.841883373571701,0.385 +2.8819714048284446,0.3805 +2.922332143780814,0.38575 +2.9637837135156797,0.38425 +3.0005992524249336,0.36575 +3.0401418682904318,0.3765 +3.079957191851552,0.3915 +3.115409192282687,0.408 +3.154679100452558,0.4265 +3.184949654666836,0.447 +3.2242195628367085,0.4715 +3.2574899017028507,0.49875 +3.2959416867858504,0.52875 +3.3292120256519926,0.564 +3.3665729799524957,0.6055 +3.4031158111661277,0.6515 +3.438022396206014,0.70675 +3.4756560582021407,0.771 +3.513562427893893,0.77075 +3.5522869206725183,0.7785 +3.621827383056667,0.79575 +3.65918833735717,0.8045 +3.697367414744546,0.81725 +3.7377281536969154,0.83325 +3.775634523388667,0.8415 +3.8135408930804187,0.85575 +3.8522653858590425,0.87325 +3.8898990478551703,0.88725 +3.9299870791119154,0.906 +3.9665299103255465,0.9265 +4.006072526191043,0.94575 +4.043978895882795,0.97175 +4.081885265574547,1.02075 +4.1206097583531704,1.046 +4.1587888357405465,1.07025 +4.196422497736674,1.097 +4.234874282819675,1.12575 +4.286688744988257,0.73475 +4.324322406984384,0.72225 +4.364410438241129,0.731 +4.405862007975994,0.7405 +4.44267754688525,0.749 +4.484129116620115,0.76025 +4.522853609398739,0.76825 +4.560759979090491,0.77125 +4.5989390564778665,0.77725 +4.640117918517108,0.782 +4.679115118991357,0.78425 +4.717294196378733,0.789 +4.757109519939853,0.78825 +4.796652135805349,0.7855 +4.8337403824102285,0.786 +4.871646752101981,0.78275 +4.9109166602718535,0.7785 +4.950186568441726,0.7635 +4.990274599698471,0.74725 +5.028180969390222,0.737 +5.0677235852557185,0.72575 +5.109720570381833,0.71525 +5.149263186247329,0.70625 +5.1863514328522085,0.69975 +5.230530079543315,0.693 +5.269799987713188,0.68925 +5.307979065100563,0.68425 +5.347248973270435,0.68275 +5.386518881440308,0.68075 +5.426606912697053,0.68175 +5.465604113171301,0.67825 +5.502419652080556,0.6835 +5.543871221815422,0.6885 +5.580959468420302,0.67925 +5.624319992024535,0.6555 +5.660044700151294,0.639 +5.700950854494911,0.623 +5.740220762664784,0.6075 +5.783581286269018,0.59475 +5.820124117482649,0.58475 +5.861848394913139,0.57325 +5.899209349213642,0.565 +5.938751965079138,0.55525 +5.9782945809446355,0.55175 +6.017564489114507,0.546 +6.059288766544997,0.5405 +6.097467843932373,0.53825 +6.139464829058487,0.534 +6.176825783358991,0.5325 +6.215822983833238,0.53125 +6.252911230438118,0.53075 \ No newline at end of file diff --git a/Mapping/lidar_to_grid_map/lidar_to_grid_map.py b/Mapping/lidar_to_grid_map/lidar_to_grid_map.py new file mode 100644 index 00000000..60bf4db6 --- /dev/null +++ b/Mapping/lidar_to_grid_map/lidar_to_grid_map.py @@ -0,0 +1,220 @@ +""" + +LIDAR to 2D grid map example + +author: Erno Horvath, Csaba Hajdu based on Atsushi Sakai's scripts (@Atsushi_twi) + +""" + +import math +import numpy as np +import matplotlib.pyplot as plt +from collections import deque + +EXTEND_AREA = 1.0 + + +def file_read(f): + """ + Reading LIDAR laser beams (angles and corresponding distance data) + """ + measures = [line.split(",") for line in open(f)] + angles = [] + distances = [] + for measure in measures: + angles.append(float(measure[0])) + distances.append(float(measure[1])) + angles = np.array(angles) + distances = np.array(distances) + return angles, distances + + +def bresenham(start, end): + """ + Implementation of Bresenham's line drawing algorithm + See en.wikipedia.org/wiki/Bresenham's_line_algorithm + Bresenham's Line Algorithm + Produces a np.array from start and end (original from roguebasin.com) + >>> points1 = bresenham((4, 4), (6, 10)) + >>> print(points1) + np.array([[4,4], [4,5], [5,6], [5,7], [5,8], [6,9], [6,10]]) + """ + # setup initial conditions + x1, y1 = start + x2, y2 = end + dx = x2 - x1 + dy = y2 - y1 + is_steep = abs(dy) > abs(dx) # determine how steep the line is + if is_steep: # rotate line + x1, y1 = y1, x1 + x2, y2 = y2, x2 + swapped = False # swap start and end points if necessary and store swap state + if x1 > x2: + x1, x2 = x2, x1 + y1, y2 = y2, y1 + swapped = True + dx = x2 - x1 # recalculate differentials + dy = y2 - y1 # recalculate differentials + error = int(dx / 2.0) # calculate error + ystep = 1 if y1 < y2 else -1 + # iterate over bounding box generating points between start and end + y = y1 + points = [] + for x in range(x1, x2 + 1): + coord = [y, x] if is_steep else (x, y) + points.append(coord) + error -= abs(dy) + if error < 0: + y += ystep + error += dx + if swapped: # reverse the list if the coordinates were swapped + points.reverse() + points = np.array(points) + return points + + +def calc_grid_map_config(ox, oy, xyreso): + """ + Calculates the size, and the maximum distances according to the the measurement center + """ + minx = round(min(ox) - EXTEND_AREA / 2.0) + miny = round(min(oy) - EXTEND_AREA / 2.0) + maxx = round(max(ox) + EXTEND_AREA / 2.0) + maxy = round(max(oy) + EXTEND_AREA / 2.0) + xw = int(round((maxx - minx) / xyreso)) + yw = int(round((maxy - miny) / xyreso)) + print("The grid map is ", xw, "x", yw, ".") + return minx, miny, maxx, maxy, xw, yw + + +def atan_zero_to_twopi(y, x): + angle = math.atan2(y, x) + if angle < 0.0: + angle += math.pi * 2.0 + return angle + + +def init_floodfill(cpoint, opoints, xypoints, mincoord, xyreso): + """ + cpoint: center point + opoints: detected obstacles points (x,y) + xypoints: (x,y) point pairs + """ + centix, centiy = cpoint + prev_ix, prev_iy = centix - 1, centiy + ox, oy = opoints + xw, yw = xypoints + minx, miny = mincoord + pmap = (np.ones((xw, yw))) * 0.5 + for (x, y) in zip(ox, oy): + ix = int(round((x - minx) / xyreso)) # x coordinate of the the occupied area + iy = int(round((y - miny) / xyreso)) # y coordinate of the the occupied area + free_area = bresenham((prev_ix, prev_iy), (ix, iy)) + for fa in free_area: + pmap[fa[0]][fa[1]] = 0 # free area 0.0 + prev_ix = ix + prev_iy = iy + return pmap + + +def flood_fill(cpoint, pmap): + """ + cpoint: starting point (x,y) of fill + pmap: occupancy map generated from Bresenham ray-tracing + """ + # Fill empty areas with queue method + sx, sy = pmap.shape + fringe = deque() + fringe.appendleft(cpoint) + while fringe: + n = fringe.pop() + nx, ny = n + # West + if nx > 0: + if pmap[nx - 1, ny] == 0.5: + pmap[nx - 1, ny] = 0.0 + fringe.appendleft((nx - 1, ny)) + # East + if nx < sx - 1: + if pmap[nx + 1, ny] == 0.5: + pmap[nx + 1, ny] = 0.0 + fringe.appendleft((nx + 1, ny)) + # North + if ny > 0: + if pmap[nx, ny - 1] == 0.5: + pmap[nx, ny - 1] = 0.0 + fringe.appendleft((nx, ny - 1)) + # South + if ny < sy - 1: + if pmap[nx, ny + 1] == 0.5: + pmap[nx, ny + 1] = 0.0 + fringe.appendleft((nx, ny + 1)) + + +def generate_ray_casting_grid_map(ox, oy, xyreso, breshen=True): + """ + The breshen boolean tells if it's computed with bresenham ray casting (True) or with flood fill (False) + """ + minx, miny, maxx, maxy, xw, yw = calc_grid_map_config(ox, oy, xyreso) + pmap = np.ones((xw, yw))/2 # default 0.5 -- [[0.5 for i in range(yw)] for i in range(xw)] + centix = int(round(-minx / xyreso)) # center x coordinate of the grid map + centiy = int(round(-miny / xyreso)) # center y coordinate of the grid map + # occupancy grid computed with bresenham ray casting + if breshen: + for (x, y) in zip(ox, oy): + ix = int(round((x - minx) / xyreso)) # x coordinate of the the occupied area + iy = int(round((y - miny) / xyreso)) # y coordinate of the the occupied area + laser_beams = bresenham((centix, centiy), (ix, iy)) # line form the lidar to the cooupied point + for laser_beam in laser_beams: + pmap[laser_beam[0]][laser_beam[1]] = 0.0 # free area 0.0 + pmap[ix][iy] = 1.0 # occupied area 1.0 + pmap[ix+1][iy] = 1.0 # extend the occupied area + pmap[ix][iy+1] = 1.0 # extend the occupied area + pmap[ix+1][iy+1] = 1.0 # extend the occupied area + # occupancy grid computed with with flood fill + else: + pmap = init_floodfill((centix, centiy), (ox, oy), (xw, yw), (minx, miny), xyreso) + flood_fill((centix, centiy), pmap) + pmap = np.array(pmap, dtype=np.float) + for (x, y) in zip(ox, oy): + ix = int(round((x - minx) / xyreso)) + iy = int(round((y - miny) / xyreso)) + pmap[ix][iy] = 1.0 # occupied area 1.0 + pmap[ix+1][iy] = 1.0 # extend the occupied area + pmap[ix][iy+1] = 1.0 # extend the occupied area + pmap[ix+1][iy+1] = 1.0 # extend the occupied area + return pmap, minx, maxx, miny, maxy, xyreso + + +def main(): + """ + Example usage + """ + print(__file__, "start") + xyreso = 0.02 # x-y grid resolution + ang, dist = file_read("lidar01.csv") + ox = np.sin(ang) * dist + oy = np.cos(ang) * dist + pmap, minx, maxx, miny, maxy, xyreso = generate_ray_casting_grid_map(ox, oy, xyreso, True) + xyres = np.array(pmap).shape + plt.figure(1, figsize=(10,4)) + plt.subplot(122) + plt.imshow(pmap, cmap="PiYG_r") # cmap = "binary" "PiYG_r" "PiYG_r" "bone" "bone_r" "RdYlGn_r" + plt.clim(-0.4, 1.4) + plt.gca().set_xticks(np.arange(-.5, xyres[1], 1), minor=True) + plt.gca().set_yticks(np.arange(-.5, xyres[0], 1), minor=True) + plt.grid(True, which="minor", color="w", linewidth=0.6, alpha=0.5) + plt.colorbar() + plt.subplot(121) + plt.plot([oy, np.zeros(np.size(oy))], [ox, np.zeros(np.size(oy))], "ro-") + plt.axis("equal") + plt.plot(0.0, 0.0, "ob") + plt.gca().set_aspect("equal", "box") + bottom, top = plt.ylim() # return the current ylim + plt.ylim((top, bottom)) # rescale y axis, to match the grid orientation + plt.grid(True) + plt.show() + + +if __name__ == '__main__': + main() diff --git a/Mapping/lidar_to_grid_map/lidar_to_grid_map_tutorial.ipynb b/Mapping/lidar_to_grid_map/lidar_to_grid_map_tutorial.ipynb new file mode 100644 index 00000000..9e8a00f0 --- /dev/null +++ b/Mapping/lidar_to_grid_map/lidar_to_grid_map_tutorial.ipynb @@ -0,0 +1,318 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## LIDAR to 2D grid map example\n", + "\n", + "This simple tutorial shows how to read LIDAR (range) measurements from a file and convert it to occupancy grid.\n", + "\n", + "Occupancy grid maps (_Hans Moravec, A.E. Elfes: High resolution maps from wide angle sonar, Proc. IEEE Int. Conf. Robotics Autom. (1985)_) are a popular, probabilistic approach to represent the environment. The grid is basically discrete representation of the environment, which shows if a grid cell is occupied or not. Here the map is represented as a `numpy array`, and numbers close to 1 means the cell is occupied (_marked with red on the next image_), numbers close to 0 means they are free (_marked with green_). The grid has the ability to represent unknown (unobserved) areas, which are close to 0.5.\n", + "\n", + "![Example](grid_map_example.png)\n", + "\n", + "\n", + "In order to construct the grid map from the measurement we need to discretise the values. But, first let's need to `import` some necessary packages." + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [], + "source": [ + "import math\n", + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "from math import cos, sin, radians, pi" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "The measurement file contains the distances and the corresponding angles in a `csv` (comma separated values) format. Let's write the `file_read` method:" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [], + "source": [ + "def file_read(f):\n", + " \"\"\"\n", + " Reading LIDAR laser beams (angles and corresponding distance data)\n", + " \"\"\"\n", + " measures = [line.split(\",\") for line in open(f)]\n", + " angles = []\n", + " distances = []\n", + " for measure in measures:\n", + " angles.append(float(measure[0]))\n", + " distances.append(float(measure[1]))\n", + " angles = np.array(angles)\n", + " distances = np.array(distances)\n", + " return angles, distances" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "From the distances and the angles it is easy to determine the `x` and `y` coordinates with `sin` and `cos`. \n", + "In order to display it `matplotlib.pyplot` (`plt`) is used." + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAYYAAAJCCAYAAADEEWDaAAAABHNCSVQICAgIfAhkiAAAAAlwSFlzAAALEgAACxIB0t1+/AAAADl0RVh0U29mdHdhcmUAbWF0cGxvdGxpYiB2ZXJzaW9uIDMuMC4zLCBodHRwOi8vbWF0cGxvdGxpYi5vcmcvnQurowAAIABJREFUeJzsXXd4FcXXPptOhwQIvfeidJAmAtKlCChSBGkCIgiioNIE7Kg//ewdey+gIipcwAIiqPQq0qRDKIGQds/3x5vJnZ2d3ZsCScB5n+c+gZnZ3dnd2XPmdIuZycDAwMDAQCAktydgYGBgYJC3YBiDgYGBgYENhjEYGBgYGNhgGIOBgYGBgQ2GMRgYGBgY2GAYg4GBgYGBDYYxGBgYGBjYYBiDgYGBgYENhjEYGBgYGNgQltsTyAqKFy/OlSpVyu1pZBjnzp2jAgUK5PY0sgVzD3kD5h7yBi7Xe1i3bt1xZi4RbNxlyRgqVapEa9euze1pZBjLly+ndu3a5fY0sgVzD3kD5h7yBi7Xe7Asa29GxhlVkoGBgYGBDYYxGBgYGBjYYBiDgYGBgYENhjEYGBgYGNhgGIOBgYGBgQ2GMRgYGBgY2GAYg4GBgYGBDYYxGBgYGBjYYBiDgYGBgYENhjEYGBgYGNhgGIOBgYGBgQ2GMRgYGBgY2GAYg4GBgYGBDYYxGBgYGBjYYBiDgYGBgYENhjEYGBgYGNhgGIOBgYGBgQ2GMRgYGBgY2GAYg4GBgYGBDdliDJZl9bcsa7NlWX7Lspp4jOtiWdZ2y7J2WZY1TWqvbFnWb5Zl7bQs6yPLsiKyMx8DAwMDg+wjuxLDJiK6kYhWug2wLCuUiJ4noq5EVIeIbrEsq05a92NE9DQzVyeiOCIakc35XNl47z2iSpWIQkLw9733cntGBgYGVyCyxRiYeSszbw8yrBkR7WLm3cycREQfElEvy7IsImpPRJ+mjVtARL2zM58rGu+9RzR6NNHevUTM+Dt6tGEOBgYGFx05YWMoS0T7pf8fSGuLIaJTzJyitBvo8MADROfP29vOn0e7gYGBwUVEWLABlmX9SESlNF0PMPNXGbiGpWljj3a3eYwmotFERLGxsbR8+fIMXDpvID4+PtvzvXbfPv0D27ePVuTAs7gY95DbMPeQN2DuIe8jKGNg5o7ZvMYBIiov/b8cER0kouNEVNSyrLA0qUG0u83jFSJ6hYioSZMm3K5du2xOK+ewfPlyyvZ8K1SA+kiBVaFC9s+dAVyUe8hlmHvIGzD3kPeRE6qk34moepoHUgQRDSCihczMROQjon5p44YSUUYkkP8mHnqIKH9+e1tUFNoNDAwMLiKy667ax7KsA0R0DRF9Y1nWkrT2MpZlfUtElCYNjCeiJUS0lYg+ZubNaaeYSkSTLcvaRbA5vJ6d+VzRGDSI6JVXiCpWJLIs/Bo1QruBgYHBRURQVZIXmPkLIvpC036QiLpJ//+WiL7VjNtN8FoyyAgGDQowgmnTiB5/nGjTJqJ69XJ3XgYGBlcUTOTz5Yp77yUqVIho1qzcnomBgcEVBsMYLldERxNNnkz0+edE69bl9mwMDAyuIBjGcDlj0iQwiBkzcnsmBgYGVxAMY8iLyGjqi8KFiaZOJVq8mOiXX3JyhgYGBlcwDGPIa8hs6ovx44liYxEBza7xgQYGBgYZhmEMeQ2ZTX2RPz/6VqwgWrr00s/PwMDgiodhDHkN+/Zlrp0IEkX58kTTpxupwcDAINswjCGvoUKFzLUTEUVGEs2cSfTbb0Rff31p5mVgYPCfgWEMeQ261BeRkcFTXwwdSlS1KjyU/P5LNz8DA4MrHoYx5DWoqS/CwoiKFSO66Sbv48LDiR58kGj9eqLPPsuZuRoYGFyRMIwhL2LQIKI9e7Dz/+ILosOHiV58MfhxAwYQ1akDtVJq6iWfpoGBwZUJwxjyOrp3J+rYkWj2bKKTJ73HhoYSzZ1LtG2bqexmYGCQZRjGkNdhWURPPUV0+jRURcHQpw+yrs6eTZSUdMmnZ2BgcOXBMIbLAfXrE40aRfTCC0Tbg5TYtiyiefOI/vmH6M03c2Z+BgYGVxQMY8htZDT9xZw58FaaMiX4Obt0IWrZEmqlCxcu5mwNDAz+AzCMITeRmfQXJUsiwvnrr4l++MH7vJYF99Z//yV66aVLM3cDA4MrFoYx5CYym/5i4kSiypWRbjslxfvc7doRdehA9PDDRPHxF2W6BgYG/w0YxpCbyGz6i8jIQNW21zNQBXXePKJjx4j+7/+yPkcDA4P/HAxjyE1kJf1F375Ebdogwvn0ae/zt2hB1KMHmMmpU1mfp4GBwX8KhjHkJnTpLyIivNNfWBbR008THT8ONVEwzJ0LpvDUU9mbq4GBwX8GhjHkJtT0F+HhYBQ9e3of17gx0a23Ev3vf0S7d3uPbdCAqH9/MJNjxy7e3A0MDK5YGMaQ25DTX/z0E9RDM2cGP+7hh5FH6d57g4998EEYtR9/PNvTNTAwuPJhGENeQvPmRGPGED37LNEff3iPLVMGZT0/+4xo5UrvsbVrEw0eTPTcc0QHD168+RoYGFyRMIwhr+Hhh4mKFweDCJYIb8oUonLl4L4aLNX2rFlwcc2IXcLAwOA/DcMYchIZiXIuWhT2gN9/J3r5Ze/z5c9P9OijROvWEb3zjvfYKlWIRoyATWPPnizegIGBwX8BhjHkFDIT5XzLLcioet99SLnthVtuIWrWDGODBbJNnw6mNHdu1u/DwMDgiodhDDmFzEQ5WxYS5iUmEk2a5H3ekBBIGIcOBTculytHNHYs0YIFRDt2ZG7+BgYG/xkYxpBTyGyUc/XqkAI+/JDo+++9z92yJdHNNxPNn0+0f7/32GnTEEE9e3bQKRsYGPw3YRhDTiErUc5Tp4JBjBtHlJDgff7HHoMB+r77vMfFxiLn0ocfEm3c6D3WwMDgPwnDGHIKuijnqCjvKOeoKKiU/v4bRmYvVKxIdPfdsFn89pv32ClTiAoVyli8hIGBwX8OhjHkFNQo55AQotKloQLyQseORAMHgjEEK9IzbRpRqVKwSzC7j4uOBnP48kuitWszfy8GBgZXNAxjyEnIUc4ffIAqa088Efy4p54iypcPKiUvgl+oEDKqrlpF9NFH3uecOJEoJgaeSgYGBgYSDGPILdx0E3IYzZoVXNcfGwuJYdky9wpvAsOGIT/S1KnedonChSFhLFmCVBwGBgYGaTCMITfx/PMIaBs2jCg52Xvs6NFImTF5MlFcnPu40FC4r+7bh79eGDcOqqfp070lEQMDg/8UDGPITZQoQfTii8iLFMy4HBKCMp0nTwb3PGrXjqh3b6JHHkF8gxvy5wdTWLmS6McfMz19AwODKxOGMVwqSOkvWgwY4K4C6tsX0ctz5hD99Zf3ORs0gG3g5ZdhR/DCE08gQC6YDWHkSLjMPvCAkRoMDAyIyDCGSwMl/UXUkSPu6S+IUHozJgYqpaQk73PPno0I5ttv91Y/VatGdOedRG++SfTnn+7jIiNh5/j9d6JFi4LdmYGBwX8AhjFcCmQm/QURmMLLLxOtX+8d10AEz6Nnn4XB+tlnvcfOmAHX1MmTvaWBW28FI5kxI3iWVgMDgysehjFcCmQ2/QURUa9eREOGgDEEq8XQuzdqOc+a5X3OokWholq+nOirr9zHhYWhmM+GDUSffOJ9bQMDgysehjFcCmQl/QUR0TPPEJUsSTR0KOwDbrAsqJ/8fqIJE7zPOXo0UZ06CGjzOueAAUT16iEaOiXF+5wGBgZXNAxjuBTQpb8gCl6Gs1gxoldfJdq0CTt9L1SqBHvDV18FlwaefBJpNZ57zn1cSAiuuWMH0bvvel/bwMDgioZhDJcCSvqLxJgYovBwpKAIpsPv3p3ottvgvvr7795jJ00iqlsXRmavWgxduuA3dy7RsWPu43r3JmrcGGqlYEZwAwODKxaGMVwqSOkvVn36KXbrP/yA1NjB8NRTqOk8dCjRhQvu48LDEduwf39wCePJJ8E8vNJtWxZSauzZQ/T668HnaWBgcEXCMIacwqhRSIHxwAPBs58WLUr02mtEW7fCwOyF1q1RsvOpp7xTa9SpgzrSL79MtHmz+7jOnXHOefOCp/o2MDC4ImEYQ07BsqBeKlsWAW2nT3uP79wZhuP584MHsz32GOwTt9/uraqaPZuoYEGk5/aa57x5RAcPIirbIO/gvfcQLOlWMzwjNcUNDDIAwxhyEkWLIqvqvn3YvQeLNJ4/n6h8eQS+qXERMmJiAgzESwVUvDi8jpYsIVq82H3ctdcSXX89UmoEqyNtcHHhRtzTgiajjhzR1wwPVlPcMA2DzICZL7tf48aN+XKCz+ezNzz0EDMR8+uvBz/4xx8xdtIk73F+P/O11zIXK8Z85Ij7uMRE5mrVmGvXZk5Kch/322+47rx5+nu4DJEn7uHdd5krVmS2LPx99117X/78eO7ilz9/4Bi5XfwqVsSxXv1e5w02p0uAPPEesonL9R6IaC1ngMbmOpHPyu+yZwwpKczt2+Pj3Lo1+AnGjcNHu3Kl97gtW5jDw5lvvdV73Jdf4tU/95z3uJ49mYsUYT558rL9EGTk+j0EI9BexN2y9H2WhWO9+rPDNC4Bcv09XARcrveQUcZgVEm5gdBQonfeQazDgAHenkdEsCFUqgQ31nPn3MfVro1YibffJvL53Mf17El03XUwbHul8J4zB7aQJ5/0np9BAF4qm2CpUrwi5oMFTXr1e5032JyMCuq/iYxwj7z2u+wlBoGvv8YO7c47g59k+fKMjT1/nrlKFeaaNZkvXHAf9+ef2E0GU1HdfDNzgQL88xdfBJ9jHscl3+UF230H2/VnVx0UGanvz6okcomkict1ty3jcr0HMqqkXIakt02IjXX/mO66C6/hq6+Cn3PCBIwNtigXL8a4uXO9x40YAdXTjh3uY7ZuZQ4J4X39+wefXx7HRfuY3XTy2bEDiPPmy+dJ/FNDQuzMQsbkyQGiLvdn1XYRbL5ez8IDlytRlXG53oNhDLmJzOy0LlxgbtiQOTqaef9+7/PGx8NwXKkS89mz3mP798cOcudO9zGHDjEXLMjcq5f3uYYN45SICOYDB7zH5XFclI/Z690Gkwgysi5efNFOgJU1c75UKeYhQ/Rze/99HLdli37eYWHO817q+9HgciWqMi7XezCMITeRkZ2WjO3bmQsUgFdRSor3uX/6CR/m2LHe4/79l7lQIeZOneCx5IaHH8bcli1zH7N7N6eGhga/Zh5Hpj7mrEgFGd1hR0ejvWxZJxE9cwZ98+drp5UQG+vuXPDqqzh23z59f9GizOPH6+81NNTJNLIrAbngciWqMi7Xe8gRxkBE0UT0AxHtTPtbTDPmOiL6S/pdIKLeaX1vEdE/Ul+DjFw3zzOGYDstHRYswJgHHwx+fqEy+OEH73HPPotxH37oPiYhAR/y1Vd7MqUDPXtC7bR7d/D55VFk+GPO6i46ozvoTz5B34YNzmsnJ7OXGjAhNpZ52DD9vJ9+GseeOOHsS0x0X1+JiZj/7NkZfw7MWVvnfPkSVRmX6z1klDFk1ytpGhEtZebqRLQ07f+qcdvHzA2YuQERtSei80T0vTTkHtHPzEFqW14myEra7VtvJRo8GAnsfv7Z+/zz5hHVqIFUGGfOuI8bNw5J8e66yz3SOioKXk/r16Pamwv2Dh4cyMB6pcPLU8fr3YrkiWJM4cL4/6BB9rHR0fh74oTzPGFh8Fpz81Tz+xGdroPwWCtY0Nl3/Dj+lizp7Nu/HyS9YkV7u7gfcb2KFe33k9X08gZ5HtllDL2IaEHavxcQUe8g4/sR0WJm9gjjvQKgS7ttWUT33+993AsvEFWuTDRwINHJk+7j8uUjWrCA6MAB1FlwQ2gokuwdOeJd+/mmm4hatsSYs2e1Q5JKlACjefttou3bve/jcoeXe6fu3ebPH6i8N2gQoo4rV0amXJUpECFSncj9HefL55qnymJ2Zwzx8WAsERHOvqNH8VfHGPbuxV+VMRARtW0LpvHii0iuKN/PQw9hjckQz8K4uV7WCMvm8bHMfIiIiJkPWZalWXU2DCCip5S2hyzLmklpEgcza6vJWJY1mohGExHFxsbS8uXLszXxS4qyZankpElU5bXXKPLoUUosUoQiTp+muDfeoI3VquFjcUGhe+6hhuPH04nevWnzgw+6EwEiqnLTTVTh1VdpfbVqFNesmeu4ar17U9nnn6c/6tWjszVr6q87eDA1HjeO9o4ZQ/+MGuXoj4+Pp1/atKEWL75IJ8aOpS0zZ3o8gLyJ+Ph4x7op+eOPgfdUsiTtHjmSqpQsidQTCi6ULEmr5Xd75AilRkXRjkmT6GjZsqiUl4YGhQoRbdpEf2nWaeTRo3QNEW3/9Vc6JKQHCS1DQ+nY33/TTs2xLfx+OnT4MG3X9FXbvp1io6LoF01fsbVr6Woi+vPAATqt9Jf67juqRUSrDx2iC0pfsTVrcNyFC47jqGxZahEdTeGnT1NIcnL686OtW6nm/PkUKgpD7d1LqSNG0PatW+lox47a93C54Uq4B08E0zUR0Y9EtEnz60VEp5SxcR7nKU1Ex4goXGmziCiSIHHMzIj+K8/bGBT4fL6At8nMmcEPmD8fY194wXtcQgJSW5QtyxwX5z7u1Cnm0qWZGzWCDtsNgwfDk+mff/T3wMx8//2Y2/r1QW8jr8GhF3bToY8dmzFbwbXXMl9zjf5igwa5G2HPncM5H31U31++PPNtt2m7LsTEMI8apT/uttuwFnR4911cc9s2Z9/MmbALJCY6+4TdQpdm5dw55pAQ5hkz7O1BjNKXq35exuV6D3SxbAzM3JGZ62l+XxHREcuyShMRpf096nGqm4joC2ZOls59KG2+iUT0JhG5b3svd9x+OyKX58whWrTIe+ykSSisM2mSdyrtqCiolA4fJpo82X1ckSJE//sfakm/8IL7uEcegTQzzWEqCmDKFJzvMpQYHHCzJXz7baDQEhHqXuhsBTVruqvVKlQg+vdfotRUZ1++fESRkXobAxHeq4uNwQpmY9DZF4iCq5LKltWroLZuhU2kRAln3/r1sHk0aWJvz0rNc4M8hezaGBYS0dC0fw8lIo8ak3QLEX0gN0hMxSLYJzZlcz55F5ZF9PzzMAYPHky0c6f72JAQEPxixYhuvtk7s2rTpkRTp8Jw/M037uP690cq7+nTQbB0KFeO6J57iD76iOiXX/RjihUDc/jqK6I1a9yvdznAi4CJQkvTp4P43Xijc1zNmrATCMOujPLlUTtbo5Iiy4KdIQs2hvTjdTh3jqhAAX3fsWOwPxQt6uzbu1dvXyACY6hdW3/NtWvxt3Fje7sxSl/2yC5jeJSIrrcsaycRXZ/2f7Isq4llWa+JQZZlVSKi8kS0Qjn+PcuyNhLRRiIqTkTzsjmfvI18+Yg++ww7s969vVNalyyJfErbtkFy8MLMmUT166MYkBuxEYwpKcn7fPfei+pxkya513aYOBEpvGfM8J5XXkGaIfTa9u3thtCMELBGjbDr10luwl6jkxrKl8dfN+YTHZ0liYGCGZ+9JIYSJfTHZoQx6LB2LVGpUlgvMh56CPcgQzbQG+R5ZIsxMPMJZu7AzNXT/p5Ma1/LzCOlcXuYuSwz+5Xj2zNz/TTV1GBmvryT/2fEE6NiRaIPPwTBHz4cH7obOnaENPDKK0SffOI+LjKS6K23sCucONF9XNWq2AF/8ol7PYYCBaBS+v13ovff148pVAjqpu+/J1q50v16eQFSnQKL2V6nIJiHERFRw4b4++efznNnhDHs36+fV1YlBmZ35wUviUEwBhWpqZijjjEcP46fG2NYtw7SgspsBg0i6tUL/7Ysu5trsGJDBnkDGTFE5LVfnjQ+ewQDaQ1Vjz+OMU884X3epCTm5s2R/lpjFLZh1iyc0yvh3YULzLVqMVeuDOOhDqmpzE2awJAZH8/MGmPb+fMwaLdp4x1ZndvISH6iMmXQFh3tNDD7/ahxMXq089zJycwREcz33uvsO3EC53zySf28+vRhrltX39e5M965BkmFCzPfcYf+uFq1kApFhxYtmDt2dLbv24d5vvyys2/lSvQtXuzsi4+H4XnWLP31uneHY4SMXEjxfanwnzc+G2QQwdIXq5gyhahfP0gEy5a5nzc8HFXfmBHfkJzsPvb++4kaNIChW6f3JoJ08eKLRP/84y7ah4SghvS//6IynA758kH6+OknSA55FcEMoYMGIR4kNpaoWzengdmy8Ex1EkNYGFG1anqJoVgxSB+XQmLIio3h6NHMxzBs3Yq/Oonhr7+galTtC0SQQn7+GTEQMjL7jRjkGgxjuFjIrCeGZRG98QZRrVowMHt5bFSuDFF81SrUbXZDRARUSnFxRHfe6T6uXTtEWj/xBNGWLfoxbdqAcT3+uLuxeuRIEJTp071VYjkFnSovI3YEyyJq3drd4N6wIWwMKSnOPjfPJMvCNbwYw4kT+ucWFZU1xhAf72181qmSgjGG/PkDajEZboZnIjyr06edjMF4K102MIzhYsGNAOk+KoFChYg+/xwG4b59vQv23HwzUmA88oi3hHH11TBGf/gh0aefuo974gkYKseOdSfqjz0GYugWsR0RgWI/a9fCSyk34VbzuFu34HYEIqJWrSBFHTzoPHfDhng327Y5+2rWJNq1Sy/JlS/vzhiio/HedYWX8uVzd1cNZmPQGZ8TEhDRrpMY9uzBX9363bIFGxfd9datIypd2ml4JiJakeZj0qaNvd2LSZtI6TwFwxguFnSGTCLs9r120zVrIs3E2rVEd9zhPfaZZzB+8GDsAN0wdSp2cmPHBvzXVZQsCWlg5Uq4xupQpQq8k95+mwq5+esPGYK8TTNmuHsx5QSCxSRUqEBMhHeki0lo3Rp/dVJDMAN0SgqYiory5d13w15pMbKiSkpOBqPRSQxirbipkkqU0K/dYB5JavyCwMqVWPfqpuihh6DKlJE/P5i3jqkb5pBrMIzhYkEkHKtYMeCJ0asX0YoVVP6jj7yP7dUL6pg33sA53FCgAGIMTp4kGjbMnYmEh0OldOYM8hu5jRs+HDmSpkxxd528/36ikiWp6vPP688TFobEf5s2YW65hWAxCXv30uEuXSDl3Hyzc1yDBiBSugSGNWtCvZMVz6QjR0CwVXgl0suKu6pXAj3BGNxUSZUqOdvj4yHt6BhDfDykJ50aiRmMQVUjEeE9dOkCBi17K337rbE95DEYxnAxIYKi/H78/fxzoptvpiqvvIJ/e2H2bKKuXWEbWL3afdxVV6EG87ffQoJwQ716INiffUb08cf6MSEhSLJ36hSkDB0KFyaaO5eKbtzorpq66SbEUcyapdfD5wQyYEs42bQp7vX3353jwsOJmjXTSwxhYXjuWWEMzHobTRYlBtckeiImRicxBIt61tkXhNpMxxj+/BP3pZMYtm2D44OOMRAR7d9Pp+vXD3wjgwYZ20MehGEMlxIhIURvvklnateG+kdHkARCQ4nefRfEpG9ffcSswLhxkDLuvRdpLtwwZQqI3bhxSJuhQ/36SKfx+uvu6b5HjKD4KlVwPd1ONiSEaO5cRHO//bb7fC4WdProDMQkxAmf+yVL9Odt3RreNrrAw0aN0KdKTdHRCPbLbCxDMIkhNdWdyep0/l4Sg2AMqsQg1DaZ9Uhatw5/dRKDiGvRMYbDh4n++INOqgkfTaR0noNhDNlFMKNZvny0ad48uEP27Om9C4qOhmQRF4dduJtrqmWBkMfGEg0Y4Joqm8LCoFI6d45ozBh3ldKsWfgIx4zRqz1CQ+nvceOww3OTUnr2RHqOBx8kStQmyL04cDMyE9nzG4lIb8mWkFKkCHa5bu61rVqBIP/2m7OvYUNIG8JYK8PNM0kQNh1jCCYxEOmlBrdcSYIxZMbGcPQoGL0bYxDuuCrWrkVupVKlnH0rV8IoXbWqsy+NIZ9s3tze/tBDzjxNJn13rsIwhuzAjUgpize5WDHkMUpIIOrRw7u4ztVXE736Kj6we+91HxcTg+v8/TfR+PHu42rXRmGfr75yj2QuUIDoueeINm8mevpp7ZC4xo2JbrgBH6tb/p9588D4XnvN2X+x4OULL1R5336L96HTqXfuDMIfF+fsu+Ya3IdOchIGaJ2EVqvWxZcYiLTSWVBVkpvEEBkJLzgZwVxVq1eHik2FiHhWwQyPpLZt9XNcvJioVCmKV5nNoEGw8YSE2G0PRMYonUswjCE7yEzATp060NFv2YJdvpcuftAgpLb43//ciTkRPsAZM6C+efdd93GTJoHo3Xmn3h2TCES/d2/s+HW7YiIEuyUkuGdWvf56uCjOm+ed+C87yIg+un17EMEvvnCO69wZu+6lS519RYpAtaazM9SvD3Wfm53h6FFIFDIKFECgm27OkZHoz6zEQJQ1iUGXJ0kwBp3x2c0j6exZMEGdfWHPHthTdGqklBRIal26OOdx/jw2JaNH220PJiAu12AYQ3aQWaNZx46IOl68GOU2vVxTn3gCH9jIkUhv7Ibp00GMx451z9gaGgqVUkICoqLdrvvMM9i1jR+vH1OjBlxqX3uNaMMGZ7+QGg4f9k7vLRBMTZDVgLXISFRPW7jQmfa6eXMY1L3sDKtWORl3VBQIZVYM0F6xDJmUGFxzJQWTGDIT9ZyUhNgML8NzZu0La9ZASuva1dm3ZAkYW79+9nZjlM41GMaQHWTFaDZqFIzCzz9P9H//5z4uPBzeRMWKEfXp454+ISwMBDM8nOiWW/Q2AiIQ9UceIfr6a3cDcYUKkBi++Ua/2yaCtFCkCAzWOubRti1Rp05Ejz7qbvsgCq6Gy27AWp8+2Cmru//wcEgUS5bo59+qFYisLptqw4bejEEXAOfFGNzSYnhIDK71GLwkBrcEenv24F0WKWJv37kTDFXHGLwinleuBLOrU8fZt3gxGNr11zv7Pv0Uz+Laa+3txiidazCMITvQecKEhmLX7IXHHoPaZtIkEGo3xMbC3fTAAYjWuqIvRCA+b7wB3a9XXekJEyBdTJyIc+owcSLsHBMm6Al7dDRca5cudZ/7vHnYCXu50wZTE2S0iE5ICKQTNWCta1dIDm7qpP379Tv8YIFuhw45bSxVqoBBuxmgL6bEQJQ37K1fAAAgAElEQVR5d9VjxzLnqhrMI6lcOaxNFStXYn3pJJrFi6HOLFbM3p6YiMJVvXvjGcowNaVzDYYxZAdqUFvRoiDeq1Z5q4lCQmATaNgQ9oa//nIf26IFJIvvvsNu3g29e8Mt9ckn3VNqp7nPUnIyVFRuAWsvvQRbxKxZ+vOMHYtd8pQpegmlaVO4086frzfyEgVXE2SkiM4330AnrSs+U6gQdqdffOG8z86d8VenTqpQAYTPywCtSg3h4WAObqqkkyf1NpcsSAyuqiQ3d1Vmb1WSm32BKCAJyXCLeD54EOonnRrpyBEwFJ0a6YcfsAFR1UhEgfGFChmjdA7DMIbsQg5qi4tDBbQXXvBOdkeEnd2iRdhB9ejhbhQmwqIfPhyxAgsXuo+bPx9G0qFDsbPVoWpVpMJYsgQurzq0aIFrPvOMXnUSHg4GtGMHbCY6zJ0L7yu37KzB1AQZUSN06hQoaKRDnz4gGirjrVwZHjdedoaff3YylAYN8NdNnZQVz6SL6ZVkWQGmInDuHBiMW9Szm8RQsaJT+jhzBu9cp0b66Sf81TEG8Zx1jOHTT6HKat/e2ffRR9horVhhjNI5DMMYLjYeewxEfM4comef9R5bujTUMadPwytIl1CNKOCT36QJchPt2KEfly8fPqb4eGRPdctdNHYs0XXXwU4gDJAqHnkEgVtjxuhVWN26YUc+e7aeuNWvj9QTzzyjz9ekU8NFRARsBRkpohMWBrvKokV6yeSGG7C7dlMnLV+uV9e0agXvGlVqKVoUkoEbY9i1y/msvCq5CYlBZUBuEoMY52ZjKFDA2ecWw3DqFAi9G2PQqZGEq65OYli5EtKKYJ4yFi+G6kntS0qCG3WvXvp60wsWYB2pxxmj9CWHYQwXG5ZF9PLL2K1OnOjtRkoEff5HH2FXO3Cgux0hKipQFrRPH/eyoLVrgyH9+CMkAx1CQmCTYEbGVp1KqVgx1GRYs0afv8my0H/mjLuK68EHQdwefdTZp6rhwsPBiG65xdkvrvfss05bwpAhIDC6CnclSkDnrWMMnTphbjpbQjA7g44x1KoFfbnKaL0khpgYvG81rsVNYvBiDG4pt93SYQiXZJUx+P2QfLIS8dyqldNOkJoacFNVVWA+HxiUTo20fTviTYYOdd6vMUpfchjGkBUEM3yFhSH+oH17omHDKGbVKu/zdeuGnfXChd5BbRUqgIls20Z0223udowRIxA5PX26e96lSpWg5lm6FIxMh4EDcQ/33UcROl14vXrwsnrhBb1HTo0a+LBfeEFv7JbVcG+8AXWabB8R/b/9hnvV2TMaNQIR81InbdqE3byM664DM9Kpk+rXh17bzc6waxekPBluLqtly+JvZoLcgkkMbjaGzCTQc3NV3bsX19V5Fq1dizWonuvECTxjNzfVkyfd1UgFC+o9lRYsgOFZ3QgQQWpUn4HI0moM0hcHGSnzltd+uVraMzPlCc+cYW7ShFMiIlAmMRjuvBPne/FF73FPPIFxjz/uPiYujrlSJfxOndKP8ftR7rFAAebdu/Vjtm1jjojgwx066PuPHGEuXBilHHX45x/m8HDmMWPc58qMEqblyjG3a6efZ6NGzPXr68uIPvwwnofuHvbsSX9WjnKM7doxX3WVfj6dOun7vvkG51uxwt5+9Cjan37aeUypUswjRjjbFy7EMb//bm8/cgTtzz9vb09KQvvcuc5z9eqln+/rr+MYtSzsM8+g/ehR/f39/LPzXNWroySpii+/xDE//eTsmzEDJUBPnEhv8vl8KItavDjzLbc4j0lJwVro1s3Zx8z8xx+4XrFizJaFMq1jx+Zo2VBT2tPAjswYvgoVIvr2W0qMjYWB2cv7iAjpKLp3R4CZV7nMu+8m6t+faNo0fQQvEfTh77+PnapbUJvIuRQSAruIziZRsybRtGkUu3Qp1FMqSpaEZPLNN/o5V6oEqeK114h273a/p/BwBP0tXx7wlZfnOWYMYgt00tfAgfir2yFWrAipws3OsGGD3lDfqhWup0Yzu3kmFS8O9VtmgtyyKjG4qZIyk0Bv715cp3hxe7uo6Keqkk6fRnyDm30hKgreaCoWL4Yzg7hX+Zjjx/VqJJ8PEubQoc4+Itjb8ufHehJGaZO6+6LCMIbMIrOGrxIlaP38+fC86NzZPTqZCKLzBx8Q1a0Lwr9pk36cWhbUzYB8zTXwDvroI4zXoUIFMKTly92jle+7j86XLQt3WJ2xdsIEGGUnT9an+njgAajX5szRn19g1ChEJT/5pLNv4ED06bygKlZEcNQ77+gZYJ8+RKtWUYRKgDt1wt8ffnAe07o1zqWq4kqXhiFVZQyWBSaamSA3t0R6WbExuNV7PnYMRFTtEx5J6rm2bgWzVwm5MDy72RdatHAW4Tl6FEzeTY2UPz9sDyoWLMDGpmdPZ9/Jk9gADB5sd1M2BumLCsMYMgs3A5cu02QaEkuWxG7a7wcxcquhTAQp4+uv8SH36OGefrtgQeyCk5O9y4JOnUrUoQPyJAn/dBXDh+MDnTrVqYsnIoqKop133QWmpjMkR0bC0L15sz6BXpkySKXxzjvucyAC4R89GoZkNV9TgQLwtPr4Y+w0VQhvLV1q8z59iIiouGpMbtAAO2mdnaF5czBqNztDZl1W9+3Tp+wmckoM4eG4dmZsDF4Sg1tJz8x4JLlFPJ85A6aRGTfV1FSsXV0U+9mz6XVM0hmkjDffxFq/4w57uzFIX1QYxpBZuJXwjI8PiOE61KoFsfr4cUgObikuiEBIFi3Cbq9XL/dkajVqgNiuW+deqS0kBGMKFkQwnY6BWBYyuoaHw6itUSnFNWkCj6FHHtG7y954I4jDzJlOwywRmE7+/MHjOyZMwHx0UdMiLfhbbzn7+vUDIdEZoevUIapenYoLX3uBkBAwasG0ZRQoAMbh5pm0ZYszvXjNmlBLqV5G5ctjR6+qpQRj0K2FqCjnexdzzKzEkNHKbczujGHdOjASVfX066+Yl44xLF4MpiTUb2kosnkz8mnp1EiffgoVkE6N5PdDqm3TBoWTZDz0kNMjyhikswzDGDILXQnPJ57AR9m+vfeOuEkT+G3v3AlbglvcAhF2Zu+9B6+OoUPdYxJ69kSG1TffdPcuKl0a4vmGDYhW1qFcORDjn392j7946inopXVMyLKgkjp+3Jm3iAjE6a67sOP3srWULw8G9uqrztiEunVBFF56yfk8ihTBs/jwQ2cdC8si6tOHiv75p/OcnTtjzjoJoHVreESp52vYECozVdUnPJNUxunmshoWBilJFweSL9/Fc1dVJYZz53DPqsRw5AiYl5vE4GZfCAuDKklGaiokBo2baomVKyFlduvmPN+CBQg+VM9HhOj/3bud0gJR4DoilqNiRXw3CxaYCOmsICMW6rz2y1WvJDds3cocG4vf1q22LocHw+efw1OjUyfmxETv886fDw+L++93H5OaCg+O8HDmX391Hzd5Ms71xRf6fr+fuUcP5qgo5u3b9ffw/PM4x3vv6c8xbBjmsWuXsy8ujrloUeYbbnCfIzPzn3/iGo8+6ux7/330LVni7Fu0CH0LFzr7Vq1C3zvv2NsPHUL7Qw85j/n4Y/T99pu9fdcutL/6qr190ya0q54w4tpff+28RuXKzIMHO9vLlWO+7TZ729mz7t5o+fMz3323s71sWed5tmzRv8Nly9D+/ff29pMn0f7ww87zt2rF3KKFs13c8wcf2NtTUzmhRAl4UanYvRvHzJvn7GPGGi9VSv/NPPggjt24MdBWsaLdS0n8KlbUnz8TuNK9knKdyGfllycZAzM+uNhYLN5t29KbtYtIuBHedBPc89zg9zOPHo2xb7zhPu7kSeYqVZjLlAGx0yExkblxY7j57dunH/Pvv+i/5hrbvNLvISWFuVkz5pIlcU3d8QUKMN94o/78Dz2Ee1m1yv1emOFGW7q0kwhcuMBcooTebTIpCS6Q/fs7+1JT+UJMjH5eV1/NfO21+nshYn7ySce5uHBh5nHjnHMLCYGLpowDB9jVDblxY+auXZ3t1as7XTnPnMF55s93zoeIeeZMe7vfzxwRwXzvvfb2b79lrUuqYPoHDtjbf/xRzzDOn8cmQD0/M+aiuKkyszuDZgZxtyzmvXudfbt2oW/WLGdffDxzTAw2NTIsS88YLMt5jkziSmcMRpWUUWQkm2Pt2kTLlkHNcd11ekOkwPDhUEF9/DFEY3YJVrMsVFe7/nqIwT6fflyxYjDoeZUFjYiA11NyMrw6dFHWZcogad+qVfpqbqGhUOUcP67P5FqmDOwJn3+OHDcqJkyAWmnGDP19CEyZAn39Bx/Y2yMj8ewWLnQa8cPDoYZauNBp5wgJoeOtWkEdoeruO3eGLUHNJlumDPIqqXaGkBDYH1T1U2QkxqvvvVQpqFvcPJOya2MQbpqq8fnMGdhkVFWSW3Db1q1wfihTxt4uIp4bNbK3CzWbm32heXOnd9Nnn5E/LAyOFTKYkQ7+uuv0BuMXX8TaE2VcZbzxBtRx06bZ241BOuvICPfIa78clxgyE9TGDJVCiRLY8W7f7r27mDoV53vgAe85xMUx16mD3bwkjTjw3ns438SJ7mPefhtjZs/W9/v9zL17M0dGMm/ezMyaHdJdd2Hnpdv5nzvHXL48gtJSU539Tz2F63s9F7+fuV49/NSgtr//dt89/vYbzv3aa46uv0Rg4Jdf2juWLkX7V185zzdkCKQjdQ4TJ2INqNJet26QQFRUqKBXGQ0YwFytmrO9WTPmLl3sbXFxmOdTT9nbhTpMDYjbsQPtCxbY26dNw05fnXuHDriuiv79ofJSIXb4cXH29qNH0T5njr3d72euVImPN2/uPNdPP+nnyoz1VLQopGsVSUl4tq1aOfteeskpLYjv9t13oVISAXKZDIS70iWGXCfyWfnlOGPIiq5y40YwhzJleLVObBbw+5lHjtR/8Cp278Y5q1ZlPnbMfdxdd7FW1y1jyBCI+moEr8DhwxDPmzZlTk52fghnzkB/ffXViGJVIRjUm286+86fh8qrVSt9JLPAW2/hHN995+zr0gXnUK/t9zPXqKFVDS3/4QcQmKFD7R0XLoBgqKoh5gBx2blTP7ctW+ztkyYx58vnZIitWunVVXfcwRwd7Wxv29Y5Xuj61ehqYfNQieovv6B98WJ7+y23QO2oonRp57Nhxth+/ZztHTowN2jgbH/nHdZGdK9dy0zEW++5x3nMyJFQQZ496+x77TXWRpvL11q0yNk3bRr6Spe2M4DMbvQ0MIwhD/5ynDFkVVe5cSNz8eJ8oXhxJ2GRkZLC3Lev/uNWsWoVdvKtW4Og6ZCUBMKSLx/zX3/px5w5g51quXLMx4/rx3z0EQujo/ZD+Owz1urgmUGgmzeHvUX3sb/4op5oyUhMBPHv2NHZ99VXOP7zz519c+eib88eW7PP58OuPTrayVC6ddPv3IVB+a237O3r17PWgCsYiXJtHjBAT4xnzsQ6UnfvnTvj+ck4cQLnfuYZe/tff6H900/t7V98gfZ16+ztLVsyX3edve3UKdYa/MU11fbERKyvCROc9zRwIKQslTnedx9zaCj/pEps58/DZqNjSn4/mI8uHYqQKuvWdV7ryBEQe13KjYtglL7SGYOxMWQEbjpJkSDNDfXqES1bRiFJSdCd/v23flxoKGwWHToE9OduaNECLng//+xebEeUBY2Odi8LWqgQXDuPHHHPsHrTTYjAnjWLCujSWfTpA7fbmTOd+nPhvnr4MFKRqxg+HLaa6dPd7SsREbBJ/Pij08W1e3e4geoioQcPxl+dHUg8D1GfWKBzZwT3qfdZuzYibNVAt9q1YVNQ7QxuyfQqVECaB9XNNjoa96/GOOTLl3Ebg1uRHrcEerrgNreqbW4Rz3/8gfmp9gU3N1VmBC62b08painRL7+EPUQXu7BqFd79HXc47/vbb+EyPHWqM+jv0Ufh7quLmzFR0sGREe6R1355wsYgRNT9+4Mevua116CWKV8e+nE3nDkD1U1kJPPy5d4nnTcPc3jwQfcxq1fDK6VzZ3fPJ6Hvf+45ff/Ro8wlSvCZ6tUhiajYvRs7R52XEDN2ylFRek8ToY7R7foF4uKYCxZkHjTI2TdnDmvVPMzMbdow16pl22X6fD54sERFMY8fbx+/bRvO9cILznN1785cu7azvXFjqFNkHDyI8zz7rL39//4P7YcP29uFKmTHDnv7gAFQickQifr+7//s7d9/j3Y1iZ1YIwkJgbbERL195o039PN45BG0qx5ojz2G9iNH7O2rV7PWTVVIWC+95Nxtd+6M3brOHnXLLZAmdFJn69awL6jr8t9/8Y6HDXMew4xjdBJDTEyG7Q5XusSQ60Q+K79ccVdVjVUPPMBcqBAWmeLzr8Ln80Hcj44OzhyOHQMRKlQIWSTd4PdD9NapM2S8/DLGTJ/ufp5u3cCM1q/Xj/n0U5xDNSYKCOKhix/Yswcf6cCBzr7kZOaaNaEK8HLZnTSJOTTU6WJ78CDap0xxHvPKK6zqudM/5l69oEKTVRN+P96rzr9eZG9VVW4jR+KdqucpVAi2AxkiA6mqdxfZTFUj/m23Ya3IEFlXVSb++edo//NPe/uECSCqMoQ9QrX93HMPNhGqiq1fP70KrHt3MF4Vbm6qov3wYTtR/fdftOvW5+HDMJLrHCl+/pm1ajVmPPuwMPeMwRMnOplCeDjuP4N2B8MY8uAvz8QxrFsHY3CJEp5EPH0R/fknvIoqVHBftMyQQipUwHm9mE5iIgyUERH6NMnMIFQjRrDWG0fgyBHYAmrXxo5ag8Pt2+NjU4mPmEedOpiz7vgHHtATP+aAHcOLue3ZAwagC+Dq2xc7PXlXzAxJIyLCRlTS34OQVNassR8zahSIuroDXblSz/heeAHtqjTUtKnTLrJuHcZ+9pm9Xeywv/nG3j52LN6/jMOHWSvVuEkdt9wCRwUZwgNr2TJ7e48e0NerqFTJ6Q2UksJcpAjia1Q0bYoYGBV16qSnVLcRVSF5qHNnDtiKdN/ADTfgvavrbc8eEPnbb3cewwy7XOXK2BhUqBDY6MXEOJmFh93hSmcMxsaQHTRqhFq3UVFE7doF6t66oUEDpMk+exY2BzVRnEC5coGMn9dfry9yQwQd/OefQ1/cu7fehiHiIERZUF1sRcmSqDS3bRvSVmiwc8IE+NwPG+YsmBMRgdiGffv0GVSnTYMv/6RJTntCv37IezNrlj72ggj3d9NNSEWixieMHQsf9k8/tbcXLYrSnh984Mz4esMNsOuoqbg7d8a7UTOqNmkCu41qZ3BLwa1LpueWFsMr9XZGbQyimp+aEkOXDsOtctvWrc7iPCdOYLxqX9i4Ee9BtS8cO6bPprp1K3JL9e1rb2eGvaxlS6TBkJGSgjXVqRNygsnYvBm5xO6803nP8+bh+bil237mGaJ//kG+rb17A2m73XKX/UftDoYxeCEjQW01ayIAqkwZLOJvvvE+Z8OGMKaePg3m4JYyu0YNBGPFxeG8unw6RCAs33yDBd69u772sSgLGhmJZHdqIBcRDN/TpiE76kcfObpTihRBLqb16/W5kNq0gUH5qadAOGQULIhjVq+GwVtGSAhSg+/ahQAnN9x9N+b96qv29vbt8ax0RughQ0Ac1ToR0dFI060yhg4dwDDUbKv58oE5qIFuV12F+esYw/799lxYxYvjPaiMwSv1dkZzJbkZn48e1ddhsCxsPgQSEkAsVcOzCGxTcyQJw73KGJYswRxVxvDZZ/h7443O82/Zojc6f/UVAhh1eZEefxwJ8saPt7f//Tdyht1+e4ARyzhyBIzjhhvwrmW4OZhER/83k/BlRKzIa78cUSVl1tf56FEYI8PCHGoRrdi5di186itV0htmBZYvh/6/WTMYp92wYgVE6Ouuc8+/tHQp9Ln9+unjB5KSkPemcGGHqiv9HoYMgVpHdYFkhn0kJgY++6ohMSUFbofly8M9UYbfj/urUMHdBZcZ91a2rPP+nnwS70e1kSQmYj4DBtjvgTlgDFbyWnHLlsxNmjivPWUKVFOqyqp2bWfuJ5FjSVW7Va+uV8tYljONhlCjyDp/kVrj5ZftY2fPRrtqpylVCnYQGUOHQo0iQ7i7fvihvV3YVtQAtr59sW5VuLmpXn21LQAt/T2MH4+1rZ6fGWqnihWd97R3L74xnd3h1lthzzp40NnHDFVhWJheNSWCHzNod7jSVUm5TuSz8ssRxpAVX+fTp6HztyybgdB1Ef3+O3S1lSt7M4evvgIx7tjRm3CKiObhw90Dx0RSvsce0/f/8w/m1Ly5Tdeefg8nT8Ibq149/VyEd4sm8ph9PvTpkqQJzxrV40aGMNSqAYMnToAgjB3rPGbcOPSdPm1/D/v341xqYjgRzasGEArjsWrLGTjQSWiFB47qmdO+vV7/Hh3tNFYLQiV744g5q8n77rkH9ygjNRVrRk2+2K6dM0r4gw/0jPXGG52xHX4/bB+33mpvT0kBEx4yxN6+cyfOLQVv+ny+ANO++WZ2QMSO6JIoTpwI4q5+L1u3YtOjc0RgBpO2LDgyqPD78Vzy5cO7zIDdwTCGPPjLEcaQ1aC28+eZe/bkdC8ev997Ea1ZA0JcpYp7YjvmgMG0Xz9vD54ZM9w/KmZ8BDfdhI/ohx/0Y8SO97770pts9/D11+jXZXz1+xFcFx3trCfMDLfWAgWcuzq/H0y1VCmkQNAhNRVGzKuvdjK+oUPh1qpKVSJp2xtvON9D06b46carRF24iqrPVRBwmZGcP491oqYc0e3WmUF806SadDz3HM4rP8O9e/VMd+xYEDEZIjBNjZKuXNnpISY8hlRpqGJFJ+HeulU/B2FEf/99e/ujj7JqoPf5fAFPqm+/ZQfGjoUkoTLn48exY1eZEjPmWaCAfs0Jwh8To0/8KL6tl16yt3vQAMMY8uAvVyWG8HBvAs4M8f/WWzH+rrvYt3Sp9/jffoP6pmpV77gIEXMwapS7ROD3wxuFiPmTT/Rjzp6Fi2hMjDNCV2DUKHwYP/7IzBqp57bbQExUzx5m5FcKC9NHsu7ciWeopoJmDuTL0aWVFhBZaVWmJgi6+nH7/VDhXHed8x6EqkR+5ikp8BzT+cDXqOFUG7llHq1Y0Rl1O306npnqEtq8OVKwyxBpIOS1tmcP2l5/3T721ludkqwg4LJaMyUF70Vi+MyMXEiq99KxYzj+iSfs7cL9WY0dmTUL96a69DZp4si/5PP54BZcqpTzWZw+DQavWztCZbZpk71dSGhuqelFBLiaS0rcZ0wMJDlVBeZGA2JiOCE2Nst5lnIThjFkFzobQ2QkfmXK6HXsMlJT4UdOxIc6d9bnE5KxenWAOahpj2Xcfz/mMm2a+5iEBCz0qChnLQGBHTtwvUaNnDp/Zuzaa9fGx3vkiJOoxsVh91u7tnOnyQziQ6RPlHf33fiodM+wSxdIG6dP6+d94QJSm3fubG8XqRN00kSaeujXjz6ytwviqaqv+vfHO1bPM3w45iYTELEzV1VznTrh2coQRFVVg3TtCvuUDJFrStaH//MPC+nHhhtvhCQlY8UKJwPdt0/PPOvVc6as/u47jFXdWgcOhCpRfTbNmjnrMghGpjybn7/4AgxKp/YRth91wxEfj2evq+XRuzekbp00cOECvqk6dfTf4G23YS4bNjj7BCPKoN3hcoBhDBcDugyMGzfCgFqggD5xlwy/P1BApFcvPQGVsWoV/OirVXNnDn4/fLR1uzkZR49CbRAb6y4VLFyI8wwbppdANmwAI+zaVS/1COKhy8d/7hwMlLVqOY3FcXGom3Dttc7r/v47zukV0S1qOqg6cUF41WJFaUFdu3R+97VqQfcvQ+zWVWIhpBU1cV6FCk5V0IQJ2PnK9+dWB2HwYGf2UpGHSr5HUchGzdvUubMzK6oISpRzZQmJTE5KmJwMQqcmthNR06dOBdr8fhj/VfWSyKaqvjPhFKAUbdoxfjza5aI64vy1aukzvD7zDI755Rd7e1piPtf1IlR9usJOy5ejb+pUZ9+5c5AQRVBqFuMd8hoMY7iUOHgQO7yQEGfqAw12pEkOfN117jthgV9/BXOoXh1RoTqkpMBOoNs9ytiyBTupevXsH7iMmTNxHl0RGeb04i07dYZdZqicQkL0leOEsVhnbBbBYbp0GH36QJpRo2cFTpzALk1VN5w9i2en00G3bMnxlSo5GVFaYjebCkTsrNWCONu3o/2VV+ztvXsjgluGruiNMKqq9ouJE50RyoKJrF4daHPLotq6tTMpnni+si3n3XfRJntiidTcaiR0nz5YgzIEY1JVMuK86i7/mmu02VfPVK/ulKaYA2o59f5Eau3WrZ3HdOvmLmEePYrn2r27s+/CBTChSpX0Ni2RoThNlZqOS1j8JydgGMOlRnw8pAAi7A49DMI+nw8fT2godK5eKbOZsSsqWBA7FjfmkJgIdUVIiHupTmYs7LAw7Cp1onSwsqB+P3OfPpwaFobdmYrTp/HRVq+u/8D69YNKSy31mZwMO0fVqk7vpo0b8aF5qcvuvBNzViWrceMg5ai6bpHNVY1QX7OGtbvw2rWZr7/e3iY8clSGJDyZZA8iQeRkSev0adbaUIRUKUdcizKbsipOePi8/bb9+AYNnCoWoQaRzykkLfk9iSy1MgNixi5ZtZEII6260x80CM9FVrEJ11p1U7BxI9r/9z92oHdvSJKqZC287dTSqL/+inY3R4sxY7D2VZdk5kCeLZ3xe/lyvE/VU4z5kpYLzQkYxpBdZKSQR0pKYGfRs6drOol0/fyiRSCStWoFN2D//DOYQ82a7n7ZZ89CrxsR4dQFy3j1Vcxx7Fi9yujkSRDo0qX1ZUFPnOCEkiWh4tLFUggiqHMFPHAA99Gli/PaQhWlU4kNHAipQE06J7B7N5iiqsbasIG1u/0TJzg1PNw5R78fthI1R9Jdd4HBqMyud2+noVao5GgdyzgAACAASURBVGQ1h3AtVdNXFC4MpiZDeCDJCemEMV1OSy5296q7bvXqTlXWHXfAiC5j1Chnmg3hNSRLlCInk/oMdTaW1FQQc7UI0bPP4hxqUakpUzg1NNTpPbR3L96nuhlITcUGQlewqUMHxE3ovrsNG3A+XbzDjh14t7rCP2fPQq1Xtar+vI8/7mQK+fPj28pG4Z+cgmEM2UFmg9v+7/+wCBs10u7wbYbbFStAHDKQfI9/+gm2jFq13Os4nziBD6dgQWeCNhn33ov7UN0XBdavxz22bq3NovrHM8/gHlU/dYFx4/BRrFzp7Pvf/3Dtjz929nXtiuehEoodOyBheVWiu+kmHKuqEVq1ArFUvEyOtmkDm4sqOY0fD4YtE4LFi52EmTmgs5bfh2ACshHb78e7U+dft66TCb3/PjtsF3/+yQ5Vm1BlqXmlSpdGPiwZ/fs71VudOjndc2+9FYZ2GUKNpWb4rVbNOXdRMU+dU9u2uFcZycnMpUrxsZYt2YH77sP6Uu1hixbpmaGIidEVt/L7wTSio53qSNFXuLB+wzVmDNaxLvfY+fPMV13FXKgQJxQvHmACY8dmu/BPTsEwhuwgK+Li11+DEJQv7zBaOjx6Mph8j5lBaAVzcNs9HzgAXWnx4nqxmRlE8sYbsZh1WVCZAwRKU3zF5/MF1BOqKoPZe6eVnMzcsCEImErEt2wBA9DZMEaMgDTkJl0JNZBKHITOW3Fp3SjUByqxF4nl5AR3585hV6lKGGInLxfF8fvx7IcPt49t2NDpPdWli1O/vmQJO4zSIg24HBcgvKjUWIHChZ0MqF07p06+Zk1nJbamTZ2pw0XUtfyu/v0XbWpRptmznQGBhw/rU3unMZyNqqH4wgV8C7rMtq1aOVNr+/24tzJl9B51QoLTBUuKtaFzXRXvwS1Ibtw4Fuon2zd9GamXDGPIDrJqYPrjDyzWQoVsnh/aYJjt27HgCxfW77JlrFiBHUidOu7MYccOiNXly7sT0nPnYOMoUMCdIU2axLodms/ng+qsbVscr8uGKbw8VFUJM4i4Zen7xo/HblHVXYtMmTpvIoG2bZ2E48IFEOobb7RPb8kSqFfUAK/kZOwuVXVIx45ON9DEREgXKsO4/nowAhkDBjhTR+jUOcITS645rYtZ2LKFHcZrvx/PTvXhr1PHfv9+P+YtZ6gVKcLV2hS9ejmljQ8/xLVVqbR5c2elOWHPUd/nzTczR0fjPcgQ2WHVWBDhRaU6eAgCriPuiYmQFmvXdkq+J07g2Tdr5rQJBnO/Fl5eaUzD9k1fRgZpwxiyA7cdQGxs8GP374cvfWhour+4a5Tkvn2QBKKinIY1FcuXB5iDWhxF4I8/wGhq1XI3cB88COZRpozeJTYpCW6k+fLZcv2k38P+/SCijRrpU2IIDyzdPd9xB4iYSlyOH0feqE6dnHrk8eNhQFSN1wJid6juou+5B+9AUu35fD6oCvLlc9pKhg7FHGRiItRGKqNt29bpUnnvvWBismvurFkgDvKuVuzGZeIjvH1kzyCh55eJ3+bNaJNzGiUkoE1N7VG8uD31tEjZLRNZoQJTCWy5ck7mOW4c1JWyGu7YMX2Ed4cOcJyQ32VcHCSwO+5wfg/Nm4MRqQFmPXrgPmQ7T7C8WiIIVFcyduRIrAld6vihQ9GnC9gUaWKaNUt/v7Z7KFtWTy+ErSEP2R4MY8gOdDYGy8LvmWe8C9gzg+h064bj7rnHO/JZTr4XbNH4fCBqdevqQ/+ZIV1ERUEycEu6t2EDdooNG+orYx0+jMVeuXK6jtb2IYi8QTpjc3w8dNGVKjnPfeoUAuYaN3bu2MQHrdYlOHgQ9+Nm20hNBVFp1Mj+XoRrp6S28Pl8gQIvqkukuCd51yoM2Wr6h/vuw/uSCZbINyQTHaGak1WLwrNHjhwW9ZZlY6/wYJLbhLurbKsREcpywRpdYj5hC5ClEpGfSnZcEAxEVc/Vq+dUi4kgPDmI8tgxfY4mEWOyZo19LQlpSS24I7yXVLWT2AjocnEdOwYC3rWrs09IHzo1kfDM0hULkhNLSgW20u/h3Dl9RThhkM5jtgfDGLILldO/+ipcAolApHS6TRnJyek6yaNt23qPP30aOmEi9xKbAkuXgjnUq+fOHBYuxMfZvr17UN2332L3fsMNeldbpSyoY5cngpRUQs6Mj9Cy9HYDQUBV/a9QAdSq5VQBTJmC823erL8XUa1N9czq1AkMLm2X6/P5wDyqVHEW0jl/PvAxC/j9sIv0728fK+Iz5GcibAJyXMkff6BNTk2iK5Tj9zuJaVISxsnunoJRyefTqZyEtCE/Y5H/Sg6YE0FjsiFd3NuKFYG248fR9tBD9ucweDB29PJOXwQHqqrKli2hplFzhw0bBtWkGmczZAjaZbfj1FS45latqi8zO24cnqMagOhVSOr4cWgCrr5an5V46lQnM2ZpLQ0ahLV5991OySAP2h5yhDEQUTQR/UBEO9P+FnMZl0pEf6X9FkrtlYnot7TjPyKiiIxcN9fiGFJTAz7nDRu6RxQL+P3MTz7JfsuCuOxmH2AGAVeS77nixx+xi65f311lJHy/+/RxT8ch3CR1O3/mAMF94AEnY0hIwMdUvLg+1mLyZByr5jTy+0GwCxVyHid2birTOHYMagzVcCrPpWRJSGkyRI6ctMp16fcwcyY+YFWVduONYAQyoRs6FHYJmXmePInzzp0baEtNxRxlG0p8vJO4C5dTNW6iRAm76kfYDh54INAmcgLJhm8hRcjqJbHbltuEWkwmwGPG4N7ktSZiMmRpU0hTck3p1FTMWa3F3bUrJE35nOKe0+IN0t/D8eNQL40ZYz+HqNh31132dqHn1zk/bNyI56WzYYmcWLpMBTffDBWgHCEuIGwZGhuXz+cLSLnyOpCRB20POcUYHieiaWn/nkZEj7mMi3dp/5iIBqT9+yUiGpuR615SxpARneCiRRAtY2LsAUwu2DhnDnb5lSq573qZ7cn3Jk7UF0cX+OEHMIerrnJnDsJNdMQId0Yj6t+q/vYCI0cyE/FG3eLfuhW77PbtnVLH+fPQM1eo4PRE2rlT70fu9+Nc0dHOvDcia6yb0Vx4HMkJ1pKTITGkqUDSCZIgVGqgmTCCyiVIhTpIDQCrVw8eRjJatXJ6ApUrZ1eDnT+vJya1ajklkwIF7MZiUTdB9p4SKiLZRiWC42SpZPx4qFlkXHstdvIyevZ01nKePBnvS9bpC48w+fs4eRJEVk2vIZIHpjHi9PcgynqqRuoJE6Cqk207KSnY9deq5Vxrfj+M/8WKOQMbd+3Cd6I4IjBzoKysLjL/0CFsNurV00r7fz75JJhXnz767zQhAc/sPyoxbCei0mn/Lk1E213GORgDEVlEdJyIwtL+fw0RLcnIdS8ZY8hM/ML27VioISHQA3vs8H0+Hz6k2Fh8nF7MJDU1QKxvvdU7+d7332PRX32184MQEARVl8+IGR9Zjx5Y5DqDXUICc9OmnJw/vzNYiTmgOlCNn8wgsCEh8MRR4eY6+tdfYMrqbjEuDh++Lr0BM5hjvnxOl1HhYrtrl13qadECEpeMkydBkORnJQysqq779tuxOZCJ1PjxkBpkQtGhg9NQXaKEcxfasqUzZ1NMDNQjAiK2QY5010VICw8imUn26IFNhIySJZ3xD2XKOL2zmjQBE5Ghq1uxYAE7bA6pqdgcSNlj0z3cKlVynle8RzW6XNgz1ESIzIE08Go0td+PTUGhQk7p8NAhPN+mTZ3fWGoq3lu+fPqN3J49nFikCFRjOjteaiokESJnwr3wcFw3l4zROcUYTin/j3MZl0JEa4loNRH1TmsrTkS7pDHliWhTRq57yRhDZnWCZ86gmhURXBODRT7v2QPDcViYd44jvz9AOHv29E6+t2QJdiYNGuiZg98f8L92K85z9iyOL1TIuXtjZt63jxOLFtV/CH4/PoLQUH1KDRFYJyduY8bus0YN6PvVHdnIkfpKW0IloLsOM+4zIsIeuHTgAOZ27712xiByGakqhE6dYDyXGX2TJs6dtZAuZJ29SLInz3vcOGwG5PM1auQ0kN5wgzOvULlydka3bh3LqjFmDhhjZU8vkaFU9l6rX9+eNkPYDWTj9sGDaJODIM+cAXNXK8y1aOFkeD17wuNNvlfBuKQAOJ/PFwhcU4MeZ81Cu0yQk5Nhf7rqKufuPCkJ66hmTafdQdizVMO234+5RkY67RHMgdQhOgP3+fPMDRtycoEC7gGq06ZxukQqayBiYnI9M2tGGUNYsNKflmX9SESlNF0u1ba1qMDMBy3LqkJEyyzL2khEZzTj2GMeo4loNBFRbGwsLV++PBOXzxiu3bePLE0779tHK9yud8cdVCE6miq/9hqdW7OGNs2ZQxfKlrUNiY+PT59v6KOPUt3Zsyl6+HDau2wZ/TN8uLOGLxFRmzZUZsIEqvHssxTXsiVtmjuXUtXC50REERFUbM4cqj99Op275hpaP38+pRQubB/Tty/V3raNYqdOpe3HjtGh7t0dp4m8/35qNHYscceO9McLL1CSKFIv+u+5h1rMmEHHe/SgzbNn2+YcOngwNVm5kqw+fWjta69RilR7OKRDB2r80UcUNngw/f7mm7a+omPGUIPJk2nv6NH0z4gRgVvq2pWavfcenbrtNtok1ZcOadCAWhQrRufuuIPWP/WU4x7ytWxJzV58kfbdcw/9M3Jkenvdli2pyMsv0/kWLdLfQ1jZstQyNJQOPPII7R4zJn1smbp1qcb339Pvb71F5ypXJiKiyrVqUYX336dfvv46ff5RoaHUgoh2vPEGHezdm4iICqamUhMi2vzuu3SsfXsiIiobEkLVT5+mX7/4Iv2Z1suXj6K2baO10pqqlZRERQ8epNVSWzNmOrtnD21Nayu4fTs1IaKNmzbRiSJFiIio5O+/Ux0iWrN5M52Pjyciokpr1lBFy6IVGzeihjURtd69mw5Xq0a70s5VZONGakhEG5KT6WRaW8yqVVSfiP4MDaXTaW3F1qyhq/1+Wl+kCMWJZ3f6NLX67Tfae+uttEes63PnqNXixfRvr17094oVgft67DEqnj8//RodTf60sfHx8XRyzhwqULw4rS5WjDitPSQhga55+mk63bIlbTp6FDWriajU4sVUa+dO2jR3Lh0X9abTUPbTT6n6jh204eGH6aRUkzssPp6ajRtHiTVq0Lq6dYmk5xq7ZAnVXriQdo0dSweOHEEt6DQU3riRGs6YQUfbt6etVarYjiNmqvXIIxT711/0x4wZdP7gQaKDB23zKb1oEdV86in6t2dP2tmkCb6Tt94iIqIWAwZQVFKSbTydP08X7r6bVis0I9eREe7h9qMMqpKUY94ion6UF1VJbhJD2bLBj128GKqOokUd6hGH4TYpCSI8ERKVeUkEIvle48buXkji+hER2I3qspImJkInHhJi11HLWLsWO5hmzRw5gnw+X6AsqC5p2erV2OX37+9Uq61Zg3vQFecZMgTitbpze+QRXEtVuz39tL5d4MYb8R5kV9k0t8zNqgtlz55QncjqoIMHsbubMyfQJmobyM9NeCzJ/v6JibgXOY2zyAclp5fQ6fsnT4ZNQUb9+tBhCwjXTjlyXeTBkvXxt98OpwCBuDindCAcC+Ta3iKKWX5299+P9ypLwzq7i2iTDdRnz+KeFHXVaiFtqeo5YROTJcLERKicGjd2riuv+JcxY7DW1Zof+/fj2bdu7bRVnDgBiadqVX22VjG/OXP0sUmLF2Odd+2qVwG7GaOFViIH1EuUQ6qkJ8hufH5cM6YYEUWm/bs4wQOpTtr/PyG78XlcRq6bozYGIuiNgwWgMcPP+aqr8IIffjh9sWoXkd8fIH6tW3tnXM1o8r1vvwVzaNxYX7QkPh6pkCMinOmEBb78EvPv29cmtqe75918Mz44NUqVOZCQTU1LzRwoMKR6hhw5go9brc2QkACCcNVV9g84IQGM+ppr9HYdkXFTDuRKTWWuVo3jVJvCJ59grHov11xjj2JOSoKaTbUL9O8P/bmMBg3s1dhEcZ2XXw60CaOrTHyE+kI28DZrZjdwC4OvvBYFsZI3A2rhHmGbkN1cJ02CDl1WzfTo4Yz0bt3aGdk8ZAjUIvJ76dvX6dElbA5KZP++fv3AQGU32aQkEOU2bezXeuklnEOXBVVEzKsV3cQaUO1UwiMuf35nwKTfjwSJ4eH6nGPLloHo9+7NnJrq/Kb/+gt0okEDvd0hORnP281LKYfUSznFGGKIaGkasV9KRNFp7U2I6LW0f7ckoo1EtD7t7wjp+CpEtIaIdqUxiciMXDdHvZKeeALGXSLs6nS+zjLi42FvIMLHcuaMe+QzM4xpkZHQa+vSTAiI5Hvly3sn3/vmGxD+Jk2wU1Rx4gQ8LQoW1Ed5MgcKrEiZLtPvIT4ex8fEgOjJSE2Fd4jOaHfhAo4rXdop0YjgJzXoTHiNqIxGEAtdDAUzvIMqVbLv2oS0IwebJSRg96gGz4kMmvL99eqF9SAzI0GUZWZ9220wLotxqalg6pMnB8aI3bVM0EQaCdmFt21bxLcIiLrK8n2LgjoyQ2nd2n6ccDeV33eXLk6bRunSTg8qtYiPcFOVJaX4eLxzNU11+/awIcnPLD4e+nk1G6xgIvK9eW0CNm8GoZaN88xgMPXrwz6jEmixbnSpNIRdRpeUb+9eSGC1aqUzc9s3vX8/5lmunD6bQGoq4jWE8dmLKQSza2YTOcIYcuuX43EMCQlY9EQguG7pGQTS4hc4JIS5Th1erfO7lvHLL1h40dHeeZP++COQfM+rtOiiRViATZvqmcO//8LXPCZGb3zz+yGKE6UHTtk+hB07QFB1ZUEPHcL86td39q1bh49Z9XpJTcXHX7y4nWn4/SDyJUvad9dJSSA4DRvqXQVF/ILswXL8ONJuq4Rk1CioO2RViah7IBthReEbmSmL6mFy7iKRblomEFddZfemEtHXsspRBKDJxv/One27dZHAT949iyhsmXDWrGl3fRWBbLIqUq1JLZLkyYZakftKllCEOkvOpSUkL9k9du9efboMsQmQEwampkJSqV/ffh9i3jq1YZcuWIOqpC2kMbVGyd9/4z137OhcM3/8AQbYo4eTAZ0/j3VeuLDNKy/9ezhzBhvHQoWcFQWZcT7hZTh7tnPj6aZaukSxDoYxZAYZzWfy+edQexQq5MzNo8PSpczFi2OHFKwM6K5d+KAjIrzFSDn5nhydqmLhQjCHZs301dt27oT7bLlyzhrEzCC+nTqB6Cxd6pR6hFfJ0KHOj0mkrFaJMHOgYpz64a5fD6YxcqS9XahP1Dz9YocpB3sJpKTAi6VpU9vcDl1/Pd6drENfudJJ6Jgh3bRtG/i/SLEhq6iSk0Fs5CR0gujL77t/f0iEAnv3skMSEjUtZFtEr14gOgJCRSIzlDvvdNorihWz794nT8aOXjwLEXgnx1II7yaZYAuXVHlzMWcO2mQmM2AANgOyhCYkGdmG4fczX3UVn61a1b5mRGCjvO7PncP6lCUfAZEWXN3d//MP7lPN0pqaClVl4cLOtX7mDNZK2bJOJuP3Q4JS7TqcxhiSk8GgQkP1pUOZA+7Sd92lV33GxuoZwyXKs2QYQ0aR2doLe/bAdZEIroQuLqry+DPVq3P6jsEraO3ECSzgNAOXa2xERpPvffUVmEPz5nrmsH49iEqNGnrD9qlTcK8tWpR/U9U8zAHXQl1w3N13o08t3ZmYCBVGyZLOD3HKFCdxYsbHGRlpV+2kpOAZ1KmjT+khVDMS81wnIr1lfX9qKtROsl2AGe6ZISH251K1qjOOokMHu0rm7Fmn8Xr6dBAPoYZMTna6gOrqLwwYgHcjIJiOTISGD7c7R4hUGrJht29fe9CacHuVmerMmZiTvJ7Ve2OGZCfXdDh/HmpJ2f7i94PYyoyVOZ0Jb5PzFfn9OKeq+hPqPNmYLe6vdm2cX1br+v2IfC9QwGmHEyo/nYv4kCG4b90mS0gsmnrSvmXLcM9EcADQQThK3Hab/rv/5Resa52N4RLlWTKMIaPISj6T5GSkKrAsLFK1aLyCFd99F4hovuEG9/rLzFjsYpcydKi7TePYMai1giXf+/JLjGnRQu9p8dNP2GU1aqTv/+cf5pIl+XyZMk7mkZoKQhke7izSnpiI+RUr5tyl/fUXjlH1zGfPwoZSr57dJ33/fsxRjZQW6hd1t8+MHWfx4jbffd+yZVDrNGhgZ7oiMleOfxB5jmRf9nHj8HHK+nxBUOVnV6OG3ZtIeOHIaruyZaF3FhBShExkhg2zG7dFIjjZWH7TTXbmIWIRZGbduLE9AZ6Yj2wH6t7dXlgnMRHPXK7NceIE7lWusyDsFzKzEpKNnL+JGY4LRYvyClniERKbnAblzBmoOdWkfcwBW4BaU0SsBVWK2LYNGyidmkhInRrCzz4fmHmvXlqivkswBdXTTeCNN9Dft6/eQ+mnn8BQq1fHPeVQniXDGDKK7OQz+fFHZAuNisIO1WWHn+7R8+yzINI1aninxvD7AzmZ2rXTexgx25Pv6YqSCHzxBa57zTV64v/NN+hv107vOrt6NadEREDfr/bHxQXKgqoVsXbuxOJv3dr5cYj007KnDHOA0KjpKoR0oubr8UqqJo5JK17k8/kCkoTsaikS4MlFaPx+fISyhCBUHrLOW2QolQnjzTfbP2ChDpOlgRYt7JHOQr0jByGOHWuv3SCIqJx/qnt3e+EfkTZDlgaKF7fv6O+/3y7B+P1QacjRxrqCRCJgTH52Q4aA+cvP//bbwVTktXbwINbYpEl2tWT37s7U2kINJUdQM4MxRUfDTiB/a6dOYf01bGhfZykpeM7FijnX5rZtkC7atXNKnHv34rnXrKn/XoRTxIABekng00/BQDt10qcGF8W3vGq6X6I8S4YxZBRunDkiwr0amozDh7GzIUKSN42x1/YhrFgBNUrBgu7xBALvvIN51KplS/lrg5x878EH3dVPn3+OD7NlS707nUg50KuXdoezSRDZgQOd19iwATvpVq2cEo6omDVzpr09KQk72eLFnfUlevbE+eQkhfHxiDlo0sT+MQpbh85F9sgRMO20lBw+nw/3XrCgM+VC06ZOtcldd+H5i+d15gyeoRynICKD5fsTbrvCkC5SaD/ySGBM//7YLQr4/biWnI5j0iTMVUDEU8iMqV07u4unYFRCNSIYjpyypE8feyGeAwfYYT8RRlz53ahuqhcuQBUpx6ckJMAOpybXE7r2nTsD34PIFiur3eLicLwcpS0wcSKetSqh33EHCKbqZSfeg2oPTEiA5KhLAHn+PNZloUL67//nn5kjI+H6rNtEffcdpOFWrfRq5uXLwRS8arkzgwEaiSEXGYPOxhARgZcXFQXR1MsuwIz+xx8H0ahY0Z6EjTVxDPv3wygsRFGdjlxgxQrseEqUcJw3HcnJIHRE3sn3Pv0UO8VWrfTMQYjpw4Y5iL/P5wukpFBLNjIHdpO67JZDh+KDVmsIb9yIZ923r/16e/finajivxD9ZS8vvx+7wnLl9B/q7bdDj3v4cOA9jBmDdyt7QAlvItkrSBBi2bupbVsnA2nY0F4eU2TllAl4qVJ21dHdd2MO8v2VLm03vovgMgGfD+eVvX+aNLGn1xAMXhA1UfVNrslcqxb88QWElCYHlnXvbrdL6NxURYpu2c4ldtOyuispCfeWFpOR/h4GD8Z3Jr8HkdtLLaazdSuehZqJ9bff9JUBxdrq18+5kREehqq7s98fUPnKdSsEduwAY6xenX+S05II/PwzJKUGDfTegMuWYV3Xru1ew93vD0hMISF2umRsDDnIGJj11v9Dh0CYiEAM3HbsMlatghEtLAy7lTQCrY1juHAhPXMpd+niri5ihthbtSoIiZpbRiA1FTtcIu/ke598AubQurW+SI/Y2d19t+2DSleHCX9s3QIVqbZV99yzZwOeH2o+JxHkJ6eIZg6kiZa9l1JTQQjLlrXvxoRHj5oThxnPLq1oTfp7EOmrZX300aPOBHopKSCGsi1EBKLJKdTHjweBE8/86FGMkSON27WDKk9AGERlA3zdunbbhMiXJc6rS5hXu7Y9HbkweApiKzx4hEE/KQn3ed99gWOEoV2oc1JSIAnI6iedm+rw4fD0kdUl3brh/cibHcEs0hiIz+eD7So01J7y/fhx7NR16dW7d8e1ZDtXcjKIcJkyTnfmhg3x7lS72GefBda3CrE5UF1smfGeqlWDlCFLPQJ//hlw5NBVWBR1VLzK86amgsERgWkuWGC8kjLzy7E4Br8f5RYLF8aH72FHSEdcHBY2EXSM8k5Vh5dfhuhZpYreD1rg2LGAN9Sjj+rn4fcHdPdeyfc+/hgfZZs2Tubg9weK8Eiqj/R7SEwEkYuIcMZcJCejLyrKmR573TrcZ8+e9rknJ0N6io52RsKKQCV5jsIAK3+8fj+uGxurF9979WKOjrYbPVu2dJaf7NHDSdRGjACxEsRPxC7IzE9kM127NtBWtqxdnXL77bhHAUGg5OfUtq0926hgjuL+RZEfWfIqX94uiQj7gZAahU1l/378X0gQ8vy7drVnmhUeUjIhUt1Uk5KcdbIPHcK1Vdfitm0RN5P2XH0+HwhgeHhgXsxQ0VmWM5JZpBWRGS1zIBBTdVkWak/VJXrPHqipmjZ1qjyXL8fce/Z0StwJCVgvkZHpUpXtm96+HUyoQgV9ZgKRIr9uXfeyvImJgcDYyZPtc7iIbquGMVxM7NsHg5cg9l5pKZhBbF56CYshNpb/Uhe0il9/haidP79z5ywjISGQznfUKL3BlTlQgKddO73xjBnXCQ3FR6sS09RUqAyI0l07bR/CiRMgqjEx9hKVzFj4ZctCclIjnMVuVjWUb9mCj65XLzuh/uUX1u7u+vfH7ksmKsKVU5fHKY2ZbJ84MdAmChnJ6h6xs5XThYiUziKoLDUVu0aZIIrayXLaZzW9exxHOAAAIABJREFUhCjqIiQEYZCWVRa9e8MjS0Co9gQxFpKRzJCjo+0xCyNHQm0lMG0aJATB7ARDEkzM74fNS2Yuwk1TXueqm+oPPziJr4gul3Xzwo7wxBPpTT9/8QXen3zNw4ex/lXbRHIynmO1anZivmcPxnfvbl8z/8/edYdHVaXvM5NKSCMgNfQSEIlURZp0AQGVIk1ABEEQAUUURX+66+oqq2tb26qIuiBW1BUUFEMTpaOgdBIgQEggJKROMnPP7483b75zZ+4ErLv7PDnPkwem3Dv3nnvOV9/v/bZtw/36F1GWlOAe/Fp0aq1xn0w2+yMGfT4gv5SyASXK98PRo1DONWs6MxKsWiVNtYJxneXlQa4ohdyOeT8/F05/gVGpGC52XKw2tixAAKOisLgWL76w9/DDD1q3aoUObvfdF1yQa41EFD2Cu+8OHgry+YR3qF+/4NDXJUuwQSoi33vnHYQQrr46UDmUlCAs4HJp/f77gV7PwYNQDC1aBIbBNm+GR9G/v936tixs5IiIQLprWsf+8z91KhSY+f0jR3B+fyqLgQORj/GfE8vS+sorAbnl9RQVQaiaYYvCQjxbU2AVFSEBbPaUGDMGgsC06ho2tFcbE8bK8Azj8QzpnDoVqCQnT0ZYhIO9LiigmVg2kVn+CeuhQ+19F8aMgTfKwfg1n/exY3httpQdPhyKnYMwVTPBPm0avGhWt1sWhJ8/Ffe0aQH5nFTG8U347pw5eM7+tDCkRzdj+paF5HRUlL22pbgYVnnduoFr8r77tGPIsqgI4clgyWa29jQUm9ZliiEjA+s/Ls65A9znn2OtV9RMKysLcxYS4lxn8RvDVisVw8WMX6KNDx1CCIbhmmBJJI6CAn3i2mvx/S5dKm4H6vFI74Q+fSom1nv9dQj+yy5zrlzWGtbuhcj3li7Fpu/ZM4BRVRcUIFEdFqZ3+W0MrTUs1/BwHOvvmpP10x/nnZkJ7ygpya6MvF5YdNWq2ZEiZ8/CmrvySrsgJue9iURhmMcpOU7aBhMJNncu5tBEh0yeDEVgzsWNN0IRUKksXqwDwkBjx+K+aCyQloPQTlZOE9vv8yGUYgr1e+6BIOE5iOiiJcqktpkvUMqO6rnqKnsivEsXrXv1ktfjxtlrI3idBDZYFuZ7wgT5DoEF/I7Xi/kw60pY92HyEJ07h/1kopby8nRJTIw9+Z2ejvv2Z9/Nzobx0bu33Qj76CNHYV0uxP2bP61eDQPHv2GUmTNzSiaTW2n69AAjcMO//42q9KiowBoerYWzLFifFK0hC5KSsEedkt1a/+aw1UrFcDHjl2pjrxfxzYgILFynrlLGSElJweaKiUGM80Iw1UWLcO6GDYO3stQaoYW4OIQOnBghtYbwJvmeUwc2reFduN0QIP7K4dw5rZOTtTcyMrC9pdZSLDVpUqAHdeut+My/+vnrr7Gw/but7d/vXIzEsM/LL8t7ubkQTl272r87bBjm2X8zer3wGDp3lu+zxadJDUHkjwlxpGCkpc4iMhN+Si4lUkCkpeH1Sy+V/36Add+kiZ2viPBKKkyGfZh7Yqydgoh02mb9RdOm9nPWrWv3gNq1sxeOLVgAa5WW/969OKdZ2Ddhgh2mSg4lEwgxezbuzwwfMsFu8noxpGYi7KZPh4I26TO0RmLa5bJb4+fPI1SZnGz3wDdtcu4WyBadrVsHrm2G6vyh1FojdBgSAq/Z33vPz9c5rVvjfp1Yhj/7DJ+1a+dMga818ij16mH/BuNHI7dYpcfwByuGX6uNf/oJcVelEPsPYhmUh2EOHYLbqhQ8g4r6MGzZgsRrZKRz83OOH3/EIqlSxdnq0friyPfefhsbq3fvwA106hSEakJCYGJQa0n2+bf3LC6Gm+zkpi9YgGNMAjqtJQ+xeLG8Z1lQWvHxdkQHewqYAmrPHjw/h1am+2fN0jaLW2uE4+rXF6Hn88GiNiGgubnY6CZDanKy3RIn0onPyrLg/ZiC6tJL4WVyXH21vUe0f28Fhp+okMlBRaHK+gOT4iMmRqqVPR7MBT0onw/rxKSjHjDAHnoiyR1DOj4fBKupbGbOxHmYFC8pwdoaPly+4/MhzNK5s7zn8WidmKjPmfxPaWnwnPxhqPv3Q1n4C/rZs3FPpmIpKADqrWFDOwzb50NusEqVwHW7bh3OP3hwYLKZFNrt2gWCM4qLte7XT1vB+pqQo6xDh+BK4ZtvsDbq1AnOmrB8ObyRhATIgMocw3+BxxAaGtiKMtgoLUXcNiwMqBj/Un3tl7j1eIRHKDm54iK606eFO2nWrOA5iowMCGCXC4LVKfdB8r2YmODke2+9hXP07RvAjPrtkiVYyHXrBtJtW5Ykq/3htEzstWxp37SlpZIMNC1Fnw+hurg4e3J53z4IZzM56fViDhs1sivZceMgDPzCfOtWrsRGM8MYtMpNV/6++2CpmUpo4EAgazi38+bhmVNweL24l2nT5JjevWEIcPgXlt10k93y47UQw094KlFI/oqCFdsUEkVFeM3m9gxfvfEGXqem2hWJZSGRbnpu48bBA+V9+qOwfD6sAxNWy4pwc+0z7GUKsDfe0Fop/b0JEJg8Gd6x+ay1Rg4hJsb+DLZuhfEyfbr9u1T4Zn2H1lJ3489ldOwYlF2LFoH5KJNC27/4rbQUHqlSeq9Z5Mjx8cfCahwMfv7ZZ1ibzZsH7iOtMe8LF2IfXnEF1nAlKukPVgxOOYaICGwMpQAfu1AOgWPXLggppeC6GwvOEa66YgU2ZVQUNkywRHZJidD29ugRHANdUFC+aPXttzsnr48fF/K9YGyvb76JBdivn005pKSkwLqJjwdCxP86iooQ1nEKObHJybBh9vtMTYUCuPJKu9I7eBDzcs019u+z+MlEDRGpY4Z1Dh7E7/kVPaWkpIAXyeWSuH1pKZSd6SEQ0mnSbtM7YViDqBxzHgcMsPMNzZ2L9cR7I0KIr0mZ7R+iIVLKn02VCClSRfj3gGYimVXghLdSYLKmgaEL8jMxL2BZEIhm7oDwZ8IsiRQzC+aGDYPyN5/h0KF4jzBfnw81F8nJ4KzSWp6TycektSTZTXqQ0lJQf9SubS8eo/L0L3D75huce9SowAZQnTrBI/CnnM/NxR6OiQm05M2eCs88E7inySxwxRXOxW1aY2+xG6MTbNXjgZJWCs/An7b+NxiViuFih5M2Li4GvUREBATXCy9UXJ3M4fEgROJ2Y4OVxR+D1jGkpwvX0bhxztXIHG+/DaFbr14ghwyHzycMpYMGOZ+P5HshIcEtj8WLMR/9+5cvzvJ7+OYbqe70t7YyMxE3r1kz0Boi5twfTsqksL8Fxvivae0VFiKG3ry53UMYOjTQupwyBR6GkZgvR5KEh9tDFw89hPs1PZcOHewcRBkZ9rBMURHmwaTcphCltcjkMYUMk9ZUSsxLsHcDoZ30ulhPQEgo6T+YcGdlNrmTqCj4fRK5EZ7JZ0BQAz0Urid6FCZCqUsXu9dz552YP8Kgz5yBlWyGp1JTMVcLFsh7rK5essRe+ezv2ZWWAlDRpIm9cI75CjOfd/48vMVmzexAhrNn4R03aWJfo5aFXJg5RxwlJTBEnCi0LUu8kjLCPdue/uADKIVgLMZaC+quTx/nfXn2rMiCBx64MNvCLxyViuG3GAcO4EEqBUvAv0w/2Ni8GZa5UlpPn67XO7Ul5PB6gSpxu7HAK2rAs2MHlFd4eCBzpTleegkLvG1b545S588jPq6UnR/HHIsWYXNfc43WRUX2jfD559gIPXoEWjV798KraN06cFOOHu3cFpRMleb7Ph+uMSbGjuRiAtZkxHSKRx89inky3iu/hylToGQJ4z1+HPNlKicKIpPssFs3ezx+4EA73xET16SI+PFHvCZlOYnpGHKhoGe8nM1ymGRnIpiJcPZMYA0CPQAezxwEk9P/9394hkSMTZli7wVNyg0qWVKOUJERpkp6cMuCwB08WM7Bmhlzb9x7L45jroS0JWXU2ikpKZgbl8veHU5rKcgz4/fHj8PCHzDAbv1PnYrfMVFBloUwV1hYIHcSoa8m3TmPIVDCiUKbObQ77wxs18ti0WAElZaFe6QX4ESqt38/1lF4uHM+sTKU9Acqhp9Tv/Cvf8EKDglBAtKJSsJ/FBbiuy4XErcVdWbTGtZfYiIW9DPPBA8tZWVJsd306cFpuT//HEK1Xj1njHVREQrKKGSdfu/11/H5gAF6nb8V9c47mLshQwJzH2vWQOD072//jG1BExLsHkVBARRJrVp2qz81FQKhTx/79Y0aBW/OxLzPmROIYLnjDjyzsiK88s3MUJFZPX399fbQR0YGjjWpI2hx0wKn8qCnUVBgp5vweu3J3uxsfJ8wSyas6SEwR/Doo3hNZBPx7bS6aTzQ26Igp2DnvEycaO/V0LWrvUdC//523qfJk5EUpbXKim5yKLEozwQGdOpkV5ZFRUAwDRsm79GzKfNEUlJSUPMRHW2HZOfkQHH59/++4QbMo+nRUQn6KxYqKhOppTX2X2go6mj8rXGiwZwotImiuuWWQIoYFokG4x4rLZXw0+23O0cdUlIw5zVqBPae0LqywO3n/P1qxfBLJjs7Wyzb+vWDI4D8x/r1UAwuFxRFRXHDM2eEKXXIkOD459JSoG6UgqsfjKXx+++hbKKjnfsjmwt31ixn97WsyOrMlVcGWjsMhYwfH3gslcq0afZNfvAgwnPt2tnnYvduWPHXXGM/F7HkhH1qjfuNjbXTL2dnQ+GYmPdTpyBQyqpgbV7P4MHYjLwGJktNmOrAgbCQeT1HjuA7rGSngjFhtFdcYWc77dzZTnNxySVClEdFYQqxqCip9M7I0LYcAGsOCGEuS+aWC0xWHtNT69kTQktrzElCgiTHLQsCfPJk+e3mze2oqYkTcQwF2j33QLgyVMb7N6+f4TKzonzQINx3GdptC9FXDzygbePuu7FPTIg2E9tmDik7Gwrv0kvtIcWdO2F1+1dDHz8Ow65588D4P5XfmDHB1/CIEQFC/Uf28OjWzVkpFBQI11pFhldoaMXsyZUFbn+gYvg1k/3NN7B6lYLFfSF6DK0RSpo+Hce0bBk8R6A1FtCzz2KB16tXcfvOd9+FIKlTx7nIRmuEJ9q1wyJ2aoJuku+NH++MfGLi9dprA5UDid6cWheyCM3femMSdcIE+zEMI5gUIpYFBVC1qt1ipGVoCnKSoJkIo3vuKeffsSkGJnop1H0+5C9Mob50Kb5jHnf55XZhW7++HaFz551QcJyn6dOhCHmf3brJb1gW7suMzycmSt0B6bo5fyzsYtiGc8BE5j33YN3wtxo3FjbU06fxXdJ2MJ9AhcvaDP6WzwcPjgSCloWYvVkDce+9geitTp2QZOY10CsiUkprndW1K+bERO4cPAhv2VRUwRo3jR+P3zW5qfLygDKqW9fuhRQVQVlHRwf2QNmwAZ5n9+6B6/r997Fnrrkm8LMlSwBX7dHDOXqQnY014nLZDRoOn08Mu379gierta4scPs5f79aMQSbbKWCU1GYo6QEiIkqVbCxn3qqwuPKBdLq1dj4ISFIzAULA2mNcEGzZlicf/pT8OT3Dz9gw4aFBSf5y8sT6+WuuwLPdRHke/vInDp4sH2jmM3Ojc2vtcYGGD4c8+3vYZHF1VRWloUQRFiYvWDv6FGExXr2FKvO60VStFYt2VglJVC8ZttHMnYOH25XDJaF45s3l3OynSQx7wUFONaEcz78MO6HwnDKFHgvFFxM6DL8QqVKi3DyZFivHC1b2vH/l18uVrvHY59X/4I3/4K4m2+W0JHXaw9rMf/BkOAHH+A14/C0nDnvTGQzP8JEOGPwXi+EsNnIaPNmbYaMtNYAVURHixJgOMqs1tYaobzoaHsimmvONHroNfkXpU2YEEjtblmC8vEvsjxwAN5QixaBnnlFPRXK6n2y27Z1JmxMT4ciCw8PbEKlNY65/npc0223VUyTs2ZNIPV2pcfwH/AYlEKsO1hjb/+RmoqNoRRitUE8AZtAOndOwjeXX+4c/+c4fx4bSymEI5wSyVpj0w0cqMtjoU6Fc16vUPpef73zon7hBQg9B/K9lJQUCesMGWJXaj4fwjVKBfZ/LiiAxRYVZU+s+3xQMqGh9o1/9iysxKZN7ddA3iCTW2j7dmycGTPkPWL9TahpWfJwq1kIprUIQyqtrCxsaBNpdPPNEPwMOdEC5rkY52fRHMM/zCOQrppCgsqHgrJfPzs5Xa9edo/E7ZaQi39O4cEH8byo2K69Ft6h1gJdpUfEsB893PnzIfyo5GfMgGCmgUNOJSpAVkjTGmfozaxbmTAB5+BzO3IEx5gkiAMG6JLYWPuzJazWDBft2IF7N6m/s7KgVNu2ta8/5lb8qVB4z/4hq8xMrK8aNVDrYQ62unXqqUC0Xq9eqInxH/v2QbbExNhDaRzp6UC6ud0V5xF9PsyF2w3lW1ng9gcphmA5hjlzsGAYNglGIWEOy4L1xTzCjBkBkDVHuOonn8DaDQvDJgzmcVgWFmRUFBay2RTFHF6vVBN36hRYMMTx7LNYcB07OtdoLF3qSL5Xfg/cbEOH2jdnSQkEvcsVSFR26hRi9XXr2q/r3Dl4RbVr2/MkGzbgGseNk81jWUClREXZGV1ZCUulbFlIqsbHiyWYk6N1tWrIk5ijtBQb2aw+HjcOisCf6pr3xJBKWdMZnZ1tR+5ojXtiEV1REYQjE5uMmRNJdMstdjbUESMQiuGoWlUEK/sas5nQnXfic45OnSTUQ3pyFmrecQeENuezXz9RIlrDyjXDRF27Yg3wnpOS7K1Ix47FHNMIycyEUjWZXm+/HeubBk0ZA+4hU9g7FSl6vbiXmjVFgVoW5iYszF5jwBadV19t94Q3bMA6HjTI/n5hIRBEkZH2xkRaQxnFxjr3VHjjDayzPn20LigI3NNbtmB/BmMX2L4d6z86Ovge1hp7gnnGUaOwDitRSX+QYtA6+GQXF8Pai43Fwpo9O3hpuzlyc5HAdbux0ZctC4S2+Y+sLKHR7tSp4irovXulgO6uu4KHoT76CIuvZs3g+YlPP4WAbdDA3rGMg+R7SUnlFqbtHgj7u+46+3UUFiJeGxYWWDm+ezcsqcsvt8dld+92bgvK3IWJgDl+HLHpbt3ESs7NxYZr21aU6+7deA6m5c+wi38uhsgiCmrSdzNk4vMh/GeGTObOxT3SAOjc2c4qOnEiBASFcJs2UkC3f7/9vhia4r1PnWoPNVWvLsKWtOAMdU2dCuOCo1EjoZtmDQXXVN++Uo/gT9dx5gy+SzQUlR0t7T17tM0bzM2FVW3WgrDhEuP4bKtqhuF69dK6Zk27tc1Qmxl2YQ2LWURHviqTdqWoCM+9enW7N52ejnlp1sxu9ft8QEO5XIE9HPbtC95T4fXXA4o+bfth9Woop0aNAtlhtRZ6i/r1K+65snMnDNPQUBhwJplipWL4gzyGC0306dNAcLjdiEU+91zF8UCObdtgaSkFq/Lw4Yob9WgNJUJOlKeeCp5PKCqStoQdOwa6wRw//QSh7r/A/K+zTh0oQCciMD/yvYB74Oa94Qb7vOTkCOukv0X2xRewngcPtt8jQzqmIPd6EdKqWtXOc0/UixkqYojFfO+22/BbrG7Nz9eeatXs/EZaQ0nFx0ucn/TR7dvLvDHJSg+KyoOJbxbI0UMh6obXPWGCeAX+HdSIfGFindXQ/O3ERBGunCfe09ixdkrtqCjhc2KnOfJe1asnNOVEVzHMRBgs4ZJUQFSiVF70MBnWM9lWGzSwexSsMKdiYoWyWTWckwNh3L273O+JEzAg+vWT906exP648kq7Z82GUqYFXlyM70VHB/IjMeHr3x+lop4KVFxGsafWhmJYtgxGQnJyIDrQspCLNOktgo3Fi7H/69a1Gy+VcNU/SDH83In+4QcpcmvZUhq2VDS8XgjkmBitIyP14cmTK040a41FM2QIfqd79+BCX2t4BfHxOL8/CR1HTo64pOPHO8Nkjx2DEAwNdS7s2bEDm+WSSwLj81oLCmjYMLtyyMiAtVatWqBHwlCU2TRHa+GPYrJTa1h+1asj5MFYuGVBsURGyia2LFjk0dESqsrMhGIbNKj8dAcoSExKDa0hjF0umXN6RAxP0WJmMSARO+y/QOoKVuUSxskiRBIDUjAkJQnOn/QP9O4IOWUMvlkzIbAjSorC9rrrpIYgP1/b4vS33gqhq7Wgm/gZQ1JE9dx1F9A5nOObb8azo/Ju08aO1ure3d79joqFRWnnz+N4orUsCx5hvXr2Ykkixkx00YgRuBaGC83nbYZ2mYQ2W4NaFpL75rVwMD82Y4bdUMrIAADBqacCjxkwICBvl5KSAuPI5QI6yT8fcbH0FkVFAoPv1SswhFUJV/2DFMMvmWjLQvileXNZKP7QN6eRng5LVClgri9U5MZ8wsW0Ek1Lk8Y+kyc7J5N9PiCalIJwdSLtys1FbFkpJCT9sdwHDmjdsKEujYqyIz44GIoZPtyuHFJTYf3UqRNIp0x4rIleCdYWlNW+JqTzxAkInquuEuF15AiONQurSENQFtZat2oVLHCTeltrWHphYRKyyc3F/Jv9Adq2tSeJp06FIioqwrXHx4tlzxoBviY0lkbF0KHCqcTqZhompLHgnLVpIwJ2yRJ8RgHZp4/0kSb8lMqof38JHREtxCT7vffaE88dO0qthc8H72bUKLwmUR/7aR8+rG1hJ61h3ScmijXPQkB/VtiyUFRKSgqUcHi4fY4JYzbRbazVML3Bo0fx/Dt2tBtchDv7F6qRQvvaa+0eR3Z28J4KNGAGDQoEc1iWTh0/Hp9ff32g0L9YeovUVIkuzJ/vnGeshKv+QYrh10y0x4MFGh+PhXb77RU30ykb3z/2mCikW24JXrjGcewYNptS+DdYrURpKTaBy4WEZTAK33//G8qmevVAa5nnmTYNvzdyZOBCP35c5zdsCMHrwB5bbhGPGGFXDnv2YAM3bWp3o71eeEdut90DO30aAqZRI/scEU1lhgwYQzebtZBNk8R2xcX47UsvFSoGhgb8SQQnTULcnL87dSpeM/lJYUehTGHH8wwfDouYCmfIEFjVWsN7M4XpvHmwir1esfQZO2dymlZ0p06S6PZv3NO5M9aH1iL8eT1JSdKdzp+jqU8fSSyfP29PnrPhDnMgDEnRE2PYjGuSioPC3OPBPPTsideEBTdsWC7EU1JSoMCrVpXwS34+vtOqlQj7Y8ewbnv0EOFaUgKDKCbG7lVv3AhlN3CgPUy5c6czhXZ+PpSqU08F1of4Q7O1xrlp4U+eHCjMTXqLt9/WQcfKldgbcXHBi2WXLg0uryo9hj/IY4iIsPP0VzSysqAUQkKgJJ5+usJQUUpKChYiK0dr1Lhwa1DLggVUtSo2R0UMrF9+idBGZGRwL2P/fghItxvhCv/vWJZY2FddFdAOdOPHHwv5ntOCJ3XAyJH2zfLtt7iHyy+3u9t5edis0dH2hJxTW9CiIhxfo4ZQIVsWrLWICPHePB4IloYNJbZO7P+LL+I5lJRAWbRta7fkGC5i0x7i9mmpnjyJuSMxnMeD50KLlwqHce0nnsBrzmPTpiKoGaNnbUO1akIlTTQRIdM9eoiQZVMkhlnatBH0E63t777D3ERGCpqJhW+lpfgsPl5goOSeIhEfFQFhqu3bS08Fnw9Fc2aHuFmzIJD5fXo8ZISlojO4vXbSkDC9DvIJMaRmFjaaVcFsa2uGUE+cgJfTtKm9aO74cXit/hTaZT0VtFNPBYZHhw4NVApFReUMxmljxwbuoQvRW2iNNU3lmpwc2DNdayhrtj9t1gwGiimrKnMMv4NicMoxhIVhkysFi6MiIjtz/PijhGGaN4c17SCUbYnbH36A4FUKG74iJJLW9laiQ4YET2BlZEhD8REjnKspz5+X0Nbo0c7hpw8+gFBp0sR2bSkpKTi+d28c70S+x/j4qFF25bBqFea4Wzd7E6D0dGzc+vXtiTsKTpOnaN8+PLdevURhZGTAC+rUSX6PvDzz5+O1ZSFMUqMG2jFqLQLWv3fEwIHIqTB00LkzLG8+02uugdKhQhkzBr9fWioU1qwcZoKaLJ4jRkBwaS3Cn97S5ZcLMR3zExR8/fsjmaq14PVpKTduLCgkMwTFWgo+oyFDJHTFHg2k5iaRHtdCt27CKsuwEZO1nFsSveXlYd+wR4bPhzzc5Zdjznw+/L9ZM3k+Xq8+36wZktVmbUhIiL3qmaEcs3L4yy8hUEkpojWEd+fOUCBmPisYhbbRU6G8TwUHFdb11wcaerm5Eh5yot0mvUWrVsHpLc6cEXkxYUJgQyytYRg1bSo9tktLK1FJF/v3u6CS8vMBaaxWTYSrP197sLFypbCp9u0bENIJWEQ+Hwqk4uNhyT34YMXd3Hw+WOQREUBnBGsl6vPBUg0NxX2ZXa44LAtJSJcLFqdTkvu77yAg4+PL6SDK76GoSCo3H344UBHS6xg92q4c3n0Xv3nttfZw044dEPgdO9o3Ct1106Kj8DNj0ETqmDDGm2/GHNB6375da5dLH2Xc3OuF99SypT3swJoFJuIZgmH/AIZyaNUyicu5adlSagGKivBs774br2mJ5+TAi1AKz1RrKAV2NaNQZ/7luuvkM14PBU/NmsJ9ZFZBM6xEapBmzcRbIeKIxk+3bqJ4zp2TqnytpRiP+Y5bboGHRyXCmD7RZ0wIU6lxfkwPk0qfdSE+HwR7jRoSxjt0CILeRCZlZMArvvRS+zohK6oJPyWFdmhoIGOv0VPBNujx+gMp+Nvt2uF8ZRDa8v1wsfQWW7ZAGYaHY+/77xuvF2s4NBTf8/c4fiPlUKkYfunIyYGmjo6G1p44MTB56jRKSmChVauG4267rTyMEBSumpEhlc3Nmok7H2yYrURvvDF4fuPbbxGnDw2FonBKfn3xBa41Pj6webrWuOdWrWDpv/mm/R4uRL7HMMqYMXblQJTHuHH2Yz5Kw22sAAAgAElEQVT5BAt+2DB5n21Bo6PFc7EsnDMkRJKFToVPWVlQoGa9w6RJ2hcaKq47KSFMFJRlQQC0bInjCgsxR2xck58PgUX8f14elDUbzcyeDW+LlnDXrhKGIUX22rWBhHbTp+O11lhHSgllxKhRkqvwJ80z4alz5yLkoLUI5F27oKDMHMK8eRBOHg+uMzxcGEp5HEOqV14puQjSg5DHybLghRDWa1n4fuPGeOZeL9ZPq1aifHNzta5VC/2SKRipXMwOcd27wxNhHsPng+cUGWn3CtiG1PQsLQsehVL2vtUOPRXKB40Z/xyZ1lDCTZtiro19Uh4evhC9hWVh3YeHQ6A79WY/fly8kRtvDFQuvyFktVIx/NqRmYnNFhkJoTN9emCrP6dx9iwERGgoFvff/qbXXohi48svBfE0dmzwLm1aY9M9+qi0EjUJ48xx7hwWulLYVE7nPHwY7rbLhXP6WzHnzpWHjlL9Ce98PkAFlXIm36MFO3as3Sqn5XzHHfbz0Y03ezUfPy5tQQnfzM1FmKtBA4knZ2bie+3by3WwPoCx7ZMntTcyUhA+Ph+UQOPG9msn8odhp7vuwrNkCG/CBCQM6eENHoxrsSyh4+DzvucePKfCQhxv5iyuukpyB0ya0xKPiRE478034/xai8eUlobrV0o4g8aPl4QkBd25c9L8hzUXZrtRoqV4r5MmwVAwQ2OEuNJbooHAYzm/fM0iOH7fDNeVkSpuY3jo1CnMpcmIS8vdLGzkWjIh0998g7kdMMC+vlhoZzYJ0tqxp4LWWoyYG28MXMM7d2KPJSQEdCX85r33hJwyGL1FQYHkCgYMcAadfPghjI+qVfF8nc7zG0JWKxXDbzXS02ENhIZCSdx990UhkfTeveU8SoV168LNrijZXFSETR4ejs358ssVd3HatQshBqUCWomWD1orkZFIzjl5JPn5CPvQjfanEPZ4pOvVuHGBBHrk1BkyJBDNRIF3002yeS1LyNFMy82yhIHWrKlISYGHcMMNMn+bN+N5DB8u79EDoKXt88FjSEgof15HiCuncKMgNwVOSQlyHoRvslKZ4SvWHbBSlwpo2zbMZXi4WPGE2jL0VLs2BIXWeGZ16uD/zHnQM2rUSIrRbrtN6hEYhjl6FN6KUtL+8pprRODPnAmBq7WEjnbuxFzFxUnF8p//DKMgOxuf1akj3hEVNSt5+/Wz51dGjsTc8pkPGIDQVmEhFEuzZjA6TMry8HCtJ0wQ73P0aLxHtNTevfDAhgyR57ppE57/jTfai+Ccks2sjvZPDAfpqVC+Pv3DnlpD0bHA0z+kvH27Lq5Ro2J6iwMHxOj6058C93J+voRLO3QILKwzx28IWa1UDL/1OHwYm9rlgkX30EPOHZv8x6pVOr9RI0x1z54X7gK3b5+4lVddFRyCqjWE9gMPYOMkJgYn//vhB7j0LheSjf6WkWUhaep243v+i9SyUKSnFNx8f8uH5HtXXx04J/QQxo8X5eDzIURnxtK1xuYcMABC34TVcmObJGu09EyhPmYMjuUc79mD12XIoXVffIGN3q4drsWyMMeJifYcD6GpZB7t0wdWu9crrKJkQM3MtKOV+vQB75DWQjXB/MfAgcjraC2WbW6uJHUZD2/fXgrz7rwT601rqag+diywV4N5zODBUvjGquXCQoTRTMXbt6/kL4jCoqVudqs7fhznYDgqPR1rjvmTXbtwLFFGVJamNztiBMIf6elQDIT7sllSaSlChwkJ4p1lZ2PeGzcWw6e4GM/MP9m8YQOUjD+FdrCeCjRoxo4NVAoffQQF1apVIFS8jN6iqFat4PQWy5dDqSQkOIdpd+yAF+xywasMhmgsKkLNiZNSqPQY/ksUA8ePPwqyJyEBAsoJXWCMtV99BRe7enVBVVQULrIsxL5r1MAGnDfPGUHEYbYSve02Z474/HypCu3Sxd4uk2PNGvxmbGwAzj8lJQXhiPBwhL38YXYk32vfPgDqWk7pPWGCbM7SUghXl8veUyE3F4I1Lk4sNcuStqBUfmbcmUnmM2fg+l9+uWw29oRYt07uQSnpimZQNdiuITZWirzojXBO7r4b90rPsWdPJEW1loQtuXtatRKBff/9eJ5FRdJbYetWoahgWKZfP8lNkCJDa4HEHj8u6CIKcrOPQ5s2sLq1xj2QNoMW9c6dMA6iohDS01qs54wMIMRcLvG+qMT4zNkylEnwMWOEWtvjgcDq1Ems8/XrtenNrfv8cwj7Fi1EiNOAMMkKhw3DvZusxbSyzRDV/v3Yi0lJdl6zYD0VyMNlerIcr76KYzp3thtAfvQW3/jDXLW2N9Dq2DFwjxFEEh4O78yppojjm29wP0rB4PqNIKuViuH3Htu2wbpVCm7tP/4RVPOXu87nziHMEBYGK/Cvf60YjXTmjAjzhg0Di7LMUViInIjLBUEQjEBv6VL8dnx8IIZbayzm9u11uTVX5gKX38OGDVBw1asH1n2sWBFAvlc+uBlvvlnc6qIiLPrQUHuhW1oaBHzjxqJk8vMh8BISJPl66hTCF61bS0iD9AyMvRcUIDTTqpVeu3o1NnjnznhmVKC9e+M8pvKdNw8CIjUVQrROHRHwpN6mt/Pss3i9f79Yz1Q8U6Zgrn0+UTBbt0o/6H/9C+vG5RLredQo6SXNeSstlWTriRNyDR98gHuKiJAkcmysCPzkZCEAnDsX3yspQczcDIl17y4wVVKC/Pgjzt2ypVCBezx4Njzn4cOYJ3oPhJnSUvb5cN769csNqLSxY7UtpPf999gTpBgxr8HkNeL9E4qstVBoX3KJHSYarKcC+4CYHqzWuE8qp4ED7cc40FsEAEoyMsTTnzYtsAbi1CmBqg4dGjwcXVAAL9HlgrdEL7ISlfQ/ohg41q+XOoNGjYAc8XNNAxbRgQPSb7lRI2zOivIP69fDImUeIBilNr/bpAkW0J13OnO0HDoEi0YpcMf4K6fCQkmaDRmidU6O/R4OHpTqTn+upg0bYO2Xke/ZBjflpEl2dtT27WERmYpm82YomS5d5PoOHYKQbdtWvDT2BTCZPtnhi5DMsuKvw8S/f/stjmH4h1xHZqgqPV3YdbWW3gekFUlOFpgnE7WPP47naFJKEGK6e7fUBfzznxAcJlqodm3B8c+YAcWrtXggeXmC4Dl5EhYlBTC5kP72NxgfFKheLxQBhXbPnsICy/NmZATCVHv1EupvQl9Z90Cvg4p8xgyh1i4qQtVz166ynomkole4e7f2hYQglKg1hG7btlDMFJa7duG6Bw6UdbJpE37nmmtEoJsU2iY026mngmXBWKBxYioFn08QSzfdZA+1BqG3sO2HjRthOERG2pPmHCtWQHFFRkJxBtvra9cK7f/06fZ8X6Vi+B0Vw29YKGIblgULhbwnSUlwdZ0WkTm++gpWMGP3JpmY//B44O5HRsJtf+aZ4CyseXnYsLwWpwZCHo8kgZOTAwvtLAskYaGhWrdooTf7FwOdOSMK0R/RtHMnNnqNGoHFgkSHTJ4sm/70aYQV4uPtcVuypo4eLedfsQLPb/x4eY9Vs8SyZ2djo152mVhuw4Zpb3i4PfwRGQmhrjUs4GrV7FDBCRMQy87Ohgfkdgs0ksgfJmc7dBBFMWGC9EpmXP/llyX5yyrnpk3FSu7UCaExraEs3G7MD1lss7LEGj91SpLgGzbIb7z5pngs778v77/+Os4VEyO/fe218AS0tsNUmTOhwpoxA/PEGH/Xrrhun0+otanQyJvFuo+8PCg8clP5fFp37YpGPVQCDz6IY0gLkZeHNVunjniLJ0/idZMmEiry+ZA38KfQduqpYFkQ6krB8jcTwR4P1oJS2A/mZxXQW6SkpOC8zzyDPdK0aSAJX1GR0LkkJweyvXKcPy/7tUkTeytZrSvhqhf794sUw29MX+s4LAvhGVr3bdtq/dlnOoUbxWl4vXCRL7kEi/zmmyuGxR4+LCGs9u2dcdEcbCXK5KhTqOuzzyDAo6KcaTfWrdO6Zk1dWqVKYOipuFjqMCZNsp+/jHxPx8QEtlukMJgyRTZiWhqszdq17UV3hCqajXBIDMhQjscDwRofL3FdUkSQUO34cdzDwIG4hqNHIdTIXEqOILNlJMM1TB4PHQqF5/HgGbE6VWtJZqanC+R1yxb8Vq1agjK6+mpRIIMGSYJ32DAR1EQEnT1rTzgzvJKRIcVkO3aIx7NypYTStmwRVNSmTYKuev11rLm4OKHFMGGqzGPs2oXnW62a9H2m0mF194IFWLP79iH0UrOmndacjaMI9Sw7915CkrduhadCpJbWWP8ulygXjwdeY1SUHYjhRKHt1FPBsqDM/deb1lBCZAt44gn72v/66wrpLdavWIGwklLw/v1rD/bsEaNv9uzgIePVq8VYnTPHOZdYCVf9HRXDb0xfW+HwelGw06SJ1kqhoCeY18CRkyOcNlWrImEbjKrXsgBDrF0bwumOO4IjpHJyBG6anOzcSjQ9Xdzlm24KhKweP65zmdy+777A2Cy9gN697Rvk+HGEJPzJ90wL7tZbZbP++CMs7SZNhCLDpFJmMZrPJ21BGX46dAhKqGtXCeVNmoT5KUMXHWQvC8bVeQ2s3B0xAt6YGf/t3x/zXFwsSBomSPv1w7ValuQMXngBlqpSwrs0bBjyJVpj81epgjm86y783+fD+1Wr4lxvvYXjDx6UeoADB4TcLTNTIK4HDogy2LZN8h2nTwty69w5UVa7dgkC6V//CoSp9u8PqKllSU6E+YJbbxViwfPnoUzIZsvf4vNIS0M4iJQdGRn4fo8eMJSKirA26tWTNcN7MpXzbbfhPbPanyE1k0LbqaeCZQmqZ+pUu1LIykJYze228ThprS9Mb/HTTzq/QQMc+/jj9vNaFtZAZCSU1IoVgcdrjX3JQrwWLSrmaauEq/6OiuE3pq+9qFFSovXLLwPzrBTggUH6QpePQ4eEy6VBA8R0g8Ukc3JA5udyAUJZUa7i008rbiXq9SLR6XZDMPiFgNauWiULecAAO35cawjtsDBsJrNSPCsL1rw/+Z5lCSHatGmyuTZvhoBs00Z+w+OB0gkLk6T6uXNw8822oBR+9C7OnYPH1KqV1kVFQIe1bYu5ys2FxVinDix4nw/C3eWSJK7WErJZtEhI5FjjQO6ijRtxPy1a4BlrDW+OLUMJtz1xQo758UdJpqalCUQ2O9tOiEfh/P33QvCWlSVV5CdOiJV/9KgoG8uC9c0GQXfdBWFVUiLK49gxURJvvAEPJTQUwlRr5Jfq1MHayM7GeZmnIS/W5s2Yy+rVhQVWa+RYqlSRfNi4cXh+e/ciDMPwHzv97d+P5969u6xNektm0eOKFVijJoW2U08Fy0JuRSkoF1N4Hz2KcFVkpB1S6/PJdQWjt1i2TOuqVdH0yT8SkJUlPVCuuSY4r9mKFVCIbjfuLZgBeOyYICArPYY/2GNQCsVT69ZVnAD+FWPdF19g41NBXHddxfUJWiP80q4dvt+lS8UKZfNmCDylEJ5ggtR/nDkjxWydOjlzQa1bh0UbFmar6CzPk7zyCj5r0iQQx52SAquwZk17pahJvkdef61xbsJJb7tN5v/LL+E5dekiSebsbGzmhASJ6+/eDWHSpYuEsRiK4PWSPfSee3AP332Hz5lUZjUx20iOHw+BZnosyckID1qWhLZ+/BGKJSpKqC3uvReCNTsbnlVICJQ3E7jvvSeVyP/6l1QLr1olcf7vv5fk+MqVUoS3ebMI9DNn7A19iKYpLIQgYUjqyisltNOjh4Swhg8H6EFrgameOiWJ4q1b4XGEhoqSpHLbuRPeU926cm4ip1j3QQJBoqyoXMsU9vbnnsMzYCiruFhadFKRfPttIMvujh143iaFdnY2no/ZU8EsovRvzLNnD9Z3XJy9P4pJbzF9eqDh5PFgzZTtx2/8CRi/+gpKNDwcoUCn4tSzZwXU0bq1zJf/8HiwzqKisBZHjqzMMVzM32+WY6hSBRo+IQGv27YFqsAfavYrR7lQPX8e4YXYWGyMsWOdaXc5vF64tbVq4frGjw+OSCotxeatWhX39fjjwVuRvvsuNmFEhHMr0TNnpJvckCFanzljT6Bv2oRNEBUlYRWOvXthVUdG2nMSwcj3THd/+nR7JbPbjZwAhf6hQ1CuzZtLEpKVvWyyw+Rl3boSErr1Vq3dbr2dOYnp03Hu7duFGoNwykOHIBDNNqMM7axcKU3vyY80bhxi0cXFAgF96y0R+suX4zlUqQLBUlKCeZ87V2gynntOlMFnn0k+4O23hdhv7VpJ7p49K3kWrxfnZRFchw6wVi0L6+z223GP0dH4v2UhxMG4fvfuuH+tYYU3bIjvMM+xZw+Ob9pUIKssGlu1CoI5Lk4K/nw+IN4SEzGfhYXwQJs1wxrIz9cF9epBMTFkyQQt4dinTuH5NW4sz/nYMWHiZQ4uLy+wp4JlSSMof9qVb77Bs6pTx27UpKcLvYVTK9z0dGmKNWeO1iUlsh88HihPlwsKOVgB6/Ll8N5CQhDCDCZj1qyBh6sU9guNvEpU0u+kGLQOPrkFBXDHW7fGlNSsibh5RT1af8YIQCWdPQtLuUoVLJRbbw3ejEdrbKD774dAqVIFgjVYUd2xYyKAL7sssDMVx6lT4vZ26xbIskrERViY1vXq6R3+bJQnT0JQKAWX3bSwMjOBRHG5gN7hRgtGvmdZ4sJTeGktIZIxY+S7GzdCEFx9tSgMhgwIFdy5E98htUJurtYNGugCCqtz56BsO3aEYKUQZ05g6lTcNxPZbD7DnsZjx0IY5ueLR/Lhh7jGunXhgXo8EMaE0fbsKYR0HTsKPxCFd3o6zvPSS1Ix/eyzklj+4gsR1ufOSbMfXg+L2GrUwPWfOIHv/uMf0iVu0SL5/2uvCUz1/vvh2YSFCZ1H27ZyvcytLF2Ke0xKgiA1c0UM4TBUxr3Fz0nHwvaq3BPMj7BDn8eDdRUVJcI7NxehxdhY8bSLixG2c7tRLMh1RNjp7Nl2Ab9iBfZO8+b2UOf27Xhmwegt1qyBPKha1ZbnSElJgQInEnHaNOc9mZmJsBoNT7M7oTnS08Wbb9o0MDdRqRh+R8VwoWFZWMCDB2NqwsJgWV1sf4YgIyhc9dQpWDXh4fibPTuw56s5UlMFCZGYCIsyGJ/SJ5/AulIKisesCOWwLAjTuDhsRCeM9bZtWjdrpi23G1aq6V14PAKz69PHnrQtLIQLzE1DxeHziZtvYsbNmPDMmXIdDN2YCoO5hIkT8V5pKcIakZHyrBh2Yejqyy/xmj2CWQFNL4IdxU6cgHIND7f3ByDuf/t2qeR97TX8du3a0jBnxgwIoIICKKbGjUWAhoTAyr31VliuloWQXt++mNfQUEnuu1xIwhIttXy55CFycuy1Dn37QhGb3eB4v2vWSAL7hx8kr3HggMCBN2yQ72zaJGgs9nO49looUo9HKraXLcPzjo4WyG1eHoQsczY//YQ9xAR0mfdzfPhwvGaLzg4dxIImXxY90ZIShJNCQ0W5lJZC+ZrGgGVhjfAZm+v4rbcw9x062PdXGb2FbtAgMCzq86Guxe2GJ2CGXS1L7503D8cmJIhiModl4R5q1MAcPPKIswdfUoLnGh0NRf/ww4EIpkq46u+oGH6uxj1wAEI7OlqXW9UffODcl/UCI6hi4EhLA77a7YZwuv/+wOSuOTZskAK1K64QVI3/yMtDyCIkBOGDt992zqNcqJXo+fM6o29ffN6zZyCcdtEiLOqGDe1K1OeTHMKAAYKcCka+Z8aGZ80SOmcqDBOtwlAK+XkyM6EIGzaExW1ZOHd4eLmVlk4KjvXr8XnfvrBCT56UHsSklZg9G/PGfEZODsI1JGhr3VpI61jNfvasCOTlywVFdOCAWN1ffSWomrQ0CM369XGehg1FiFarBgVJC3/pUnteYcIEYV1NTob3xyY/S5ZIovrkSUFClZYi9FW7Nu7hllsEpnr99fCKqLjDwiD4jxwRniTLwnpr0gTHMITCDnqEIW/aJPTZ1apBGJd5bbp5c1BilJbCM4iJkXAqSQKZ1zAptIkcMnm2qPR9PlEoc+fa1zjnrE8fCV350VsERAbOnRNvetQoO0ovO1uMs549nUO7p06J4urUyc7pZI516+DVKwXlG6zBTyVc9XdSDL9G4+bkIHbfuDGOa9AA4ZGKBLffuKBi4Ni/X9zJ+HgIPSfeI62xGd58ExYawy0s1vIfu3bBiuMGcWJyJBNrkFaiKV9/jfeiomAF+bu6W7bAi4mMFG59jldfhZBt08audF58MZB8z7KEzpvhAAoxUxhYFoSoaV1u2QLh3q8frO6sLMxPixZa5+Xp9StX4jk2bQrr+sABKDTi9O++G9ezfTuQLlFRUAQcd92F+zh6VArPtm4VZM9LL8ECrFYNgpsFZv/4B9YRmTaZi1i+XHik8vNhfBDx1LQpnmlqqi4PA7Gojp34yM9Upw68GyqfjRshKOPiME/duyMWb1l4RmQqrVsX1n5eHp7bHXdAYNeqJR7QvHm45/R0hH94n6dOQdlQkfnXhTAPQcK+KVNg+GzahP3AGgdWRH/3nf3ZaS2J8QcekGfOfITJost+5ffcY89dMTw5cqR4JA70FraxaxfmPjQ0MN+wfj32f2ioPnzrrYG5OUKNq1XDunriCWdD8tQpWbsNG8K7rwj4UglX/Z0Uw2+hcb1ebOSrrxbFMmNGIO2Dw7hoxcCxa5ckf2vWRGw5WIFMXh4stchI/D3wgLMy8XohiOPisAEfftg5AXb4MBAstObLrKnye9i7FxaqUhCUZlHb6dMyP7Nm2V3n1auhcOrUsXsVTuR7liUIkDlzJFzE3Alhr8XFEKYREeI10eokn87XX2MDTZqEe2A+gVxC9DxWrYLwrlED90/ElMslFt/RoxCSd92F70ZFCZVz69ZIUGoNkEC1arj/Jk2E0C45GYKvoECqixnO2bEDQpW5giuuQBLZZFFlOCs/H5916gTByBAUPRE2funcGc+9alV4H1Qy//iHndOJCfx16wQqu3w5hGZCgnR/u+YaodaeNQtzQWvfrCTPzLQ3SiKyqgwGu+vJJzGvt9yCY81kM4nrGOozKbRJaXHXXVJJzQ5u8+c757JmzBABHoTeonwsXox7qFvXXldQWirV6E2bar15c+CePn68nGZfd+niLBdKS+HJxcZiDz7wQMUEnIWF0m2x0mP4HRRDsIlVChszGO1tsLFzJxZeeDjOMXAgkoNBtP7PVgwc334rMM/ERCRjgyGNjh7FJlIKwnfxYuf8w6lT4pW0aBGIxdYaxz39NDZJQoLWy5bZ76GoSOK5HTvaE9clJYIK6dHDziK7ezcsrqgoe8EbE4NJSeL1mIlECoKiIuQSQkIkUZiVJSRqTCrSgiRVQlkC9EdanjxvSgqUS4sWOEdhoQjXDz+EIImNleY+WmOOo6MRbmDB17lzkgs5dEji8F99heRzdDTW2PTp+H9pKaz9wYMFvvrOO1Lg6PMh9Naxo/AgPfWU/EZBAYRur164RqXg1c6fDyXh9cLqnzRJwkuLF0ti+IcfhDH15ElY1LVq4biRI5G78HgEypuSIl7RY49BCIaHi2AnbxPrRyZMkNaqZ89iPbZujbnOyNDFCQlA3uTn43e6dcM8MoG9fj3O36OHGC/Mr0yeLEqBhY/33y97j7kdpezotwroLXRRkayZXr3sa/bIEenRPnFieVipfD9YFoyR2FjcQzCqmm++kf4p11wjIUqn4fXCO09MxPfbtsVe/CURD79RqRjMEcxjCAnBvzVqIDZ5sT2eOTIyYHHWro3ztGoFweJX1v6LFQPHmjWw/pQC7G/JkuBJ502bJGzUoYNjOb/WGhZyWWW2Hj/eOem9dy8sV6X06Z49AxkhP/wQIa+YmEAyvX/9C4u5Xj17DcbJkxB4brckN7UW8r3ERHsrT4YOGDvOzcV9RUYKDn3fPljorVpBSBcXYw6io/FMy+LZpVFRENz5+ZjHRo3gXX31lQi20lIIsSZNcB56FOSxYjJ44UJ4PgxvsWcBEWNVqkB5kroiJUWS5jt2INZfrx6UEY9jeIotX5s0geBUCjkZCvPCQgiLwYNx70phvulxZGfLNRJqu3s3BGm1alg7PXoIGWHVqlBg2dkQnIR5tm+PubAsGBMxMZjf225DDiI1Fee64gpY2Xl5QmNOKpJx46AkCA3u3x+cVUQXEbzA9bNvXyCFNr3AkSOlJwY9AuY+tMb1d+2K+WSXOK3t9Bb+FcapqZKvu/dee+hnyRII/NhYOzW8LtvTqanIUykFT9mpf/rp08I8kJgobLhOw7IAiSaVRqdOQiczfbrIq5AQ4bz6maNSMZgjWI7hrbcQlx0+HItXKSysRYsq7n/gP4qLcS5C16pVg/VXZv3+asWgNRbNp59KGOeyywD1c1pkPh/umRbHyJHasW91YSFivWFhuOZXXw1UOGWtRH2hoQgj+LcSTUsTi2ryZPu87dgBpRwebu+/m58v7LKzZomFZZLvURCbaJN58/A6MxOCIzZWcOMpKXiG/frBazl+HOdKSoIySUvTJdHR2GweDxSRyyUbzKjMLWdsXbgQxyYk2Kt6+/SBUPd4IBRbtcJ19e4Nz8OyJJl77pyEetLScN7nn5ekaGYmFNSYMXaeozvukByB2w2vhzH34mJYv6NHC0Jq9WqEMHr1Egv+s88QkouKwnNs3hxJ1ZwcCJf77rN7N/SWtm2TuooXXxRq7XnzsI5CQ2XeSGPx5pvifTVpgrX14Ye63HLXupw2Yx+RYcxDkP01MxPHmhTa772H3x4wAPPt9Ury+aGH5Jmkp2NPhIcL5Ql/Ixi9xeef49nGxkKBc+TmwlhiWIi1BBw+n94/ezYMj+hozJH/vmHoNj5eqskrkinbtkl0oEkThPe4t//XUElKqQSl1JdKqYNl/1Zz+E5bpdS3SqkflVI/KKVGGZ8tVkqlKqV2lf21vZjfvWjFYCKR2Izm/HkAACAASURBVEMgGCrp9GlsVnICxcQAD04itIsZlgWLZMQILOaQEK1HjtTbn3/+t6uq9vmQbGWP6CuugFBwOn9BASzeqCjE4e+7L5AHSWtY1cwrdO3qyAK55bXXxBWeONFOF1BSgnO7XNiAZlV3VpZYVbfdJmE7cgUpBdefeREn8j3LEsuSCcZjx4DmqVVL4twMfUydiu+sXYtncP31Wvt8ejetf6Je+PtffilcPj174thBgyAwTM4hel9M8r75plQLr10r/9+0ScI2mzdLrwMmf0eNksK1VasQWmjfXryRDz8UivLSUjy/uXMFyeXxwEKfPFmE786deO/mm8XCPnwYz7NLF3hqSmGNk2Zj/XqExqpXx+907iwewrhxuP+8PCiB8HCg0SZNwlpKT4egq1cPFrfPJ9f8xReBfbi//RYCcuRIABk2b8Y5+/TBbztRaH/+OZR1t25Yy16vCGyzLez+/Vgz0dGYV+6TYPQWvFaXC4aWWWS6eTMEs9sNxeOfPD54UPJo/fo5N7zavFmMxN69K45EHDkiIeAaNeBF+4e2/9dQSUqphUqp+WX/n6+UesLhOy2UUs3L/l9XKXVKKRWvRTGM+Lm/e1GK4ZdqWQr3m2+W45OT8cCcagGCjbQ0LMz4eJyjY0dpyvJbjNJSWEMNGuD8PXsGL2ZLT5dS/Fq1IDicEBWLFkFIhIYiXm0kxlJSUi7cSnT1apw/MlJopnmtZMOkkOJ44QVswvbtBQabno4YfESEeCiWJZBEJhr37sVmatRIjiWTJlk3WRT22GO4B5KyrVoFYdSiBeYwN1f4h956C5s5JATfLyjAfV19taCkLrsMLn9+Pp4xYY1VqkCJnT2L4+fPF4F++jS+V6+eFLE9/ji8puhoCFOlEKdmWCkzE8/k9tsFwVRSAqE9e7ZY+ampEHQPPQQlEhmJ5xUVhfMzwbxlCxQKC/RiYvCaIamFC6EkGVLKyMC5pkyBAA4JkWI0KoKNG3F8eLhQpA8bhte7d0MoN2yI53TunN744YeYg0aNMA9OFNrsqdCuHTyc0lIRoCxE1BqosBo1oIToZVZEb3HmjLATT5gga9zrBQowNBTrwT8E6/ViLVWponVcHOoY/I2xM2eQdyJ32bJlwQ3CM2eAvgsPxzlZZOg0/tdQSUqp/UqpOmX/r6OU2n8Rx3xvKIrfTzH8Flo2JwfColMnHBsRAZd/zZrgMX7/kZ+v98+ZI55InTpY2P7tL3/pKC6G0iJtxqBBwasrN2+W0v62bZ0ZX7OyJH7buHF5QxZbOGzLFinb928lmpEhVMYjR9ottXffhaCqU8euxFasgGBMTJRCozNnhHyP8FcTmsiE49atOLZ1awhjnw+/63IhPGBZECgul961cCGUQevWmK+MDFinbrewvHbuDCFz9iwEo9sN4ca6ABZZ0TtYtQqCMiwM5xszBuEJjwfWcFIS5ot5AAr8tDSsxVGjhE77+HEI4blzJR+xdy+E6C23CCdRSYlULNMLYpJ50SKAIS6/HJ4fPZvbb0cuoaQE5xsxAhQUSsEyv/9+3OvJk6LI9u7F+y4XlMLYsXh+GRm41ipVcP2WBcMkLg7gBl47GxcxVPvdd1p7PPpccjKOZRiQlj3pvLdvh+JLSoIyLS2VngmsW9EazyI6GgqGydyK6C22bIHQDw9HoR8/O3ZMvIAbbwwkz9u7V/bNtddK32oOnw/AkIQEPJe5c509c62x/h5/HHPldkMpsw2s/9izR6qm/8c8hhy/1+cu8P0rlFJ7lVJuLYphf1mI6WmlVMTF/O5FKYaKtGwwNsOKxq5dEBT0AJo0wSKtqHdC2UhJScHi+fxzsVYiIuCWO9Fg/5KRn4/kZLVqIpT9m+9oLRWZ9DRuuME5abZ2rSizESP0N2bcVmsgOYj7b9zY3krU50P4JTQUm9bsrvXDD4jDh4XB2uXm3LkTAismRmiencj3fD7p+7tgAY5fswabndW/hYVIPlepAisyP1/r5GRdEhMD133PHgjg/v1xPnozX3yB5xESgt84cwbz2a8f7rd+fYTuLAsKuU4dfEZr+7HHoEiVQr6ABW67d8PqHz9ewkVLlmDuW7SQ5PeaNQgR3nijUG188w0S5WPHihIoKBAhOXMm1iRDU19/jTkfPdrO5NqmDe6XVc2vv46QYFyc3NuAARDCiYkI/+Xm4tzDh2PO2Lxea+DwIyKg4Pg7L7+M/VCtmkBl6dEsXIjjSInBZC6bD7GynV4geyqUlopwfPxxWUfLlmENJSeLBxqM3oI1OuHhEKZmD5MPP8T1Vq0a2I+ktBS/GRGB7xgFouWKYdu2coCG7tEjeDGb1wtkGPN+114b/LtUCC4X7mXo0D+857ML3w0+XC7XV0qp2g4fLVBKvam1jje+e05rXS3IeeoopdYqpSZqrb8z3stQSoUrpf6plDqstf5zkOOnKqWmKqVUrVq1OixbtqzC6+48erSKPH3a8TNvVJQ6062byuzTR51r317p0NAKz2UOt8ejamzYoOqsXKmq7dyptNutznburE4NGqSyO3dWOiQk4Jj8/HwVHR1d/jrq6FFV76OPVO3Vq1VIcbE617atSh8+XJ296iqlHI7/OSM0P18lvveeSvzgAxXi8aiM/v3V0YkTVXFt+yN0ezwq8f33VcMlS5TL51Ppw4apozfdpHzGdbpKSlSDd99VDd9+W/lCQ1XarbeqE0OH2q4xbvdu1fLxx1XkqVMqffhwlTplirIiIpRSSsX+9JNq9cgjKiIrS6VOnqyOjxqllNutQvPyVKtHH1XVN29WpwYOVAfnzFFWeLiKyMpSbe67T1VNTVUHZs9Wp4YOVe6SEtXqL39Rl2zYoNImTlRpEycqpbVq8fe/q7orVqi08eNV2qRJqsbGjar1ww+rc+3bq92PPaZC8/JUhxkzlMvrVTtefFG5SktV+2nTlKdOHbXz+edVrdWrVdLTT6vD06apE8OGqQ5Tp6rQggK19Y03VMO33lL1339f7Xj+eRW7b59q9sIL6ofHHlMR2dkq6ckn1e5HH1Vnu3RRDZYuVU1efVVtffVV1ezFF1WVkyfV5rfeUleNHq1y27RRB2fOVF1uvFEdmTxZVU1NVdV27lTfvvee6nrddep0v36qJCFBNVq8WG1ZvFhdOXGiOjB7trpk/XrlLilRh2bOVB2mT1e7H31UNX7tNVWUmKgKmjRRjd58U21cvlx1u+EGdXDmTBW3Z4+KPnxYHRszRrVcuFBtWbRIdZo8WaVNnKjCcnNVnc8/V98uXaq6DRumjkyerHRIiGr6z3+qb5cuVR2nTlVnu3RRGf37q7Z3361+evBBZYWFqcv+7//U7kceUVEnTqimL7+str/0kqq/bJlK2LpVfbd0qapy4oTqcPvt6uhNN6njI0aoKyZOVEWJiWrns8+qNgsWqPhdu9S2V19V7pIS1WH6dHWuXTu1+69/VbVXr1Ytn3hCHb7+enV89myV8N13qs2CBerslVeqHx95RIVnZal2s2Ypt9erdj73nCquXVu1+stfVM1169ThadPU8dGjlVJK1V2+XDV//nmV26aN2vPoo8obHa1qbNyoWj36qCqNi1O7H31UFTRtinVeXKxaPP20qr16tcru1En9tGCB8sbFKXdRkWr2wguq7ooV6nxSktr7wAOqKDGxfF1XTU1VSU88oWL371dZ3burg3PmqJKEhPLPPRkZ6rJly1TdTz9VpfHx6vD06ep0375KuVz2Dam1Sti6VTV55RUVfeSIOp+UpI7cdpvKads2YO9GpaaqRm+9pS5Zt075IiPViWHD1PGRI5U3Lk7V/Oor1eS111REZqby1KypjkyZojL79v3Z8qFXr17btdYdL/jFi9Eewf7URYaSlFKxSqkdSqmRFZyrp1Lqs4v53V+VY7j3XrjlcXF4r0YNhEPWrbv48BDHwYOIaROuWqcOYsp+jKlBUUnZ2bCkyGnUpAnimMGa7vyckZmJ5GpEBCyrGTPssX2OkyfhubhcCKG8/HJg/uHgQX2WkL6OHQO5o/xbiZqU2+fOCad8//6CEfd6hWCtUyepiD5/HuEwpeCR+Hyw3Aj5u+MOvGfi2IlOIcpl1Cicf88ehCSSk7U+f15///jj0hbU55MQx+bNCDOEhOB38vJg2TGH0Lw57qugANZ7cjKOz86GpTl+vNBmEwkUHo7Pr7gCc8bQ065d8DKSkyWUs349zjNrFqz4evWkP/TixZifgQOlwIvoptdeQwina1d85nLZKb67dEHi9pNP5HeuvhphJnokn36K64+Lg6fVuzes9YICrOfevaWGgdDQzp2x5vPysJdCQ+EJcv6ffRbz1rIlznH6NOY3IkLrPn3QF4MU2u3b4zwZGZhbtnctKZF1w3yRZckcXHcdrtekt7jySju9xcGDmGfCgU367qQkvD9/vj3vV1KCkF1YGGSDiQ7SGs/9jTe0Jz4eoaBZs4LnBrZvRziRe3vZMmcZs3s3vER6CPffL4V+HP9LJHpKqb8pe/J5ocN3wpVSa5RScxw+o1JxKaWeUUo9fjG/+4tQSf6TWVwMd58NRZSCMJg7F+7hz0ERlZZi8w0ZIljjnj3xe4WFF4arlpYCYke20uhoLLiKKLkvdhw/jrh8aCjuc968wEWnNRYxezi3aYPwhjFSvv4a7n+tWtgQc+YExlG//BJKzu3G4mZxEl35yEgIFMbptQZcMjoaSokopNJSgagOHw4hZfIokXzP5xOFQUgkaSPY32HVKjyTQYMgkBinf/55CO4GDbBpc3OlcdC//y31B3/7m7TIfO45IZsj0+bs2ZjbI0dwb4MHY/0ohTg2aw+YZ3jiCYSEXC7JCzz3HATkNddIhW1Wli6Pu3fvjvVELiJ2i1u2DPmSG24QhcL4/s6dQvVNAyEzU4AFU6ZIwjsqCjkWXs9jjwmyafVqrOv4eCh5ViS/8QaMKaUQXkpLQxiwZ095Li4XQlwZGdhbDRtqnZWlN737LhRG/fowTMyeCps2QVCTa+jvf8c8e72SX7rlFqyRiugtPv4YRkFCgoQmfT7MZ1gYQk5+a1zv2CHIu9GjA/OAu3aV79Gc1q2Dh4FTU6XlbfXqUJROoJPdu4VoMphC0Pp/Eq5avUzoHyz7N6Hs/Y5KqdfK/n+TUqpUCSS1HJaqlPpaKbVbKbVHKfUvpVT0xfzub86umpeHDTV4MBaNUrASH3zw5xe9nTiBjdW0Kc4TH6+P33DDxecStm6F4AsLw8YaMgQL+NfCXQ8dgmXocmEDP/xwoGdiWUCFkBdq6NDypF65cmOBk8uFzf7RR/Zrq6iV6A8/IGntcmETEC3y00+w4EJCJGFoWfCeSHSWkYH32JSG5Hs+nyTLCWFkfwdWOpehjY7fcAO+P2QIBOSGDYjhh4QguVlUBLRRnTrSkyIqCkKvTx8ImawsCOOkJFx/aqpg/NkDOTUV99mtm+QfnnsO5+7dW3IKK1dCIU6ahN9v1EioxtPScF0LFsDT6txZ6wceAMstvYJ//xvHT5smnsMDD0ivCaUQF+/YEZ4Coa1r1sAaHjNGPJmNG6GMw8NhdbdogSQueZ3+8hco6Pr1ocQKC+ERsK9C794QbkeOiPJ88EEo8B49oKR27NA6J0fnNW4Mob17d2BPBY9HalyYVyoqEu/hvvuwDkx6iwcfFEu8tFSef8eOAic9dUpAEdddZy/WLC7GPIeEQLmbNQ1c07NmYV4vuUTrN97QKYTFmuPsWSjh8HAYQcGQRv4KYcECZ4XA8b8GV/1P/f1utNtaSwP23r0lgX355UhCOWGWgw2fD4nAsWO1j8qmY0ck44K5nuY4eRIL/pJLcOxll+G6fkni3Bx79kjr0OrVEcry52spKsL9xsRAQd15p95gUlhojYQyi+0GDw6cm3//G5uMlMNUAvn5EgLq0kUoMHJyhNFy/Hi5z+XLIVQaNRIWT5Lv9eiB48yip0cesbNyPv00jqG38dxzOIZtQU+cEBTOG29AoIaEQDmnpUExXHcdwhv0lChgSfk8ahQE3Z49+M6CBVKMduQIlESvXvBGw8Oh5NiwpX9/IMSIq2eR28aNEuYcOhRr8P77oRhYXfzVV1L81rgxEtTDh0OoU+Bv3Sq8TFOm4DpZwPfhhxCuzZphTqKjMfe8v3ffhRdTvTqEP72t9esFOrtihSTZX3kFhkR0tLToZOX6kiVQEv36aV9ICLxG/54KxcVCZ/H885jb3FzMnfksg9FbZGTId6dNE36xzz7DPoqMtAMetIaSZR+WiRPtkHTLwvlr1cKzmTGjnDwzgCJm4UJ4VW43vBgn1lVTIcTEXFghWJaE/Jz+/lvhqv+pv99VMZjj5ElgykkxQWH2/PN2PpULjA2ffIJjKEirVMEi3LDhwp5AURE2OV3c6tVhiQSDuF3s2LoVm565kRdeCHR3MzLKcdklsbH4jokJLylBqCUqCn8LF9q5nCpqJbp0KTZHfLzw2ft8ED4uF6xVVpxu3QohHhcn7v8778Dqb9cOMWyz+Okvf8FrWplvvqm116uzunbFxl2xAkKcbUELCyEgo6Jg4TOOvXy5FLd9/DHmIjQUyJn27aGsPB5cH8M+Q4ZI0R0V1f33QxGQMG/FChRA9ewJ6zYsTCqIWYn8zjvwSm68EYonKUnr++6DUGVoiwL+mWekuvrSS6HIZs6EgCaB3erVCDUNHw5sf1SUhI7+/GcR7t99h2fVtKkQDi5ciPUWFQXBRlbakSNxn1FRWEtFRZiXhATkjKic2B+hzCDYe889gT0ViouFhO6FF2T9tWuHe2PYJBi9xcaNCA9FRorCLioSxZScLIaF1njm8+ZhPSQmBrIF794tRZ9XXCE1EmUjJSUFa+zNNyVHGAxp9MMPgAdTITzwQMU1UcXFgB2TktvtdlYMlR7Df0gxmOPwYViB5DFxu2HtvP66c9NwY9gIt7ZuhTUTE4PzJCVBuFbUoIfHrl2Lwh2XC5tlzJiKe0FfzFi3DiEPpSDoFi8OTD7v3Kmz2X/60kulgTtHWppYesnJdniq1kiEspXok0/K+Q8dEp6a22+3W3hxcTiGiiAtDZZdaKhw869cCSXbogU8D69X6IwfewwbrE8fCOVPPtHrVq6EoImORoiLCeMZMyD4qleH9X7+PBRxzZowDi67DJv/8GE8tyFDBJZKTp6rr8Z3mOh9910I/hYtJL/wyisQXLNmIfZfpYqEXRi7J/Rz4UKEWPr0gRHRoIHW8+eDmuSdd/Ad/haF+gsvQMnMn4/QU/fuUEqsIVAKoaratSGo6AHQq+nYUbyRl1/G9deqBY9ywgQ8v8OHpY/FsWMIX8XFwUImI+4nn2CdR0TA8y6jVWHYJ2XNGntPhaIiARxwPg8fhnKKipIcgRO9hWWJYmzaVEKXu3fLXp0zx85OvHEjnotSUPamB3/+vPQwSUjAfDkkjHctXCjGGufNf/xchXDmDAwJ1iQlJ2M9LF4cmGMw6Vx+xqhUDL/n2LMHbiBJ6MLDYaUtW+bIh+KYfM7Ph0XFhHNoKKy5lSud2RnNcfgwrLDYWBzbuTN+Oxjz6oWGZWHztW+P87VsCevW2BApX38Nq5m5k0GD7HUSlgVrt149LNrbbrMrzIwMiR2brUQ9HgnzJCfLOQ8cgBJyu6U9aE6ONBS6/35cnz/5ntcrib+//hUbvVMnrSMi9I6nn4YCqFcP3z95Uoqr3nhDUEKzZkHAhIXB42Fz+7vvFobTL7/Es6tbF9Yn6arffhsKtlcvSeB+9x2UxpAhsKyTkkQp0Ysgnv8vf8FznTkTIbp27TCXNWtqfe+9CEvyvMuW6XKPgUJfKVibkZFYI926weOl58Mw0TvvIITUs6cog8WLEdqqVUtoP559VhTbffeJIvvHP4Tv6c03RUmxC2FiIpRZZqYkxMeN09rnQ66HnkpRkdT2vPIKnv2uXVBeCQmYu2D0Fnl5UuMwdCjetywoyMhIzFlZgabWGntu9mwBo5ggCNb31K2Lz1nH4j927BCKl8aNMY/+iuPnKoQDByDkCYIZMADXZkYTpk8PrM36BQnoSsXwS8fPgYVZFjbNnXdKw5yqVWHJf/ppeWjmgqikn36ClVKjBs6RmIhwhj95l/84fx4x82bNcFy9ehCGFcUtKxpMPrOquV07uNiWJfdQXAyBEBsLq2rWLPuiP38eFprbDQGzdKm9ecpbb0kr0RdekE312Wew2KOipNCIDWmUggDIz4fyIwf/6NEQLLt24bdIvuf1Cn3CE08g0diqlS6tWhUbe+dOPKcOHaBseveGdbt9u1i9n34qcfT330d8PiQEz7tRI0FuKQXkjM+HeWvXTqzjLVsgoGbOREgjIkJQSkwgP/kkPJiZM/Hcx4+Hh3LdddKlbc4cCJh588BMSkVAeCjPyepsCuJFi2C0zJsHBZCcjPuLiEBoiQpx2DDMPYnzHnsM3kpiIpRely6Y37Q0CNsrroDwi4jAdR49CiFO6OnVV0ubVX8KbbOnQkEBFJHLJSSLa9dibSUmYl8Eo7f46SfMt9sNZe3z4TnTcx0wwB7u/fprMeRuv91erf/TT1JI2aGDsxfObntKaV29uj5w++2B/Uy+/17Wa0wM8jrBFIJlwVtnV0G2knXgKdNa/2YJ6ErF8EvGr4GFeb2gmJg6FZtEKcRCp0zRO5966sJegNZQJB98gEXtcuGvf39Yl05NdTh8Pli7tGSqVIHwDLbILuZe3nxT0Eldu8LaNkdmJixZtxv3+eyzdo9l+3YJE/XrZ4feHj8uCJG+fSUBnZ4u1AQ33QTFYFnSrKRNG3galiWWe9euEAgm+V5KCgQI8xsLF2p9/LguqlULScj9+zFfbjeETkaGtAUlpUL16lDMHTpA4bAi96qrxFJ/5RVc/yWXQNDQkn//fXgbs2cjR1Cjhgjiv/9dl1v3jRtDKHfrhvvo21dqFtq3h8ERHQ1LPSxM67vv1t6ICFE8VBDkhyJ3Eb0PUm6/+y480nvugcC97jqsD+YZQkLwGZPo9GJeeknu9bXXcExICMJEHTtijtLTcf3R0XgG7HXx9tuBFNplPRVODhoEgd+3L57rokV4/suXQ9m0aoUwVTB6i3ffhWKvWVNCOF9+iVxZeDiS1DQ4zp8XfqymTe0V+vn5kuOJj8e8+e/Ts2cFNBAZibnOybEbe6ZCiI2tWCGUlMBY4t6oXh3fryhnuXu3s1JgSOlnjErF8EtGMK3MnrwXOzweWNo33SQ9o2vXxqb59tuLg54ePYqNTuqKGjVgZZkJNKexezc2MBt79OsHa/znFu/xPl56Sbyhfv1gBZvjhx9EISUl4bd4f14vku4xMdjwf/5zYG0DW4kuWoT3vF7ATt1ueEIspvviCyig+HiJOb/3Hs7btCmEvT/5nkmn8OST+ru33oIQb9gQyunZZ/HZvHkSE+/bF8KyalUoqV27IBSGD0eoRSlcd7duEEz0Gh59FN5LrVpQ7KNH41rJZLp8OYTAmDEQzsOHY33UqgVvoWpV5DpiY/H8LrlE0FK0su+8U3spnEJCIFBcLlial1yC8yUm4jwxMVIvQQVBhfH66/id8eMFYrt2rcBuO3SAV5STg/XXtq3ULMydK57Ue+9JkeKSJZIfmTMnkELb6Kmw7rPPBPXHRPGrr+L3O3eGx7ttWyC9hccjHl2XLnjeHo+EmVq1ssOjV63C9btc4qFw7X3wgSSNJ00KrFkoKkIIMz6+vAOgiTRKSUn5eQohJwfeIX+zRQuso2Aow6IiKFeGmoP9VXoMf4BiqKjTW9++EHI/B7KqtdYFBXrPQw8BgRERoctjk/fdZ6enDja8XgjFkSOlxuKqq7C5g/WD1hpW9GOPiVBv3hzXX9ExwUZhoT44fToEm1Kwsk30hWXBAmdCr39/u7dy4oTA9Fq2lEI2re2tRAcPlurstWsRGgsPF2vx8GGpZH30Uby3aROET0IChNeZMwh1kHyvtLS8efvB6dOhaGJioECysqSQ7p//lNDM/PmiBB55REI177wDZREfLzDCe+/FdbMAjMKcFOD//Ceu78YbUW8RFyf/kjyP52cfZHI3UXFR+M6cqUurVIGBERcHS7hGDcx3x44Q6P36Iadw9dVYs5dfDkUTGwvhaOYoVq6EchsyBOcKD5c5WLRI7mX1aiT+69dH3UdYmFCHU2hu2wZjpGdPWOmdO+P1d9/ZeypkZwPIQIVl1qYMGAAr/qOP4M00aCB7JD1diOxmz4blvX+/0FuTBVdrPAcWvrVsKW1ftYZXQzTe5ZcHNu7x+XBdNMgGDQrcp7t26UwWg8bGQnEH6wGflgbPj2CTnj0RpgxmqO3bh+8z6tC8ORTKSy/9JkVulYrhl4xgHkNsrBDKcUE9+CCszIuwxMvdzpwcxHSvuUYqpFu3hvBxIrLzH5mZcMeZA4iOxqbfvDm4F1JSAoFGyG1cHASEU+OeC90DseyxsdjY48bZQ0QeD8Ib8fG4vxkz7IVEK1fCElUKwpGfObQS1Vrj88GD8f0hQyD08/OFaXPYMFzT4cN4PuHh2CjnzwsVwTPPQDlQMf397wg1RURgTs6dQ+iG2HqGHd5/H3mKkBAoqSuuEOUTFgZre8IE/CYTzw88gGuMigLq5tJLERpifoHII1ZYE6JKcjyGhObPtysGvj9tGrrQ3XILFP7w4VgLSUn4f9WqUHQREdKgh7mLYcMw94MGQQDXry+exDvv4JgpUxCua94cHmvVqjiONRkffgjFXKsWQmu1a2PeU1NxvgYNEBIZPhzr48MP7T0VynqCW243npPPJx7AuHFYP070Fl9/DQVWtapQWb/+Ou4vIcFekPbvf2Nu3G7MI9FIBQVQvOHhWL/PPRfYa2H1anhHSkHh+Bex7dpVXgNUWrVqxQphyxYoz5AQ/I0dGwB5te2bZcukYK+sb4Ves8berIeGGUNQ/62Vz/+pv/9YjmH/fmjvHj0EW1y3LuCnK1faIXHGcEw+nz4Ni5FQUaUgRP7+9wszx3SlggAAIABJREFUtloWLLdJk+R627SBEKwo8fzttwhxhIbi+m+4AULvIkJbtns4cwaWcpUqwkRqFvScOQOBFBICRfTUU1IjUVAgvYkTErDB+fv79okCGzkSioFwxLAwCLh16/DeU0/hHlq1wnHZ2bKx/vQnPAuiXx56SGuPR2fSM3nmGSCsQkJgYWdmYv7i4pCY7twZSnfzZoSpGjTA3DHZSsFOGvGRI/FHiomZM6WwTykJsbz4IoTbxIm49v/7PyjRSZPwfVI+3Hkn/l24UJeHupTS+pZbIJBGjYJ31r27VBUzIU/vglBUIof4/pNPCmXJVVdBCcyfD2HMnMWSJdLT/OuvobCHDROP5uOPoVwiIiDsevaUZPPdd4sCNnsqpKfjet1u9N72eAQgcOedeF7+9BbMJbndUEA//YTnTCXfq5fU85w5I8nhyy4TBlXLwvXS6Bs/3s6npDWeOdFujRtDgZsG386dspbKPISAgk+t4d0vXy57OjYWz448YP7j0CHsIxaxNmoEJex/ff9rlBj/qb//ClTSmTPY8LTUlBILa/Fim6V8QVTS0aMQAqwVcLmw2V555cIIo9xcfI89I9gs5auvgnsz6ekQDLRA2raFJxNEsQW9h5MnRQhGRCC2bNZj/PijQBGbNUPcn0pg926Jn3bvLrmT0lJsjrAwWIkff4z3t23DOdxuCH6vV6gdYmMFBUZ8PJuwGOR7a1etkqrv556TcBFbn9aujc25axd+u0ULCMbQUBxHQb1oEeLnLVqIwH3rLVzb3LnY8KySjopCDqBFC4R3hg/H71x5JRTQoEGCZurbF4KU10xPglb1hAlQDNdei+8nJYlHxSZGDENRmRhhKB0SAiVJ618p6Q0wfDiE76WXCmJq3jx4t9HRmN+QECgMzsNLL+Eeef8Mjc2ciefFngqHD0NYhoRovWyZXr9ypYRzHn8ca9yf3iInR+DNN94IL3D9engmoaE4joniDz+EFxMaCmVLI+TwYSmaa93annjWGmEe0sQkJMBrNUEe/grhoYecK5/z8wHfJTqwYUOcy6knQ0kJrpeKiB0Gv/gi+H6tpMT4L1AMv2QUFcFlvu02iem73RB4f/sbkp4XO/btQ9I5KUmXu5WDBiHsEKz5B8f33yP+zJ4MjRsjThysSrqwEEk/UgLUrImN5W+x6Asot9RUCDO3G8pxwQJ7DcPKlRL+6tNHmvH4fPj9atWgCO6/X5Jx338vbv2ECTjf+fNSo9CzJzyrtDSpv3joIQgLWss9ewqqRCl9ql8/KAtu9uefL0fK6KlTIRCrVIHAXr0am/a660QQvvACrOxq1QTP/8ADyIV06AAhExmJ6xoxAt7AhAlQDrS2aZVzvkiMN24clFxysijTsusuF/pjxqCnRM+eWFv/z953x0dVpe+/d3pJMqmTXgm9944gSAcbCqKuqIBtrVhAsSy2XVEsYF3LumJb0UUXG6LEAlakSJHeO4QkpCcz5/fHk5f33ilJKEr4fXM+n/uZmTu3nXPPeZ63nffExorzk6XtCRMAYiNGoA/17w9tKDcXxNO6Nep31VV4LiYf/vzPf3Btr1f8JDNngjTS0mBu4zk3rAndfDPMaSYTTH6rV8uaCmvWwDdgNuPaBw+qwhYtcOwrrxjTW7AQtnIlntdiQXtVVkpywdxcCYDYv1+0h44dxfFcVoYxZLeD1J54whgxl58PzcZux/u66y5jf9UTgsdjIATDeNizB32W/QHdu6OOgSYqpdBPp09H5BQR2vJvf6s7g8H27aFJgQXI4yyNxHC6it8Paem++wTYiDBI77wTzq76hK76/Yi5v+MOiWRwOjEQPvigVulelZVBHebYbJMJkuX8+aEnwfn9GPAsfbINXWcTrVPrUQqkxlFA0dGQ/HnCX2UlgDg2Fs8zebJoF/v3SzqLnByZWV1RAUAwmwG+n3+OZ33tNYBafDyiv0pLZenSkSMhbc6dC7Bp3hwSPNvJ+X+OjZ8zR0xD06aJJD12rCwL+uCDkHAdDtiwHQ5c5+KLAS6c0XXmTIDZ9dfLTGMGdw4lnT5dZq3r9/PiQyNHAvw4uR6TCJFSY8YgNUmXLsZV8ohkLkLXrtBMPB5oTxaLnK9f9pSX60xOhkmmSRP0V14C9KmnIIV37iymrfffh0aVmQkTpMOBe/34o8wLWbsWoJeYCNNSjx54hnnzAHLNm2Muxvz5odNbvP46+nlKCvZt2QIyZtLjEOa338Z5Nhuc19yvP/5Y5iuMG2c0y5aVoe4xMQDVCROMZp7ly6VfeDx4N6GyGqxcqfYOGSKJLi+4AM8aaJKtroamNWKEhJ+PGIF9ociDS34+ghbY9Blua9QYGigx1MfstH27Wn/TTVAdOaooPh6d8oMPQs6UDio8w/eGG8QeGRWFa3z2We2dbNMmAB9LKomJkJB4KcTAsmEDnKUcZtunj1Lz5iFldX3L8uVCMl4vQIaJLD8f5geLBXV47DFR37/8UiKbxo0TzUW/lOg11wAc1q2T3FNTpuAas2fjus2aQVL9+msQUXy8UkuXqvW33irJ9w4ckKR9zz4r9v3HH5dZwvfcc2xZUPX222i7Vq3k/1mzEG1yzjkA5JQUSOJWK7SoPn3QLzp3xnl9+0LyHjwY4MURSlaraEJjx4I4O3aE5sCzr4mUOu88EEPLltK+LNn26AHJ3G4XkmQTFPs0rr4a/7N2wGYlBv558wD87dqhPUwmaHSaht9jxqB9P/kE2kB6OsA/ORm/V6yQNRW++w4StMWCfr5mDQjD41G/Pv20pLdo1Qomn/Jycfz37w8n9ptvon2jotD+SkFKZxNTt24S/bZ1q+xv0cLoOPb5oHFzpNGwYaK1KgUBrC5C4IR2NSagap64GCpoZNcutDGv1pacDIGgtojG8nIQL6+VTYR+/OCD6GeNPoYzhBiOwyFkiEp6912AAC8RardDinjxxXotE6qqqiA5s8mACGRx/fUgj3B2yqoqSLvnnisRUWedhQETKpa6oAAdsmaSW1liIiTicFEYocrSpZLtMj0dIMMk9vvvAm45ORgUvGTmAw9gcHBIZ3V18FKieXl4bl4gqEsXDNJvvgEZRUTgmuvXA6zsdrX6vvuMyfd27pSZss8+K9L3K69IdtYXXwRQxsSI6WTyZIB8VJSYrVjyv/VWWbaVM6Uy6bBjlqOOBg5Eu/TogU3TxDR09tlwoiYlCYGNHKkqPB4AnH6GL+eVYpJgP8sll+AZW7YEGcbFAdxzckBaTZuiHTIyALKsVc2eLdlEc3LQ3hwh9cgjeKd2O6K72rTBPZYsgcnK5UL/7NoVpDZ/PvpBTAwAcvlytZ21ysGD0c+2bZMJX3fdBfMfa5C9ewP0/X74hKKjoanMnIl+UV4Oc6nTiXv/4x/GZJBffCG+u06djGsw1IcQysvRH9jcmpys1KOPIjGmvvDSveedJ+Nr8GD0wXCpanw+CC+TJgkeeL0g9J9/NmogjVFJZwgxhHMIZWQEHRrSDFNZCVX6lltkhjERBtSDD0KiqU/m1Q8+gEmD86ykpwOAli0Lf/6ePYid57xHHg+0kV9/DT62JtIin81iLhcA4/ff62yiY2XRIok2ys01Rn1wjDwTFT/D+vViCuvWTRaO//ZbPLemoe1KSzH4oqMhXb7zDgCf1+GdNg3SJzu6H30U5gZOvrdhgxDUnDmQCE0mhKsOHAhwe+stXL99e5GuZ89GWwweDI0gKQnA7HRCMjeZoNXwugbs4OWwUF5rg01FNps4qIngV4qKgkTN7TBkiKqIiYEWxGTRsyeOITo2X0MNHYp+yGs3EwnRsZbA+ak4Bfrbb8v6wm3b4lx+Ts69NGSIOJtfeQXXtlggcPTogTq8/z5A3mpFsAG3dW4upPvA9BaffYb6REUhoueHH0BGJhOAuqoK5p5hw4Qo1q9HX/j8c5BbjZnNYBZasULMbVlZ0D64z/36q2gXHg+k+0BCOHgQpB+Y0C4wzc2+fSBLHsMJCSC32sLPV69Gv2QNxuVCRFVt2v8pikxqJIY/utQ2Ge688yCBrl9vzDMUrvj96CyPPGJM8Z2VBWfyokV1J8grKkInGTECg5UI9vX77w8P4j4fpL5LL5XJd506IawyYM2IxYsXA5wZxFgl/+yz+s3k9vsBFJzxsm1biVKqqkKES3w82vWqq2BG4nz4CQmQwm67DRP0iotlYhovJbptm9iiJ06EZsNgOGSIUrt3q30MsBMnQuPg5HsrV0r0yjPP4B3Y7QC8Fi0g7b70Ep7tkktAOtHRYpLhxXEuvxznjRmDQTtuHDQOIpCC1Qoy8HoBpGweY8fxwIFifmAg7NVLIs4GDgQx2O1CZs2aycQvJhOvV/5nABw6VGZlJyWBzHJyIAH36SMmMI5qYg3or3/FcyYlGaOO+JlffBHPbTIBODt1Qv/43/8QqWQ2Y9+KFcfSW2z4618hcPAaFJw88aGHcHxmptjsX3oJhO9yQWvx+UAAnKSuaVNjtt/t22FK0zS8t1mzxFRZH0JYvx4mLRa0hg0LXijL51PLH38cGiaPtQEDIJSEWqlNKVgDHn9c/I484W/u3LonnVZVCUEFbo0znxsYMYTTGCIijP9lZKg9w4ZBIgucdh+u7N0Ls8uoUZLawuMBKL39dp1pvtWhQxiwAwYIgXXsCHs+5yUKLPn5kII5lbDTiQH2zTfB5LZ/P6QpXuu6ZUsAe339JW+/LZJet26i3h85An+B1Yp2fOQRaEWHD0ucfnq6hLAuWiRLiU6bhgE2bRrq3LIlZqy++CKul5OjfnrpJQnfHDQI2gcn31u6VFI/P/kkpPDISNwrPh4SLztv77sPANyzJyT8yEiY9jRNzDj8+eOPIDbWBNhEwsCanS0aAZNBYqI4Hs8+WyLU+vVT5RxxxpFLHKXEUi0LFgycrVqhja1WWW6TfRBsOmPSmzQJ733YMLRr8+YCss8/L85mJsR77jE68Tt0ACl8/LFEe519NkhYl97iW54HQYTrr18v9R07Fv1gyxaZpDhgAPwQFRUIU3W58JwPPSSgn5+PQA27Hdudd4rZc9ky0bCY0PVjiFPajxqFurJWF5h+5uBBmLC478bGQlgJJ3gVFsL8xTmh2CLw9NN1r+dSWgon9ZVXSnLNUFtjrqQGRgy1qXZ+P2YEP/+8UhdcoCrZkUuEwXP77VCDA1dOC1VKSgBOV10ljmeLBYPm6afrzsC6ezeAjk0rrI7PmRN6DQiOqrr2WvFhNGumNk2eHNyZKyog0XNagpgYDMhw5KMvVVVIzcARVwMGSOqCjRsFcDIzEQLo90OK5MVLzj0XkmNBgYBs27bQahYuBLg6HMhHs2SJUsnJcBi+/TZMIxYLTFh5edDMIiPxThiwHn8c++PjYUqy2yFZjxyJc9kkc8MNklcpOVlmBnfvDjI/91wB0q5dUZ+4ONFQ+vQByDVtCi2CCOTM5rXBg4WAe/cWYmApnQj+DpcLoMzmkx49xJHPvofLL8ez9+sHrcLrRbufdZak1nC7YZLi+SJEMJ9lZkKb4XxLl14qBPPww3hmux2OadY6LrpIJgFyeouff4a/ymbDu3nvPfQbt1vWApk9G78jI3GMzwdnMmtY550n/T4w0uiKK6T/BRLCjBlGTZgT2nH/jY8H6ev7ud8P4Wj8eNGU+/RRa+++O3RkYGUltCX9WvLZ2Yiuq8v8euQI8EM/N8rjwb3DkUOjxtDAiEGpek+GW7xoESTHhx+GdMfRSbyQyaOPwtlUVxhrdTXAc+pUsSuzpDh9OqJ3akvRsWkTpCwGHbMZYPDaa6GXGy0uxmDlmZwWC0Dm44+Nz8qgPWYMAMVsBiiECuELLOXlIDivF/cYMUL8CV9+KZFHffqgjSorITU6nRg8TzwhjvWkJDzjjBnGDK4XXaTUunWqgEnl9ttBHh4PQHzBAkm+9957MD1pGt6L1wvymj1bHZNomzbFeePGia+DTVR8DJHY/BcuBEmxI37ECPxu3VrexdChMv+kRw88GxMDm/m6dRNi6NNH4ufbtxfQ5OR+VqtoKW3boh2jo2ViFRMg5ylijYx9DtdcAwm/Vy9xNr/4oqTQZqf/XXfh2g4HSIFDY6+9VrLidu8Ov1bN+WWJieJ0JYJPYsMGCASsOQwZAoDfvVuisnJyJKGezyfjj4/neQx1EUJBASR/FkqaNw9OaJefj2g6blePB9F6NTnCDBq034+Z8TfcIAAeF4c2Wrq09jGwaxdMdOecI2ap5GT4YD7/XExTc+cKbvBmtTb6GPRbgyGGepYgH0NxMSIYbrtNgI9V0zFjMIB4harayoYNAMazzhLpMTkZUTMff1z7XIfffkMYKzvNbDZIYu++G1KT+fH116Gqs9aSlgYpKFBj2bYNx3GURZcu0CrC2V71bfLII3LexRdDwqquhlmNieOKKwAWW7aI6adDBxDvoUMyP6BLF9Tx738HUWVlqWVPPy2+iYEDQVxZWSCZ11+X5Hv//KesE/DAA5Iri6OJOBtqt24AlaQkAJrLhXfhdoNo0tMBEIMHY6BbrWg/JloGL6tVZgInJcmEPZNJzExESnXqJMTQubOAotcrJqSkJHG0N28uGhaT1YABkMRjYvBc2dl41uRkiYJq3Rqmx5q08YoI7yYmBu3A0VXXXotzeH4HO9OnTxeCGDsW74VNa0OGqF9nzcKzaRratLQU/djpBAC/+ir6yxNPgJzsdrwHBm59pFHHjrLgzi+/yDOEIoStW0HirMH374/nZmGKAf6KK8SE2707nidgTCxevBgmsPvukyAOhwP9VrcWS8iybh1IU6/FN2sGkv3++9DCHc/L0RODflJgPUsjMTSgsuaee2rXLDhme8IETOTiF5+TA5B/773aV4BSCoPvjTdALNzxXS5I+K+9Ft6/4ffDeXvzzWKyiIiAqWDBguAojIoKRJ4MGyaTds45B4SiTydQXAyzAycfTErCQK1rCdMjRwAsbjeA8corQTaFhRg4NhvqNWMG7vHee7Lq1vXXAwgClxL99lulMjOxXvI//oGIGrsd72LhQgxQ1hDYrv3YY6iXpsG34HAAjFl6ZS3hoovwTGefDcDt3h3HsuTLfoM338S1evWSkFsO0WzeXMw+7duLJOv1ikO9xkl7jBhatBBbN5upOINn795iijjrLJBdmza4h8kkxMTrIZ97rqz9YbHInAqOwLrqKvRFr1cmA44fDwJxOiU/kKZBEtent1i/HnXSNIDoY49hedKUFGiEa9eKCW3kSEjQX38thDZ8uET4rFghBMrjyOcLJoQHHzQSwo8/inmM68fp3JVC33ruORHSIiJAeqy56sv+/Uo98wxmb/N7GTgQY6ywMHSf9vnwDNOmGZNxdu0KjW3t2ro161OUFqORGBpKmTsXi6voX2ZtYWZ+PySK2bMhUfJg1zQAydSpGFC1aQPl5YjUuP56iXLRNADGY4+Ft3VWVyOEdtIkMWvExio1ebJaPmtWsKlr+3bYobnTxsUBMPUptzm+m00XHOOvz5sfquzfL3MCrFZI+nv2QJNix2p6OmzEBQUAOU0DAb3zDhz47Kfo3VupZcskid6QIWiftDSA+D//KfMHrrlGbPLTponj8NZbAbD9++N6drsAKCeDY9LgiKDu3WVBmb59cV3OTMvPwk5ebj8GUSJIogyQNaanY8SQkoLzuG/l5Ih5MSlJzvN6RYPo1w8kFhmJ9xEZKYDO70dfF6cTRNatG74zKYwaBROL0wkSbtMG133qKWN6i/nzoQHExuJ3jRnrQJ8+EuZps8n/e/ZIIrzMTJzv9wdHGj3xBPq/nhBiYoyEUF2NUG4mQY8Hmqw+2eMvv0AjYhLt2BHaemDqmeJiEPvw4cfmKBxt0gQkGC6lRWUlNJnrrxdhz2wGicyZEz6xnr4cPQqNhgk81NbofD5DieFkmb6qCs7Tv/0NnZztkE4nJLzHHoNkE8634PdDOrr/flG/WXW9/XZI06F8GxUV6JTjx8vASUkB8Aem+fb5IHlffLHYQXv0gHNZH4q3bh1MKuy0798fg78238rOndCaLBbU+c47oR19/bXUp0cPaD0//yxmmKFDIWnqlhJdf+ONsOfa7QDP//xH7PA33iix/UOHSvTQNddgMPPsXyL4CHJzYU/u1Uvs7lYrfjudAOrUVNlHJKu3tW4ttmj9O+3YUbQ2TufBoFKTkO4YMbjdIA6e0W61QuLlgIGcHEkN0aePLJbE4ZIXXgigatkS/pK4OPgiYmPxmZGBe3M6hylTJLlj8+Z4h//+N/pxRIQ4gOPj4dBns1vnzugH8fFolxdeUD/985/i8L3wQoDrM8/g2W02RDuVlEB7vPNOiTS64w7Y/n/+Wcg3JgZ+M5bWi4shVLF5JysLhMVgf/QoBAG+Pyc5/OknY5/miaSXXy79Pz0d9frtt/DruM+bB3Jjk6jTCYHg3/+uW+uvrsZzPPSQ9Ce+Bpu2GjWG/0+Iobb5DlOmQKqpK3RNX4qKANg332x0QCckQMp7+eXao4K2bwc4cq4XllSvuAImolAx1cXFavW990ICZztnkyYYwPoFe5SCyWrWLHm2iAhIZfqV6/LzQWg8wScnB5FT4VRxpQDyl12G9oyKkpDDV18VML30UvgennoK93U4oKpv3iwmiIEDoS20bIlr3XWXLEfZrx+ey2yWtBBEsJMPGABTBEu0Y8YAlHJzoXmkpgKks7JARDxfg+cgJCXhe8+eEpPevLmsT+HxGHNrJSejjbm9Y2OVatJElTPgEOGe2dky0zY52dgnOJW41QptU9MAhGwiY62la1fcp3NngGDPnkaNaPJkXKNrVwgUbjck6/h49DvO/8SZWdkvctVVkuaifXsIMA88AFNSQgLMgEuWSL0HD4bpqbwcWkFsrITXbt9eOyHs3g0Nj4kzMKHdypWysh0RtJw5c4wmJxaibr1V+pTHI/NedMLXMWI4eBB9cPRoAe/YWJiF58+vO/Jw2zaEC190kTw7Cwl33omQ7LKyxglu9dnOKGIIpzGwFMS/mzSBdPLCCwDb+i7FuXs3HKeXXy6dmTWC66+H/TfcvIfCQgyeyy6TTmm3Q2V+4QVDio5jA4HBmGcI8yBjAObCq6txFk+WlJ98UlKSV1UBHFjdj4gASOsX/wksv/0mpp64OEiq+/eDpOx2SFf33QeA4RTbrVop9fXX6vfbbsM9oqJgU+Yw1169QCZOJ8D26acBIMnJcDSzFsFOfr7/uHECmHY7tBWTSUw3XbsCtKOjxbZ8111C5GxCiolBP+FIpIgIEAY73Pn4rCxVoScGnjOjf++5uaJF2O3i4IyIEIcvT9Bzu2XeCs+QZp8Ik8IFF6BdWrdGH42IwDvke7NzevBgSNgpKQDIBx8Uc9Ytt6Av1Njw9w0cCLs6O6jT0iBpV1fDZMNkOXgwyOSnnyS8N5AQVq6EUKNPaLdkCf4rLUVUHfsw7HaMkyVLjNrBli24Jr8jqxVC0Lx5oU2227apDTfcYAz6yMhA3/3qq9pzlxUWYmLnDTeIX4m18QkTYBoN54e77joRAsxm/D7O0kgMDaXU5mMoL8eAefxxgI0eCDwegNGMGfAp1GdJTp5B/eSTAHdWgXkt3enTYYIJFTFRVQWp6NZbxQRBBElzxgyo/4EOsn37oLazqYQltaeekiU6lcJgeOklASmbDVL4F18IAf7yCwYtD/BRo4JnnOrLTz9JOGpKCoB+wwaJvklJgfr+4YfHNJM9w4ZBImTz0YgR0J4iIwGUTzwBULLZYHpLS5O1mNlHwzZ5DvvkkFSWvrktOnYEEHk8YtZISQFYNmkivh+rVSJ7GLzS0wH2DDpE0DLS05ErSd+X4uPxzPyuLRZcm8khIUEAyG43hrA6HCDJ1q2NGsSIEZI2PioKz5udLetIW604h/0S114LLdFiQd+ZOhXX9nrR/nffDSBLTlbqgw/U+ltuQXtbLCDKo0fxrtkM2KEDTJN6QoiNhfBRWIg+8emnQmZuN0yB7KReuxYaNZNo8+Z4Pr0p5/BhWbub27JvX2hCgSYfvx9zMGbMMJpj27TBmKot/Ux1NcycM2YYzYYuF0j4yScxka4u53OjxvD/GTGoekQlcfH70blffx1mjDZtxBTFqQVuvBGTtOrjvKqoABHcey+IgYHG7QZxzJoFCTywU/r96KyPPgqzAj9DZibu/8UXweSybRsiftgsoGkwv7z0knGgrVqFQcsx+FlZkC7ZKbhnDyR+Dott0wY24XCLpufliYSenY22+/prMeF07QrQueMOLCkZHw+Nh5cSjYnBd7Y5X321mEIuv/xYGgd15ZUY1O3aSZswCTB4sWTasiUGrccjJJuSIiYklpTNZslGyoM9KwukwJIhE2liolLJycHEYDLh+PR00UA1Db95bZCYGJkhzjmUGDAZwDMzoRl06IBnb90aGllqKv6LjBQ/Q7duaAeTCQ5YJuMhQ8RkN3SocR2OCRPQb7idBwwAgK9cKQSTkYHIuh9+CE0IZWUwlbK5LCUFfTQ/H0LWm28KuXFW2sWLpX+XlUFDPfdcMaO2bInrB4ZdV1cjnHnKFCF2fuczZ6of3ngj/LjbsgUEc+GF8m41DXWfOhVahT6Cr65SXm7UCvVbo4/hzCWGeq1lEK4cOQLpaPp0ABZLhqyCjx0Lx90vv9SuwvK1/vvfYDU2KQnmpH/9K3SUxd69at3tt8OOyrM5o6Jw77feCjZVrVsHcOdwSqsVtuE33xTNp6wMBMfhoSYTyOqDDxDRUVaGEEA2dcTFQfIM9Xx+P0CIpbmWLWEie/11AcexY9WKv/9dwj/798c5HP9/4YViD2/XTkwk3buLdsBJ8nJzAY4mE4CUtQkitKvTifbhOSI8s5rbOjcX9UlJkffpdGIfA7h+8EdHgxgSEpB2OxAczGYQaVqa0TyZkyMEbLWKxhYfL07tVq1APExcXi++JyfjuPR0PDub3fr1w38REZC4W7aUlN5JSbjWY4/BkW8y4ZnefRfsd/2XAAAgAElEQVSRbpqmVHKyWnPvvfAZcBqR6Ghozd98I3NT9IRw8CA0Fdao27eHNlhRAS3x9tsl82iTJhBQ2BzD+cCuvlpMdUlJeL5ffzUKReXl6BOTJgmJW60grhdfNCxgZRjTBQUYV9dfL6u48fi86qrjS4ejFJ59/nw42zkCLhQpMOEcR2kkhgZU6kUM9V1StKoKquszz0Ai4ph3Vi0HDACJfPpp3TmVtm9HTP8ll4iEzsB6002YqFMTzXGsDiUlMA9cfbUMVIsFpPXUU5CWuLAz7/bbRUp1OkEo//2vSE2bN+OZGcS9XjjeapIQqrw82Hw1TRa5+fHH4Pr4fJAIWUrt1AlEc++9SjmdWCDm7rvhQ4iOlgiYGTNkKVFe8pRNSC4XQILzCvXpA4BJSYEEaDKBDKxW3NfhAKixKSc3F/9ZLABjNgfw5DbW4FhiDyQFBv2EBKViY5FeJXCiE28ez7Hjju2LiwPAWywAeLbfu1wiCbdocSyflIqIgOQeFYXnjYoSX83ZZ0t6i5kzcWx8vJjTWraENsYCweTJ6KdxcajHlClK7dihtl9yCdrJZpNZ6HpCeOQR9Lvff4fmzGa24cOh/ZWXg/hZqDCbQex60+SqVehD3O8iIuDEXrjQGAVXWAjgHjtWyDsyEr/ffjt0QERVlVo2Zw4m3fHqdPweR4xA/1q3rn7JJX0+aO0vvghfiZ5YbDYIMrffbhyfjRrD/xFiOFn74Y4diN2/8UaAIXdUTYMpZvJkSM8bN4bvrD4f5hbMnAlzAGsGFotSvXurLRMmQLXWZ3n1+RBtNG2apHYggv36nnsA3jxQfT5IhNddJ6GaHg/MKgsXgvCqqjCpTp/Tvl8/SIclJSCQW2+VkMwePVDvwMyz1dWoL4Ngnz5Kvfee2sc26aQkmI94lnRuLkxe+lBO1gBGjIDkb7XKJKlWrQSA27cXE43LBUKIjUW78f2josQUYDKBgNLSMPCjo/E7EOytVryDyEj8HxurlMcDYnC5cJ1AEuF3zllj2Z5tNuP9mM34PyUF1+ZFjRjUzWbU1enE83o8Ar79++Pcrl0llUWHDhJ9dfXVeLeahno/95xoY/36QUCYNUup2Fjl1zSY6ebPDyaEwkJI+Dw/QZ/QbssW9DWW5jMz4TRmf9bOndBWeKKa2Yz399ZbxgSPe/cCiHkhJBZGJk2CxhDKzLNpE3KfnX++aB7cHnffDeGlrtn9SkFj/vJLCCO8lga/u4QE9P3HHoODXO/4DoURmnbcDuhGYmhApU5iCBe5FBmJDrF6dd1mIn3hzvfgg8GdLzERnXvmTDi+w9k6y8pgC502TamuXTGY+ZlGjYIkGDhjc9MmDP7+/QXYk5Iw4BYsED9BZSVCRq+4QkDe60UE0JIlIJG9e5HOgiWoqCgMgmXLIE0+84z8l5oKW/OhQ8Y6VFQAoGqk98NdukCiZcDq1AkmDL7O2LEwMZjNAM/LLgP4ZmcLUQwaBMkwORn3dbsFdL1etHVEhHHFPK5jdDTs/QzovXsLeDOQWa0AyehonBcVBYk7KkqpiAhV5Xbj+pwrisNy9T4Jljbj4vC+bDaAiNcrUnF8vBA0R+M0aSKaU3S0zMxmE9To0WKKGzgQQBUbCzMPm80mTRKzUWIiCFofaXTOOWrt1KkS/cSEcPgwjmMHNCe027UL2uXQobimyYTn4HxdBQXQevWZhLt3R1CEPrpn40b0eZ55TgQNacqU0MvtHjmC8O1rrzUGY2RkKDVxIhZ9CuxvgcXvh+/trbdgvmV/lV5ou+aauoU2Lky8JypAqkZiaFClTmKoba4Dbw4HBujkyZBcvv++ftlZlRJ19YUXoE6zCYElst69oXbPnx/WFvrthx8ifO+aa4znp6YC4OfONc7HOHwY+y6+WMDI5YJE9OqrMmjLyjAAx4wRk0FGBp6HJ+7l5QGk+f+OHRFNdPgw5nSwJuB0ApT0M6+VAiHNnCn2+fPOgx2azXDnnw9ty2oFIE6bJuaokSNBElarREG1aiWrxGVmymQ0Dk2NjwcAsGnMZsPxDN52OwiCzQNmM9ooLk78EzYb7skL2jscSjmdqoq1CCYFXvoyOhq/ObeQvu+kp4u0abVKxBOnBSECsLNznsNreQIcESR8rxfXYWLt21fmdXBa8oQEXOemm2ByZGdz+/YwsTAhxMWBzHfsgISsd4i/+CJ8B/fdJ76Q1FREiu3YAcL/8EOY97iuubn4n5esZTPm9OkSNst9Z8YMmJr0QFxZCYK47z6QHwN4RAQEodmzYdqqOSfkmK6ogJb85JN4Nn7/RHhfAwfi+p99VreZV18qKzF+9Su46bfjMCc1EkMDKiesMWRkoEP8+9+QZAcMME6CMZkwcC+5BINr4UKZI1BX2bcP9vcpUzAQ9KaMpk3hGHzpJajwPl9wHTjy4qKLjDbttm3xrJ98Iup7eTli3G+4QcCYIzz+/nexxxYWoq7Dh4sk3aIFJNINGzCYnn1WTD4OBwDr668x0CdNEvIYNAhaim4+yDcLFuBakZG4/7hxiLHnlNUTJ0r4Yvfu4hxNTxdJuUsXgEVsrKw0lpWFzyZNAKbsl2DJl0HZ7YZGodcSWreWtB/hhAKWlO12VeVw4P42G/axUMHfLRbcIypK7PhMTtHRYiJkrYSJg/d5PPjtcAghjhsn5jLOYHvlleIov/xyaZ9evWD/ZwJITwdgc+RRXJzaPGkS+rU+od2AAQB7TsbH9Rk2DAILA/d110l/i4+HlvnDD7Lg0+LFICWePGkyIUT3qaeMkUd+P/rUs88iSomFF5MJ7376dJg+wyyQtXjxYmgMH32ESKN+/Yyzk7OykDVgzhwIOPXV+IuKkI1g9myY5zp3rt35zP2jnqWRGBpQOSU+Bn2K4dRUDKr774dazYOAt7Q0SLr33gtpfMuW+i0T+t13kKTPPdeY/z0mRh3q3h1RIosXB2sq1dWIiuIkdNyROfXzQw9h8FZX4zlqZsAeMxswGU2ZApCvqgLBvfACzmfw69QJ5oAdOyANXnedmGmaNgXJ8Ep4LK01bYpBVlQk7+HQIWgkbGe/7DLJv5SQIIujmM0gXTYlnHUW6pSYiDZnYmapjT/NZgkxZU3G4xEp1GrF+2WiqEtb5M1iwZyYcOkRQm0xMQA9JiOLBZKnxYKNn9HjwRYfj+NZg+nbF/9z9FF2tnH1OPa7JCRgHog+0uivfxUtKy4O7+fLL9V+nhjGCe0++wxmT+7HiYmw22/dCqFh+nQxVTmdeCcLFgC0S0tBHBMmiETtcGBcvPqqUVDKz0dwwuTJYtrid1ZXskqfD6bTl19W6sorVYk+6MNqBZnceiuuUZ+12/1+mMkWLMD4GDPG6Hhm4hs0CM7nN98U82SjxvB/hBiUqj0qqT7EcegQIjYefxyDrVUro3PS4wGw3XILwlJXrqx9uVC/H1FBr72m1MSJqliv1VgscLrdfDOkw8AQ0tJSaC933GGcEBQdDbMNT0bz+wHyzz0XnKLjL3+B6aqoCNd/4gmZm0AEwHruOdhwX39dAMxshqlo/ny0D5s9oqLUjosuMkZN7dkDLYZNNrxsJ0vyeqmXwZBzCGma2OY5CofNHikpeA42zTCxud2SNTaQyHnWNpNVqMgjTUNkVeD5mob72e3oF3Y7rqGXNE0mWSKTAZa1z8hI8Y3ExMhENSY5fvcDB4oZavRoADgvxXrLLaKhjB8vTuu4OBD13LnH/DRVbjf6xptvIuKJSWvgQADrjh2Q8NnHYTIhZPj119Ef8vOhWV5wgdQnOhoEP2+ehERXVkLqnz4d/YDbLTISws+zz0o/DCzFxRCCHn4YGqxeU4+LUwdZ2/3mm/BzbLhUVUHznjsXID9oUPDCO7m5IIeHHgJZ7NoV/FynYJJbIzE0oHJS8xiUOvFEfKWlsHm++CKcaN27iymBCIO4UyeorLNnQ2MIM8N68eLFkKYWLIA0d9ZZxmtlZgJYWXXWO/MOHED00NVXG7WbzEzse+cdHFNYCGC4/HIxF9hsMEM8/zwGy8aNkC55kpPZjP//9S9oLXfeKWG0qakAhfffV2rcOKTd5pQWeXky8LZuhcRpMgG4L7hAzCt9+ohPpU8fIQW+P0uerKGw30DvU4iOFtLjpSPtdvEj6NuRN7PZaHKq2XyBTmZ2WIfyU9lsuI/DYSQJPUG43dC62OlNBJu804nndrlwvH6eBmt6XbpAy2NJfcgQmWAWFwez3eOPGxPaPfig2nLllaKFxceDJJYvx+S2IUMEwDt1gkCwezcijubMAXlwG6SkIKT4iy9AAizMzJ4NcxSbqXjm/333BUfWcdm5E/3wpptQL307t2oFM+Nrr9W9jvvRowigePZZmDa7djVqeHY7zENXX436fPddcDbX2spJpsVoJIYGVE6aGGpzTk+ahMHz8ccI56zPKnBr1yJS4o47IL3onVqaBgn44osh6X36qVL79oWuQ2Ul0hY89VSwsy0iAte+7z74FzgenG27zz1nDP0jgnZxxx3QNoqKYFaaMsWoYnfuDMD59VeE106dKuBstwPU334b2/DhAjKDBqn1N98M4uD6duiAwc5hgevWSUx+dDRAKiICAN2nDwa42y0znFNTJa0EO4NtNqlTbKwMYs6QGSrElDU6vc9AL+nriUH/O9y1TCaJRNLvt1ikPvxM7G9hiZjDjvWJ/tis1rMnPnkBHzbvdOkiPob4eIQq33abMaHdAw8Ys+/26wci+OgjaLhMVJmZEDzWrEE/ffhho6bICyZxKPShQ5hAN3GiUejIzoYw9P77wY7eykoIEU8/jUi0UHOB7rkHY4rXjQ4oi7/6CoT18cd4xosuwrjRt3lsLIhsyhTU9bffatfS6yp/osag4dgzq3Tp0kX98ssvp/sx6l3y8vKof//+J36BrCyi7duD99vtRFFRRAcPGvc1bUrUooVxa9aMKDIy9PWVItq9m2jFCqLly7GtWEG0deuxQypiY8nevTtRhw5EHTtiy8khMpmM19mxg2jJEqKlS/G5ahWR30+kaURt2xL17k3Uqxc+s7KIfD6iZcuIFi0i+uILnFdVhXr06UM0aBA2p5NowQKijz4i+v573Csjg2j0aKJRo/D/vHlE775LtH8/6nreeTh3yxaif/0LbRgbS3TJJUQJCUTvvUe0Zg2R10t07bVE111HlJSE+t97L9HHHxPFxxM1aUL0009E0dFEyclEa9diX0EBtvh43DMujig/n8jlQr3Ky4k8HqKjR9EGFgvaSyn89vvxXdPwX1UVvptMOD/UqyIiLdQfJhPO5Wvqi9mMzWTCMxER2WzYiovRh44eJUpPx/vzeIiKiohatkRds7Nx3KFDRMOHS1/JzcWxy5ahDS69lOjAAbwHn49oxAi844ULidavR/v95S+0JjqaWhcUEL3zDo6PiSG66CKi8ePxTB9+SDR/Ps4hIurWjej88/E+c3Lw/hcuRH/55RfUNyqKaOBAosGDic45B++HS34+0Q8/SJ/86Sei0lL8l54u/bFXL6J27YisVmP7+XxEGzagzjVb5c8/k+3IETkmJwdjg8dHhw5Eqal4J8dbfD68h40bjdvChUTV1cHHZ2YSbdtWr0trmrZMKdWlzuMaieGPLydNDG++STR5snRmIoDPSy9hMB4+jEH0+++yrV9PtHmzEWBSU4MJo3lzorS00B24oIBo5Uqi5ctp36efUtK+fQAK7pyRkUTt2xvJolUrgDqXoiIMRCaL778HCBEBZPWDsmNHospKom+/xaBftIjot99wbGwsBv455+B+v/0Gkli4kKisDM8ybBjRyJH4vmAB0fvvow5xcUQXXkibTCbKPXwYwFNZCcDp0wd1+vxzgPO4cUQ330zUuTOe9557iPLyQBhRUQCI9HSikhKiI0dAwhs2gGgOHgTIHTmCY4uLAdRuN57R70ddGMSJjLK+1Qpy4KJpwSBfn2I2y3maJoTB97dasZWWglCVEmKqrER7VVXh/4wM9KOWLVG3pUtBpF4v0erVOHb0aAgReXnol8OGod99+ilRRQVRz55EF1yAvvDuu2gvmw2EPnYsnuGTT/Be9uzBs/TvDzIYPRrtuHAhtrw8tL3ZTNS9O4hg8GCirl1xnlK4/tKlsq1dK+3SsaP0uZ498S71paQEwoyOBOi33/D+iPDcbdrQ3sRESh42DH2xXTsQ5PEUvx8Eqwf+DRvwuWUL3gMXlwv9bOXK0Nfi91uP0kgMDaicNDEQgRzuuQeSREYG0cMPgxTC7SdC59q8OZgw1q3DIOXidoMg9GTRogU6o9NprEN5OaRs1i5WrECHLS7GtaxWkIOeLNq3l4Hj8+H8JUuELFgzcTgwwHv3loFbVUX05Zcgii++AHAQQSIcNIioXz8MjMWLQRT79wMA+vWDdOvx4L8PPwTQpaYCbBwOAM2aNaj/0KG4zmefoS59+hDdcguO/fprtPFPP4HMfD5IupmZaPfoaJBlWRnAye9H27vdABpNA1lWVtY+gE2meg/wkKUuImFtxGrFezSbiSIiiAoL5VlTUtDGKSmoo8tF1Lo10Y8/oi+kpgLA4uIA3mvWoF8lJYFoN25E/4qMJBozBu2Vl4f3TER01lm0oX17ataxI97nxx/j/kwo551H1KMHtBAmg127cG5uLgSDwYOJBgzAuy0rg9bAfWnpUghKRCCyXr1k69oV9eSyb5+RAFasQN24DWNigrWAFi2IrNb6jWmliPbuDZb8N24k2rRJtDci9MfcXIy5wC05Ge8unOWgUWNA+T9JDKFKXZpEuKIUADSQMH7/HR1PL21mZRG1aEE73W5KHzRIyMPrFanX70dH15PF8uW4B5ecHBlc/JmSgmvs3Stq/pIlRL/+KlpJixZGrcLvF6LIy4P2oWlEXbpAo0hPRx0++QQSLRGAbdgw2nL4MOUcOgTwr6oCufTti2t89hmAkUlxxQpcJyOD6K9/Jbr6aqLvvgNBrF4NICwsBNjHxkJbSEwUM9bRo5AuiXCMySRSeV3gfTJjkk1VgddgzcFiEWnU40EdrFacZzKh3d1uaFpt2wLEqqtBCGyK69wZ7XPwoADXzz8DpDt1wrvYuRPvqLoa7X/++dCivvmG/J9/TqaqKtE2Ro5Ev/3mGxDBr7/i+aOjRUs85xz0oT17pK8sXWrsK82bSz/p1Qu/2Sy3aZP0Td70/TM7W0iAt/T0sKagY2NaKRBoOPAvKZGTbDbUgQG/WTP5nppqNMuGKtdfT/T888H7r7uO6Lnnaj/3WDdoJIYGU/4wYggnQSQnQ5KLjj5+G2dpKTp1AGH41q0js17CiY4ONkm1aAGwZRvt3r3BZLFpk1wjISGYLJo2BXD9/LMRAPLzcU5cnAz87t0xMNn09MMPAAGnExpDx44AjWXLADo+H8B78GA8/5o1IBe/H+DVvDm0l+XLAaDdu0N7WLkSwHXFFSCJlSuJ7rsPdfF6AZAOhwAUg1F1NcCAgdhsxmcY/8EfUvTv32yWZ3Q6Yebx+wHYRUViBktJAaAVFoIA9+1DezVvjrqXlxO1aYPPTZvQNv374/pM1ikp8DF4PNC0vvsO98rMpJ1dulD6qFHwWXz1Fc4pLUWb9+gh5qH27aF9sCawZIn0d4cDGgoTQY8e8HOUlsL0oyeAVatEeLJa8a71mkC7dqhfbeXwYQPoH/juO/IWFqL+eu3bYgHJhJL8MzKkD5xIYQ011P5GjaGRGI4Vlg7DlYgIdEbe0tONv9PSRKqto+R99RX1z801ahe8sXmHCAOjSRMjWfAWE4NBtGqVkSxWrxbbusuFgcpmqA4dAELbtxud2uyYtFohpfbujWOVAhF88QVAhQgE1K8f7SkvpxSTCaahoiIhkLg4mBC4T7Vvj2dduRJAmZwMgFyzBiA/dCgIYs8eogcfhHQcHQ0pOyICZMKfbFpiB7xey/qji54U9A5t9nH4fELifj/6gssFEIyNBRl7PAD5detwbJMmAKfSUki8GRlol717UeeBA3EO2+mJoHkMHnysnSsWLCD7oUP4r1kzMQ916ID78Hv+8UcxUaakGAMX2rdHe+sFDzYFcdtGRwdrAS1bhu/zBQWhJf+NG9EPdG1ZlpREzrZtg8E/MzPYeV2fUlwMn8Pu3TCdhfq+d2/499zoY2gkhmMlnMYQH080dSoAa8cO2fTRS0ToUImJRrIIJJCEBCJNq70ORUUA6kDC2LjR6ETzekMTRnIyBrQ+ImrFCpHEzGYMaL1mkZ6OezCI/Pyz2GyzswEerVtDQv79d5if9u3D/02b4nrV1QCwXbvQFh064Bm3bUNdNA3X8PkAWJoGO/DBgwCRFi2g3peVET3+OPa7XABNux0SuZ4YiMKbev7IEso8xY5uhwPtFhcHQmBCi4yEJrF7N/Z5PPhut4OojxyBk5SdwDExcPJu3Yr79egBglcK72b5ctw3JoYOtGtH3vHjQQr6KLY1a3C8yQTg12sDlZUgar0moAfKzMxgf0BGRrDGfPRoePBnsuI2S08PBv5mzYiysylv6dL6jWm/H9etC/QLC4PPjY6G8Jaaiu3990Mf16gxoDQSQ02py8cQ6Ji+/344VfVksWOHkUA4+oKLw0GUnk5HIiMppl270CTicoV+vupqAVk9Yfz+u3EQ2u0YcHrCaNYM92bCYMlQr51kZIhm0bo1wG7TJtEq2IYcFUXUvTvtcrkoLTkZDvklS9Bumgagi40FcbAmkpEBwuLBa7HAPnzoECTpqChoHPv3YwBPmID7v/QSBq/FAkLhiB824ZysD+FEi96xrdcYmAiYyNxuPG9hIepVUYE+kZyM/9gU2KIF2mzjRhCi1QoAT0pCG/3wgzjje/WCszg1lSg/nw4uWEAJGzbANk8E0unZE0TQuTPaVR8eumqV2OotFqMpqEMH0fC4lJbiOfWRPrzp/QpEeKZQZp8mTdD/wpS8vDzq36sX+mNtoL9nj1E44vZPSjKCfqjvgePqRH2KutJIDA2o/GHEQFR7tNLxdiKlIDUGksWOHVS4ejV5CgvR0QP7TFxc7SarpKRg22qoENvff4cUqrfBp6UZCSMxEQNt585jobSGSJLYWAGM1FQcu3Ur0fffk1q9mjSWSNu2hWZBBPLi+RZOJwiAHepVVZCe09IAKvn5ANGEBLSF3w8N7fBhXHfkSADdvHnS9kwGp4sUAu+raeJvYNJyOtHulZXilLZYQAj79qEdkpLwrrdtA1C73WhHmw3vgDUyDhhITATp/PILzHs1AFmalkaugQNxblQUtA/WBn7/XQgsKipYC2jZEu1fXg6CDyX5795trH9SUnjw10cp6UtRUXjpftcuqty2zTiPgYvTWTfgJyaibU+kXH89xrDPh3c4eXK9Hc9EjcTQoMofSgzhSjgzk9tNdMMNADb95vXiM4z0f6wOlZUAxFDaBm96ZxwRBkFqarC2oScRDmcNFWLLW7gQ2+xsDMjSUoDTqlVwQFZU4FiHg6htW9obG0vJTZviuC1bYOJgSTQ5GdcxmaQeRJCaY2NBCiUlApb5+fjtcAAYi4qMUUjt2wOQvvpK/CenixgCi96cxc5x/SS7qCh8lpVBo4iNxTuvrkZ7ZGQA8LdswfViYuAIZufvypXyn90OLaB1axxXUUGHf/iB4nbuDNb+Av0BKSkg9VDgv3OnsS3j40ObfXJzjRM7/X5oKrWAPu3eLb4NfYmLOwbuezSNUrp1Cwb9Ewn4qG+ZOxdEoNfqGzUGKY3EUI9Sm2NaHykTWFwuI1HUbJuLiqhJz57BhOJ2Bw+EwsLQhMH7du0KnsEZFRVe48jIAEjk54cmDD0Bcohts2aog8UCAN+9m6pWriQrD3iTCeCRlQVwLyoC4HDMvMMB263ZjH1MSnFxkNYKCvA7NhZ2a7bX81wFNs3Ex+P5V6z4cxzOtRU9MZnNqAdrDJom5Gq1gqjZ3BcXB3Bls4jFgrkqCQkA0LVrZdKi1wsSiI9HfffsAUlzu5vNVJyZSREcLMARQQcPBk/22r7d2GYxMaEl/6ZNcY3yctyvNtDfuze47zHZ1ybpp6QYTEsnPKaVQn/Mz4emdOSI8XttvzkyL7A0+hhQGomhHqW2yTBbt2IgHziAARm4Be4/cECk78DidIbXPkLti4jAYN+3L7zGsXOn0QdBBOBKTg6tcSQkAJjZR6APtdVJV1VuN1mbNQOImExog507jU7MpCSAgNmMgbhtm5i2vF6A5oEDuJ/JhPowaehDQNm5y2BsseBZdWlGTksJNGvpZ1vzJDciEF5lpTEqKC4OvxmwNQ1aVmIivh86ZJxtHxkp4J+ejraqqqJd331HaWVlIICtW41AHRUVDPq5uWj7srLaQZ8ntulLRER4kw5/93rrnkMQUL75/HPqx0744wH3I0dCp7XgYjaDAGNi8A74e0xMeJNRY1QSSiMx1KOE8zFccQUmf4WaKR2uKEXffvop9W3RonYC0e8LdGJzYft8KALR/46IAMjm5wO8QxFIIFk5nUaNIy0N4OTzER09SntWrqSU0tLgEFuzGaTj8QAsCwpAMjzY3G48ExHqx23qdKI+rD3oI5BYIicKBmMObW0IRU9gLpcQg8sl2hBHwjgcIAiLBe9FT96cbiUpCef6/TC/bdoUlOLB53CQuXlzsfN7vXjfFguIJ5TUH6o/eb1GkA8F+lFR4eteUWEE70AArw3cwwlKRGjL6OjQAB8I9oH/RUSEN0X9iTOfT9AD0lgafGGw1zumhw8nev11Abbt24kmTQJYXXZZ+GtpGvlcLjhlc3Lqd/+SkvoRyPr1+NTPENUXm81IHomJcFrGx0uen4oK1KmgANfdsQN5egLivlOIcI2MDMx9cLslsVxBAQBp61ajmS0yEoO1tBSAwNK12Yz766U/TpRXWQlSYCJg4Ys/mRQCcyP9WUVPVPpoKYtFCI0nnNntEtJaXg4AyswEoLdpg/MPHcL+L7+Uezgc6Cvp6dAa3O5jDu/8DRsoobISebM++CBY2jXlj6gAACAASURBVLXZQEBpaXhPo0YFA35yMo6rrg4G94MHYYqqC9z1QlOoEhVlBO1WrY793lJQQDmdO4cGe4/nuDWQepXhw0PPfB4+/JTfqlFj+BPKadEYQpVwEgcRQM7tDrvtLSqC47aWY8jtBojqf7tc9ZvtWVpaP7MW7wvlHCQC2MbHgwDi4/EMViuRptHBvXspwe2G6Sc/H0QQSEgWC6Te6GgAj8+HYw4cMDq/mRgqK41E4nCAqPRpRRrqGNMTk8mEZy8rk+dl7Y79JYcPGyV3ts3HxMh7rqxEOx04YJwUxsXjoZLoaHI3by5An5KC9na70aZ+P8izPpI8+zbCFbe7dgk93H/R0bVGDv0hY9rvRzuXl8snbxUVROeeGxxuS9SoMTSWkyyhptNzsVoh+ZWVQUVne3INeMZy6uKSkuOXch2O2skjHMEkJUlIYeBmNoNM8vNrJ5Dt2/G9qIgSQj2byQQgiIgAALLEXFSE+hcUBEu0Tqeo/CaTkRjKy42O/4ZKCppmfI82G4CQI5OIAEZ79sicjZgYtH1hIY6prhYzHxG0Oa8XZNGiBcjC4RCAra4mKi6mii1byH3okMwoLiysvZ3sdiNoZ2TI3IW6wL6eM/sNoFxeDvNVIDDrfifyLOsw/5/Q73ABIXWV2sb1CZZTQgyapg0loqeJyExELyul/h7wv52I/k1EnYnoMBGNVUptq/lvGhFdTUQ+IrpJKfX5qXimxhKiZGSE1hg0TaThkhLMQA0IgfteLyFVVeG4khKAJ3+vbQt13N69wfuOd3AEko5+S09H3LvbTWS3046dOykjNVXi9XnyVmkp6l9UBCI4fDj0DFNuKyIMZqVCPy+blPQznhtSCaXF+P1oi0DS9/vx7sxmAH1MDDQxIgB9eTneW1ERpNlQEi0R2qMGtM1mM6RcTuUdHS0mO5cLJORygRDsdjEXhgPWI0fgEzoZYD5OYadluDqy6Y23wN+RkbX/r/8d+N+ECTIpUF8yMo7r2etTTpoYNE0zE9GzRHQOEe0iop81TftIKbVWd9jVRHREKZWrado4IvoHEY3VNK0VEY0jotYEE/AiTdOaKaX+xCxj/4fKww8HO6RDgURpKdHEiVhIxWwmslio1eHDIAu2Q9fsr/W7xQJNJC4O0mR9zlNKpFH+ZHMNb+Xl8qkf5GVl8llQAMBi4C8poYzjJR2bTQao1Ypn5Pby+/F8Fgv2BToja4s8Od1F/75NJlm/IdwzV1eDLHkRIgZvux2gnpAg7cNtpG8nTihY877srOWdICiHLBZL3UAbFVU3cNfz9w8rVlCP/v3lf7v9xCet1bfMmhV6/P4BPoZTUZNuRLRJKbWFiEjTtHeI6Fwi0hPDuUT0QM33eUQ0R9M0rWb/O0qpCiLaqmnapprrfX8KnquxBJZQDulwPofyckSE+HxEPh9F8ExQHuQ1+0N+r65umJKyvuhXNeONAS0wKoS1C/2iOqwN+HwNv66hih646/v8HIMfyi/D4BgIpA6HmJRqjjly5AglZ2efFDAbfv8ZoBxQyg8cgG/kzyyXXopULi+8YDRVvv460onUc5JbfcqpaM1UItqp+72LiLqHO0YpVa1pWiERxdXs/yHg3NRQN9E0bTIRTSYiSkxMpLy8vFPw6H9OKS4ubjjPm5qKZS5rSo9x48gRQv2vjIoi/549ZD9wgCq8Xvr9ssuoaOTI+t+nBnQ0n480vx9bzXfy+ereH/A/ncj+6moyVVWRqbqatMpK8pWUkF3TSON91dXHPg3fa87Vap7HxNcLcS/S39PvR8qNwM8AjewPmhd7fOVU+j5qfAdhAwKISNUQrjKZyKtp5DObsc9kCv6sIWn9p6ohb/11SNNI1WgoYc8J/C/U/jquE+oZ030+2vHCC/U61nD9UHUN0wahrtP87bfJFkLDL58yhX5IDQmdJ1ROBTGE6ueBvS7cMfU5FzuVeomIXiJCVFKDiPKpZ2kwUUmhyhNPBKunNhvZysqO+R0c+/dT+zlzyNyxY2ippLpanGcVFbLpf+u/6238tR13sv+dynUP9OGcrGFw0UtvrDE15HIikVIsmes3m03MbLyGtM0mS4eyKdFqJa3Gsa1ZLLRz715Kz8rCdVlj0Wtfgdup3F9VdUquU11VRRaeWKY//jQFGzgOHDilGHMqiGEXEekXTk0joj1hjtmlaZqFiDxElF/PcxvLH1lCmZeKi4NmkZorKuD8mjYtGIBPpSnFZAoGnsDvdjuceOGOY1+F3r7t89G+HTsoKTbW6HgsLT3mg6CSEoQ/hopvZ98HTwZzOnEvDsWtrhYnaUMqNhv8O5mZmFfg8Uj47b59+DxwwLjMZOD5bAritmVSrKiQgAF2QtfDX3BswNvtcDhHRIjz+WQ3m+2Py1WkK9+FE/YCTY2nmthGjJBkhfpyih3Qp4IYfiaippqmZRPRboIzeXzAMR8R0RUE38EYIvpKKaU0TfuIiN7SNG0WwfnclIh+OgXP1FiOp1x6qVETCDc5h8MTIyJg02zXLrQEWReo1/afyQSHcWEhHMj6Ldy+3buN+8KAXBJ/MZvhNI2OBlDGxIhznOtZWQmCOHoU18zPF01AKSEUjp4hCk2Qp3seA2ei3bkTq6gRyeLyvXoBaLp3B9FxiG/gFmp/OK2Io5a4fRnw2VlttdL23bspMzMT7cURa/qN56nwVtdENH2xWE4Nweg3l6v+ZMM+qj9ighsR1v0IldHg4YdP6W1OmhhqfAZ/JaLPCeGqryql1miaNoOIflFKfURErxDRGzXO5XwCeVDNcf8hOKqrieiGxoikBlBqc0oTYbB++y3R5ZcHm5aUkvh/PZDz4jb1Afy6pE6bTYCHwT09PXifwwEpq2Zm9LbffqMsjwfPsncvYvTXrg1NJB4PwitdLsyniI8XTUrvfOUJX5pmDF3VNJhRTjQ2/WSLfv2FwMIZUFeulJm0kZEIH+3XD6uwjR4tYamBhdOGhCMSJpPdu/H98GEDOWbqn1GfCoUXcvJ6ZUtIQFRbRATOCUUk9dk4Y6p+qy9ha5rMranZOvh88NedKNnwuhfHW9gBrU+9fcUVp9TxTNQ48/lPKQ3axxCqhMqzFKo4nVicJRDc6zItuVwAXj2QM5jXZ59SAuy1baFmxbrdMts2Nlak/YoKSamxc6dxHoOmAZx4zYKCAmPbeDwggaIiIYKGMo8hMRF10o9zfR4nNt3xvAx9iY5G2ouzz5ZFdOLijv8ZONy1hjDW5uVRq/j48FpJYNp2Lna7kTD0BBJqfy0L7ZBSIPUTIZniYjqyaxfFcG4n3o4ePT7/ksNhJIv6mNNWriR65RWjyfI4Um83JtFrQOWMIwYi4wJAtfWRPn2OD9w9nvCzUTlDaiDA80pYvIVKtWC3A+z1W3IyBlNNWosdK1dSBhFm3AYu4m4yIQdPbCyer6ICM8H1CxM5nbgmr3DG0VyahnrxhDl+Hh68tUnvf1Zp3RrPwOtg8zNZLKgXkygDULgoo7g45D4aMABrMHTujDY7jlLneCgvN85mr828tX9/eL9OZGT9iSQ+/rgk+LB14Iy0p3ILl5BSX+qZFqORGBpQOSOJQV/C5VgymwEudWVp9fkwiOuS8EPN6uTMpyzlhwJ/s1lSPjPo86bTGpTJRFp2NlJFc6KzkhKQ0YYNRiDMyRESKCjAtfn/yEjJPMo58l0uXI+PcTqNA/p0+xq4dOoEk9HSpUgYyBMLKyrw/LzqGrdbaiqA8+hREHS4LKddukBI6NoV96iFLE7peGDTZW3+EP3+gwfDR6vFxdVNJDX/5a1cSf0HDDg1daircL6u4mIIL6H6UT1TbzcSQwMqZzwxvPkm+a6+GpFJ4YrdDp9DZmawtL9/f/Bg1DSAUCiw128JCTh2714j6Ou/623+FguAPzcXm8eDAVNYSId+/ZXi9+0zrong8SDvTloaQPLIEVyb1342mXC9qCgQBJ/rcEDKzM+HWclslmUq+Ty/XzKTNhRi4NKmDdGYMSDF//wH9XA6xSRGhHo7HBAK9OtjZ2XhfW7aZFx/QV+SkrCOc/fuII1OnY6ty3xax4Pfj3dUXyIJsziO32wmU21mrMD9oRa0OpFykqm3G4mhAZUznhiIaO306dRq7lyYlkym2ucIxMUZwT2UtB+47i2v9hUI+hs3Anz0Nn2rFRI9g3/TphiAlZUYzGvWYHnP1atFwjWbqSQtjdw9e2J1N15TYM0aop9+Ep8Cp1d2u6GFrF4NadpiwaDUNAzAqirJ3Ll3L9qDzUcc119SIvb8P8ucVN/78HGZmUS33op38p//EP3vf7LynNUqqcuzs+HgLyrCimxc3169JGHetm1Ipa1f60Jf0tKIevSgzbGx1OTiiw1k0WBLVRX6QQBpbP/5Z8p0OoPJJNwkP6ezdn9I4P5w5tY33yS68kpjgIbVSvTaa40+hkZi+POLoQ61LRuakUH0yCOhO6nfj7QaoaT+zZuNZgqbDeDPK3gxAWRmgiTWrgX486ZfAD4hAVpAu3aQcKOiiA4doj3/+x+lbNuGc3k9gjZtYH+326HZ/PijSP1MOIcPY3EfIhBabCw0h/JySb3t8+HYwkIAKy+fyp96hy+XU6FFuFzBQQK8XCd/hip6H0N1NYjg5puxLseiRVhf+OuvcWxODo7buBHPm5ZG1LEj6rZhA4iCCD6ks89GQEJ0NJz4S5ZgbW02TQXWOTNTtIrOnUEW0dHGZ9X7u+q7uNQfXMKOaU4fX1e4L+8PF7Xm8YQmjO3bid5+2/hebTaiV19tJIZGYvjzi6EOta3rQASwvPlmDHo9AWzebHQU2u1Iq82gryeA1FRIanrwX7UKoM7SktUK6Z5JoF07SLZbt0Jy/f57pAqvWRinKjKSrH364Hhey/mbb8Q8lJaGa2ganLS8oH3z5gCrjRuhZTgcuPfRo9AakpJwLIeoVlTAD3H0qAA3x7YHrur2RxUmJHYk64teq2Athz9dLqJrr4UW4fMRvfUW0RtvoD1sNhCp2Yx3UVEBiX/QILTd4cNEeXmSBjo9Hf8NHIg+s2UL0Y8/0tHPP6fIrVulLQJJMycHvoouXUDSM2eesIT8R5VTMqaVkrUr6kMkhw+H1wYbTUmNxHA6iqEO9Q1nJQKIMuAHEkBamqygFqgBrFqFAcKFQbtdO6zg1q4dTEJbtggJfP89TEOsDbRuDTt3p05EFgvt+OILyti4kWj5clzT40HcfnIyBt3XX4OMLBZIsVFRAMRt27DP65UlP1u2BPBu3ixhkeXlkLwPHQIgl5QIGfDkOV7ZjejUEUNaGkgusDApJScbV7PjSVh6jYEJhJ/bbIbP6I47YCpavhxaxFtvQbOKiQF4axq0rIICCASDB6PNzWaQ8ldfiQbWpg3RoEG0yuuldhMnQlj48Uds338vwganH6ltPktcXPC64H9iOS1j2ucDKTY6n0OXRmL480tQHVi9D6c5aBokx5QUmQWqFMwLgQSwYYNIjE4nAIRJgDeOAvrpJ4DI0qUAHgad6GiYMHr2RBilzYb/Fy2COaOykvxWK5l69xbgWrUK/5eWggTOPhuS/m+/Ea1YgTpkZclqYnFxIKUNG2BHj4mRNN8MzjxLtqQEnxz6ardLnp5TvZCP1xs6ootnlh89CnBnc5heQufoKdYwYmJQ1+hoSXFx7rlEU6eifaursYTnG28Q/fe/aLusLMxzIAK57tqFe/Tti3Nzc0HYixZh9nV5uZDvoEHYunfHfZkoeKtthbbTiF2nbUw3Op/Dl0Zi+PNLkMbANt9wjuj0dDgzA0lAP3EsOzuYAJo0kfUBNm40agOrV4tUxNpAz54ALJMJ0umiRfjk+3ToAOBp1Yo2L11KTdavB1H4/QDzoUMBgsuXEy1ejP3Z2QDK9esB7n36QLvIy4NUnZEBbaasDBrQtm04Lj4ehMFgy1K42YzrlZUZU3tzXY5jDIbLPEkdO4ompC9eL4ipsBCEyePGZBI/hFIioXP68eho1NHrlTxS/foR3XUX0bBhOKa4GOQwdy7a3e+HFnHWWbj2woXQBPn5zj+faNgwWvH119Th8GGcs2wZzouIwHkDB+J9tWmD56ptWdj/i8QQSlv/Aya4kVLqjNs6d+6szqSyePHi0/0IJ12O1WHuXKVcLv3KBMGbphl/R0Up1bu3Utddp9Tzzyu1ZIlShYXGGxw9qtSXXyr10ENKjRihVFycnO/xKDV4sFL336/UZ58pdeSIUvv2KfXmm0pdeaVS6elybGamUhMnKvXWWzh22jSlWrWS/9u1U+ruu5V6/HGlxoxRyuHA/rQ0pXr2VCo2Fr9TUnDtESOUMpuxtWqllNOJ+rVrp1RkJL63aIFPp1PqazIpFREhz8/3N5uVsliC2+hkt+HD5bvJhPvwPdq0kXoNGKCU241nIMKnzYbv3OaRkfiMjlYqMRHfU1Pl/3bt0A+qquT97d6t1BNPKNWhg9Rz+HClZs3CO+3Z89jzlaakKDVlilLffafUwYNKffCBUtdfr1SzZlKHxESlxo+XZwvc3O4/qeeHLqd1TM+di36uaficO7fepxLSFNWJsacd5E9kaySGP78cq0NmZu0AZbEo1a2bUg8+qNSHHyq1datSfr/xYn6/Uhs2KPX660pde61S7dsDzPgaLVsqddVVSv3zn0qtXq2Uzwfi+PhjpW69Vam2beXY2FgA/AsvKLVmDY655hqlkpMFoAYMUOrJJ9Xq6dOVmjxZqZgY/Bcfr9Q55yjVsaMcO2oUyKRXLwH5Ll2UstsxEHv2lGu3bYv7axqOI1IqKUmei0mBQdhmCw90J7vZ7UoNGmQkHE2T3yNHor5ESg0bplRGBuqrJwK7XSmrVQiAPzMypM45OfhNpFRWllKzZytVUmJ8v7/9ptTUqULYkZFKTZig1LvvKvXcc+pQt264D5FSXi+I/OOPlSorU2rHDqVee02pSy8VUgq1xcX98Z2+lnKmjulGYmhA5UztRPpyrA7hJF1NCwYILkePKvXVV0o9/LARoBh4zzlHqfvuU+rTT5XKz8c5lZXQLP72N6X69hVwZQD8+9+V+uUXSJxvvAFyYAnd7VbqwguV+ve/lfrmG6XuvFNAyuWCFjB6NCRiIqWys3H/GTPwncGwXz/cz2TCPVu2FOJicvJ6hRDcblyfP3kjgmZit0u9TSZsodrzRLWJe+6p/f9bbhGwHTVKpHiTSYiNP9PTAd5OpxBp+/ZCfK1aKdW6tTpGsDNmKHX4sPG9+3x471ddJddNTVXbx47Fu337baXGjhViiohQ6uKLoe0VFECAqK2/ncZypo7pRmJoQOVM7UT6UqfGwBKc36/Upk0A6+uvhzTOkikRzC5XXqnUSy9BsqyulvPWrFHq6acBWgwWmgaJfepUpRYtUqq0FFrIU09BE+BrJyVBG/j4Y6V+/12pRx+FCYU1gcGD1e4RI3Atlt7HjgUI3X67mHu6dFFqyBCAosWi1LnnKtWnj5DFsGECpNHReD42VTH5pKbingyoLpeYmUwmkITVimOYIGojivqQhaYp1bUrnpevY7PhvnptbM4cAffRo2GuIcJxVivA2WbDM9tsSjVvjv9TUrDPYlGqf38hmC5dRLtyu0E+O3YEd6DSUmgMo0YpH7+zdu2UmjlTqc2blfrkE6UmTRKitVrxHtzu2vvbaSpn6phuJIYGVM7UTqQvBh9DKHOIyaRUp05KJSTIvshISNr33ouBHyhR7toFc9Lll4upgkip3FyYmObNwzl+v1LLlkGqb99ejmvVCmafH35Q6sAB+C8YxIkAWHfeqdRll4k20bIl7N5ffKHUJZeI/2DkSICq1Ypt/Hilzj8fABsTA9NGUhJ+5+aqY2aV1FTUvWlTeSYiAc6ICNEa7HYAXX00Aj2ZcvuGIgn9fiK0WeC1mJjY97BgAYCeCPV+8EEVpC0w2RKBHLxe3LdlS2mTc88V7a9fP5Am+1CuuAJEH6J899//gqC6d5f6DBqk1L/+Bf/RkiUg6yZNwrdPIzGcUGkkhgZUztROpC+GOugdw/qNAeHFF5VatUq0AS4FBfA73HijmGWIQCbjxin18svQBpRSqqJCqYULlbrhBgEqkwnAP3MmfBQlJTBHjBolpqaWLWFSuf9+IRGnU6kJE9Syp56Co7NvXwHCq66CGcpsBuFNnAjNw27HdtVVQjZNmgAQLRbRVpKTAbIWi/gq0tLk+kxIUVGiNbA0z+Yl1k6sVuwPBPtAIgn8X+9svvVWqQ9rJ3ycw4HrezxK/fqrPOewYZDmHQ7RnDIzcY3YWNTB6VTqrLNwzZgYMSM1aQJiZ7PckCEgVa7r6NEA+nB9acMGEH5OjryrSy6B5ldZGZ4YGk1JJ1QaiaEBlTO1E+mLoQ61Sbz6CImKCqW+/hoaQ8+eIgW7XEoNHYrIoBUrYItWCpFK77wDkmCAcjohmb76KrSCqipEG11+uYBuaiqiXF5+GdoBg2HHjko99xwiZmbPRjQMg97UqbBnM3j+9a9KTZ8u5qHx4+HEtliwj6Nt2rZVqnNnfO/RA+cmJgIoOUqEJWqOWoqLE+Bm/0MguNe2MenpQTGU1qZpAPJffzW+o8hIMWuZTDg3O1upnTvFNHjOOdC8kpLQ5nY7rsUaEWtJnTpJW7RuLT6Zvn3RXlFRuPf554PU2Qnfty80Fb8/9Hjw+0Eg110n57A5MdSWmflHdfV6lTN1TDcSQwMqZ2on0hdDHWqLTHI4AKrDhokJxWQCiE6frlRenlLl5XKtnTuVevZZhKNypEpCAiT1Dz+EVuD3A7RuvFFs0B6PUldfrdT77yv1j3+ILTwyEmaoZctgqpo69RgoFrRqBTK66CKAl8sFQnnmGYm0GToUGklqqjpmIvF4AJTjx+N7RARMH0Swsaelod4ZGQDduDgApM0mJqXISJzLgG21Yp/bLeYrJk7WAFhrCUUidnto7YJIqffeA7lyWCzfk0GfyaZ3b5Axg/uAAUpt3y5RYgkJeI6uXfF/bi6e2enE9Vl7GjRIorMuvVSpm25CvUwm/J4+XbS+Nm3U2rvvhjYQrlRUKDV/vjxrKAI8jhDNP6KcqWO6kRgaUDlTO5G+GOpQn7kMLVpACp8/H3ZjLn6/UitXIoqFJW8i2Ohvv12pb78VE9T69TAzsLRqtyPaaN48pf73P5hMmEx69UKYY3ExSOGyywBaJhOO+9e/1AE2IUVEwDfx7rtiburUCecz4LduLTbwHj1wXyJIyywxjxkDAoiPB5G4XCAuNiHp5wBwRFJEhDGElYmAHb8OB0DV6Qx2HAeCI0cNsQ/B4cA2ZIhS69bhXIsF9+ZncbmMUWGXXgqiZnt+375KFRXBBEQkpNGzJ0ghKkrq36sX2oAI5Dh6NO7ndoOQb7oJz2OxgMRnzRITVEYGCLm4OHynq00zPc3lTB3TjcTQgMqZ2on0JagOc+eGH7SB9t+qKoQt3nyzAA0D7qOPKrV2rcx12LMHAMLRQ5qm1MCBSr3yCpyZM2aIxhIXB5s6z3X46CNEzDAA33ILiKkG5Krcbpi1Fi8WAsjKgplq6lQArceDaCW3G9vtt4OYNA1kk5CA/ddeC8Br2hRk4PFAImeiiI8HMLPtnEmDwY7NOyc7r0HTQkc1bd8u5MjHxsaK0zkxUUxuf/sbpHR2oPfqhXd2xx1C2pqGCWhMpL17ow4uF9qZAX/AAGhdTBZz5sCkxHM4brhBrZ06FefzO3zgAaUOHQrudOE009NsRlLqzB3TjcTQgMqZ2on0JWQdahu4R49Csr/8crEZ2+2YQ/DSS0rt3SvXKSwUaZ0l5E6dMJN2+3aA+4gR8t/ZZ8PpXF4OifO55wTU0tNhLlq4EOYsIgDwjBnqp5dfhoTMIDlrFnwabOa44AKQFRHI6M47AaxpabB9m80wWU2ciGO6d4f/ISEBWkFUFCRh1hi4fVJSBITj4sTeT4T9sbHYdzx+h7q2v/0Njl2zGdpEVJT4bdq2lUl57DR+802QQYsW+N2tG8j21VdBmOnpODYqSkxx2dnSXmedBS2MtZ2JE8UZ37Ur+sLkyUpZLKraZoMJ73//Q+AAE+fNN+N9cwmlmbpcp92MpNSZO6YbiaEBlTO1E+lLyDpcd11oUEpPF9NJbCzIYd48kAWX8nKl/vtfmCL42JwcSPTr1iG2/e67JYw1KQnAs2kTzt+9G/8z6XTtCpD/6is4UhmEH30UkU633aZ8ViuAeOpUTI5jybZdO0i1TifAc+ZM0TzOP1/MKuedh40IgOZ2gwiYDFq2xPVTUnDviAghHdYiGNySk40RQ6xBxMUdv3OaNQe7HdeJjYUm5PNhxjFrDTznwmQCabFfICEB4P/ddyAHlv47d4ZZLy9PyIt9OZddBjK0WkEUERFoj4ceQpsRgWSmThUt5aKLlMrLU3uHDMEzuN14p999p9Rf/oLntFjwffVqvOeTSP/wR5YzdUw3EkMDKmdqJ9KX49IYzGaYFxYvNubT8fkAMpMmidSckABfxPffIyXCO+9AWicCeIwYAY2BnZXLlwM4rFaJfvn2W+RZYjD3egHuBw7AMV3j9N0zdCik6OnTYdaIigJwsXN19Gik4YiJAWg9/DCA0GRC+Gu3brjnhAky+SsrC2DcrRvq3bo1ALpJE/ElsI/E5cLx3E4xMTDp6OcsREaiTbxeEEddcx7MZjxrfLyQCv/3xRcgWJ5sx87vxERI+zabaAhMXJs3gwzatcP+Dh3we+NG1NdqhUOeCO09YgS+9+sn+wcMgKbBZsOxY2GSq5k0t33cOKV+/hkObNZcHngAEx5vvlnqMGoUSKMBljN1TDcSQwMqZ2on0peQdahPugK/HyGpd9whcfNuNyTOTz4B4K9ZA18Bz4/IzIQvYedOXMPnQ6jj2WfL+TfeCLBauFDmGSQnY0Z0URFMU3y/4cOVWrlSrXroIQHm8eMBVlYrAPG118RE1KULcgBFRACkX30V5zmduK/ZDDNJkyY4hjUUBkb+TE/H+WyfOtw1UgAAIABJREFU5+ijnBzRFtxu/Nb7Gmw21CUhQaKbQrVzRAQkea8Xn3otgyOHlEK9WGuIjBQyYD8LRyHxf0eOgAzYFNS2LX7n58s5w4bhuTIyIPU7nXjeG2/EdSIiMIv9nnvEd/Pww9AeWSB4/nkQ/QUXCFE++qhS27aBKLg/9O4NsxOHNTeAcqaO6UZiaEDlTO1E+nLcPoZt25R65BExS1gskC7fegt+geJigDGnU7BYYFb67DOJSiopQXI8Nl+kpkIDOHwYE6A4aoidnKWlIBvOY9SlC7SWzZtFsm3dGj4OlogvuQSpNpo3B4DfeSdIigj287feEsfybbdhf9++8GlEREhUDl+fP9l5npkpIbZt2gBMNQ2koc9mmpoqZjEGdq8X0r1+fyB5JCbKjGXWsuLj8Z/NBqfu1q0A59RUmfvRpw+O7dcP/zVpgutYLNDYKisBxFyPVq2g/VVWwvHOGkNaGjSkGTOkTa+6CloDEa715ZdC6l26qDXTpgl5tm6Nd75smbRdQgL8S/+PveuOq7Js/9dhgwgJIoIIrsAF7r03Ii7U3CM1tzkaltZraWWZ2qvZW2lZmWVmZWblKtFcuc09UHGiqICAbJ7798eXi+t5zjkoNhT6nevzOR949v2M+xrfa928aQwlrlEDmfL3CnV9SFRc57RNMBQhKq4fkZ4K9DGYWw1OTuIIZm3vf//DJFcKDGDMGGFmwcFKzZ2r1I0bct64OMA9zDjr1oVzlOPbOcw1KAhZ1hkZ8Bkw86lUCZBUaio0T2dnpdzdVcxTT8FK4IzlNWtwbWaa33wjcNT48dBoHRzA0CdPVvnWR3AwNP2nnsK67t2FCTo5STgnF6mrVEmEQ40aYi1UqiRhpE5OYM56IeDmBoGkD3fln5cX7l9f0psd5fqqpAsX4plyFBULWC8vPIOQECwHBeGdsLAfORLWnqaJgzkkBExZ03BeOzsIYQ4DHj4c9bHYCpk5E4LI3R3P8osvlCpbVmkmE/b7/HMJkw0Ph+W4e7dYJX5+sNxSUrAv174KDIRleK9Q13+YiuuctgmGIkTF9SPSk9Vw1YJyGapXB2zA5S2SkiAc6tbFdhcXQEnbthlLch85ggJ7rFV37459cnLAtDlUsnJlhK9mZSl1/jy0fsbJFy6EAPnxRwkV7d9fqe+/V3fZETx8OEJk2ZcRFYXKruXKQVP/9FP4HogAE40ejf/79YOD2c1NQjkjIyEkatUC3OTnh3EEB0sJciLAMtyngc/BDJS1eHd33BtHChFBOFasaFzn4iLMXA/f8fV5XUAAtHhNQ2E7FtqcGMdRW4MHY7lNG5yHGfDbb+O9aJqEl1apIhr7zz/D2vHzw3tjS2nZMmj9rq74Dlhgd+ig1NGj6nLPnriery+e9bx5EHD29lA24uPx3lnglC8PK4/fK6/38oLwYaXjIVJxndM2wVCEqLh+RHqyuIeCYCQ/P9E0d+yAo5aZYFgYNEAura0U9lu/XnB6Nzdo62fOQCCsXClwVHAwSmlnZ4MZTJ4sSV7Tp0MAXbggGny1amAkEycqZTKpdF9f+CS+/14ctUuWYEyM/f/+O6JniGARDBqE/0ePxjhcXVF0zs4ODI97FXToAEHQpAm0+5o1cQ19OY2GDcGUHRwgJO3tMYaQEKkiWrassY6UiwuYMRe0Y4ZYsaLRMihXTpzczEz5He3bh2c9YYLUhOLmQpGRWMfWD+P9tWtj+3ffyXtq1UrlWzqcvX70KK7j6gph6eGB+/7qK3mnUVFg/iVKKFWypDr1zDMYEzv927ZVatcuGZ+HByy59HS8L4YMK1UClJSTg/IZHC3m5oZkutjYf3IKGKi4zmmbYChCVFw/Ij1Z3IM1ocCa64IFUmXU3R1MZ+9eo3WQloYIIN7P3x+Ox9u3wfg//1x8C9WrA+vPyYHf4Y03RPseMQKlLzIywLA5c/itt6DRVqiAMU2cqLZ/951o/3XrwvHJjD8yEuW6GzXC/nPmSIz9Cy+A0bu4KPXOO2D8DRpgX3ZIE4m/gUNa27UDowsNBWN3cAAMxjWNGL9/7DHB51mA6qvUPv64MZopIABCgEtGsNOYLQ9/f4HznJ0BIymFEF9nZ7mWtzcsGT8/3F/z5nh2bdti3NWq4Rr79+N4TRMrKygIjFspwIDsK5o8WUJi33hDoLqAAAh59j106gQh/v77uH9HRwj3gwfF11CxIsp7cPABO8NDQnCu3FzAT0OH4tna2+N9Hjnyz04GVXzntE0wFCEqrh+RnixKYtwvjLJRIxS10+cuKAUmMnOmML7atWEFZGYColi2THDnsDBhDDk5gI+4hlHXrhLrvmGDaMt9+kCLHTFC5VsZ27crdeiQSmUn5nPPAUoKC8N9zJ6NYzjy6MsvhYG9+SbgHhcX+DM8PcGEn3gC2195BUwwPBz7tGghf1ngEOF8jo6IvGGB0Lix+FFCQ42d0ThyiDVlFpIsKPTWQZUqxgzrsDApFVK7NoQoN1GaPBnj9fKSa4wfj79PP431tWrhGlzqw89PeixoGpg6WyV83vR0SR7s10+EZM+eCFF+/HFcd8YMdXriRAggDw98I3FxEq1UoQKEwKZNEkTQvLkoFt9+KxZkaCgsGobKJk8Wy6tLF7z3hzEfihHZBEMRouL6Eemp0EX0OnWyrrEdOwZmzU7UyEgko2kahMKSJaIV160LuCc3F9t//FFw74YNgT8rhSxZhj6Cg8FM1q6Fxmxvr9S0aXBQzp+vlJOTyihdGhFIP/wABu/lBaGyebNEHm3eDGvA3h4RUbVrY8yffYbtAQGIXGIB4+sLplerFhhp06ZgeHXqwOFcuTLG5uQkYbUNGmCMTk4QEpyd3KCBFNCrVUv8Cuwr4GccGio5Au7u2Kb3WbDwrFpV9lu+HM8sLg7XYt9HzZoQVn374rrz52P90KE4d2goLJJatRAGzMRafbly4gTWNOnt0LQpIpXs7XH/e/fm+yGSatTAO2RoKjwcoclbtwqM1qMH/EdLlojjftAg7JeTA+HNPaLr1kWUmqbB4pw1S5IJmzbFN/E3h7oW1zltEwxFiIrrR6SnQpfd1pOmKbVxo2iYrq6ANU6dwvb0dFRWZadww4b5pZmVUmAmHCVUpYpSX38tgmTOHCke98YbYBj9+ql8S2P/ftRd6tgxn9Fs//ZbRDsxM7lwAXAWRx7t2QMYxNkZjKduXTDvlStx/VKlEA3DWnGLFhjD8OHKoHkPHWr8260bGGSVKqLtMj5eqZJAJLVrG+EzhoO8vY0FB1mwsEDkc5YsKZFQnp6C4Zcvj/BQpmefhQCqWBHC2N5emiWFhkpG+/Tpwrjt7SEM9D02+B78/IxC4+uv8V4qVIBz2dcXmvxXXym1ciVqVnl4IErp3XfxDD09YS1mZODdcnHAuXMRcvvii3gvrq7Ijk9JAeT46aci/Bo3hmDXNFgy774rSkz16tg3M/Pvnw/FiGyCoQhRcf2I9FQoi4GLm6WnA/ZhLb9sWZRK4OiRtDQwWGZuzZpBgLBAiIkRqMbHBxOcJ/TmzcI8e/YEc1+5EhqioyO0xcxMWAWlS4ORfPCBUjdvqtvMKIcPB+OYNk3lWzkHD2L8JUsimap+fQiF1avBlF1dkXfh5gaYjHMaXnxR+jd4eMAq8PHBPr6++OviIiGY3btj/5YtJQGvY0dpF8oRPGXLGqO4mOEztMKZ440by3lq1xYtukkT7GMyCSx25gyeYXw8GDXnEvA1584VgcAW0NNPYx23AJ00yfhhsMXm64uaV0z79kFglCwJ6JF9EFOmqN8//1zuZ9gwJEDyWCIi4DO6cEEET40a6N194YIIfz8/CJLcXECQH34oz6FVK+yvFLatWCGwVEAA/ETmEOdfmQ/FiGyCoQhRcf2I9HTfsttubnAkvvqqmP5hYdDSOIIlNRXRKRxN07q1wElKgWFNnAgG7+YG7Z6ZzeXLIiwqV4Zj+epVYR4NGsBPkJYmsfS1a8OXsH+/UkFBqJW0dCn2YQx8zBhs9/WFZh4djXM5OgK/Zgfy8uWATcqXh4BgphYQAGYcEQHhMXQomDGPYeBALDdvLt3euPsbC4t69USIRkSIf4AjnIjAODmzuV072addO8lP4A5rpUuLj6NePWjudnZwojO98IL0ifbygiCqUwfjdXAAlu/mhnfEPbD79sU5Fy82fhx6Ia4vsX75Mt6BnR0CEiZMUIpIJdaqBeb/8svSBGjPHoQac72qTz/Fd7F2rfhehg7FN7Jrl0Qq1amDd6YUFJJFiySCi5sPKYVz/fyzCKBSpXD9+Pi/Ph+KEdkEQxGi4voR6clCMOjbez72GJgdJ25FRADLZ4afnAx4gHHf9u3FT6AUtPfXXoN2aWeHKKarV7EtMxOabIkSOP/s2WDsH38MBuLignj77Gz0eeAop2eegUD66CMw18BAtf/995W6fl0ij+bPR0jtY4+Bwe/dCw3c0RHJb8zwli4FAy1RAtaEpycYbu/eYKKvvy7XtLeHwChZEs+hRAn8ZYycSEJDGzaEH8DBQXIKWrQQi6hpU4HZ2rUTIcH7OjkJTBcUJLkGrVtDCDk4yPYWLbCOa1fdugUfQrt2kjPCVkPZsrAYPvwQ62bMAOTl7w9ma2eHEGM9seO5dGljb++UFInSGjtWqU8+UTnOzjjXzp34DgIC8MznzkUPDvbFdOmC7yA1FYLMwQEM/cMPxc/AQqNHD7GI7t6FAsLfW2QkLEKmXbvkfl1dIbA45+bPzIdiRDbBUISouH5Eesq/h4IS2xwcUFb5xAk5KCkJjJyzeTt3xqRkys4G02VIqVs3YwP5LVvEGdmtG5yRFy4YaxOdOQMB9N//glGWLQtYKj1dGHCHDkrdvKn2fPKJRB6tWQPHs6srsPxjx6ChOzjAUsjTbtVbb0FAmEzAzmvXBnNiJ+306dCUGzQA8/XywnOws5PSEb16SQOdMmXAwKtWhRDhnImICAiocuXEr1KvnvgfOnaUcFS2kgIC5Fk0aybRXFzdtEkT3JujozDnH36Q58v+lshICJ2mTTGGzz7D+pkzAd3Y22OdmxvOGRYGwWceZDBkCI7z8jImneXmCmzXoYM6sHAhBI2jI6yPW7cEkurQAdbEO+/g3fB4NA3fBjusGzdGuHFaGnxM7u4435QpkieTnAyhzU78Xr0kkk0pfKtPPind8wYOhHLxIPOhmJFNMBQhKq4fkZ7y76Eg/0JAgOx8+zY6r3G5hm7doI0zaRoYFGv3jRoJJqwUtETOZq5YUQqoLVoEDdzdHZnUubmwALh8dteugAZiY8VZO2MGtMvNm+H0LFsW+PfXX4Mh1K4Nn0azZmAO334rkTXPPAPmyJo0h8B+9BEYY4sWwN4dHBDWSgTLx9ERsIeHhzDdgQNxfhYWLBAGDIBAq1lTsH7OnwgOFv9ARIT4FfTd5NhKiIiA8KpSRSAqhstat4blUaYMNGWmhASMsVMnCK6uXTH2YcMEUtq+He8gMBBCnCE0f3+s0/fVUEqeUalSxjInSgGCc3RE2PCBAxLKO2gQrIIlSyAMSpdGEMKZM3J/XbsimEDTAOv5+ED4TpoEuDEuDooAh+IuWiQZ2omJ+B65B3f//rBMmC5fhs+IQ10jIiyz8guaD8WMbIKhCFFx/Yj0lH8P96qoevMmNGhu4h4VZTThlQLmy/j344+j1AVPwKwsYNElS4KZzpwJjfDUKYEXwsOlmcuPP4JBuLgguknTELLKPZfXrsV+eZFHKZUq4dilS8FAmjUDU2jRAkx79WqBTwYPRtQMEbTKjz/G/9x9zMNDfA3TpoFR1q0LpuPqCqHC8AmROHE51DUyEoy6dm0paDdsmAjSEiWg6TLkkbe/ZjIJ1t+6tSShsTCJiIC/pHx5gZHYcTxgAO7z2jV5H6+8IvfIOD4Rwj99fTG+nTshJHr1Eqf7K6/AgmjQQHIZmEaNwj6enpaCY9s2lcXZ0dHRCBYwmQBdxcRAi+fSJxMnQmAsWIB3XKoUEh81DUJtzBgc6+eHiCduG8tJeCEhUCr4+7p1C++P+10MGwYrlOn2bSgFnGPTuLGETRc0H4oZ2QRDEaLi+hHp6b4Wg4cHmJnJBOjFHGY4e1a05DJlwMj1VTK3bTM6YGNiADW9+SaERKlS4pBMT5ds47Awae35+utS6+fMGSOE0amT+u3HHyXyJjwc1kXLlmCWq1bBWrCzw/V37MB1W7SAtePiAo3+1VdVvt+hfHlYPcwsWVBMnYrxdukC5hoeDq27dWtYMvXqgWmyY5qZMjus27WTZ8FMvXt3pfz9Va6Dg+D5XbtCeNSoIcyQt/XujTHUqCFJd7ztzTfluScl4Rzh4WCIzZtL3sQ332D/WbMAqRHhvbVti2czbx7G36uXJfPke/HwEH9RHu1esQJQmqMjIot+/hljfewxCPv0dClaGBYGCOnUKYlk6tZNBM6ePRK91bGjQIvr1omvpl07RD4x3biBd8T9qEeNkgQ+pSDoFi+WvJpq1fBudaGuxXVO2wRDEaLi+hHpKf8eCuraxkxJ72NQCpNwwgRMQDc3mPT6mPe4OHHKBgVBQ2PNj+GgqChhBEePCtOcPBlMJDFRNOYBA6BlmkceZWWpWGayffvimDZtIAhWrkRylbMztMRTp6SZTUwMsHt/fzhc7e1hFYwbB6b41VcCv3TqBBjjP//BdfjvnDn4y34JhpPYeuAyHcOGgTlWrSr5F5wj0bOnUkFBKsfFRbB8Dt2MjIQAcHMTQcI5FU8+iTF36waB3Lw5ICo9TPLaa8bxsDBduBD36ugIPL9jRzDTbdukcx0LSn3EE9OkSdhWsqSB8UZHR+P5s3/k+eehOHBNqZkzIWh++kmK8X3wARSFefOkHeoXX+A+cnIQ0uzhIZZmejoUj0WLpFPdyJFGC+bqVTwnR0fAeRMnGq2p7Gw4uDm5MCAA7zA5udjOaZtgKEJUXD8iPd3XYvD3Nx6Qmgqz3N0djGn0aMtJt3ChNKKZMQOaWmYmGKqDAxjZ6tXYX9MwyZ2dwbQ5KubIEeDqDg7YrmnwO3C3tfnzcS1mvqNHQzC1bQuhsGIFmB635oyNBZTh4QFLpEcPjH/TJlwnMBAMiwVThw7Yd/VqEQKlS0MDr1ULQqx3bzCnl17CmEaMAHMbORLPJzIS2m2zZtDunZ3Fx8Lj7tlTqSpV4Ccxh31GjADzrF8fwo57LhOJE501cGb+ep9OcjLG16kThFJIiNzXsWN4D3XrAnbz9YUQYouqbVuBjj7+2PLDYUitRIn8Inf531JWliga3bvDguN76twZ0E5cnAjJnj2x7tQpKQXeowfet1L4vvi5Va6M4AKlADtNmQIB4O4OyzItTcYYG4vnxRnozz5rDGPlQo8cFFCqlLowePCfDnV9lGQTDEWI/lWC4X5d27KzgdNz+ecePdDDWU87dgiO3LGjOAL37JEs3kGDgAkrBauDQz4jIsSpuWIFJrKfn7SAPH4cwsvNDZFHmZn5mHzsgAEQPu3bY7zLl6OJj68vtMHYWIyXwzHfflvla/ojRuCYTZvgG6lYEdokESJo6tWD0GDrYNEi2eboCB9D1aqAripWBMzE+Q9lyoizmq0BjqhiSCYqSqlq1VSmp6c4ePkvM99+/SCUmjcH46xaFczex0f6MnMo7dChxnfCznOGjGbOhMDmft1EsCw2bhSB9emn+H/KFLxHBwdEkpkTWyBubkqdO2ecDyzw7exgMVy6hHwYR0c8p0OHYD3Mmyd9M6KjYSXMnQvh5OWFd8FW0ObNkujXuzeinJQCzMQRW4GBxmOUgnU4ZIj0o54+3VgJWCn4yHr2hK/H1RUWh95PUcTJJhiKEP2rBENBFkNgIGAgLszWpIllv94bN8TBGhAgjue7d6VMQ7lywJmZ1q8H43Z2BlzAJTFYE27ZUuCBzZvBXDny6O5difl/6y21beNGMDCTCUzt+nVpjnPihBFC2bYNGmSvXvA9ECHLmff58Uc8i5o1xUn90UcYa9u2sAJ8fBBKSSTM9eWXVT7OTyRlJxjO4e5xDAWNGwfront3pcLCVIa3twgpFh4cdsp+l7FjwdTHjAGDGzwYPo0BA4DljxgBJq3PVE5JwXjbt4dmXLq0CJxt2+A3cnQElMdWxzffyDg//hj+lscek5IneuL7dHWFj8Gc9L0d9u5Fw55y5XDvn32Gffbvh1A2mWBhZmXhvXGyW1SUKA36arvu7nBgcw5HdLSEATdqZAyhVgqKDDv4PT0Bl+mflVJqz2efAebjUNcBAwod6vooySYYihD9qwSDtTwGFxfR0IKDpeIlU04OnHlcXvmFF6Tw2rZtUil01Cg4Q5UCRswYdc2a4sy+elXKK0ydKg5srnkUGorIo8REaM4mE8Ig09PVLS4c9/HHmOh16uBedu8W7XfMGEASZcuCCZ06BcFRrx72s7cHY2X/webNEC5hYVJH6fPPRQiEhEBITpuG8c2YofItCb3/YeFClY/Vs0DgPgm+vrAw6tVDT4mhQ8Gw2GLgkFpuHmQufDgBj4UU+zo+/ND4kufNw/olS1S+JcLC7+pVCIt69QDDNGyIMXBCmpsbmDsXDrTWPCdvnDlOTtaFB1e4dXFBOPGNGwLfjBsHhSAlRfwujRtDW8/OhqXj5IRop1Wr5JznzolyEBaGCCv+Jj/5RCzbvn0tk9z++EPyP7y88Dzzvtv8+XDlCp4T55h07gx/1T1CXR8l2QRDEaJ/nWDQZz1zo3pfX0AA5v14d+8W7axdO4GVkpMFJqlUyQhBHDsmDr+JEwUP3rpVCrLx5NdHHoWHg+Ffvw5YwtER+2VkCBS1dCmW27YFo/75Z8TqOzpifGlpYEaurohk6dABTO/oUcBffn6AN9gPsHgxzrt2LTTcFi1wX05OgLJYEAUFgWk0bowQzyFDwGgnTsT5OXdi6lTJnvb3B8MKDoal06iRSvP3h3YaFAS4zcFBsoLZj8CC4Y03RLt2cgKcVaoUjqtZE+PQ0927eL6tW2MfZ2fJXViwAMyaz3vuHKyzJk0A//j74z1u2IDjmjeXUih6mj1baUTYR59sxnTjhuQuzJ6N74kFXuPGAgutWgXB5OEBSEgpwIhcD6t3b7EeuFw311IaOVJgypQUCHlXV4zphRcsrAO1f798P2XKKLVggdrG/gumhAQIYH2o65o1f3tV179KNsFQhOhfIxgKynqOirIsSnbzpmi0/v6YyKxFbdgA6MlkAnSiL9v83nvQGH184OTl9fPmgWGGhEh2tD7yaOxYaI6xsdD0XV0BQ2Vm5kcsnZo6FZoiH7N8OTRObsWZkCAa+2efiVb/wQeida9ZI3kGp06BUbRuDaHI8IqbGxzEgwaBcf3yi8q3CkwmhH+WKwfcv2FDZPP27w9m37cvGGznztDOw8PB7Nq0Uap5cySH9ekDwdmtG87z5JOwup54AoJr6FAwwf794TRu2RLnqVwZ78TdXXwJ5mHFbPWsXAlGOWgQmGLJkrAaeveGkDl2DPswHLZrF4RreLj4XgYNsqo5xzAE5uxsHX7JyJD+DAMHwnpcvRrjLlNGaiNduCDW49ChUDays2GFOTnhvX79tZw3JUXKlnh7Q2Az4758Wa5ZpoyU3dDTrl35YcEZpUvjWzUXfmlpSL7kiq9VqyIk92+q6vpXySYYihD9awTD/aqqKoXJ9MEH0EwdHOA74PDU27cl6qRaNSO2Gx8vIafh4eI3SE6W/IeoKNHm9JFHCxaAAZ08CYbo6Qn/RmamJIi9/76K3rJFomDmzcO5atTAWE+fhtZPBPjmyBEwrm7dgGM7OYHxckTSW28JhLNzJ55Bo0YCDe3YAQE3Zgz8IS4u8JGwdUEkLUWnTYMGHxmJyKIOHWCdREZCI2/fHhp4mzZI0uvRA5ZJq1bYv1Mn/OrVg2VRpw4YeMWK0LYdHUXIcaLesmW4J/NqqWlpEOTNm4sl9v33YiHduAGm2qABmPDw4XgHv/5qrK3EPpNZs6x/SwxbOTnBAjMnTRNh3LQprnviBBQDe3scr2kYw3/+I8X4OMP+2DEJd+7TxxhBdOSIWCXNmhmF4759kkwZGopgA8sbUIlcrTUwEL4lc0s5OxuCk0Nwy5XDmPWh2o+AbIKhCNG/RjDcLyJp717pTta6tREq+O474Pb29mAcek1r0yZsc3KCxspa3MmTECB2dohAYe3z2DFj5JFSMPdLlwYUcvgwJipHoORVAz3Pju/nnsPE7dwZwuvXXwGNeHpCw05MBKP29YWAatoUGPPFi2A+wcGAT0qUANNhZvv992AA7dpJVNKePdBAe/WCkAkKgqZJJNDM119jHC++CCE1ZgyOeeopOHR79YLQ6dhRJT/+OARGZCSYTteusB7Gj8f4n3kGTJwtAtbq2e8xZw7uq3dvCDovL0utl+GxNWtgubVuLT6VLVuQu8E+jNRUaMV+fmC+HCb77bcSYcVQj/5bUkqElaOjtA81p9WrpbfD0aMQ5lwSpE8fYbS//YaEQwcH3HtuLt7x66/j/D4+sOaYcnMhHL298U0++6xYvZqGfbkrXkSERX5O9JYtiNBiv1XlyrBAza0MTYOFzKVNHnsM3795uZCHRDbBUIToXyMY7lUnafRoKU+gDwO8fl00/tq1jSUyMjIka7h6dWN26jffADrw8TH6H/SRR8xMtm4F1BEUhJDErCxhHosWYR+GeoYOxdgYj//gA0AVdepg0p4/L07v9euFwS9fLs7bjRvBiO3twTAqV4ZA4eikdeugbdati/ESYRv3h+7VC0yMncC//qry/R9sjZhMYMYMFdWtq1SXLuoOh6AOGgRmOWoUntGCBTiWhQ4LAhY606ZJ+Q22YNgHonfW8nsJCABOzkJi9WpYINWqYXtUFATQiRN4b87OYKDsmHZ3lz4Lzs7i9FVm84GtKEdHCFFrpO/twJ3a5s6FwlCtmjiyExIEJmzfXvJmjh4V66FvX6Nj/NYtEWYBARBo/O1mZCBk2cMD73o6EyJVAAAgAElEQVT8+Pxj8++B636xZVCtGp6nNd/Cnj14biYTnv+4cVBIHiLZBEMRon+NYBg71tJqcHKC5mxvD38BQz2aBubk5YV9Xn/daG6fOCGTadw4cTBnZ4uzsVEjYL9M5pFHSoEJu7hgQl65guNZEL3zDvb55hulTCZ1q3FjaepCJDAKY94//CBx+hMnAsMuUULqM7m5wQo5exbjGDtWGPB338FaCgkBRJYHX6nhw8HQOAFu40Y8k2HDoLEHBcF3o9fuWUC8/z4Y7OTJsAq6d1dJXGxv/HhYFwxnffedCDD+6+AA/L95c4yN+x8wHLZ8OaCQjh0tX/gHH8gzCQnBjwXJ3LkQ+F5eeEeceUwEAXX5MiyekBA8wypVILzymKDFfOBrOThYho4yXb4M4W1nB6tS0yBQfXzwfL/9Vr67pUvxrkqXxvehFN777NkQQGXK4HnpaedOCXiIiDAy7Ph4iRLz9FRq3jy1deNG4/G5ufjOuDBkWJhk8ZvTqVPw9Tg64n769zcqRf8g2QRDEaJ/g2A4PmOGdcczERiP3ol4+bL0BG7SxGiGaxoYAVfR1JeBvn7dGJ7IEEdursTOc+SRUmCo9vZgejdvQihw/Pn8+dhnyxYIpqZN1bb168FMuP8Bt4YkgtP55k1YIjVqIEKHS13HxoKJu7iA0fXti2dx5QpglNBQhN0SwfHIeQLx8WAkgwdD+Hh4IEGKNfrAQJxr2jQwCRYQ7LxlZj9zJgRf794qoXZt+BemT8e9syXEVsennwpcV68ehMjMmWBA7AT/9FNYLJGR2GYy5Wcl51NmJoRW/fpgcHxv7Hi/fFnG+fbbeK/duwsstG0bnnP37oAES5XCPSQmWp8PLAzt7AB1mUwiNJlSUyV8NK/Mibp0SeCcadMkV+HkSVE8Jk6EVagUvlOOkuvfX6KTlMKxCxbgnXPvDz3Mdvx4fuhrmr+/0bpgysmBdchtWevXR+SbNQFx9SqUIC462akTHOv/YKirTTAUIfo3CIZ07rpm/vP2lg9Z0xAD7+EBxvjOO0bM9eZNcQZ36GAskbFrl2VCk1Jg0AwLceSRUgJxtG4NQZGdLeUQ5s7FPgcPYtLVqKHU7dvq9+XLwaCqV0e+xB9/4Hpt2oDJ9OgBIXL4sAiMxYuF6b76KmANImjfjLWvWgWIwMsLPgkuW8EM9ccfIXCeeEKyqQ8cUPlWTUQEhAs7W1etwl9m5AsWQOvu31/drl8fEA/7EHgM27eDmb76Ku6vWzdYFe7uEI6M+5ctC7jl2WfBxA8fxnEzZ1q+9I8+wnFr18LR7eMjz+yJJ/C+e/QAVHTyJJhsQADGmpwsuRmzZgHuc3RUqn17tXXzZusfGZfW0P/c3IzCITdXIsfatQN8lJEhpUPathVHc0aGJAyGhorPKysLz8nBAUKI/VRMV66I1RkcjPegpw0bVCoX2GvZ0rp/JDsbPgzer0kTfEfWKDERMCV3PmzYEErBPxDqahMMRYj+DYJBu5/j+dw56SfQtq0ldvrLL8CJnZygzfNHr2lgvo6OcPbpI1SsRR5pmsT8d+sGTTAnx7JyaEyMlJ++fFmphAR1t3x5WCnnzkEwVKmCMV2/LhrrvHlg7qVKSSx+9erA1+/exb1xC8uaNWExnD0LTffFFwWm2rULJSq8vQFTEIHBhYfjGLYGdu/GGAcOBOzk62s8B5HkQQwZom41agRLgOGXdeuEeQcEwOHbty8YEsNcBw6If2PkSAjL3bux7aOPIKQDAy0dp1lZeCe1ayOwgAiWyqxZ+H/zZnlWTZrg+G3b8CwGD8a7GjQI7++nn/Krz17t0sW6VlyYqDemvN4OKiQEz18pMGJnZzwHvb+CE+9cXGBh8bUPHxarYuBAY+c5peBj4uZH/fsbFJmtv/yCd+Djg/sbOlRyLPSUmYn9ypUTRWb7dsv9lAKc+v774vQOCcH7sZYP8ifpoQoGIgonotNEFENEL1jZPpWIThDRESL6lYiCdNtyiehw3u+HwlzPJhgePhVoMQQGQut1c4OlsGSJcdJnZsJcNpnAEPWM/+5dqazapYuxLo0+8uj777FO00QDHDwYWllOjkS/vP469ouLw+Ty9oYmm5WlVLt2KFn92284T1QUIJfffoPD2s0NGmhuLjRqZ2dgwezUXbsW0SVEcEgzY1+xAj4ABwcwhvr1YaGkpOCcY8YA1rG3x7jc3KDJP/88hOT16yLQWrVCBBT3SNi/H3+/+QYhpCNGqJvNmgG/ZkuBrYoPPgDTadZMLI+DB/F36VLAYtWrA7ojgq+Dm/qwhWKOmyslltN334F5urjgeVWuDG06I0MgMIbvePzLl+Md16kDwcSd+pjRmtP9lA9z2rYN79jLCxaJUhCCFSrg2X74oTEIgvtT9OghEFJmJqwlBwdYU9zDgyktDUEATk74vhctUionR+Z0UhIgLCcnvNtXXpG8HD2lp8OC4nnUqVPBzvbsbLxfhrz8/WFpmife/Ql6aIKBiOyJ6BwRVSIiJyL6g4iqm+3Thojc8v4fS0SrdNtSH/SaNsHw8Mmqj8HFRcpZdOlidBQrBcbKtfJHjzY2dImJAYPjhC+92bxpk2XkUXa2VBWdOBH75+ZK7aXZs7FfUhK0QDc34Pmall/m+sS0adiHo4HefhtCo0EDaL2XL0tdpDlzwMhLlgSunJOD3IKKFcEM69TBvd++jX0GDoTQI4JzlPH3rVsBY7RuDSHETLZlSzhut2/Hup9+gqY7eDCeVenSsv/mzdB4x4xRN1q1Ala/fj22bdsmUNCIEWA8zPx37ADjHDFCoKdz5/DeJk5EjSU7OzjWvb0BD5lTdjbw8tBQRGw5O2OMfP05c/CMu3XDeU+fxrNq2RLMUi8MzH/h4RD+7E/QZ9Trf2XLFvxhxsRIbweu7nrrlgiB4cMlsCE3F4JeX4yP6dAhcT4PGmRpPZw5I2XC69ZV+//3P+P28+elR3i5coBDrUFBd+8C6uR77drVeh6HUtJ4ii1xT09YbO+9Z3xu1mpPFUAPUzA0IaKNuuUXiejFe+xfh4h26pZtgqEY0PEZM4wT180NWrCXFz5MvZWgjwzx9rbEcH/4AR95qVKWTeWXLMF59ZFHHB5JBAaoaZh0XDPnlVewX3o6GLCDg5Rc5nDTadPwHrZvx/l79sR5uADd6tWwWHx9wfSzsmCJODmBKegdwz/+iP+XLROLYv9+OMydncFUunYFg4iJwfYFCzBOkwkx7K6uiIr63/+w/cwZbHvlFTDZsDCBifbuxbOaMEFdb9sWAolhJoZJRo2ScNrjx1W+FRERAQuGfSNffAGnM+cFEAHKmzQJ96p3xjLxvX/9tSS9HTiAZ+jmhvd07RrCfZs1g2Dg5/4gPycnMG1za4GFfEGk7+3w3HO4fk6OlAapW9dYB+ngQcA0JhMYLUfL6Uu++/lJRJP+u161Sik/P0CrY8ZYVl/dsUPKctStC8FtjZKTkQTI/ah79zb2OzenvXslFNf8Z+6HuQc9TMHQm4g+0i0PJqLF99h/MRG9pFvOIaL9RPQ7EfUozDVtguEh04oVKsfZ2fKDbNhQauEz3b4tTLxdO2P3rpwcYcR16xrLFRcUeZSSIt3J/vtf2Zdjz19+Wc7N1+VJsn49NOLu3ZXKzVU7vv0WE75KFVgW27dj+5NPYn9uanPwICY4EfwGGRlgpHXq4DoNG2I5LQ0aW4sW0AS5gmlCAhjc1KnigI2JwX716gnEs3IlmIunpzDzzz8HY+nUSRjy6dNwIk+ZouI6dMC1ef8vv4Ql07WrJMxxf4lx46R15u3bYEIjRogP48gR+EmaN8f/+mesp5wcaOXVq+M83t4QwBcuQMBFRWE/DpXl3tR/5uftbdSG//tfwIIlSxpyISwoO1tqb3XvLslqrIR4eRmhstRUKdnSqJHRJ3bgABQTIigH5sz/zh11uVcvfDtlyuC+9YpRbi4EcPnyOEdUFN6/NUpMxDfs7o57HjgQSkJBVJAFZs0PY4UKKxgc6K+Tyco6ZXVHk2kQEdUnola61YFKqWsmk6kSEW0xmUxHlVLnrBw7iohGERH5+vrS1q1b//LAHxalpqYWq/GaU+NnniGXzEyL9RkXL9LvJ08SnTxJRESPHTpE1d54gxyTkujC6NF0+YkniM6cITpzhhzu3KHqr79OXvv2UVx4OJ2dPJm0ixeJLl4ku4wMqjZnDvn89htd7d6dYiZOJHXwIDkkJ1PYCy9QydOn6dS0aXSjVi2iLVso+L//Jf916+jioEF0oU0bouhoCn7nHfJft45ixo+nK+XKkdunn1LdCRMoo2JFOjR6NOVGR1PNV1+l3Nu36eCsWZSxfTs1GDmSVNmytL93b/KYN49qffIJXRwwgC4kJFC9MWPI0ceH9rZoQf7PPENVYmPpj/HjiRYsoFp799LpKVMoZ+5cqnHxIh0bMYLsZ82ianfu0OEGDcjljTeoanY2HQgOpkpLlpBTUBAdOHOGmu/eTVd696aM5cspmKAJVduxg1RgIF1eu5ZCiejgnTtUPTaWEr29KWXfPgomol3HjlHjzEy6EhdHRESZqal04MQJakpEZ/btI29nZ3I8c4bOJCZSfSI69sMPVD4wkNSOHXRx8GCqpRT98ckn5F+zJrn/9BMdCg+npkR0fuFCokaNqNLHH9PukyepRtWqZLdwIe0PCyMyGae1T58+VGP2bDrxzjvkOHAgPb5oER1duZJKDBxIlT76iI7MnUsOd+5QNTs7MiUm/ulvTSUk0LZvvjGsc37zTao1dSo5tW9PR996i+6Ehlo/uE8fKufgQFUWL6a7tWvT0TfeoMwyZcj1vfeoxn/+QyXCw+nC8OF0acAAIjs7okGDyKdcOQqZP58oNJTOTJlC8e3bExGRaf58Cvr8cwpasYKyfv6ZTk+dSglNmuRfKnXYMLreqRMFv/MOeQwZQknz59OZyZMprUIF7ODvT3ZLllD51asp8MsvyfTDD3Q1KoouDh5MOe7uxnG3bUuO9epR+a++onLffkt2K1fS9Y4d6eLQoZRRtqxh11ZxcdYZ7qVLtO3v5DGFkR73+lEhoSQiak9EJ4mozD3O9SkR9b7fNW0Ww0Om+zkFMzMBMZhMcEgeOGA8fv9+aDROTpbO6bg4iTx65x3ZdvUqIBCuUqoUtnGtoxdekH25XAP7EG7ehJbp6ytwFPcDWLYMy4MGwTrYvRvaZYUKgBfS0wXeWbUKloW3N6AKTZOeyBkZcBRXqgSNulkzYPGaBguncmVog1z9lB3XGzdCC/X1hWbp6Yl74uJ1cXFSHoOhobQ0aKczZqirXbtCS01NxbY334SlU64cxkoEfwJbIomJeLavvSZJaOfPw0neuDEieogQjcWRTtacorm5eB/BwRhPcDCsiNRU/F+mDJ5nYS2Dgr6pgjTfq1fxfkqUEEdzQbR+vfiouHZSaqq0Pe3WDc+FKTZWaicNHmysZ7R/v7SSHTYs/7j8OZ2bCwuMa4PpS8ozXbsmPTS8vQHdmddWYrp+HcEMzs6wOseMMfruHiRyywrRQ4SSHIjoPBFVJHE+1zDbpw7BQf242fpSROSc939pIjpLZo5raz+bYHjIdK+P8cwZqY/01FOWk+Kjj/CRly8vk5TJWuSRUjDrK1WCec2x35omzXmee06EApeAePJJaeLD7TEZl87D6q9FRGCZM4zZNzFpEibtjh0QKqVKIbdB06R/woEDcFYSgcHu2YP/Fy4UWOett8DY7ewAmXHk0M6dUsyOGWn37hBaRBBEEyfifm/cwLpFi8BkHB0hePLGe7lnT4xP08CIX3xRkt1ycuC0HjVKhNulS3BWR0bKOJcuRRw/+zvq18fvzh28i1GjrH8H3Gxo+XLJ0Xj/ffE7FFIYpPv6QhiaBzPcDyuPi8O9uLoWnBPAdPw4AgVcXKTkB3eLc3AAnKgvnpedje/Bzg5CXf+tZmRIZFm5ckr9/LPlnI6Pl0CIoCDL6CalAPFxzaSqVaW8hzW6cgXPyNER3/KkSbh/axWOi6KPAdeiCCI6k8f8Z+Stm0VE3fL+/4WIbpBZWCoRNSWio3nC5CgRjSjM9WyC4SGTNR+Dmxtw/hIlwKi4JAFTerqUmmjf3rJxC0ce+fkZE4SOHsU6Ly/RXDUNvQSIUCSOJ9PXX4PZdO2Kia1pErnEhdvOnwe2Xrs2auhfvAhNukkTHLNzJ84xYQL2HzUKDODYMWh6rq4SWtm2LbTQtDTkKHh4QLucMgXM5vp1cboePw4N1ccHDJvLX9+6he1z5ogTe8cOOIlr1UJsPRGc4WPHgtFnZmLda6+pS717Q4AohWc0dqxYAtevwwpo21ainX78Ec+kdGlot2XL4n7Yz7FsmVQ6PXsW8fglS1oPuczNxRgrV4bG27IlLAXG0u/100XPGHp7PGh0zY0b0OBdXKyH1+opPl4sgVmz5LvZvh3Pwc3NosCf2r4dIdgODrDG9JFF+/bll7y41rmzNJXS02+/SXvabt0sM8o1DUKDM6M7dLAsfa6nCxdgbXA/6ueeE18YEf6OHXvv56CjhyoYHvbPJhgePh2fMUMmcUCAlCFo08YyTDU2VoqWTZ9umTjFkUdhYdBomXbvhpDx95csVX3uwuTJMrl//RUwU7NmEgY7dy72+89/sJyeDobs6Ylew7/8glwBd3dYJenp0NwCA8Hg9+2THhFKIWzU0RH7sjN6/nyM2d4eQiojA/BAr144pkkT3FdWFgTSk0/CYctZyT//jPNER0uJ7qQkwCRRURIGumMHBEvlygIbvfWWutivHzRIpWBVDRggmvyhQ3BeBgUJrDRnjjibY2KwP8NYAQGI6b90KV/w5IfIfvqp9Q+BLYVlyyTp7V4/K9rsX54P8fF4xs7OllFt5pSRIXkuAwZIaYxr12BZEkEb10M7CQmS+WweQJGRodSLLyrNzg7Pz7xhj1I419y5uHdXV7wD834MmZmAD0uVgpUyapRlIIeezp6VnJ9CPOOCyCYYihAVe8GwYgXMf5MJTMXLSzQqc6a/aRMYpYeHER5SCsyIC+R17mzEcjdvhvVRubJEK2ma9B1++mkRCgcOgLnXrCkRI2vXYnx9+oiWx2US8sz6GC658Mkn2M4RUuvX45hGjXB/SUnIwbC3B8SjFKKESpcGk37+eUzm2FiBpTZsgHbHzJjLUKxZI7kRO3ZI74CUFDAqzjh2csKzWbYM+547h9wQLgNOpNSCBSp20CAcrxSipLp0kczqn3+W2kcZGTh3//4oY0EE5sElwo8dEzgnPR2+k5o18YyDg8E0rZGmYUwVKkhdpoKEgr29VYb1t8yHW7dw/05Oxh7hBY2Z/TVNmggDzsqSSrrNmxtLtGgaYFAOudbX9FIKeQzVquHYkSOtJ59dvCil36tXt+4buX0bY3BwgKU2Z44IL2vErUitWWSFIJtgKEJUrAWDNUyTk9L0lJuLjFuTCQzGPOROX/No3DipeaQUGKeTE0IEeXJqmoSvjh8vQuHsWcAXQUFSguDwYQiV+vXFeuDQyeefx/L+/ch87tMH5zp8GJNxyBBsZ4bMdZqiojBR4+PFn/Dmm2Donp44j1KAbYKCcP9sAZw/Lw7E1FTcb4kS0BI7dgQcoxSeU5cu4mvQd4pLS8tvzqPi47Hu3Xelp0RuLkJGmzfH9YjA9Pm+T52CX6FmTQieEiWkYiwRfCNsvfz8s9SeOnpUekWfPm39m2AIzMurYKFwDy32b5sPCQl4546OlkqINfrmG2jwgYFG+ObLLzHesmUty1WcOiVlM8aPz0+Wi46OBgOfNg2Cunz5gqGtdeukZtLgwdZ7MZw+DeiJmfxXX1n3PzxodrgZ2QRDEaJiLRgKEwWRmCjd1wYMsMSnC4o8UgoM2c4Omhxr/5oGpyoRtFre/9o1OBRLl5Ya/HFxmJTlyonJf+QIGECrVhBAd+8qFRKCdoy3b2NdvXoQMLduYfw+Pogyys2VOkIs/Lp2BRNMThY8f9cuSV7j/cLCgPFrGsbZpQvWh4TAQuIopNGjISQ4ioWti82b4evw9MRxoaGAeq5ezRcc5zj2PiMDDuzQUDAohoI48e3HH/EMHRxwrdatpcdzpUo4Nj0dAmPsWGjR7DSPi4O2z0LVnDRNoMSCfveANv7W+ZCYiLE4OFj6uazR/v2AKt3djZbGkSNwSDs4QGjqv1F935CaNZU6dsx4D7//DkiSCH41a9bD3buAVR0dATG+/76lta0UINJatVS+dWOe2FdcopIexc8mGB4i3U9D0U+oRYsstRx95JF5pAZnDXfsaOz7zJFAo0cLLJSUhAlTooREjKSngxG7uUmI7J07cOyVLSvtQceMUcpkUoe4lg/7Irgf8NNP434OHsT1W7QApJSSIk5aLttRpQquqRSYup0dfCwc8bNwIe6ZCNj+lSv4f948lB9nKIsTyr74Qgr4nT8Pq6pqVZw/MBDOYLYoPv5Y4LDUVGwrXx77PvYYNFqOalq4UGCuP/7AWB0coPGOHAnhk50NwRMQgPtu3x73xyUufH0LDqvk8Ns/waT+9vmQlAQmam9v7PFcEF25AjjMzs6oqCQlidZuTcFZvz6/GN9pvb9LKXyLzz2HcwYGQshbo5MnJTKpYUPL0G6lIDA+/hjfMBHgQA67Lk5RSQ/7ZxMMD5HupaGsWAHN3M8P+Lk5FRR5pC9F0bu3sXok5ySMHClCIT0d2r+jo5jrmiZx6fomLb17g0FwKQKuG/Tss3gPZ84gooVLYvzxByYzR3YwTMK1cKKicA+JidKredUqMExfX8A1SkkTnLg4wbOvXhVo5+BBgatOnpRub0eOCNPOzobV0qYNzunpCfiHLZPPPlNnObs3MRECzcMD+1arhrFqGiCwiRNFQH3+uTiNd+4UgbF3r/gcDh6UMtv798tzKwiiWbHCutLAfSXuQf/IfEhOBqxmb28ZaWSNUlMF/x89WgSgHhINDZXKrUzXryMznwhWl3kJkV274KPh81rr8axpeEa+vvhmJkywHuGUnIx54uKC3/TpWDd2rC0qydrPJhgeIhWkoXBtmpYtRTPXU0GRR7m50GyJEIanN6e5Kufw4SIUcnJkAusnPJfe5oqqSkkP4bfewvL164CIatdWKiNDRf/6K8br6QlYStOw7O0NiCknB1DB44+DUXAtoZdewvlat4Y2mJ0t1VXXrsV5qlSBv0EpaK/16+P/oUNx/txcRJ489pj0FHB0BMzTpw+OVwoQ1IAB2MdkwrVPnsy//zMcthsfD2FkMmHftm1xXaVwvxERuAcnJ0BCcXE4bv58qeg6Zw7+54ip27cxpmefxT36+QFGs0YFKQze3vf7ov65+ZCSAgXCzg7C8H6UmyuQJfd2YOJOe56eFo5nlZurzo4fL0UC9a1nlYJV9swzEoZr3s+BKTERc8FkgnWgb4mrp0uXpKy8hweua7MYbILhkZM+KqlcOYnBnjrVEmq4V+RRVpZo+c8+a5wEzOiHDTP2auBciIULZV+uCTRokJxjxw7pGMZ9GyIioGnlFSc7zWGvXIWTK6B++CGW8/oFqNWrsdyvH7DoW7ekcurbb2Nb585gCtnZUqBu6VJhtBw3HxAAK0YpCMlOnfB/ly7QSJUCrNGpE/Z3cQFTSU6W6zHstHq1OsX3cPWq5B8kJUkPaKVwveBg/F+rFjRcpbCdneY1a0K4KwVojAVZZCTgKRZe9vbGaB2mv+AE/UfnQ2oqhKTJJNFn96NPP4VADA42Bk1cuCBh1y+9ZFBioqOjjcX4XnzRci7s3ClzZexYqd9kTvv2yXXatRP/mTnt2YOABpuPwSYYHjnlJSFpHKrq4QGc37yBvFJwsHEhu/HjjZFHaWnS7vONN4xCgaGXwYONFgTDTdOny7p9+wBfNW0qYX03boBJcxkKpSTK5t13sXzpksrmnguaBsbr748JmZOD8XF+hqZhcppMUmZjyBDcd2Ii8F6TCb4QpcDIHR2hcTI0c/gwmAwRHI3JydBkuVNaYCCEpKZBKx03TsJS58+H34IIlhd3e/v+e3WShW5srEA/sbEQxs7OOB+3Cs3JwTMtVw7X7NsX11UKMJSrK2A8joS6elUK9+3YIeOfM8fyXf8FJ+g/Ph/u3oXQM5kgrAtD27cjqKFUKWM57vR0qeLbqVM+dJR/D6mpUtDRvBgfj2XKFIylQgVL64IpJwdZ/J6esAheeknKhevJFpVkEwyPnAoKVWWoRk9xcYh6MZmkWTvTnTuAbEwmMEk9cWjkwIFGocAZxCNGyLmuXAEzDwyUkL+cHDB7Z2epa3/8ODTvzp3FeujSReW4uMjE5VDY3buxzC03+V0NGQLGeeMGNGZHR8lpmDkT+54/L4liDLl0747xaZr0Yz59WiKP1q8XATBnjmRCz58vzukvvxT/wKpV0if6p5/UCYY+zp6FZUMEPwk78hMSxJl94YI42m/fFqjt6lXxl2zdKhbJkiUQYC4ukgnesqU4pO/3bRQS0ngo8yEtTXwBH3xQuGPOnYOvxsEBQldPS5aAYVeooNSBA5b3sHo1YMKSJa3DWNu3S++SceMKth7i4iSRrWJFlM3Qky0qySYYHjkV9iO8V+RRfDygEgcHOD31xMy4f3+jdfHVVxAi3bvL+rt3cR53d2MMOlsVPJEzMgCf+PiI7yPP0Xt2/HgsnzwJRs/lthMSoCl27ozlmBhAKJwBPWMGxhMTA0FUvrzAMNu24fpffAFm5OoqTLV3b4n4YasoIcFYroJzJL7/XnpLR0dL0tqGDZJ1vXGjOs49Bk6cgHOfCNnK7FA+flyE0C+/SPTQ1q0ShvvddxBOdnbwU2ga3h870nv3hnWYk4O8Dj7enP5MSQv1EOdDerpYqYsXF+6YpCREyRHBEtQrK3v24N07O6uT1kJ5L16UbOpBgyzDVu/eRX6LyQSmf69igFu2SAhsVJT46WxRSTbB8MipMGZrQZFHSuFjDgmBBmqu+bCG27evUShs2gSm3aKFsdb5AlgAACAASURBVPNWr164rr55yk8/4RzM4JWC74JI9ouPh0O0cWOUxNA0MHVPT8mA5cqwhw9jecQIWCDXrmEM3t4I69Rfk8Mix4yBMEhJkcY6mzZhzN7ecD4rhTBIDkPlAncXL4qf4+hRgXFOnZLks927pXjfli3qKDvo//hDhMq6dWAyLAy4xMUHH0gOxKJFEJrsjFYKsFmzZvh/4kS8p7t3pcTGr79i2cMDkNTfRA91PnC+B5H1XhPWKDtbCjZ27WrU7uPjpT/IqFGW/Zizs+HIt7NDvoi1SrW//Sa9pCdMsF6XSikEJrz+Ot5LiRLwKWVl/WmBrJRNMBQpKraC4X4Ww4cfWo88UgrwSfnyYCq//WbcxiWm+/QxCoV9+2ARhIYayyKzVcB5CEoBJilVCtYBC5Bff8VkGTNG9uvfH8zw+HG8B44mYmf25cuYeMz4YmNh3bDWz3WGOPy1Rw9YI5mZmKTe3hBuSsFRXrIktrGzmpu4+PjAsa4UHJGenljPTve7d8WCunNHLAC9ZbB9uzrC+x84AAFCBOji9Gm5Xm4uBBtXofX2xtiUAg7esiX+5zDZlBS5xg8/4Hm6u8sxLPyshVT+CXro8yEzU3xf8+YV/rjFi/F916oleQRKKZWdrWI5iKJhQ8tvXylYeVyMb84cyzafqalSGLJSpYI7vSkFyDIyEvuGhiKk2yYYbILhkVFBZuvnn0vkUUSEZaz2wYNghD4++F9P7Dvo1csYxXHmDPavUMFYtIy1aL2vISMDUTQeHhJnfvs2nKwhIVIWg2Px8zKTt61fj4lUs6YIpOHDITi4CiaXOr50CderVg0QlqbBgrC3h1WilBS8+/57qVzKfZM5YujKFWDXeqy7eXP8lIKw8PPD/1Om4PlqmvRGuHpVrJTff1d/cNmN33+XsNPFiyWKif0/1aohzFcphNk2aoT/n34a18jORhIWEayTzEwINRYGgwYhXDMzU6KuzP1Df5IeyXzIypLCeG++WfjjNmzAd+bra8hCzlcySpaE09paGfDEROkD3batlHDR07ZtEAxEeDcFWQ+ahrpb1sqQ2KAkm2B46KSPSgoKQpJWQZFHSsE68PCAtWBea4cjhXr0MAqFq1chEEqXNh6zaxc031atjNUpuVmPvoFPnz7QzhjOSkqCozo0NP/YC1xlk7HdY8dg8k+diuUrVyAkuB8BM352JrKfgMMJhwyB5p+RIbAOT9DOnSGklJJktsOHJQqJk5JatBAh0a8fIAalwOCJoM1zctqBA+owWxXbt0spDM7lKFECGLZS0DDDwvD/009jW26uQFeHDkGAOjkBS1cKvgU/P+zHiX7cMyAsTEJa/yI9svmQnQ0LkgjlQwpL+t4OX32llNLdw8mTEMJ2dnhn5k56TcOcKVEClpu1Pg2pqYDyiPD+zS1sPRVU4tzmfLYJhkdB0dHR9448UgpMxMUFDNHcvOYInW7djEw+MRHM290dmilTbCzKD1SubMwuZQuCtXalEIdOZAyrHDUKk5XLZ5w7p3IdHaW3glIYi4eHnP/pp2ERcHXXjh3BKDMzwSwrVRIYJi0N2iL7N156Ccfevg2hV6IEok+UwqQvUQKMifF/zqz29xc/RKtWIiS4+Y6mCeb/xx/qEEcWcdij3mdQpYrAWpMn45qaJlFKMTFScI+1/9atUaVUKXE0792Ley5VSiA27l3Nfpi/QI90PnAILxESKgtqlGNO8fF4N0RKvfqqitaHnaakiDUSFWW9VtLp07A8ifBdWAtFjY6GADKZ8P7Y8tWTLVzVJhiKEu1dtgyYqbXII6WAiTs44OOPjzduY5w+MtIoFNLSoDE7OhpryyQnQ1h4ekIjYzp2DNdv0UIslXPnIFRatpQIEo7K0QuPbt0QrsrmPEcGvfEGluPiINTYD8BZz6yN//KLMlgPzKw3bcJyWBgYu1ISRcSlOho0AANWSjTx7dtx/zqoSwUHSwLahAlgzPxs8/wNBxiK49IgPj5i4bRoIYKLi/3FxYk1s2YNGGGZMiKMZs0CU7l1C82UOFJJKcB3JUtinLduQQhxyO5foEc+H3JypNvaSy8VXjjoejtcb9vWWB5b0+ADs7dHkMGJE9aP5zLyNWviGzOnlBSpDPD445alZmzhqjbB8EhJH/lQpozK4fR/a0W/3n8f+7Vsaemg5CSsiAhjBEd2NqJFTKZ881wphUkbGYkJpi9jnJwMS8TXVzJxs7NRBsLTU5yDd+/CyqhSRTSuPIw+hhmopiFBzt9f9nn2WTBFznwdMQIOV7Ym+vZFnDprer17g8FmZ0spa3aOc9vM27exP1dRVUpKcycmSq4Cw08lS8JqUQpaLWcyc72ls2fRB4BIKoM+/rhYCU88gWWlJKpp+3ZAFVz2QilYSgxzcVjsN99guXlzlNRQSnwQLOD69oWwule/gEJQkZgPubmSmKbvH34/0jR5h40bWzbX2boV34W7e8EF/TZswHfs7Ax41dq1t2zB+zeZAHXyd2cLV7UJhkdGVj4+zWSC41hP+vj8Ll0szeNly/Bhh4dbaldcPpozk5k43FQfd65pYHp2dsasVA7d1OdH8PG8X0YGhERwsNrK2v2aNdiHs2Jv3gTsMnAglm/cwKTl6KabN43a8p07xiQw1uJZqLRsCctJKWG8XIxuwACpiMpJZrt3S5c2hsO6dZO+DZxNHRur9i1Zogz+lfr1peTFpEnS9pOzlrkTW5UqUpqDM50TEgB7ubuLz4N9G5cuQeiVKSNWDAsK83yUB6QiMx9yc6WZk3mJlvvQ0Vdftd7bQSlYpY0by3nN/XBK4Rvr3Fnlw6vmrW+VkoJ5RLAmd+7Eelu4qk0wPBIqjLmqaRKZNGCAZZ2YTz/Fh9uxo6WGOX26yjfj9cTWBSeiMTG+rfch7N4Nq2LQIFm3dy+Ex+jRso4F18aNeA/Z2TD1q1aVCTt9OsbK5v+rryqDk3n+fCwzA2ANns389u3hgFQKFoijI56N/lhOtgsNhfWklORyxMcjukrPyFu1ElhIF6G0lyu0sjbarp0Uz+Ms8pQUQHbcX0EpRChx/SROpOO2lBERYkFw9jX7QMaPBwNMTgYjrVAB9/sXqEjNB00T6GbSpEILh+jo6IJ7OyiF58/nbd3aenMeTYOvjq1xa5FNSgHGZEHwzDNQuGyCwSYYHjrdz8GVkyMa/7hxljHan3+Ofdu3t7QimMk/9ZRxEm7dCobaoYNRw9q1C1BM165yneRkOIK5t7FSmIg1ayJkldddugTLJy9sMzo6WhyxrHHfvg0Ih7XijAyY+cy8NQ1ChMM9lYKmFxiI8SQlYXxcU2njRpyfexH36SOQUFYW7pFhpfHjcW1Nk17LDJ/Vri1lNthfEB+vfmcH8RdfYFtUlAgl3saWS8WK4myfOROC4u5dPD+TCRaXUsbQWk0DFMdWCPti+HosNC9cUH+Witx80DRp8anvFngPyr+HK1dQb8vODoLe/NjPPoN1Wa6clF8xp0OH8I2ZTPg2rPXASE4W68Z8ftqgJJtgeCh0L4shIwOQREGOuy++wCRp29YyqoJDJXv0MDL/mBjEZ4eEGBPb4uNRUqJiRWNJ5CefxDX0bRiZYelLJD/xBCZlHhPbtn49NLMmTWTcXPfojz+wzBVW2RnOjJFLbty8CUHAkUBffYXtbOY//zyYP8ejly+PMFSlxKHNTDY8XPD8VauUwSqpWFGsIY5ESkhQuzkqi1uQDh+Oe1JKoB5OlmrfXrq2sbOcI79CQ4X565PxlEI+hZMTLA/zWlBcQPA//1F/lorkfND3Fx8zxlLZMSPDPejb1j71lCVjP3QIioyjIywxa4InNRVBBERImouJsX7hMmUKnpuFIJtgKEJUJCfCvciKjyHH2RlYN9eR0WchM61cCYbdurWlUNi4EROjZUsjtJSUBG3Jy8vYFCUnB9aDs7PR4c0MjiubKgUnrnkoKsMl7HBVSp3jEt4sUO7cgUOZy11wvH5oqEzeIUMAFXBZBIZ1uGDfgAGIDOKIqHr1EB2klHRv41IMLBiZ+QcHg6EoJdng7Oz28hJIjQvhpaSoXSyIWFBNmQL/CD8HInHmjxmD8yglPodly7D81FNwJGuaZfkOjur67jss66vHKoUqo+XLW29NWQgqsvOBK9MSGRtFWSGLe8jNFYi0bVtYonpKSIAVSoTnbC1cVSl83/cqxmcLV7UJhkdKZg6uk1OnQtO2s5N+BnpatQqYf8uWltmbe/aAeYWFGS2C7GwIGgcHo1NZKenktmSJrLtyBcysQQPRynJyAPOULi1hsllZSlWvDq2bJ+CtWyq7RAk4+pjYCctJcRySyveXmAh8naOZlAL2X7UqmEhWFiaxvhifHqL59lucjzNmuQRFZibG7egolse0adDSuRqsvT1q/OvHmZGhdrJg5DwEdsBnZ4MZEcHCUEpKbCQk4HqurpIAx/4cTijs3RvMnu/L01PuizOf+blwPwyGyx6QivR80HcXHDasQOFX4D0sX473+Pjjlgmeubl4XyYTLEXOlzGnS5cwj4gQEKHPi7CFq9oEQ5GhuDiVUqkSPngOa9TT6tVgZC1aWJYTPnUK2mjFipYNXzjb07xm/vr1mDxDh4rmnpsLR6ubm3HCMcyi7+7GTl19vsXUqUqzs4NWrRTG6e0tvgSlEFlVpoxYNJypzfDLlStGxs/F7Viz5jpMnLn63HN4Zhym26UL/CBKIYGPSJoEDRkivRI4QolLNzDzz81VOzgLmiPE+P5v38azcnYWYcPRVzz+Bg3wDJUS64IhKQ6DZf9Ev35iCbHfgSvKZmTg2XGU0wNSsZgP/MzNe4Tk0T3vQd/bwVr/hZ9+gkJRqhTCiq1RTg5yTOztAUOxcmELV7UJhiJB588rVbkyksM43FNP334LLbhZM8uaSVeugNn5+Bg7YykljIjLUTDFxgL+CAszwlEc3aMXIufOYVJERooAiYuDGc69GPicTk7qGpfVVkrgGXYIckE6ZvqahnDR2rXlPDwGFkxTpoARszAcPx7j4SS+Fi0QtsgUGChwF0Nd3PaxQwdxcF+7pgxWwYwZsNSUUr9xBVeG8tgnwn0mgoIkW5n7LDC0NHw43oVSELQeHhKmykX4uJ4Tl/HYtcs4Bo6umTIFFo95MmMhqNjMBy5YaF4WXhXiHs6dg9Xq4GC9WdC5c/i+OL+kINhq5068UwcHRNjl5NjCVQv62QTDP0j6j87PL1+zOfDee5b7rlmDD7ZJE8syAAkJ0I7d3S3LcW/aBE2oSxejNpaRAcebh4dRkBw+DM27Rw9h0poG7bdkSVRIZRoyBPvqjx8yRCkXF7WLu87dvQvLQB92OXYsmDwzPoZP9PfdoIHkJ7AWrbc4qlUTh25WlhG6SUrC+TjTmvMROLqnZk3xdeh6PCulBGZSeQ50vTXBVgoXK2zcWKwCtjy4LhD7MTgpq317KYehaYic4eishAQjnMWOc34ebHEsWKAelIrVfOBktj59DE7lQt1DUhL8MUSWvR2UwnfI5Tm6dDEGWOgpMREWHJFSbdogSs0mGGyC4aGRNTOVSKk5cyzv4YcfoDE2amQpFNLSkEHr5GTZCP3kSeDXNWtaHsdx35xpy+eqXh1CSp8ExBi5vjsXl6JgZqYUoo1MJqWef17ugRkkQz63b+O+hw+X40aNMpaa5jwD7vl8/Ljx+tz3gLdzO07W1nlsHO+ub7+pFKwk1t51HduUUrCq8hzMWznyaPZsbNM391EKobnVq8t9+PmJr4D3ZcuP6zuxZTZkCCAQ1l5btxboSymlatQQx7pSePc1ajxQYphSxWg+MLGvJioq3xos9D1kZwtkGhlpaVVrGoStoyMgI46OMydNg3Xo5GQ5P21Qkk0w/KN0D8eW4R7WrcOH3KCBZQmM7GyENppMliUBbt1CBq6Pj2UcPEMX5tASTyp9eYyrVyFcWrUSJpaTA9gnIMDo/I6IAJabkIB7SE9HeCfXNVJKtEKOFkpJgaXDUTpKCazApTf4GK699PnnWOYIqvfewzKX8+Yignx8795SviIjA9u4ZhLnQnAC3cSJsNyUQvE2IgkX3b8fy5xZPW6c1FhSCoycmXl8vDLAUAxLsYDkYoRcKI+hM35X/AzYQmOrR1eOujBUbOaDntiX0727UhkZD34P770nvUv0vR2Ydu3Cd+nqaj0aicnfv8A5WhiyCYYiRMVmItwjFC7/Hn76CVpL/frGCCOloNVw43Rz6CkzExqok5NlYbDjx6H1NG9ujAFn2GTSJOM1undHfoIeLmKfhV4YsXM4T4uPjo6W/diSyczEZNPDSmyN8Dg1DVo4Vz5VCvCZvgz1sGHQ+llQDR6M/gysTY8bJ815lAKEw7ATO6IZi+aoHy6yNmZMvm8gOjoa8B1bRTEx2Jczppl5swN92DDJc1AKY2KBx4Ji7lwsc+VXhoc4xJUd3bzMguXOHby3kSPVg1CxmQ/mxMEIXbqobXpFpbC0caPV3g75dP06FBYilFvRF5xksoWr2gTDQ6f7WQwbNgCHr1vXOh76wgvKoM0yaRri5okkiYopJQXhn2XKGBv0xMdjAtWsacx7YKbJzEwpQEylSiF+XO+DaNAAIZh5x2/dtAnL+gQ3ThjTtx5t1Aj+At6Hnbgs7K5fx0RkDV/T4FjmnASlYA2wz0ApCBVuo6lpYBCcp8C9mBlm4uxsLl0+YkQ+c4+OjoZQ5JIbN29iX+5Ix0KNtfzXXsMyw0UdO4pfQSn4SaKijOPu0kWWQ0KMQrNePUmaUwqCR5/nUQgqNvPBGuVZfrcaNvxzxQSPHwdk5OxsveZUdjasZiIUetTPCaVs4ar3+tkEwz9E9wiFOzx3Lj7m2rUtk3eUElN79GhLzJm36bF/pbBfv36IdtGH9Wka8g2cnIyY661bECD16xujREaNghZ9/LisW70a1/zkk/xVp7jAHocIahoYXUiIaPosBPRO1RdfBAzAjmkuaseQC/sfWHDcuoVldhBzcx59UT79NdiBzDAUl6hgH8yQIfkTPzo6Gg53dmpnZSkDDMXd3jiaiEt2s/XxzDN4j/z8Bg6EH4Lf2ZgxYPRsuT33HGBDHgvj7ZyZy74TTpwrBBWb+VAQLV2KopIdOhScqHYvunkT8B4RMu+t+WhWrYJfydfX2PbTFq5qEwyPhKyFwm3ejLLbtWoZm+boj2HnnHnkxU8/gfH37GkZksc1gLjnARP3bzCPeBk8GAJALyz27ZPSxExZWdB8a9SQ8WRnqzR/fwgVnohcn0jvwJ44EQKJHd2ahhyMjh1ln+7dYSHweTgbmovuMXPmTnEM0bDgYOcy51mwP4LzPF5+GffEz2vAgPzObtHR0casaKWAS3MXtoMHcS524HN0FdeG4npKXDCQ3wFbJ2yRsWDhZ8QQ3cWLxnemaRCsbA0VgorVfCiATj7/PN5R27YFt+O8F2VkANIjgnJkTcAcP47seHt7Yx0mW7iqTTA8cvr1V6VcXZHgZq008Pr1YNatW1ua1kePQrutU8dy8uzeDU00MtIoME6dggbUoYNxPfcX4CYySmF7o0bQqvQRTuzoXbdO1jFD1Ce99ewJJsswS1oanLxc24jHqbc80tIwPj1j7tMHoZ48cV9+GcKQ75kFBTt52dHOyXYvvYT9WYhNmgSoSX/+qlWVUnnfkq+vMRu7bFnATUohj4NIypYnJGB53jwss+Dg0F0WHKtXY5mtGY56ys7GM+LcCKUgBEJDZZlzQvRNle5BxXo+5FF0dDRgUTs7+AUeAErLJ01DmXOTCd8xV+DV0507+E6J0A/jz1xHRzbBUISo2E6E6GhoozVrqh2scerp99/BJGvVsoxOunEDVUX9/Ix5BkqB+ZQvj+16X0VmJqAdb28jtpqcjP2rVTM2++ES1Hq/RUoKGGfLlsKoc3KUCg5WKZUry7pz5zAhp0+XYzmySF/+eNIkQC98f9yBjZ2PubkI8RwyRI7p0EGK4ykl5bDZWT9rFpZZSxwxAsydadgw6dmgFHwVeYw4OjoakVccgqoUhAZnIefkQMPU15Ly8hIYKz3duD0zE/fHFodSeJ9t2sjyoEF4Jww/sZXBgu36dSgH7Pe4DxXb+aCj/Hv48ksIh+bNLUNRC0vffYd5VL689XBVTcM3ZGcHK3jevH/cYrAjG9nIGv32G1GXLkQVKxL9+itlP/aYcfupU9hetizRhg1Enp6yLTOTKCqK6Pp1orVriQICZFtuLtHAgUQ3bhB98w1RqVKy7ZVXiA4cIFq6lMjfX9a/+CLRlStEH39M5OyMdUlJRNOmETVrRjRokOz7zjs491tvEZlMWPf110RnztDFwYNl3aJFRA4OROPHy7FLlxJVrkzUurWMddUqoogIub8ffiAqWZKoVSssHz1KdOsWUdu2WNY0oj17iBo3lvMePUpUvjwRP8Nz53B/rq5Yjosj8vOT/e/cMT7P7GwiR0dZdnTEOiZPTxxDRGRvT+Tri3MyVa6MaxIRubgQBQdjTERETk5E9eoR/f677N+uHdGuXUTp6Vju2pXo9m2i3bux3Ls3kZ0dng0RrhcZSfTZZ8Zx/X+g/v2JVq7Es+nUiSg5+cHP0bMn0Y4d+HaaNiVat8643WTCt75xI9HFi0TPPou/SuHvqFFEX3zx99xPHtkEg41AX3xBVKECJnzZskQdOhAFBhJt2UJUpoxx3ytXiDp2BBPatAn7MymFD3XnTjCKBg2Mx772Go5ZtAgMiem334jefJNoxAhMFKbt24nee4/o6aeJmjSR9TNnglktXizM/uZNorlzIZSYMWsa0euvE1WvTjdbtMC6O3cgZPr2FQF0+jTGMHIkngER0bZtEG79+8u51q0jCg8XAfXrr/jbrh3+njoF5mAuGEJDZfncOTBrprg4oyD8K4KBCEJGLxiqVCGKiZHlsDCiI0dkuXFjCOSsLCy3bQvhvmsXljt1wjWZYZUtS9SmDdFXX+F9E+G9xccT/fgj/b+jJ56AkNy3D/MiKenBz1GnDtHevURVqxJ17060YIE8W6b27Y3fBVNaGtGMGX9u7AWQTTDYCEJh1CjRQm7cAOOZMAHaoJ4SEsAokpJgKegZHBE09eXLiV59FRNGTxs3Yv3gwbgeU1IS1lWuTPTf/8r6jAww6goVwNyZjhyBQBgzhqh2bVn/2mvQct94Q9atWUN0/DjRSy8Jw//oI6LUVKIpU2S/jz6CBTFsmKxbuZLI3R2WERGYZ1wcUbduss+WLdDA2SpizZsFQ3Y20cmT9xcM97IYcnIwNiZrgkHPjMwFQ+XKeLfM+ENDiWJjRbtt3BjPmoVFy5YQ+iz0PD1hIek12X79iM6eJTp0CMvh4bjuxx/T/0vq1QsW8MGDUKoSEh78HP7+UE569SJ65hnMEX5nTNeuWT/20qUHv949yCYYbARtIy3NuE4porffNq5LSwOsEBMDiKhOHeP2NWsA+/TrR/Tyy8Ztly4BQqpRg+iDD0TLJwKcc/Uq0YoVYMRMs2YRnTkDiKdECRnXhAmAoGbPln3Pnyd6/31oriEhsu/s2WDcLKRycmCttGxJVLcu1mVlwbrp2lWsn6wsom+/hfbm5oZ1P/wAhhkRgeXsbFgVbC0QQTCUKkX0+ONYPn0a+7FgSEsD02bBkJsLTfuvQEmPPXZ/i0HTIByIYDEQER07hr8sxPbswd+SJYkaNoTQY+raFdYQWx5RURBWX32FZQcHoiefJFq/Hu/y/yN170703XcQsO3bw6J9UHJzg/UxYwaUlfBwo5AJDLR+XEHr/yTZBIONCtY2dOtNOTmAXnbvhoXRpo1x30OHgPU3bEi0bJmR8WdlgTEzs2VGS0T05Zf4zZxJ1KiRrD94ELDQ8OGYZEwrVwJemjOHyMtL1r/8MhjmK6/IunXriP74g2j6dDB0IgivS5eIpk6V/dauBQz11FOybtMmosREgZGIIBiaN5fr7tsHy4P9C0QQDI0aiXXCWD4LhvPn8ZcFQ3w8mPaDCAYHBwg4JmtQUny87MPXYj8Dj4XHFhCAY8z9DPv2yXm7dsVfthq8vGA5rlqF8RPhXWkahOz/V4qMJPr+e6ITJ/Bd3Lz54Oews4P1u3w5INnGjaEgEcFy1s8fIizrLeq/gwrjoS5qP1tU0t9M98um1DR1LTwc67gUtJ6uXUOkTECAZc8FpaTeEYdEMl24gLDMpk2NCWtZWYjqKVvWGLWUnIwop/r1jfkSXLBOH4mjadivYsX8ZK3o6GhkPVeubDy+QwfkJejXDRiAaB4uS3DhgjKUg1AK0UUmk+R2mPdSVgrJcdycRynUNCJC8yL92PVRX05O0lNBKURq5VVxzb8HfTYyl8HgiC0O1+U6ThzC+u678mxKlkSZDqaePVHHiolrMulbpdaogbBkJo7i4ramSmF75coP1v2sGNJ972HjRmSo16wpiZF/hnbskN4OHC33EPIYbBaDje6vhbzwAvlt2ABtfMwY437p6TChExKgTeo1XyJADe++SzR5MqJZmHJziYYMgQhascKIoc+bR3T4MNH//meMWpo9GxDJ4sViAeSNj7y9iZ57TtZt3Ei0fz+grTxtu+SJE7B4Jk2S4y9cINq8Gdour0tLgxXRqxeidohEU2bNmQhQS+3auDYRNGylLB3PISFyHtbaWYtnzJifW0YGLKsHdT4TiXbP52I4ydcXUBxf22QCnMQWAxHGHBODCCsiOPpdXMTPQATfyvbtsKR42cVF4CQiQHnnzgEr//9MHTvCEX/uHKzr69f/3HmaNYNT2s8PFtrSpYBkY2NhncXGYvnvpsJIj6L2s1kM/wAVpIXkVdi80r27Zeq+piHpxmQyarxMJ04grb9pU8sG6dyu0rx20smTiKs37w528iQ0b31pbKVQQppI2lnyuJo2RVy4rhDZjTZtUJpCnyTEDWg481cplMomMpbp6NAhP8lMKYWkOCcnY/w/35PeygkKMvaiNi+mxxVKueLmjRvKkKCmFPI38p5HdHQ0v8s3dwAAIABJREFU+i00bSrbly/HMVxUcM8eS20/NBTJhExjxhjHsW2bMtRrUgrX0Sey7dqFffTd8nr1Qt4IW1tpaTjvoEGqICoW8+E+VOh7iI7GHAgJsax79CCUlISii0T4Gxhoy3w2/9kEw0MiZji9e6to874KSkn7Q64JpKeUFDA0Hx+BNJj27QOT79vXKGxyc5FVW6qUMQtU0wCdeHoazfLcXBT0CwoyJr5x3wF9hdeLF9Ha89lnZV12NorT6ZvtKIWEMj8/YXZJScb+zEqJQNK3Zuza1Sg87tzBPtycRyk0buFmP0qhexeRCDCuYPp/7X13eFVV2v3aSUho0iEgJVQFpArSLGBQUBAsIxrboAZ1hk9n1GEcP3WcYtefo4w6M36goCOCoKgRC0IIikgUpYqANKWFXkJIQtr+/bFyvKfsfc5JclOQvZ4nT+Dsc8895yZ5137f9RZ76+UuXX6uxs7IyKBhsDeye/99vsYa4Wm14LDGhkrJUFG3bpH/W11mLULMyWHh20MPRc55/HGeY33mRUX8edqJzupJZS8K/O1vGUZxd98txUn792BDmZ7h88/Zf6pLF2+xZ1lQWBgZ/FPJvZJMKMlAjY8/ZnglOZmhHnvoBqDo+Ne/AuPHA/fd51yTErjjDmaxzJwJtG4dWTt+nK5vq1bMIrKL1P/+N8W255931ka8+y6wcCFDSfaaitmzKVI/+mikrgBgNlOrVrx/Cy+8wO933RU59tFHDOXYRecjR3j82msjzzx/PkM37jTVuDjAqo2QkuKtPYxkZf0Epao2bRoJNVnhoIqEkqwUY3fK6tatEaHYuicrRbVePR6zMpOAiKiekcHvsbFM3f3448j7jxrFTDJ7OGnCBIbE3nwTBuDvyPz5DCcNHVr+1NK4OP5NuWHqGAyqBJmZ1AN69qRRthtdgDHPm29mhs7LLzuNO0AD/+abNND2VE6A2UCbNjHjwq4f/PQTtYKRI1nTYCE3l/UGPXsCv/1t5HhBAf8YevcGrr8+cnzJEqaQ3ncf498AM4emTMH+Cy5wpvVNmUICsuoUAD5vQYE3G6lZM6fRT0/n/6302m3bmIFiP8cyupYRLipiTDiohgGoGDHEx/N+3SmrJ05EUkndmUkA7/2rryLk0a8f0KCBU2cYM4bk+cUX/H/dutSY3nknknN/9tnUXk7VmgYVhgyhlnXgAMnhxx/Ld50QGYTRgCEGAyfWr6ehbNWKO8MGDZzrO3bQELRsyZxtFWncfTd3kg884Fx7/33g//6PIrHVdgKIeBhSeonmySf5S//ii06B+uWXuQN+6qlIaigQ8SrsBXTTpgFHj2LHuHGRYzt30jO45Ran0Z05E+jYMVKxXVgIfPgh0xAtD+LIERa7udNUAa/w3KBBhIx27CA5RJsYrFYbQUVuQKQOoWFD3pe7Ajo7O7IrjYujEbPXM4wYQeJxF7sdOkSvzkJqKr25VatgUIqBA0myR47wc7VSl8sCU8dgUGWwt8Po2ZPG69NPvVXPOTkMpxw/zoyL5s2d6wcPAuPGsYLzv/91Guw9exhi6NvXWZgG8Nz580kCSUmR41u2sJbh+utZkGYhO5veSHIyDZWFr77irmzSpEiWVXExMHkyMHgwjnXvHjl32jTujFNTI8f27uUfbkpKhJyWLuUfsj2MtHgxX+subKtXjwV8FtauBXr0iFzLnZEElI8Y4uL8PQZAXeRmvwdAnZlkPYuF4cP5Gqs4rn59fu4ffBBp2TBiBMnJHk664QZuGozX4ET//vwdy8khOdhblYRBFdUxGGI41eFuh1FczJCA1TDNQkkJQzxr1lBfsBtA+/qePWwNYC8+Kylh6On4cb6fFU8HaIzvvptpeRMnOq95zz00iO4K7GefpUv+5JNO7+KRRxivt4ecrJRBe/uLkhIarOHDnUb67be55g4jJSSwzYGFRYv4x2j3DjIz6WVYXo2U6h5JQOQ9peTnFUQMqpYY9gI3y6uzE8PppzuJoW1bvs5uiHr2pHdghYC6dGF4z00M1jNbsKrfN27k/+Pjmdr73nuRxnuNG7M6+o03IscMiLPP5ueZl0dysIrXwuCGG+h1JyXxdz8pif+PcsqqIYZTHap2GPn5HjGrwyuv8A//2WeBSy/1Xuexxxh6ev557orsePFFegTPPgt06+Zcu+suEsbUqU4P48MPuSt9+GFng7k9e3ida65xNuj79lu+5p57nG01nnuOfzz2xnwLFpAI7aIzwDBSjx78Ami409JoHO3XTE+noGgRXF4eK7/tRLFrFz0Nq/0EQGKIj4+I8QcPcuevIobTToscCwolxcby/twew549Eb0gNpadct0eQ1FRJHQUE8PKdbsAfdZZDM3ZdYbLLuP3tLTIsZQU4Ngx/g5YSE3lZ/DuuzBwoXdvivqFhSSH9evDv7YK6hgMMZzqCCNmvf46kt58k57F73/vPXfBAra0uOEGbwHcd99RCL7sMu/au+8Cc+bwtV27Ro7n5/N9zjzT+36PPEIR1e06P/oowxl33hk5tmIFhei77nLuuKdMoWdxxRXO5126lAbOwoYNNKT2orasrEi7AwsrV9LAuvUFwOsxdOgQ0SqsHb27s2q9es77DSIGgM/u1hiKipz9ejp18noMgFdn+O47GnmAu9LkZO5wrdBRu3Y0bHadYdgwEog9nHThhXxeE05So2dPhiWl5Oe3bl1139HPMMRwqiNIzPriC+C223C4b19ni2sLO3ZQA+je3SscnzhBsmjYkMbBvnb4MENHffo4K5YBthzesoXN7uxhp02b6DbfcUckZg7QsL33HknEHoJ57jnupCdMiBzbu5ci+PjxTuHcMmh2YrB2xNYOGYiEVNz6AuDs9WQRg+V9AOpUVcDpMWRnO5/BCu8FEYOqX5L9PQB+Zlu2RAz8GWfw83XrDCUlrBq3kJzM69hTJceOZVtui3ji4qgvzZsXIZWYGKYML1pUPqH1VED37iSH2FiSg52kqxGGGE51+IlZ27YxBJOUhHV//avTOAGMTV97LXf477wT6YBq4YEH+Is+bZp3psOkSUzvfOUV53W3b+fu/6qrnMIywPBWQoK3c+tjjzH0Yvcudu+msb/1Vqehfe017qTtZAHw3AEDnIY7LY0pm/ZBQ4sWMX5ub/edmUnx3l57sWYNX2el5EoZjhhUDfSA6BBDp0402lZjt1q1GNqzG6MBAyLPZEGnM5SUMLPLQkoKw2p2T+Lmm0kQ06bBQIOuXenZJiSQhGtAJpchhlMdOjFrzBh+FRUBH3yAInfaKsAQ0bJlNO5Wq2sLCxdy5z9xYqRNtX3t1VfpKVitry1MmkQj+o9/OI9//TXDTpMmObOl1q/ncasVt4WXXuJO204WUlLLOO88p9axcSPDQXbRed8+Pps9G0lKxtovvNBZ8OcubAO8wvP+/cxEqWpisPfvD5OZ1KQJf5Z2YujQgb8Xdp2hXz8SoZ0EhgwhGdrDSW3asDZl+nT+PAzU6NKF5FC3LslhxYpqvZ2oEIMQ4hIhxEYhxGYhxP2K9ZuFEPuFEKtKvybY1sYLITaVfo2Pxv0YlBFuMSslhUZywwYaXbfRB1h1PHkyJ6u5B/IcPMhQTdeu3oyi48cp+p5xBoVlO9LT+X4PPOBMW5WSow1btOAAEzsee4wjMu1ZR7m5nPlwxRWsSShFo9WrGY5Sic5COJ/jww/5vnZi2LqVorVdX9i1i+E0OzHohvMAXmJo0MDpsamG9ADqrCQrJASoh/VY72HBXcsA8B537XL2/B84kAK0dX0h6DUsXhwx7jExDLF98kkkqykmhh7kJ59EGu0BFKF37mQKtIEenTqRHBo0iLQ9ryZUmBiEELEAXgJwKYDuAK4TQnRXnPqWlLJP6dfU0tc2AfAXAAMBDADwFyFEY8VrDaoSf/wjQwQvvuichWBhwwb+sQ8e7DX8VrHa/v2sfnaHqR56iOQzdWpk5jFAY3rXXTTkbs1h/nwapYcfdmbrbNpEo/7b3zprKv77Xxo6O1kAaDVvHg2ovcurlLzG0KFOETgtjSmevXtHjqn0BSuDx04MP/zgHM4DqIlh925vN9qwHgPgTFl1D+upU4fXsRNDhw408m6PAfDqDHv3RmoXAJLh4cPOMMeYMQxNffZZ5FhKCu/Znok0Zgx/PkaEDkaHDvxdb9yYf3t2z60KEQ2PYQCAzVLKrVLKAgCzAFwe8rUjASyQUh6SUh4GsADAJVG4J4PyYsoUirZ33eXNIgK447/6arabmD3bKQ4DDBm88w538u4Jb5mZ9DImToz0GLLwwgvcZT//fKSVBUAv5k9/okF17/SfeILvP2mS8/znn2eo47zzIscPHULzzz/nMCE7Wa1aRUNuDyPl5XF3O3asUzBPTyd52D2ozEzeg11zsIysO1VVCP7hW3AXtwHhiMHyHlRzn+1ehLvILSGBZGcnBl1mkvVsFiwvya4zXHQRf1b2cFK/fvxZ2cNJ8fGscXn/fYboDPzRvj3Jtnlz6mxLl1b5LcQFnxKI1gB22P6/E/QA3PiVEOICAD8AuEdKuUPz2taK10IIcTuA2wEgMTERixcvrvidVxFycnJOivtttHIlev3xjzhyzjlYe/nlkLZ7zsnJweKMDHR94gkkfv891jz9NA5v3uwIS9TZtQv9J05Edt++WN2vH3c+pRAFBeh/++2Ibd4cy0ePRrFtLf7gQQz4859xdOBArK1f3/G6xE8/Rbc1a7Duz3/Gfms4PYDae/ZgwOuvY/fll2Pzhg0/Z8w0ycxErw0b8P0DD2CfbSfb+u230aWwEMv79MFx2/U7/uc/aBMbiy8TE1FUerzJsmXolZuL1UlJOGydW1KCIfPn49A552CD7bp95s+H6NwZK20FgR3mzUPb2Fgs2bv358+w69KlaNSsGTJtxnbgtm3I7toV6233c/7hw9iVnY2tpccS9u7FYAAbtmzBnsWLkZOTg83bt6MzgCUZGSguFfzbHTyIjoWF+PzTT1FSmm3Vu04dxGzYgJW26/du2hQxK1ZEjkmJcxs0wP758/FDKUmI4mKcl5CArLffxmaboH5OUhJOzJmDNbb6kR59+6LenDn46sorfybRDoMHo92bb+LLd99FYanuU7dnTwwoKsLmv/4VOaNGnRR/D36oir/p+CeeQJ9770XCRRdhzZNP4qjde61shGnB6vcFYByAqbb/3wTgBdc5TQEklP77NwAWlf77jwAesp33ZwB/CHpP03a7EvDDD2x33a0b20y7kJGREZkM9re/eV9fUCDlwIFSNmrknG1g4eGHvW2qLdx0E2cbWPMELOTlse98v37eiWB33MHXuFt6X3QRW2nb5jDIkhIpzzpLHrW3xJaS12zbVsrRo53Hb7+dE87srbxXr+b9T5vmfOY6daS85x7n68eM4bQzO4YMkXLoUOc91akj5b33Oq8HcDKchc2beey116SUpT+HyZN5zJocJyVbjAPOCXrXX88JdnbcdhtbZ9sxbBh/dnZccIH32J13ssWz/bN9+WW+79q1kWNr13rbnkvJyXPduskM+5yLkxRV9je9ezdbudet65wPUk6gCttu7wTQ1vb/NgB220+QUh6UUp4o/e8UAP3CvtagCnD4MIXEmBiGBeyhjFKctnEjM3wuuYQ6gRuPPsp4+8svM1xhx5o1wOOPM5zgrpr+4gtqApMmMTPDjn//m+mr7kZ5O3Ywq+nWW50tvdeuZcbTnXc6Q1yZmcC6dciyd1EFmIe/Y4ezdqGkhLn4I0c66xxU+sKaNQw7uTOS1qxx6guAN1U1O5uvDdMOA/CKz4C6kZ6qX5I9vNS5M/Wf7OzIsV69WNRmVUkDFKBXrmQtioXkZAr79spoVRV0jx6smLaHkwDqUuvXo8H338MgJFq1YoV0+/ZsbmlvVFiJiAYxLAfQRQjRQQgRDyAFQJr9BCGEPZA6FoBV/z0fwAghRONS0XlE6TGDyoa9cd7ppzMkNHeu03hZOHQIZ/3lL0xPfOMNp5EGaGAffZSjOt0ZSkVFNAiNG1O7sKO4mEa8TRtvJ9ajR3nNESO8rbuffprG7n5XAtzzz1M/uOMO5/EpU4B69bDPnk0EUHSuXZvdYi2sWEFR2J6NBFBf6NLFSXqqjqrZ2RRt7cSQk0MxN0xxGxBefA7TSC8/33nMuge3znD8OOtWLAwaxGwju9g8bBjDRXad4fTTqSvYdQaAZLtkCbORLFxzDVCvHlrZax8MgtGyJcmhc2durBIT+TfYvj3/jisBFSYGKWURgDtBg74ewGwp5TohxN+FENZf1++EEOuEEKsB/A7AzaWvPQTgEZBclgP4e+kxg8qEu3Fefj53pDt2eM8tbY4Xf/AgU0mt+cYWsrMp6CYlRYbh2PH886yiffFF72tffhlYvZo1C+7iuKefZmbRU085j2dl0dCPH+9Mad23j881fryzgV92Npv+XXcdiu2ic1ERn2fMGGemU1oa/+jstRdFRRQD3cSSmUnjaycL1XAeq+o3TA0DEF1isL8XEKllsKes6jKTAKcA3bgx607s9QwASfSrr5zC8rXX8vvs2ZFjp50GXHstWixaFKmONgiHFi2YtFFczM9ZSv793n575ZBDmHhTTfsyGkMFkZQkPeMBAR5349FHpQTkxt/9Tn2t8eM5M/mLL7xrmzZxxKNqXvS+fdQjkpO9azt3Mv5+ww3ea957L0dQbt7sPG6NGd2wwXnc0kW++sr5c5g/n8fnznWe37s34+t2WLOOZ892Hu/cmSMz7fjPf3jutm2RY3PnSsfoTSmlnDGDx77/PnIsI0N6Zk1b85tLZzFnZGREXmt/1jVreOytt7zXs4/dzM7msSeeiBzLyeH8YLd21LbtzyNFf8Z993HMaU5O5NiKFbzmq686z+3XzzmCVEoply7luVOnypMZ1fI3XZa/Ww1gRnsaaBF2ClR6OmsHrrsOu+0N5yzMns0WEw8+yLbZdpSUsO1EQgLwr395eyw9+CBDLC+84F3729+4S3fPbdi3j4Vr11/v3H3n5/M9Ro/2FuNNmcIdsb0TK8AwUoMGTs3jp5/owbjDSFbo5MILI8cOHOCuW1XxfNpp3rkSQOV6DDqNwf5eAO8tMdHpMdSrx3uzewwAn82dR5+czPe1JrgBTNVt00YdTlq+3Bm2GjwYx9u1MzUN5UEVTW8DTEuMUxNhpkDt2sXc/jPPZIsMVfO8O+6gSOnuXQSwgO2zz9gi2144BtBYTJ3KqunurlrIDRtoNCZOdOb8Aww55eV59Yg33yRpuArasGIFv267zXn/+fnUU6680lkzYRk2lb7Qpw/HZVpQFbYBkVYY9vfbsoVhGHvLjqysSBGahaoIJQEkAbuxBnjP7gZuAweyGHHv3six887j+9t1BiEoQs+fz8/WgqU3vfWW49ys0aPZbqQsraYNqmx6G2CI4dRE0BSowkL+UefmsljNPosAoDcwfjzPe+MNb3O9nTuZZZSczMwh92vvvJMx07/8xXtvDzzAHax7uPnBg+x/dM01zhbdUlLH6NXLqwFMmULD7+5X/8kn1B7sRW0A9YWuXZ3ZUXl5FNdV+kJsLIVX+724eyQB3owkIFLcZieQsFlJ1r/tlc/16/NadmI47TT+XN3E0Lmzd3JYr148Zp/NYZGePQupXj0ed+sMY8bwtRkZkWPt2tGTdGUn7b34Yj6D8RrKhiqa3gYYYjg1ETQF6k9/ojGcOtU7WAegF5CRwbbY9vbXAI3jb35DozVlitfTmD6dDfGeecY7T3rZMrZS+NOfvGNDJ09m6MmdKpueTmN8993O97KmxY0b59ypAwwjNW/uzHY6epSFdW5v4csvmbLpzozKzKQxtYvmu3Yx9bcsxGCHZdTtn0tYjyEmhq+zE4MQ3upngPeyc6dzslrPniRteyrp2WfTgLvDScOH0xOz90NKTqaRUoWT1q51zBoobNyYn/Prr0f6LBkEo4qmtwGGGE5d6KZAvf0200rvvNOZ329h5Uru5q+6CrjlFu/6rFlsQPfYY44GdgBoSO6/n7vIG290rsnSRnktW9LI23H0KEnoqquc8w0A3mtiInUHO2bPZuaLu41GTg6N17hxzl34/Pk0tPahPACJJy7O2cKjuJi7aFUYCXASQ2EhtYuwxFC7trMGIywxAN5hPQDfY7erNMi6F3t6qiozqU4dhtBUOoOUjgp11K7N1OJ585x1E1dfTdKyh5MApjDv38/zDcKjCqa3AYYYDOz44QeGfgYOpFfgRm4ufxGbN1frDvv3UzcYMIDf3fjLXxgSUg38mTePee9//as3dfWFF2g03d7Chg1s9jdxorMYDaC30rWrs18SwH49eXle0vvgA6bTDh7sPJ6ezuexp7Ru2EDSCUMM27eTSMISg7u4sCzE4G69Dag9BlX77Y4dSQRunWHQIGpC9pbZAwfSO7DrDABJdccOCvgWWrakaD9rlpMwRo5kcaIJJ9VIGGIwIHJzOdA9Pl7dHA/g/IX16xkOctckANzpHz3KqmT7vAKABuellxhmsjecA2h07r+frbjdmsSxY/QKLrvM25Rv8mQSgrvZ37p1DEtNmOAloJkzmUFjz6IqKqKXc9llzvs+coQ1GKowEqAmhtatnaErVUZSbi4/JzcxuKe3AZVDDKr227Gx9MbcmUkDB9LLsoeY4uPpQbl1htGj+XmnpTmPp6SwE+7Klc73u/lm6j32IjiDGgFDDAbcyf32tzSoM2YosxyaZGbSsN9zD3Dxxd5rzJvH7KCHHmI7BPf1rUE67hRUgLHm779n2wy3kP2vf7HQzZ35dPAgU2VvvNE7HW7KFF7n1792HI7LzmbIKCXFWb29dCnDXG594fPP6bKriKFxY28Lj7VrnR1VgQgx2MNqqlRVQO0xhG2JAeiJ4dgxai4WmjbluWEyk1SFbgA/k/XrnaSTmEjvyq0zXHUV79/dIuPWW/n5Tp8Og5oFQwwGNKSvv86ahZEjvev79qHr00/T6D3+uHc9O5u79h49vG0qAO7Slyxhm2x7VTLAsM7DD3NnetVVzrXjxxnSGjkyMnLSwssv87VuPSI/n72XrrzSI2A3//xzGlpVNlJ8vHeUaHo6wytuz8Ca2Gb3RlTDeQAa34QEZ0+nshBDNDQG+3sCvO9OndSZSfv3O9NTO3Uikah0BsAbTho7ll6WXddo0oQ/w7fecvZj6tiR13n1Vedxg2qHIYZTHd9+y9kLI0ao6xGkBG69FXE5OfQI7Hn/Fu67j4bnlVe8Iahjx5i62r+/N0wEUG/YuZOtL9xhn//7Pxoq930VFPB1F1/sFaPnzqWH4RadAbZi6NLFGZKSkrrD8OHetNz0dGoUdv0iO5uelZssNm3ifamIoUMHp4dSWcSg8xjs72mhc2e1xwA4vQYh1IVuffrQa1LpDABDc3akpFBvcV8nNZUi+EnehvuXBkMMpzIOH2bWSGIiQ0huXQBgpfGHH2LLHXd4Q0QA/6BffpkhJveuHmDoKCuLhtx9/UOH6IGMHs0Janbk5bFf0oUXequqZ8/mNd0FbQC9nw4dvHUHu3ej0apV9BbsBLRhAw2kO4y0Zw8JwB1GWr6cZKLqqAqET1UFKocYsrO9w3rs72mhUydmtdhrIax7V1VAr1/vJJ3YWDbVS093vl+PHkyjdIeTxo7lpsIdTrrySno6RoSuUTDEcKqipIQx+F27aGjtVb0WNmzgjOWRI7HLHeYBKKLedhtDAn//u/r1zz3HXeFAxeymJ5+ksXniCe/aK6/QOLu9BSl5zW7dvGGvTZtIVBMmeDvAzpkDIaU6jARE2kdbsAq1dMKzmwTXrqWxdBffbd2qJoa4OK+AH5YYVAVuAF9bXOzUE/w8hqIiZzuF5s2ZRaSqgJbSO4N4+HCm4trTXoWg17BggbNYrkEDbgBmz3ZmONWpw0y3d95x1kUYVCsMMZyqeOopCsbPPuvd/QIMi9xwA1NHp03zhnkAppZu3sxCOHdFppQMUdWvrzb8O3awNuHXv/busk+c4P2dey53pXYsWcLiqrvv9hr/qVNpnFX1FTNn4ljnzk7DDZAY+vVjppId6encyarGk3brFulNZGHtWrYPsYed9u2jkVYRQ8uWzvsvLmb2T0U1BsCpMzRtyvPDZCYB1BncHsOAAfz563QGVbfV/Hzv8ZQUYO9eNLKnswLcOJw4wVClQY2AIYZTCfYZDA88QEK48071uQ8/TAM8dao35AFQYHz2WXoM9uZyFt59l0NFHnnEW8UMRNphqDyN116j7vDww15Ceu45GrubbnIeLyhgdstll3nvd+tW4KuvvPMY9u1jWqu7qA2gURs2zBn+kjIiPLuha4UBhKthsGYxuKvBy5qVBISrflbVMgB8hnXrnN5Iw4YkQzcxdO3Ka7t1hqFDWffhDieNGgXUr0+tx46+ffk1dSoMagYMMZwqcM9gAFiIpNqlLV7M+P5ttzmH2FgoKKCQ3LIlW1u4kZvL+H+vXt4aA4AzC157jR6FOzW2sJAexoAB3rTYLVsoFP/mNwxB2PHBBzT0CtHZimvvcxPYRx/xs3DrC9u2Mf7uDiNt3cquqm5iOHaM50eDGCqqMQDhahlatWLMX+UxnDjhPW4J0HY9QQh6DYsWOY/HxzPMN2+eM9uobl3g8svRfMkSbyuM1FQOBVqxAgbVD0MMpwoefNAZ8wUo8Lqb1R0+zPBO587eiWsWnnqKO+T//Ec5BhRPPsnY9YsvOne6Fh54gDvK//1f79qMGTSyf/6z11uYPJnX+5//8b5uyhSGgy65xLs2axYwZAhO2AbbA2AYqU0bb8GdFQIJW9hmDedR1TAI4e0Sm5Xl7TiraqAH0PgL4fRcokEMMTH6LquAup7h4EHv+cOHk5BtvZAA0AvLyvIa+pQU1MrO9o6ovP56EpURoWsEDDGcKgjTy90qdMvKooF2t6YAWIj2yCOMF6tCMFu20Nu44QZnfyELS5Zwd/+//+utaSgqYo+lvn0pVNpx5AjWMcfOAAAgAElEQVTz3VNSvLvtH38EPv2UXow782ndOpKYW3TOz2ex29ixXgJKT+d7uPWIzEx+Ju7sLFUrDICfRZs2Tt2hoIBeh66BnooY3EV/QcSgqmVwEwOgrmXo1o2foSozCXB2WgX0OsOoUSQfdxX0iBEorF/fm53UuDEr72fMcDb3M6gWGGI4VRCml/sbb7AI6W9/8w62ASiQpqYyDj55svp699xDw/X00941KVnz0Lq1upfSW2/RUD30kNdYT51KIVeVovrqq/yemupdmzmTBmrcOOfxRYvoQbnDSFJyLTnZew+ZmQxxqdp9uIfzAOpUVat4rDKIQTWsx3qvgwcZIrKjc2eGx+zhntq12ZrE7TF0785EArfOkJTEZ3TrBs2aAUOGeHWG+HgcuOAC4L33vASQmsp7nzsXBtULQwynCoJ6uW/bxhDN+eezy6kKL75IwzB5srcNBcCipg8+oLDsDpUANAaZmSQet0ZQUsJ76dEDcE+LKypiI71hw7xZQkVFJIZLLvGSn5QkhuRk1mrYkZZGQ+fOelq3jqERdxgpL48xcJ3w3KOHl0jKWsMAqFtiuMNxMTH8KksoCWD6rx2dOvG53N6EKjMpNpabBTcxAPx8Fy/2ps+OGcPPzDVLfF9yMnWZjz92nj90KFOfTTip2mGI4VSBXy/3oiJm+QjBdhKKQrfaWVnUBkaN8ra4Bhia+f3vGX5ReQNFRQwfde/OIT9uvPMOi6geesibhjp3LkNeKm/hk09Yi6ESnZcv547YHUYqKSGBXXKJtyurFRJxZzCtWMFncBODbjjPsWMkmIoSg8pjAHjMTQx16/JnV5bqZ0CtM2zbxmewY9AgGnr3Tn/4cIrnbj3BCjW6Wmsf6dOHGwt3OCkmhuHAjAzvPRlUKQwxnEpw93IHmL5aqxYbyd1wgzccAgBS4oxnn6XR+c9/1DUN//gH/5j/+U91Z9Zp04CNG5lx5N4Bl5QAjz7KOoCrr/a+9rnnaMTcRWgARefERPXarFm8F3dx3ooV7OXjDiMBJIZOnbyfg7VTdhfq7d6tHs6zdSu/u4nB6iFUUWKIi/Pu0IXg68P0S7LfmyozCYiI6hYGDeJ7ugnAyvZy6wxdu/I9XOEkGRvL0N68eV7yuflmEoQVHjSoFhhiOFVhT1+18NprPO7G9Olo8u231A3atvWub99Ow/6rX6k7rx4/zvDSueeqBeu0NMa0H3zQ660sW0aj/Pvfez2J3bsZvrrlFq/xLC6mZnHppd5itLQ0XmvUKOfxoiLOqXaHkQDeQ4cO3pCUn/AMqD0GIbyhuKNHSWLuXlRl8RgAPmtYjyEpiQQTNjPJIkV3OKlFC77GrTNYVdDp6SzesyMlhZ6HW4No3Zo/s+nTvcRnUGUwxHCqQpW+mpvrTV/NygLuvRdHevUikagwaRK/q4b7ANQksrLUjfKkZJZTp07ekA9Ab6FRI+4k3Zg2jQQwYYJ3bckSEodqCl1aGknK3ZLi228ZEtERg05fAMpGDC1aeL2mo0e9xW1A2YlB1UivRQsSoZsY4uJIDm6PISmJYrpbZ0hMpIfpzkwCGHr74guGFO0YO5aZWAsWOI8PGcKMLXc4CaAIvXs3s8YMqgWGGE5VhE1fnTgRyM/HxkmTvDt2gLvBOXOoP6jCUAcOkBAuv9zbDA+gALliBV/vNpY//UTt4bbbvJ1PS0ooUiYne40vQNG5bl2vh7J9Owv7dGEkwFvJvXMnv3TE0Lq1N/V2yxYec3srquI2QD2kB+CuuaLEEBtLclClrKq6rAqhns0AqDutAiTT/Hzv2nnn8Z7cnkFMDHDttdSI3D2SLruM92tE6GqDIYZTFWHSV995h5lEf/sb8lQhpMJCVi937BjxGtx4/HGGEVT9kixvISnJ2+ICYCaSEHwPN9LTKZCqROfCQs6uvvxyby2GZaB0xNCrl7eFh7VDDtsKA1BnJAF6YlA10LOeRVUk6EcMbo0BCK5lsFcuA5HMJPfxQYOYZbRrl/P4BRfQ2Lt1hlq1GBr68EPvzIWUFD7Du+96X/PrX/NnZZ8NYVBlMMRwqiIoffXQIaavnn02cO+96mu88AIziSZPVs9p+PFHTn279VYWTrmRns4d5v33e3fFx45RWB43Tq1rTJnCUNCVV3rXFizg/atCU2lpFLnPOMN5PD+fArwujJSQ4K2QLixkwV9lE0NFNQZATwydO/P8Q4ecx3v2JMG4x27qCt0aNmQ6q1tnAOi17dsHfP2183i/fvyMdOGkoiJmyRlUOQwxnKrwS18FSAaHDjE7RLVjzcpid9XRo9UZQQCb4MXE8DwV/v53hmFU3VCnTWN4RZWiun8/PZlf/9qbbgowjNSokWciW+zx40yFVHkLX37JAjAdMZx9tjfbSjecp7CQISs3MRQXcwdcmcSgCiUBrCvReQyAN5xkZSa5dYY+ffg56OoZvv7am2l06aUMZ7mroIWg15CeTuKwo2tX6hBTp3q9FoNKhyGGUxm69NWYGGYoXXYZ0Lu3+rV/+hMN6fPPq9dXr2Yl9d13O8daWvjsMwrE993nNe7FxfRChgxRD/957TUaRVUYKTeXpPGrX3mu22T5cr5OF0aKjWVIxI7CQnaSLYvw/NNPfAY3Mezfz8+6sonh2DFv2KZVKxpf+ywEIFLL4Bagrcl4bp0hIYFFhioBevhw7vKXLHEeb9yYhZNunQEgMZSUMPTnRmoqU5y//NK7ZlCpMMRgQKi6r376qTp99Ysv6OL/8Y8Rw+LG/fdz166ron7kEWa5qIz7Bx+wDkDlLUjJXeS556rDUx99RE1DEUZq+uWXDD8NHux9XXo6Sei005zH16xhmElHDLGx3vvwy0gCKp8YpPTu2lu1ogF278ytBn9uj6FRI+pNbo8B4GexfLk3nXTIEBKHW2cAGE767rvIBsRCjx7sPaUKJ11zDZMOjAhd5TDEYECETV8tLuYMh7Zt1d1RAcaZP/mEr3Vn5QCsTUhPJ7G4W2MALJZLSvK2xgC4G924UU0oAMNILVt6W10UFaFpZia9IHetxNGjNHS6MBKgJwb3cB4gmBjc7UJKSvyzklShPFWBG6Ae1gPoaxnq1KFH5/YYAP/MpLw8L2nUqUNy0OkMgN5rWLLEq2fUr8+12bO9RGdQqTDEYECESV8FON959Woab1X3VSnpJbRrp26PDdBbaNZMPavh229pJH73O7VBnDKFBtTdFA+ggf/wQ+403cZ/6VLUOnZMHUb6/HMaZx0xtGqlFsD9MpJq1/Z6BjqPISeHn1u06hiA8EVugDplFaDOsGGDd3aCRZI6nWHVKqYp29GlC0lURQzXXsvvs2d711JTWSD51lveNYNKgyEGAyJM+ur+/fQChg9nDF+Ft99mTP6RR9SZSsuXs3bh3nvVxPLccwznqDqlHj7M699wgzejCqC2cOKEtqitpFYtjyANgN5L7dpqr8AqbHMX5h07xnRZHTF07Oit+7CMsnsuhK4dBlA1xKBqvw3w2YqKSA52JCUxDKirZwDYVM+NMWOAxYuZBGBHly7MUFKFkwYOZH8tE06qUhhiMCCC0lcBkkJODvshqfolFRayUK1nz0h2kxuPPkoxUuVN7NrFnWFqqtpIvvEG4/1+YaT27dWN7tLScLhvX2+hHMDQx3nneYnswAEaTBVhWH2Eypqq2qSJN/Skm94GRI8YLDKyejXZ0bkzs6XcbSt0mUlC0GCrBOj+/fkZq3SGsWOBwkImAbiRksJNg6rYLjWVJOQeBmRQaTDEYEAEpK+etmEDRd/f/547OBWmTKEhffJJZYdWrF7NlMW771aHTV56iSEdVXdWKXn9/v299QQAvZmFC2lg3KS1cSOweTMODhnifd2+fTR8qjBSUGEb4CUGKSmcl7WGAYheHQPg1Rji4ym8lyVl9Ywz+D46nWHjRm/9Q61abJ+t0hkGDwaaNGESgBvXXMPvqpDRTTfxusZrqDIYYjCIwJ2+au36S0rQZfJkhg8eflj92pwczlkYOpR56yo8+igJQWX4c3OpX1xxhXcUJsD8+LVr9d7C229TGNcVtQFqYrAMmE5fiI1lmMONtWu5M3a3Admzh8+iIobdu8tODOVpiWG/ph1+RW6Alxhq1eImQJeZBHiL1gDqDD/84BWT4+KAUaPQ9KuvvGmz7dox00wVTmrenFXs//2vV+8wqBQYYjDQY8YMhmZiY9FgwwYabdVOH6AYvW8fO7Cqwkzr1rHFxl13qTOVXn+du09ViipAb6FePbXhBxhG6tZNHdpJSwPOPhsn3K0uAIY8GjZkAZsbmZkMp6i0EGs4j1tH0GUkAeX3GMraEsN+TTv82mIAZctM6t+fz+6nM2iyk2plZzMzzY2UFH6uqpBRaipDe+4iOYNKgSEGAzVUbblff11d17BvH/DMM5yloCpIAyIaxt13e9dKSig69++vbrR37Bh3kikp3joDgL17liwhabhJaf9+FkipspEAGq9hw7yhr+JihpJUYSRrOI8Vg7dDRwxS0puo7FBS7doMG5WFGBo2ZJaYLjNp1y5vyOi000iMKmLo2ZPXU+kMI0eiRFUFDfD3JyZGHU66+GJmhplwUpXAEIOBGmHrGgCGiPLynEK1HT/8wD/2iRNpMNz4+GOec889am9j5kymLOrCSFaao8qb+PBDGmUVMfz4I/UAVRhpwwYSkooYsrJoKHXCc0wMPS07Dh1iGCRaxBAXpyYG6zq6Rnp79qhbTPhlJgHqcNLAgQwluausY2LYoXbRIu97NWzICW6qtNWWLfm6WbO8r4uNZev1+fM9o0INog9DDAZqhK1r2LKFU91uu83bmM7C448zE+cPf1CvP/cci6xUtQkAw0g9e+q9kZkz6W2oqrDT0tj3XyVYWzva8hS2AXpiaNvW21cpqOo5NladguvnMegG2fg10issBA4e9K751TIAep3h8GH2jHIjOZkag2Lt4ODBJF4VEaWk8DUrV3rXbrmFhDF9unfNIKowxGCgRpi6BoAzmmvV0ovSW7cyzfSOO7zTzwDGr9PTqT2oDOCqVayLuO02tTexaROL4lTeQn4+d5hjxqhfm57OXaqqtUZmJtNqu3RR3zNQ9lRVQE8MDRroU4DLEkoC9I30gmoZtm9nHYj7NU2a6DOTgDLrDD8nAai8hquuojekEqE7dOB1X33V66UYRBWGGAzUCFPX8O23/AP+wx/UBg+IzHj+4x/V688/z+vqpsNNmcK4+Y03qtdnzqRBtdId7cjIYPhLFUaSkkYrOVltkHWFbQB3z6ef7h3OA5SfGFRhJEDfEqM8xGC14tBlJknp7WUkRGQ2gxtdu5LQVMTQuTM9NYXOkN+qFfsjqYihSRNg5EiGHlXGPzWV96gStg2iBkMMBmq46hryExOdbbkBNspr1kw/pGf7dnZCTU319gcCWFQ1YwZjx40be9dzc7l+9dXqdSlJDOefTyPkRloaU0rdE9kAzlHYu1cdRsrOZmaMKowE6FthZGczc6asxKDrkyRl2dNVAX+NwX4vdgRlJq1dq9YSBg5UE4MQ/GwzMtQGfswYtiJxT28DGE7avl193Suv5O+CEaErFYYYDPSw1TVkzprlJIUFC1hQ9uc/61NYn3qK33UdVv/9bwqyv/+9en3OHO58daLzmjWMVavCSKXVzhg5Uj2zwdrJJid715Yv5+tVXViLijicSBdGAvTEUL++uvJa5zFYGkJZicFPY7DuxQ1dLQNAj+H4ca83AZAY1q7luhvJydQzVGGosWOZ+fXJJ+q12rXV4STLe3z3XW+mlEHUYIjBoGyYMYNexIgRFEx1IZDdu7mru/lmtV6Rnw/861/sdqoTradMYeO1889Xr8+cyXu4+mrv2ooVvAe/NNWOHb3ZQwB3qkKoxe5NmxiHL0uqKkBjrPKaAP+W20D0NIa6dUniKmJo3pyk5ZeZpNMZiosZVnTDIl1V2GfAAL6nKpzUoAEHQM2e7S2EA+iBnjihTp02iAoMMRiEh1XbYGUmFRczBVX1B/rMM9zx3n+//lr79+sL2r7/nqM2J0xQx/ml5I7y4ovVKbBpaQx1jBrlXSsqYpM3VRgJYPFVt25qYx2UkQSUrbgNKD8xSKk2nA0bcgevylrS1TIIoc9MOussrutSVgF12KdNG5K+qp4hNpbG/+OP1QSXksJQ32efedd692Y1+iuvmOlulQRDDAbhEba2Ye9eprDeeCN35W5IyRTV3r3V8X+AfZlq1QLGj1evL1vG4jtdJXRaGovlVKSxYgWNsYoYpIwIzyrohvMANKrNmqlDa+UhhqBQElC+6mdVIz1AX8tQvz5/jiqPoVkzEoqKGAB+xp9/rr7PMWOohSxd6l0bNYrvqwonAfQaVq/mz9Ig6jDEYBAeYWsbnn2W2sEDD6jPX7iQ4q6uoO3ECVZZX3EFww0qzJrFeLNqmM/27Uxz1YWRrB2sipS2bGFcXEcMa9ZwF6zSLXQZSYCeGKQM9hh0g3rs59hhtRwpS/UzQAO/bZvaC9FlJgH8rDIz1bv35GT20VJ1VB0xgvUeqirounXZH+mdd9T9ka67jj//qVPV92RQIRhiMAiPMLUNBw5QO7j2Wr128NxzrGlQzU0AKCwePKgXnYuKGH8ePVq9O7fi1n76Qs+eQIsW3jW/wjZAn5EE6Inh2DGGdlTEkJtLQ1yeUBKgDheF6Zekq34uLFRXFvfsSX0lL8+7NnAgr+lumgdEyFelM9SvT+L44AP1/aSkUGBeuNC71qgRtaU33/R6sQYVhiEGg/AIU9vw/PP61hkAM3o+/pjzGFS7boCis1XMpMLixQxX6YglLY2kpCKm/HzOrNZdOzOTBkvVWtxvOE9BAQ2qrqsq4N8OQze9DYh+KCkvLzIDwo6gzKSSEmo/bvgVujVtyqpzlc4AMJy0eTNbeLsxYgQJQBdOmjCBz/HOO+p1g3LDEINBeATMbMDhw8ALL3C621lnqa8xeTIJQTXWE6BRWrSIMWR351ILM2eyidvo0d617Gzmzuu8hWXLSA5+xDBggHqehNX1U0UMVrvy8hS3AeX3GMpDDPZ7siOolgFQ6wy9ejGs46czfPmlemd/2WX8rspOio/n79J776k9lQsuIJmZmoaowxCDQdmgm9kAcLJbdjbbZKhw4AAL3m66Sa8dTJ1Ko3zLLer1EyeAuXOpLdSp413/9FMaSz99ITaWRsWN3FwKmn5hJKB8qaqAvrgNiC4x6Ib12O9BRQxt2pC0VR5Dp078vFU6Q3w8s4R0xJCcTI9KNaCnXTsmIaiIAaBXeOwYvUw3hABuvZWZSyoyMyg3DDEYRAfZ2QwjjR3LP3QVXn6Zu3VV622ARm7aNHoCupz/+fNp8PyykZo2VRenAfRGzjlHHbpZsYIxez9iUA3nAcpPDEFDegB9Swwguh5DTAxDeCojGxtLL1DlMQD8zL79Vi0UX3ABn8EvnLR0qbq537Bh1IJ04aTx43nfr76qXjcoF6JCDEKIS4QQG4UQm4UQnsR1IcRzQohVpV8/CCGO2NaKbWtmCsfJBmuYj9WGoX9/9XkFBRzdOXKkPsw0bx61A53oDDCM1LQpcNFF3rWiIrbZHj1aaUxjjx9nm2i/MBIQyc13QzecByAx1K0bma1sR1YWd+KqAUU1KZQEkNhUHgPgn5k0cCC9ORVx1K/PdV1/o7Fj6YF+9JF3LS6OXXfnzaPn4MbppzO1dfp0fbdZgzKjwsQghIgF8BKASwF0B3CdEMKh3Ekp75FS9pFS9gHwAoC5tuU8a01KqfH/DWokVMN8nnxSXfD21ls0RrqCNoCic+vWwCWXqNePH6dHcPXVamP55ZfMYtGEkRqtWcMMIFUbDIDE0LGjOltJSho9v4ykjh3V6bdWqqpqrTKIoVYthn1UxNCwIdf8Ula3bFFnCfXsyaFMe/d61/wEaICf+TffqMNb/fqRUP3CSXl5+vXUVD6PKtxkUC5Ew2MYAGCzlHKrlLIAwCwAl/ucfx2AmVF4X4PqRtiCN6ugrXt3ZpqosH07++bceqs6dAKQFHJz/cNI8fHa92i0YgVFUtXsZ8C/sM1vOA9QvhoGoHKIAaB3ojLCQvjXMnTqRAJWGX+/2Qxt2nD37idAl5Sw2M2NmBiK0J98og5FDRnC6+vCSaNHM/3ZiNBRg+YvsExoDcCe+LwTgNIXF0IkAegAwO5T1hZCfAOgCMCTUsr3NK+9HcDtAJCYmIjFixdX/M6rCDk5OSfV/aqgeoah27dDsQeG3L4dn9nObbhqFfquXImNf/gDslQtDgC0nz4dSQAyu3fHCc1n1ePFF3Fas2ZYVlzMlFXHm0oMmDULeX36YK2qbw+As7/5Boe7d8dqhfFK2L8fg3ftwqamTbFL8f6Nv/4avQGsKi7GEfd6SQnO37wZu886C1sUrz1nyxbktmuHdYq19qtXI0kIfPbNN54QVeNvv0VvACu/+w5HS9esn0OT779HLwArvv4a2Tk53vesVQvHN2/G94r37Fu3LkrWr8dqxVqT3Fz0ArByzhwcdZFgrexsnAtg89y52Kkg77M6dUL9jAx8pbiuKCjAeQkJyHrtNeTccovnd6lp+/boeewYVr/wAg736+d5fachQ9B67lx8+cEHKFKMd+144YVoO3s2ls2diwJVO/Qo45fwN+0LKWWFvgCMAzDV9v+bALygOfdP7jUAp5d+7wjgRwCdgt6zX79+8mRCRkZGdd9ChaF8hqQkKekPOL+SkpznjR0rZbNmUubmqi9eVCRl27ZSjhypv4FDh6SsVUvKe+9Vr69fz/f+17/U63v3cv3xx9Xrc+Zw/euv1evPPMP1Awe8azt3cu2ll9SvbdRIyv/5H/Xa734nZcOG6rWPP+Z1ly37+dDPP4cFC7j2+efq1w4cKOXFF6vXrr5ayq5d1WsbN/K606er11u2lPLmm9VrTz/N1+7bp16/+GIpe/RQ/y4dPy5l7dpS3nWX+rXLl/Par7yiXt+wgetPPaVejzJO1r9pAN/IEHY9GqGknQDa2v7fBoCmGQtS4AojSSl3l37fCmAxgL5RuCeDqkCYgrfNmxkb/s1v1OmlQGSOr5/oPHcuwyZ+RW1AJC/ejYwMfvfTFxIS9BlVa9cyBNO0qXfNLyMpL48hHb/Oqrq25X4tMYJCSboOq4B/KKl9e3ouOgG6Z0//zCQA+Oor9XpyMvDdd6ilapddty4TCnRV0P368fPVhZPOPBM47zzTWC9KiAYxLAfQRQjRQQgRDxp/T3aREOJMAI0BLLMdayyESCj9dzMA5wJQlFYa1EgEFbwBLGiLi2MXVh2mTKHgO2aM/pyZM2kYdFlPH3wA9O3LecsqLFqEonr1aGBUyMzkmntWs4W1a9X1C4A/MezZw+9lbaAHVExj0A3rse7l6FF1wVl8PGsLdHUBvXqx+lmVAdSvH9NadcRQmg3WeNUq9fqYMayNsQoJ7RCCm4L0dArgKqSmAj/8oG7KZ1AmVJgYpJRFAO4EMB/AegCzpZTrhBB/F0LY00OuAzCr1J2x0A3AN0KI1QAyQI3BEMPJBL+CtyNHWJdw/fV6w5iVRaN+8816o7xnD3f8112nzuzZv58ZSbqiNgBIT8eR3r3Vu++CAubg64TnoiIaQz/hOSZGXd/gV8MA6Ke3ARUXn/08Bvu9uaFrvw3wM8jPVxNH3bokDp0AffbZQMOGTAJQwa8KGiAxlJQAb7+tXh83jhXxprFehRGVOgYp5UdSyjOklJ2klI+VHntYSplmO+evUsr7Xa/7UkrZU0rZu/S7SSv4JWHKFGa4+KWoTp/OFNIJE/TnzJlDg6DLRvroI67riOGnn4AtW3D47LPV62vW0NjpiMEazuNHDO3aqQ14EDFUpsdQXmLQtd8G/DOTAH6GX32l7tAaGwsMG4bGK1eqX3v66fQ6dMTQowdrYHThpHr1SB5z5qh7QRmEhql8Nog+rClv993HuP1336nPKynh7m7YMKBLF/31Zs6kQVI1tgOoL7RuzVCSCqUVt0d0xBCmoypQ/lRVoHqIIT+fhOZGGI/h0CH1POZu3Wjg/XSGY8c4clWF5GTU2b1bPSYUYDgpM1MfLkpJAZYsUXdyBbjByM3Vk4dBKBhiMIgu3FPeTpzg/1VFbxkZwNat/qLzjz+y8Z1OdM7Pp3g9dqw6zASw4jYxEcdVYzwBGqLTT2euvAp+w3kAf2LYvZvhK9XAIMCfGMrbEgOoePUzoA4n1a7NrrV+HgPgX88A+FdBS8kKdhWuvZbfZ89Wr59zDj0LU9NQIRhiMIguwha9AQw1NWkCXHWV/nrWzk9HDBkZDFfpwkhS0mNITtYTh1XYpltfu5YeTe3a3rUjR7i79vMYEhP1nWIry2PwG9bTtCnJxs9jAMqXmdSlC9C4sV6A7t4dBY0b6/sm9elDgtaFk7p0YbhJ5xEIQRH666/1nqpBIAwxGEQXYae8HTjAgTw33aQ2uBZmzaLR7tBBvZ6Wxl48uhGh69dTvNalqe7fTwOoCyMB/sN5tm7l9/JUPefnU/guDzFYXoSuP5CfxxATwxYUOmKwxrH66Qzbtql7FwnBvkg6j0EIHO7blx6DKq1UCIrQn37Kz0eFlBROhNMR14038jMzXkO5YYjBILoIM+UN4OjOggL/MNL69WyDrROdpSQxjBypH/pjhSx0jfOsna2OGHJyaPzLk6oKlL8dBlBxjcH+Hm741TLUq8d1P48B0O/IBw3imoo4UKr17NnDn68KY8bQC7RqT9y45hp+f+st9XqzZmzL/vrrao3FIBCGGAyiizBFb1IyjDR4sL7TKkDROSaGaYgqrFjBGL5f/UN6Or0NnceRmUn9QFff4DecB4gOMQQVuFWEGPxqGXTEAFQ8M0lK9ZxnIJIdptMZkpP5O6MLJ7VrB5x7rr/AnJrKEN/77+vPMdDCEINBdBGm6G3pUmat+HkLUpIYhg3TG9YPPiBxjBqlXrd6Kum8BYDE0Lu3l8wsWLF0P2Jo3pz5824UFk2OTDsAABqDSURBVDJU5VfDAASLz9HWGACK7X7E4FfLkJTE59XpDAMG8LsmnJTfqhUrrHU6Q+3abIQ4b56+ijklhcSkKoYDWEXdrp0JJ5UThhgMog+/ojeA3kKDBpGQgAorVnDHqgsjAQwjDRminwa3YgV3zDp9obiYImWQvlCvHg2ZCn4ZSVaH0oqGklTCdTRCSQcOqLuZAnym3bvV1dFCkCh1HkPjxmxRoROgAZL14sXqegeAXuCOHQwlqnD11fxcdOEkawrgggXOtvAGoWCIwaBqceQIC5Cuv54GV4eZM2n8dBlLO3YAK1f6VztboQodMaxfzzh4EDHohvMAFa9hAPyJoVYtdbZUEDFY4amgIjdVe20gkplkietuWJlJuh39oEH0GHTrycn8XdAVu40ezefWhZNatmTCwaxZ+vewxsNOn65eN9DCEINB1WLGDDaW8wsjlZRwJzhyJNNZVbAMRkAbDPTowXRRFYIK26T0z0g6cYIEVdnEoEJsbOQc3Xr9+hWrfgb8dYYjR4Bdu9TrgwaxSE1XyGaRtU5nSExkSCrN03YtgpQUVqXryCUpiSGladP4O2UQGoYYDKoGVjX0nXfS2OkyUgDgiy9Y2RoURjrjDIYsVDhxgtcJ0heaNInsjt3Ys4dziHXE8OOPJI8gYvDrrAqUjxiE4JqOGAD9sB4gXPUzEJyZFNRpVZe22rIlK9l1OgPAcNI33zCkpcJVVzFtN0iE/ukn//cx8MAQg0Hlw10NXVior4YG+Idep47eG8jO5k7Tz1vIzKRnogsjWecEFbYBFUtVFULvsYTJStIRAxBMDBXpl9S4Mb90HoNFDDqdoUcPCvo6YgBI2kuW6HUO6+erq4Ju0oRe5Vtv6T2CK67geaaxXplgiMGg8lGWaujCQmoQY8cyFKLCp5/yvKAwUkwMMHSoev3oUXZMDdIXgIqlqjZvrh9VevQon9EKC7lRVKR/LcA1XYEb4E8MLVqQtHS7ccA/M6lRI7Y413kMcXFske4nQCcnk7x15NGjB71Mnc4AMJy0fbv+GgkJLHh77z16fwahYIjBoPIRthoaoEE/cCA4jNSkCesgdEhPZ98cXZhm+XKGgYKIQTecB6DRrFdP7xH41TAA/u0wgMr1GOLiSA7lrWUA6EnpPAaAn+3Klfois2HDSN46nUEIhpMWLlRnRwHcHNSuHRxOKigA3nhDf46BA4YYDCofYauhAWYjNWwIXHKJ+jVFRQwtjB6t300fO8Y01CB9QYhIzr0Ka9bovQWAxNCxoz4UFYYYdGEkoOLE4KcxAMFFbp07Mz6vC/X07EmtSLc+aBDXdOJwo0ac0RCkM+Tl6c9p0IC/C7Nn61Nfe/XiJsFMdwsNQwwGlY8w1dAADcC771JU1LW4WLaMFa1+YaQlS0ggQfpCt27+xWV+w3kA/1RVgGEaP2LwG9IDVK7HAISrfi4p0dcB9OrFz2njRvX6wIH8HqQzZGayBYYKQ4cy3BYUTtq7F/jsM/05qan0br75Rn+Owc8wxGBQ+QhTDQ0AH3/M3X5QGCk+nqKjDunpJJYhQ9TrUkaEZx02b/YfzlNSwhx/HTEUF9NY1YRQkm6XHIYYgPJnJp1+Or1CP2JITia5LFmiXk9IoPc4b55eYB41iuThF05KSWFCg6mEDgVDDAZVg6BqaIBhpBYt9J1SARLDhReqW1BYSE9nL506ddTrW7ZQiKyI8Lx7N4lDRwwHDpAcKkIMRUUVJ4bCQn2X0latSF66EIyVsqrTGc48k/fgpzMMHOgvQJ93Hq+h0xkAhpOysljJrkLdusDllwPvvKMPazVsyJ5bM2fqvRODn2GIwaBmIDubu8Jx4/TawcaNHPbuF0bav59tFILCSEAwMcTE6KfGhclIAiruMfhlJYXRGAD/WoaSEn5mKrRsSaOr8xhq1WI4TucxAPyMf/yRNSEq1K3LJAI/nWHUKP4sgsJJhw5RqNYhNZW/Z7qZ0QY/wxCDQc3A++9zZxsURgL8u6kuXszvQcJz/fp6ow+QGM44Qz8roqqIoaIeg/U+KgTVMggRncwkILhv0sqVNOwqNGtG8vCrgh4xgkToF046/3xmkN1xB4mmfXt9Lc0pDkMMBjUDs2YxHu2XgpqWxrnObdvqz0lPZ6ZK//76czIzmY2kqx8A/FthACSG2Fh9xlUQMRQWUmyvCDHExVWMGKyK7CCdQecxAPyMdu5Uz4cG+POqVStYZ5AyQuoqjBkDrFrFFiQqxMcDv/oV6xXy8tTnvPkmyefECb7fTz/5F1qewjDEYFC9mDGDhv6jjxjymDlTfd7+/cCXX/qHkQASw9Ch+hBMbi5DTX5hpJwcGsMgYkhK0hvuivZJAsJ5DEEFbvb3ciPIYwCoM2zdqhd+g2Yz1KnDcZ1+xDBgAOtB/HQG6+c+b57+nJQUJi98/LF6/cEHvUSqK7Q8xWGIwaD6YLXK2LmT/8/O1u/gPvqIxskvjLR9O8MefvrCihU0pn7EEDScBwhOVc3KYmhDF4oKaocBRC+UpNMYWraM3KsOnTpxh61rlheUmQRQgF6+XC9yx8czzOOnM3Ttynvx0xmGDWPygi6cVJZCy1MchhgMqg9laZWRlsbQhzX9S4WgMZ5AZOdq5dirEJSRBIQjhiB9AQjOSoqG+KzzGBISWEEe5DEAep3h9NN5jSCd4fhx/VAdgD+zDRv0LTqsKuhFi+jRqRAXx+SFefPU55Sl0PIUhyEGg+pD2B1cfj4wfz7DCboqY4A7zhYt2GNHh8xMViu3aKE/xxrOoxsHevgwv4KIQddVFQie3gZUvvgMVLyWwRraE5SZBATrDEBw2uqJExy+o0NKCjUGlWcRttDSwBCDQTUi7A5u8WLuOP30BSlJDMnJ/uQRVNgGhBvOA1S+x1BRYqhfn59FRYihbVu+T1Bm0nff6XWIjh2ZWeRHDH36sJurHzGcfz4/L79w0pAhQJs26nBS2EJLA0MMBtWIsDu4tDTu4P0K3zZupIHz0RcS9u9nrNyPGIKG8wDBxCBlzSCGmBhqGEH9kvw6rMbFMa0zKDMpJ0c/lEeIyEQ3v3u98EKSu65Su1Yt4NJL2StLR0IxMcC111KAVmVKhSm0NDDEYFCNCLODk5LEMHKkXsgFIsKlj77Q4Pvv+Q8/Yti7l1XLYYihY0f1+pEjDHlUNzEA1BmCPIY9e/yby3XuHOwxAMEV0OvX+5PU8OEMI+rGiQIMJ+3bxyaJOqSk8HN57z39OQa+MMRgUL0I2sGtXMldfpg01fbt9cYapcRQuzbQu7f+OlasPIgYEhP18yKsHXg0xOeKEkOYRnoFBfriMiBSy6Ajj7PO4vcwOsPy5fpzLG/PLzvp0ktZP+IXTurXj78HfsVuBr4wxGBQs5GWxvDAqFH6c4qLgYwM/zRVlBJDv35Mj9QhWhlJQDAx1Knjb/iDWmIEFbgB4YgBCM5MOnaMnpQK9evz8/DzGM45h16hXzjpzDMp2PvpDI0bs7+SXxW0ENSIPv3UVDiXE4YYDGo20tIoKDZvrj9n1SqGKPzSVAsKcNrGjeGE55YtKZbqEC1i8PMWgIoXuAHRIQbrWf3CSUGZSQ0bsgWJHzEIQXJftEivIQAMJ333nV7TmDGDpACYCudywhCDQc3Fjh0MJfkVtQGR0IOfx7B6NWIKC8MRg5+3kJ/P0FY0iMGvuA2InsYQJD4D4WoZ/AToXr2ATZv07SiAiADtp2cMH84qd7+aByusqAsnPfigt6OsqXAuEwwxGNRcWO0PwugLZ50VqeRVIUxH1eJiDuexxFQVtm2jYQsihnr1/FuDR8tjqIpQUocO3M0HeQwlJfz8dBg4EDh0CHV0VdRAOJ2hSxeGnXTEYCqcKwxDDAY1DzNmMC48cSLj6N9+qz+3oIBDXgL0BWRm4kSzZsxx12HzZu40K5KqCgSnqgLB09ukjJ74nJ2t36XXr08C8yOGhATWMwR5DECoTqsN1q/Xn9OuHT0UP50BoBe5eHGkUNB9Dd21DULBEINBzYLVP8kaJ1lU5B8fzsxk+MJPXyg9L9uvzTYQXngGKk4MQR6D1VeoIi0xAL5HcbH/cJqgIjcguP12p04U0/10hu7dgfr1I2nDOiQnc0ynn34yZgyfff5875qpcK4wDDEY1CyUpX8SwJBDTAw7quqwbx+wdWswMaxZw2t166Y/Z8sW7rL9xPBoEINl8IM8huJi/5h90LAeIBwxdO7s7zHExjKc5+cxxMYCAwYEE8Pw4fQE/DzFIUPYo0kVTjIVzhWGIQaDmoWyxofT0zl7wTKAKpQOiQnlMXTpoh8JCkQykvzablQlMdjPVSEa/ZIAPvP+/erQjYWgzCQAGDQI9bZs8ZK/HVaFu5/OEBfHFOaPPlJ3bTUVzhWCIQaDmoWyxIdzcmj0Q+gLiIvDsS5d/M8LykgCglNVc3L45UcMxcU852QihrCZSfv2sXpch4EDEVNcrJ/fDNAb69UrnM5w8CCwbJn/eQZlhiEGg5qFssSHlyxhHDqEvoDevVHi11Lj+HG2YvAjhuJiZiWFSVWNRmdVIHiCG1CxYT0AieH4cRax6RC2lgEIbo0B+I/6BEj2S5d6007tGDmSn4FfFbRBuWCIwaBmoSzx4fR0VjGfe67+esXF7KsTVL+wbh1j9X7EsGsXs6CiUcMABLfDACruMYTVGAD/ZnpB7beBcJlJiYnIa9XKv9ANINnn5/t7Aw0bci73P/5hKpyjDEMMBjUPYePD6ekUIf00ge+/Z9gmTGEb4F/DEDYjCQhHDEHT24DgrCT7uSqE9RgA/3DSaadxhoWfx9C8OXtIBegM2d26BRPDBRdQrPbTGWbMYFFdUZGpcI4yDDEYnJw4eJCtMMKEkYBwxOA3nAeIPjHUJI0BCCdA+3kMAInVz2NAaRLAzp2Rka4qNGjA/kp+OoOZ4VxpMMRgcHIiI4PfwxBD06b+xhzgLvess/TDeQAaxbg4FnvpsHs3C8IaN9afEy2NIQwx1K3LnXc0iCGo/TbAUNy6dfr5zrBlh4XRGb7+Wp8JZSqcKw2GGAxOTqSnM7xxzjn+51kT2/zSS8MM5wFIDO3b+4d3srLYmsPv/arSYxCC7+OnMTRqRDIL4zHs3OnfD6lXL2oDPgSS06kTtaEgYhg+nASzZIl63VQ4VxoMMRicnFi0iHFoPyN95Ag1hqAwUpjhPEBwqioQvoYBqBpiAIKH9QhRtpTVbdv051ifoY/OIOPjgbPPDtYZBg8mYel0BlPhXGkwxGBw8mHnTuCHH4LDSNZQmLDCsx8xSFm1xGBlJVVUfLbex48YgPBFboC/ztC9O8NxAToDBg0CvvnG/97r1GHGmU5nMBXOlQZDDAYnF2bM4OB4AHjmGX0GyowZwLhx/Pett/pnqoQhhkOHaFyjRQzx8f6jSqPpMUSLGCyPwU9nqF2bKaQhKqCRlxdMIMnJwOrVrLpWwVQ4VwoMMRicPLAa7B08yP9nZanTE63zLGO4Ywdw++1osXCh+rrWcB6//kdhMpLy8zmAvqLtMIDoFbgBwRoDwIK8IGJo2pTZQlHITPrZiwtTzwCwk6pBlcEQg8HJg7AN9jTndZw6VX3dsMIz4E8Me/bwe1URQ7Q0BoD3fOSIv7AsRPjMpK1b/Sup27VjzUOQAN2/P5MM/OoZDKIOQwwGJw/CpidqzkvYt897sLiY6ZVhiaFjR/05YWoYgPDT24CqDSUBEXLTIWwtA+A/hU2IyEQ3P8TF8T1fecVUN1chDDEYnDwIm56oOe9Eixbeg2GG8wA0hq1aebNg7AhLDEFDeoDoi8/HjvnPUS5LLcOPP/qHr7Zu5ffBg/0NeUICkwj8DP6MGSQYU91cpTDEYHDyIGx6oua8rRMmeK8ZRngGwmckAf4N9ICqDyU1bEij6tcyOywx7N9PIx0frzbmM2Y4Q3s6Qz5jBvD++/y3n8E31c3VgqgQgxDiVSHEPiHEd5p1IYT4pxBisxBijRDibNvaeCHEptKv8dG4H4NfKMKmJ2rO23fRRd5rrl3LHWvQrIYtW/zDSACNamysv4gNVD0xbNjA702a6HfmX37J71df7b97/+9/+W+dMS+LDnTiRPB5prq5WhAtj2E6gEt81i8F0KX063YA/wYAIUQTAH8BMBDAAAB/EUL49BIwOOURNj0x7Hlr1zI84teILy+PrS7CeAyJif5tNYDoEcMnn/D7uHH+xvz11/lvnTGfMQOYNCnyf7/de5Axr6AO5DluqpurBVEhBinl5wAO+ZxyOYDXJZEJoJEQohWAkQAWSCkPSSkPA1gAf4IxMIgu1q7176gKRGLm0ahheOMNEsM//+lvzP/wB/77/PP15zz8cOT/fsa8oMB5zG3Mw+7ywxjzCupAnuOmurlaUFUaQ2sAO2z/31l6THfcwKDycfw4Q0TRSFWdMQNYuJBziv0M/u23R/6v273ffjsL6gDOgNAZfPcQm/Ia82ju3iuoA3nOM9XN1QIh/QaJl+VCQrQHME9K2UOx9iGAJ6SUX5T+Px3AfQCSASRIKR8tPf5nALlSymcV17gdDEMhMTGx36xZs6Jy31WBnJwc1K9fv7pvo0L4pT1Di4UL0enf/0bCoUMoaNgQm++8U6lBtFi4EF0mT0atnBzkN2+Orbff7jmvxcKFOPP//T/E2sIsxQkJ2DhpkuPcQSkpqK0Ye5mfmIjM0t/noHOsZxianAyh+NuVQuAzWwuJaLxnWZ+zxcKF6Dh1KhL27cOJFi2wdcIEx7r1DEHn1WScrH8PF1544bdSyv6BJ0opo/IFoD2A7zRrLwO4zvb/jQBaAbgOwMu683Rf/fr1kycTMjIyqvsWKoxf1DO88YaUdetKyag7v+rW5XE7wp6XlOQ8x/pKSnKeJ4T6PCFCn/PzM4R9zzDPEPY5rXOTkng/SUnqcwLwi/pdOskA4BsZwp5XVSgpDcCvS7OTBgE4KqXMAjAfwAghRONS0XlE6TEDg8pDBSuoy505EyYUE+3Ye5hQTFnCNaY30SmBaKWrzgSwDMCZQoidQohUIcRvhBC/KT3lIwBbAWwGMAXARACQUh4C8AiA5aVffy89ZmBQeaiuzJkwxrwyYu9hjLkx+AY2+JRVhoeU8rqAdQngfzRrrwJ4NRr3YWAQCu3aUfhVHS/PeY89RoHY7l3ojDlAj2P7dl7nsce8u/egc+znGgNuUAkwlc8Gpx6qM3PG7N4NTgIYYjA49VDBCmpjzA1+6YhKKMnA4KRD2DCMCdcYnIIwHoOBgYGBgQOGGAwMDAwMHDDEYGBgYGDggCEGAwMDAwMHDDEYGBgYGDhgiMHAwMDAwAFDDAYGBgYGDhhiMDAwMDBwwBCDgYGBgYEDhhgMDAwMDBwwxGBgYGBg4IAhBgMDAwMDBwwxGBgYGBg4YIjBwMDAwMABQwwGBgYGBg4YYjAwMDAwcMAQg4GBgYGBA4YYDAwMDAwcMMRgYGBgYOCAIQYDAwMDAweElLK676HMEELsB/BTdd9HGdAMwIHqvokKwjxDzYB5hpqBk/UZkqSUzYNOOimJ4WSDEOIbKWX/6r6PisA8Q82AeYaagV/CM/jBhJIMDAwMDBwwxGBgYGBg4IAhhqrB/1X3DUQB5hlqBswz1Az8Ep5BC6MxGBgYGBg4YDwGAwMDAwMHDDFUAoQQTYQQC4QQm0q/N9ac104I8akQYr0Q4nshRPuqvVM9wj5D6bkNhBC7hBAvVuU9BiHMMwgh+gghlgkh1gkh1gghrq2Oe3VDCHGJEGKjEGKzEOJ+xXqCEOKt0vWvatLvjoUQz3Bv6e/9GiFEuhAiqTru0w9Bz2A772ohhBRC/CIylQwxVA7uB5AupewCIL30/yq8DuAZKWU3AAMA7Kui+wuDsM8AAI8A+KxK7qpsCPMMuQB+LaU8C8AlAJ4XQjSqwnv0QAgRC+AlAJcC6A7gOiFEd9dpqQAOSyk7A3gOwFNVe5f+CPkMKwH0l1L2AvA2gKer9i79EfIZIIQ4DcDvAHxVtXdYeTDEUDm4HMBrpf9+DcAV7hNKf8HipJQLAEBKmSOlzK26WwxE4DMAgBCiH4BEAJ9W0X2VBYHPIKX8QUq5qfTfu0FyDiwAqmQMALBZSrlVSlkAYBb4LHbYn+1tAMOFEKIK7zEIgc8gpcyw/c5nAmhTxfcYhDA/B4Abo6cB5FflzVUmDDFUDhKllFkAUPq9heKcMwAcEULMFUKsFEI8U7pDqSkIfAYhRAyAZwH8sYrvLSzC/Bx+hhBiAIB4AFuq4N780BrADtv/d5YeU54jpSwCcBRA0yq5u3AI8wx2pAL4uFLvqOwIfAYhRF8AbaWU86ryxiobcdV9AycrhBALAbRULD0Y8hJxAM4H0BfAdgBvAbgZwCvRuL8wiMIzTATwkZRyR3VtVqPwDNZ1WgH4L4DxUsqSaNxbBaD6MN3pg2HOqU6Evj8hxI0A+gMYWql3VHb4PkPpxug58O/2FwVDDOWElPIi3ZoQYq8QopWUMqvU4Ki0g50AVkopt5a+5j0Ag1CFxBCFZxgM4HwhxEQA9QHECyFypJR+ekRUEYVngBCiAYAPATwkpcyspFstC3YCaGv7fxsAuzXn7BRCxAFoCOBQ1dxeKIR5BgghLgJJfKiU8kQV3VtYBD3DaQB6AFhcujFqCSBNCDFWSvlNld1lJcCEkioHaQDGl/57PID3FecsB9BYCGHFs5MBfF8F9xYWgc8gpbxBStlOStkewCQAr1clKYRA4DMIIeIBvAve+5wqvDc/LAfQRQjRofT+UsBnscP+bFcDWCRrVlFS4DOUhmFeBjBWSlmTEi8s+D6DlPKolLKZlLJ96d9AJvgsJzUpAACklOYryl9grDcdwKbS701Kj/cHMNV23sUA1gBYC2A6gPjqvveyPoPt/JsBvFjd913WZwBwI4BCAKtsX31qwL2PAvADqHc8WHrs76DhAYDaAOYA2AzgawAdq/uey/EMCwHstX3uadV9z2V9Bte5i8Esq2q/74p+mcpnAwMDAwMHTCjJwMDAwMABQwwGBgYGBg4YYjAwMDAwcMAQg4GBgYGBA4YYDAwMDAwcMMRgYGBgYOCAIQYDAwMDAwcMMRgYGBgYOPD/AVOh5xr3tl8iAAAAAElFTkSuQmCC\n", + "text/plain": [ + "
" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + } + ], + "source": [ + "ang, dist = file_read(\"lidar01.csv\")\n", + "ox = np.sin(ang) * dist\n", + "oy = np.cos(ang) * dist\n", + "plt.figure(figsize=(6,10))\n", + "plt.plot([oy, np.zeros(np.size(oy))], [ox, np.zeros(np.size(oy))], \"ro-\") # lines from 0,0 to the \n", + "plt.axis(\"equal\")\n", + "bottom, top = plt.ylim() # return the current ylim\n", + "plt.ylim((top, bottom)) # rescale y axis, to match the grid orientation\n", + "plt.grid(True)\n", + "plt.show()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "The `lidar_to_grid_map.py` contains handy functions which can used to convert a 2D range measurement to a grid map. For example the `bresenham` gives the a straight line between two points in a grid map. Let's see how this works." + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + } + ], + "source": [ + "import lidar_to_grid_map as lg\n", + "map1 = np.ones((50, 50)) * 0.5\n", + "line = lg.bresenham((2, 2), (40, 30))\n", + "for l in line:\n", + " map1[l[0]][l[1]] = 1\n", + "plt.imshow(map1)\n", + "plt.colorbar()\n", + "plt.show()" + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + } + ], + "source": [ + "line = lg.bresenham((2, 30), (40, 30))\n", + "for l in line:\n", + " map1[l[0]][l[1]] = 1\n", + "line = lg.bresenham((2, 30), (2, 2))\n", + "for l in line:\n", + " map1[l[0]][l[1]] = 1\n", + "plt.imshow(map1)\n", + "plt.colorbar()\n", + "plt.show()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "To fill empty areas, a queue-based algorithm can be used that can be used on an initialized occupancy map. The center point is given: the algorithm checks for neighbour elements in each iteration, and stops expansion on obstacles and free boundaries." + ] + }, + { + "cell_type": "code", + "execution_count": 6, + "metadata": {}, + "outputs": [], + "source": [ + "from collections import deque\n", + "def flood_fill(cpoint, pmap):\n", + " \"\"\"\n", + " cpoint: starting point (x,y) of fill\n", + " pmap: occupancy map generated from Bresenham ray-tracing\n", + " \"\"\"\n", + " # Fill empty areas with queue method\n", + " sx, sy = pmap.shape\n", + " fringe = deque()\n", + " fringe.appendleft(cpoint)\n", + " while fringe:\n", + " n = fringe.pop()\n", + " nx, ny = n\n", + " # West\n", + " if nx > 0:\n", + " if pmap[nx - 1, ny] == 0.5:\n", + " pmap[nx - 1, ny] = 0.0\n", + " fringe.appendleft((nx - 1, ny))\n", + " # East\n", + " if nx < sx - 1:\n", + " if pmap[nx + 1, ny] == 0.5:\n", + " pmap[nx + 1, ny] = 0.0\n", + " fringe.appendleft((nx + 1, ny))\n", + " # North\n", + " if ny > 0:\n", + " if pmap[nx, ny - 1] == 0.5:\n", + " pmap[nx, ny - 1] = 0.0\n", + " fringe.appendleft((nx, ny - 1))\n", + " # South\n", + " if ny < sy - 1:\n", + " if pmap[nx, ny + 1] == 0.5:\n", + " pmap[nx, ny + 1] = 0.0\n", + " fringe.appendleft((nx, ny + 1))" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "This algotihm will fill the area bounded by the yellow lines starting from a center point (e.g. (10, 20)) with zeros:" + ] + }, + { + "cell_type": "code", + "execution_count": 7, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + } + ], + "source": [ + "flood_fill((10, 20), map1)\n", + "map_float = np.array(map1)/10.0\n", + "plt.imshow(map1)\n", + "plt.colorbar()\n", + "plt.show()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Let's use this flood fill on real data:" + ] + }, + { + "cell_type": "code", + "execution_count": 8, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "The grid map is 150 x 100 .\n" + ] + }, + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + } + ], + "source": [ + "xyreso = 0.02 # x-y grid resolution\n", + "yawreso = math.radians(3.1) # yaw angle resolution [rad]\n", + "ang, dist = file_read(\"lidar01.csv\")\n", + "ox = np.sin(ang) * dist\n", + "oy = np.cos(ang) * dist\n", + "pmap, minx, maxx, miny, maxy, xyreso = lg.generate_ray_casting_grid_map(ox, oy, xyreso, False)\n", + "xyres = np.array(pmap).shape\n", + "plt.figure(figsize=(20,8))\n", + "plt.subplot(122)\n", + "plt.imshow(pmap, cmap = \"PiYG_r\") \n", + "plt.clim(-0.4, 1.4)\n", + "plt.gca().set_xticks(np.arange(-.5, xyres[1], 1), minor = True)\n", + "plt.gca().set_yticks(np.arange(-.5, xyres[0], 1), minor = True)\n", + "plt.grid(True, which=\"minor\", color=\"w\", linewidth = .6, alpha = 0.5)\n", + "plt.colorbar()\n", + "plt.show()" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.7.3" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/PathPlanning/AStar/a_star.py b/PathPlanning/AStar/a_star.py index 4498c751..88f65a57 100644 --- a/PathPlanning/AStar/a_star.py +++ b/PathPlanning/AStar/a_star.py @@ -14,172 +14,191 @@ import math show_animation = True +class AStarPlanner: -class Node: + def __init__(self, ox, oy, reso, rr): + """ + Intialize map for a star planning - def __init__(self, x, y, cost, pind): - self.x = x - self.y = y - self.cost = cost - self.pind = pind + ox: x position list of Obstacles [m] + oy: y position list of Obstacles [m] + reso: grid resolution [m] + rr: robot radius[m] + """ - def __str__(self): - return str(self.x) + "," + str(self.y) + "," + str(self.cost) + "," + str(self.pind) + self.reso = reso + self.rr = rr + self.calc_obstacle_map(ox, oy) + self.motion = self.get_motion_model() + class Node: + def __init__(self, x, y, cost, pind): + self.x = x # index of grid + self.y = y # index of grid + self.cost = cost + self.pind = pind -def calc_final_path(ngoal, closedset, reso): - # generate final course - rx, ry = [ngoal.x * reso], [ngoal.y * reso] - pind = ngoal.pind - while pind != -1: - n = closedset[pind] - rx.append(n.x * reso) - ry.append(n.y * reso) - pind = n.pind + def __str__(self): + return str(self.x) + "," + str(self.y) + "," + str(self.cost) + "," + str(self.pind) - return rx, ry + def planning(self, sx, sy, gx, gy): + """ + A star path search + input: + sx: start x position [m] + sy: start y position [m] + gx: goal x position [m] + gx: goal x position [m] -def a_star_planning(sx, sy, gx, gy, ox, oy, reso, rr): - """ - gx: goal x position [m] - gx: goal x position [m] - ox: x position list of Obstacles [m] - oy: y position list of Obstacles [m] - reso: grid resolution [m] - rr: robot radius[m] - """ + output: + rx: x position list of the final path + ry: y position list of the final path + """ - nstart = Node(round(sx / reso), round(sy / reso), 0.0, -1) - ngoal = Node(round(gx / reso), round(gy / reso), 0.0, -1) - ox = [iox / reso for iox in ox] - oy = [ioy / reso for ioy in oy] + nstart = self.Node(self.calc_xyindex(sx, self.minx), + self.calc_xyindex(sy, self.miny), 0.0, -1) + ngoal = self.Node(self.calc_xyindex(gx, self.minx), + self.calc_xyindex(gy, self.miny), 0.0, -1) - obmap, minx, miny, maxx, maxy, xw, yw = calc_obstacle_map(ox, oy, reso, rr) + openset, closedset = dict(), dict() + openset[self.calc_index(nstart)] = nstart - motion = get_motion_model() + while 1: + c_id = min( + openset, key=lambda o: openset[o].cost + self.calc_heuristic(ngoal, openset[o])) + current = openset[c_id] - openset, closedset = dict(), dict() - openset[calc_index(nstart, xw, minx, miny)] = nstart + # show graph + if show_animation: # pragma: no cover + plt.plot(self.calc_position(current.x, self.minx), + self.calc_position(current.y, self.miny), "xc") + if len(closedset.keys()) % 10 == 0: + plt.pause(0.001) - while 1: - c_id = min( - openset, key=lambda o: openset[o].cost + calc_heuristic(ngoal, openset[o])) - current = openset[c_id] + if current.x == ngoal.x and current.y == ngoal.y: + print("Find goal") + ngoal.pind = current.pind + ngoal.cost = current.cost + break - # show graph - if show_animation: # pragma: no cover - plt.plot(current.x * reso, current.y * reso, "xc") - if len(closedset.keys()) % 10 == 0: - plt.pause(0.001) + # Remove the item from the open set + del openset[c_id] - if current.x == ngoal.x and current.y == ngoal.y: - print("Find goal") - ngoal.pind = current.pind - ngoal.cost = current.cost - break + # Add it to the closed set + closedset[c_id] = current - # Remove the item from the open set - del openset[c_id] - # Add it to the closed set - closedset[c_id] = current + # expand search grid based on motion model + for i, _ in enumerate(self.motion): + node = self.Node(current.x + self.motion[i][0], + current.y + self.motion[i][1], + current.cost + self.motion[i][2], c_id) + n_id = self.calc_index(node) - # expand search grid based on motion model - for i, _ in enumerate(motion): - node = Node(current.x + motion[i][0], - current.y + motion[i][1], - current.cost + motion[i][2], c_id) - n_id = calc_index(node, xw, minx, miny) + if n_id in closedset: + continue - if n_id in closedset: - continue + if not self.verify_node(node): + continue - if not verify_node(node, obmap, minx, miny, maxx, maxy): - continue + if n_id not in openset: + openset[n_id] = node # Discover a new node + else: + if openset[n_id].cost >= node.cost: + # This path is the best until now. record it! + openset[n_id] = node - if n_id not in openset: - openset[n_id] = node # Discover a new node - else: - if openset[n_id].cost >= node.cost: - # This path is the best until now. record it! - openset[n_id] = node + rx, ry = self.calc_final_path(ngoal, closedset) - rx, ry = calc_final_path(ngoal, closedset, reso) + return rx, ry - return rx, ry + def calc_final_path(self, ngoal, closedset): + # generate final course + rx, ry = [self.calc_position(ngoal.x, self.minx)], [ + self.calc_position(ngoal.y, self.miny)] + pind = ngoal.pind + while pind != -1: + n = closedset[pind] + rx.append(self.calc_position(n.x, self.minx)) + ry.append(self.calc_position(n.y, self.miny)) + pind = n.pind + return rx, ry -def calc_heuristic(n1, n2): - w = 1.0 # weight of heuristic - d = w * math.sqrt((n1.x - n2.x)**2 + (n1.y - n2.y)**2) - return d + def calc_heuristic(self, n1, n2): + w = 1.0 # weight of heuristic + d = w * math.sqrt((n1.x - n2.x)**2 + (n1.y - n2.y)**2) + return d + def calc_position(self, index, minp): + pos = index*self.reso+minp + return pos -def verify_node(node, obmap, minx, miny, maxx, maxy): + def calc_xyindex(self, position, minp): + return round((position - minp)/self.reso) - if node.x < minx: - return False - elif node.y < miny: - return False - elif node.x >= maxx: - return False - elif node.y >= maxy: - return False + def calc_index(self, node): + return (node.y - self.miny) * self.xwidth + (node.x - self.minx) - if obmap[node.x][node.y]: - return False + def verify_node(self, node): + px = self.calc_position(node.x, self.minx) + py = self.calc_position(node.y, self.miny) - return True + if px < self.minx: + return False + elif py < self.miny: + return False + elif px >= self.maxx: + return False + elif py >= self.maxy: + return False + if self.obmap[node.x][node.y]: + return False -def calc_obstacle_map(ox, oy, reso, vr): + return True - minx = round(min(ox)) - miny = round(min(oy)) - maxx = round(max(ox)) - maxy = round(max(oy)) - # print("minx:", minx) - # print("miny:", miny) - # print("maxx:", maxx) - # print("maxy:", maxy) + def calc_obstacle_map(self, ox, oy): - xwidth = round(maxx - minx) - ywidth = round(maxy - miny) - # print("xwidth:", xwidth) - # print("ywidth:", ywidth) + self.minx = round(min(ox)) + self.miny = round(min(oy)) + self.maxx = round(max(ox)) + self.maxy = round(max(oy)) + print("minx:", self.minx) + print("miny:", self.miny) + print("maxx:", self.maxx) + print("maxy:", self.maxy) - # obstacle map generation - obmap = [[False for i in range(ywidth)] for i in range(xwidth)] - for ix in range(xwidth): - x = ix + minx - for iy in range(ywidth): - y = iy + miny - # print(x, y) - for iox, ioy in zip(ox, oy): - d = math.sqrt((iox - x)**2 + (ioy - y)**2) - if d <= vr / reso: - obmap[ix][iy] = True - break + self.xwidth = round((self.maxx - self.minx)/self.reso) + self.ywidth = round((self.maxy - self.miny)/self.reso) + print("xwidth:", self.xwidth) + print("ywidth:", self.ywidth) - return obmap, minx, miny, maxx, maxy, xwidth, ywidth + # obstacle map generation + self.obmap = [[False for i in range(self.ywidth)] + for i in range(self.xwidth)] + for ix in range(self.xwidth): + x = self.calc_position(ix, self.minx) + for iy in range(self.ywidth): + y = self.calc_position(iy, self.miny) + for iox, ioy in zip(ox, oy): + d = math.sqrt((iox - x)**2 + (ioy - y)**2) + if d <= self.rr: + self.obmap[ix][iy] = True + break + def get_motion_model(self): + # dx, dy, cost + motion = [[1, 0, 1], + [0, 1, 1], + [-1, 0, 1], + [0, -1, 1], + [-1, -1, math.sqrt(2)], + [-1, 1, math.sqrt(2)], + [1, -1, math.sqrt(2)], + [1, 1, math.sqrt(2)]] -def calc_index(node, xwidth, xmin, ymin): - return (node.y - ymin) * xwidth + (node.x - xmin) - - -def get_motion_model(): - # dx, dy, cost - motion = [[1, 0, 1], - [0, 1, 1], - [-1, 0, 1], - [0, -1, 1], - [-1, -1, math.sqrt(2)], - [-1, 1, math.sqrt(2)], - [1, -1, math.sqrt(2)], - [1, 1, math.sqrt(2)]] - - return motion + return motion def main(): @@ -190,38 +209,39 @@ def main(): sy = 10.0 # [m] gx = 50.0 # [m] gy = 50.0 # [m] - grid_size = 1.0 # [m] - robot_size = 1.0 # [m] + grid_size = 2.0 # [m] + robot_radius = 1.0 # [m] + # set obstable positions ox, oy = [], [] - - for i in range(60): + for i in range(-10, 60): ox.append(i) - oy.append(0.0) - for i in range(60): + oy.append(-10.0) + for i in range(-10, 60): ox.append(60.0) oy.append(i) - for i in range(61): + for i in range(-10, 61): ox.append(i) oy.append(60.0) - for i in range(61): - ox.append(0.0) + for i in range(-10, 61): + ox.append(-10.0) oy.append(i) - for i in range(40): + for i in range(-10, 40): ox.append(20.0) oy.append(i) - for i in range(40): + for i in range(0, 40): ox.append(40.0) oy.append(60.0 - i) if show_animation: # pragma: no cover plt.plot(ox, oy, ".k") - plt.plot(sx, sy, "xr") + plt.plot(sx, sy, "og") plt.plot(gx, gy, "xb") plt.grid(True) plt.axis("equal") - rx, ry = a_star_planning(sx, sy, gx, gy, ox, oy, grid_size, robot_size) + a_star = AStarPlanner(ox, oy, grid_size, robot_radius) + rx, ry = a_star.planning(sx, sy, gx, gy) if show_animation: # pragma: no cover plt.plot(rx, ry, "-r") diff --git a/PathPlanning/Dijkstra/dijkstra.py b/PathPlanning/Dijkstra/dijkstra.py index 89eb632a..bb73ed50 100644 --- a/PathPlanning/Dijkstra/dijkstra.py +++ b/PathPlanning/Dijkstra/dijkstra.py @@ -1,7 +1,9 @@ """ -Dijkstra grid based planning + +Grid based Dijkstra planning author: Atsushi Sakai(@Atsushi_twi) + """ import matplotlib.pyplot as plt @@ -9,210 +11,235 @@ import math show_animation = True +class Dijkstra: -class Node: + def __init__(self, ox, oy, reso, rr): + """ + Initialize map for a star planning - def __init__(self, x, y, cost, pind): - self.x = x - self.y = y - self.cost = cost - self.pind = pind + ox: x position list of Obstacles [m] + oy: y position list of Obstacles [m] + reso: grid resolution [m] + rr: robot radius[m] + """ - def __str__(self): - return str(self.x) + "," + str(self.y) + "," + str(self.cost) + "," + str(self.pind) + self.reso = reso + self.rr = rr + self.calc_obstacle_map(ox, oy) + self.motion = self.get_motion_model() + class Node: + def __init__(self, x, y, cost, pind): + self.x = x # index of grid + self.y = y # index of grid + self.cost = cost + self.pind = pind -def dijkstra_planning(sx, sy, gx, gy, ox, oy, reso, rr): - """ - gx: goal x position [m] - gx: goal x position [m] - ox: x position list of Obstacles [m] - oy: y position list of Obstacles [m] - reso: grid resolution [m] - rr: robot radius[m] - """ + def __str__(self): + return str(self.x) + "," + str(self.y) + "," + str(self.cost) + "," + str(self.pind) - nstart = Node(round(sx / reso), round(sy / reso), 0.0, -1) - ngoal = Node(round(gx / reso), round(gy / reso), 0.0, -1) - ox = [iox / reso for iox in ox] - oy = [ioy / reso for ioy in oy] + def planning(self, sx, sy, gx, gy): + """ + dijkstra path search - obmap, minx, miny, maxx, maxy, xw, yw = calc_obstacle_map(ox, oy, reso, rr) + input: + sx: start x position [m] + sy: start y position [m] + gx: goal x position [m] + gx: goal x position [m] - motion = get_motion_model() + output: + rx: x position list of the final path + ry: y position list of the final path + """ - openset, closedset = dict(), dict() - openset[calc_index(nstart, xw, minx, miny)] = nstart + nstart = self.Node(self.calc_xyindex(sx, self.minx), + self.calc_xyindex(sy, self.miny), 0.0, -1) + ngoal = self.Node(self.calc_xyindex(gx, self.minx), + self.calc_xyindex(gy, self.miny), 0.0, -1) - while 1: - c_id = min(openset, key=lambda o: openset[o].cost) - current = openset[c_id] - # print("current", current) + openset, closedset = dict(), dict() + openset[self.calc_index(nstart)] = nstart - # show graph - if show_animation: - plt.plot(current.x * reso, current.y * reso, "xc") - if len(closedset.keys()) % 10 == 0: - plt.pause(0.001) + while 1: + c_id = min(openset, key=lambda o: openset[o].cost) + current = openset[c_id] - if current.x == ngoal.x and current.y == ngoal.y: - print("Find goal") - ngoal.pind = current.pind - ngoal.cost = current.cost - break + # show graph + if show_animation: # pragma: no cover + plt.plot(self.calc_position(current.x, self.minx), + self.calc_position(current.y, self.miny), "xc") + if len(closedset.keys()) % 10 == 0: + plt.pause(0.001) - # Remove the item from the open set - del openset[c_id] - # Add it to the closed set - closedset[c_id] = current + if current.x == ngoal.x and current.y == ngoal.y: + print("Find goal") + ngoal.pind = current.pind + ngoal.cost = current.cost + break - # expand search grid based on motion model - for i, _ in enumerate(motion): - node = Node(current.x + motion[i][0], current.y + motion[i][1], - current.cost + motion[i][2], c_id) - n_id = calc_index(node, xw, minx, miny) + # Remove the item from the open set + del openset[c_id] - if not verify_node(node, obmap, minx, miny, maxx, maxy): - continue + # Add it to the closed set + closedset[c_id] = current - if n_id in closedset: - continue - # Otherwise if it is already in the open set - if n_id in openset: - if openset[n_id].cost > node.cost: - openset[n_id].cost = node.cost - openset[n_id].pind = c_id - else: - openset[n_id] = node + # expand search grid based on motion model + for i, _ in enumerate(self.motion): + node = self.Node(current.x + self.motion[i][0], + current.y + self.motion[i][1], + current.cost + self.motion[i][2], c_id) + n_id = self.calc_index(node) - rx, ry = calc_final_path(ngoal, closedset, reso) + if n_id in closedset: + continue - return rx, ry + if not self.verify_node(node): + continue + if n_id not in openset: + openset[n_id] = node # Discover a new node + else: + if openset[n_id].cost >= node.cost: + # This path is the best until now. record it! + openset[n_id] = node -def calc_final_path(ngoal, closedset, reso): - # generate final course - rx, ry = [ngoal.x * reso], [ngoal.y * reso] - pind = ngoal.pind - while pind != -1: - n = closedset[pind] - rx.append(n.x * reso) - ry.append(n.y * reso) - pind = n.pind + rx, ry = self.calc_final_path(ngoal, closedset) - return rx, ry + return rx, ry + def calc_final_path(self, ngoal, closedset): + # generate final course + rx, ry = [self.calc_position(ngoal.x, self.minx)], [ + self.calc_position(ngoal.y, self.miny)] + pind = ngoal.pind + while pind != -1: + n = closedset[pind] + rx.append(self.calc_position(n.x, self.minx)) + ry.append(self.calc_position(n.y, self.miny)) + pind = n.pind -def verify_node(node, obmap, minx, miny, maxx, maxy): + return rx, ry - if obmap[node.x][node.y]: - return False + def calc_heuristic(self, n1, n2): + w = 1.0 # weight of heuristic + d = w * math.sqrt((n1.x - n2.x)**2 + (n1.y - n2.y)**2) + return d - if node.x < minx: - return False - elif node.y < miny: - return False - elif node.x > maxx: - return False - elif node.y > maxy: - return False + def calc_position(self, index, minp): + pos = index*self.reso+minp + return pos - return True + def calc_xyindex(self, position, minp): + return round((position - minp)/self.reso) + def calc_index(self, node): + return (node.y - self.miny) * self.xwidth + (node.x - self.minx) -def calc_obstacle_map(ox, oy, reso, vr): + def verify_node(self, node): + px = self.calc_position(node.x, self.minx) + py = self.calc_position(node.y, self.miny) - minx = round(min(ox)) - miny = round(min(oy)) - maxx = round(max(ox)) - maxy = round(max(oy)) - # print("minx:", minx) - # print("miny:", miny) - # print("maxx:", maxx) - # print("maxy:", maxy) + if px < self.minx: + return False + elif py < self.miny: + return False + elif px >= self.maxx: + return False + elif py >= self.maxy: + return False - xwidth = round(maxx - minx) - ywidth = round(maxy - miny) - # print("xwidth:", xwidth) - # print("ywidth:", ywidth) + if self.obmap[node.x][node.y]: + return False - # obstacle map generation - obmap = [[False for i in range(ywidth)] for i in range(xwidth)] - for ix in range(xwidth): - x = ix + minx - for iy in range(ywidth): - y = iy + miny - # print(x, y) - for iox, ioy in zip(ox, oy): - d = math.sqrt((iox - x)**2 + (ioy - y)**2) - if d <= vr / reso: - obmap[ix][iy] = True - break + return True - return obmap, minx, miny, maxx, maxy, xwidth, ywidth + def calc_obstacle_map(self, ox, oy): + self.minx = round(min(ox)) + self.miny = round(min(oy)) + self.maxx = round(max(ox)) + self.maxy = round(max(oy)) + print("minx:", self.minx) + print("miny:", self.miny) + print("maxx:", self.maxx) + print("maxy:", self.maxy) -def calc_index(node, xwidth, xmin, ymin): - return (node.y - ymin) * xwidth + (node.x - xmin) + self.xwidth = round((self.maxx - self.minx)/self.reso) + self.ywidth = round((self.maxy - self.miny)/self.reso) + print("xwidth:", self.xwidth) + print("ywidth:", self.ywidth) + # obstacle map generation + self.obmap = [[False for i in range(self.ywidth)] + for i in range(self.xwidth)] + for ix in range(self.xwidth): + x = self.calc_position(ix, self.minx) + for iy in range(self.ywidth): + y = self.calc_position(iy, self.miny) + for iox, ioy in zip(ox, oy): + d = math.sqrt((iox - x)**2 + (ioy - y)**2) + if d <= self.rr: + self.obmap[ix][iy] = True + break -def get_motion_model(): - # dx, dy, cost - motion = [[1, 0, 1], - [0, 1, 1], - [-1, 0, 1], - [0, -1, 1], - [-1, -1, math.sqrt(2)], - [-1, 1, math.sqrt(2)], - [1, -1, math.sqrt(2)], - [1, 1, math.sqrt(2)]] + def get_motion_model(self): + # dx, dy, cost + motion = [[1, 0, 1], + [0, 1, 1], + [-1, 0, 1], + [0, -1, 1], + [-1, -1, math.sqrt(2)], + [-1, 1, math.sqrt(2)], + [1, -1, math.sqrt(2)], + [1, 1, math.sqrt(2)]] - return motion + return motion def main(): print(__file__ + " start!!") # start and goal position - sx = 10.0 # [m] - sy = 10.0 # [m] + sx = -5.0 # [m] + sy = -5.0 # [m] gx = 50.0 # [m] gy = 50.0 # [m] - grid_size = 1.0 # [m] - robot_size = 1.0 # [m] + grid_size = 2.0 # [m] + robot_radius = 1.0 # [m] - ox = [] - oy = [] - - for i in range(60): + # set obstacle positions + ox, oy = [], [] + for i in range(-10, 60): ox.append(i) - oy.append(0.0) - for i in range(60): + oy.append(-10.0) + for i in range(-10, 60): ox.append(60.0) oy.append(i) - for i in range(61): + for i in range(-10, 61): ox.append(i) oy.append(60.0) - for i in range(61): - ox.append(0.0) + for i in range(-10, 61): + ox.append(-10.0) oy.append(i) - for i in range(40): + for i in range(-10, 40): ox.append(20.0) oy.append(i) - for i in range(40): + for i in range(0, 40): ox.append(40.0) oy.append(60.0 - i) - if show_animation: + if show_animation: # pragma: no cover plt.plot(ox, oy, ".k") - plt.plot(sx, sy, "xr") + plt.plot(sx, sy, "og") plt.plot(gx, gy, "xb") plt.grid(True) plt.axis("equal") - rx, ry = dijkstra_planning(sx, sy, gx, gy, ox, oy, grid_size, robot_size) + dijkstra = Dijkstra(ox, oy, grid_size, robot_radius) + rx, ry = dijkstra.planning(sx, sy, gx, gy) - if show_animation: + if show_animation: # pragma: no cover plt.plot(rx, ry, "-r") plt.show() diff --git a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py index 3144d9a2..fa1dcc62 100644 --- a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py +++ b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py @@ -10,15 +10,26 @@ import math import numpy as np import matplotlib.pyplot as plt -import sys -sys.path.append("../../") - show_animation = True +def dwa_control(x, u, config, goal, ob): + """ + Dynamic Window Approach control + """ + + dw = calc_dynamic_window(x, config) + + u, traj = calc_final_input(x, u, dw, config, goal, ob) + + return u, traj + + class Config(): - # simulation parameters + """ + simulation parameter class + """ def __init__(self): # robot parameter @@ -29,15 +40,19 @@ class Config(): self.max_dyawrate = 40.0 * math.pi / 180.0 # [rad/ss] self.v_reso = 0.01 # [m/s] self.yawrate_reso = 0.1 * math.pi / 180.0 # [rad/s] - self.dt = 0.1 # [s] + self.dt = 0.1 # [s] Time tick for motion prediction self.predict_time = 3.0 # [s] - self.to_goal_cost_gain = 1.0 + self.to_goal_cost_gain = 0.15 self.speed_cost_gain = 1.0 - self.robot_radius = 1.0 # [m] + self.obstacle_cost_gain = 1.0 + self.robot_radius = 1.0 # [m] for collision check + def motion(x, u, dt): - # motion model + """ + motion model + """ x[2] += u[1] * dt x[0] += u[0] * math.cos(x[2]) * dt @@ -49,6 +64,9 @@ def motion(x, u, dt): def calc_dynamic_window(x, config): + """ + calculation dynamic window based on current state x + """ # Dynamic window from robot specification Vs = [config.min_speed, config.max_speed, @@ -67,9 +85,12 @@ def calc_dynamic_window(x, config): return dw -def calc_trajectory(xinit, v, y, config): +def predict_trajectory(x_init, v, y, config): + """ + predict trajectory with an input + """ - x = np.array(xinit) + x = np.array(x_init) traj = np.array(x) time = 0 while time <= config.predict_time: @@ -81,42 +102,44 @@ def calc_trajectory(xinit, v, y, config): def calc_final_input(x, u, dw, config, goal, ob): + """ + calculation final input with dinamic window + """ - xinit = x[:] - min_cost = 10000.0 - min_u = u - min_u[0] = 0.0 + x_init = x[:] + min_cost = float("inf") + best_u = [0.0, 0.0] best_traj = np.array([x]) # evalucate all trajectory with sampled input in dynamic window for v in np.arange(dw[0], dw[1], config.v_reso): for y in np.arange(dw[2], dw[3], config.yawrate_reso): - traj = calc_trajectory(xinit, v, y, config) + + traj = predict_trajectory(x_init, v, y, config) # calc cost - to_goal_cost = calc_to_goal_cost(traj, goal, config) + to_goal_cost = config.to_goal_cost_gain * calc_to_goal_cost(traj, goal, config) speed_cost = config.speed_cost_gain * \ (config.max_speed - traj[-1, 3]) - ob_cost = calc_obstacle_cost(traj, ob, config) - # print(ob_cost) + ob_cost = config.obstacle_cost_gain*calc_obstacle_cost(traj, ob, config) final_cost = to_goal_cost + speed_cost + ob_cost - #print (final_cost) - # search minimum trajectory if min_cost >= final_cost: min_cost = final_cost - min_u = [v, y] + best_u = [v, y] best_traj = traj - return min_u, best_traj + return best_u, best_traj def calc_obstacle_cost(traj, ob, config): - # calc obstacle cost inf: collistion, 0:free + """ + calc obstacle cost inf: collision + """ - skip_n = 2 + skip_n = 2 # for speed up minr = float("inf") for ii in range(0, len(traj[:, 1]), skip_n): @@ -137,28 +160,18 @@ def calc_obstacle_cost(traj, ob, config): def calc_to_goal_cost(traj, goal, config): - # calc to goal cost. It is 2D norm. + """ + calc to goal cost with angle difference + """ - goal_magnitude = math.sqrt(goal[0]**2 + goal[1]**2) - traj_magnitude = math.sqrt(traj[-1, 0]**2 + traj[-1, 1]**2) - dot_product = (goal[0] * traj[-1, 0]) + (goal[1] * traj[-1, 1]) - error = dot_product / (goal_magnitude * traj_magnitude) - error_angle = math.acos(error) - cost = config.to_goal_cost_gain * error_angle + dx = goal[0] - traj[-1, 0] + dy = goal[1] - traj[-1, 1] + error_angle = math.atan2(dy, dx) + cost = abs(error_angle - traj[-1, 2]) return cost -def dwa_control(x, u, config, goal, ob): - # Dynamic Window control - - dw = calc_dynamic_window(x, config) - - u, traj = calc_final_input(x, u, dw, config, goal, ob) - - return u, traj - - def plot_arrow(x, y, yaw, length=0.5, width=0.1): # pragma: no cover plt.arrow(x, y, length * math.cos(yaw), length * math.sin(yaw), head_length=width, head_width=width) @@ -184,21 +197,20 @@ def main(gx=10, gy=10): [12.0, 12.0] ]) + # input [forward speed, yawrate] u = np.array([0.0, 0.0]) config = Config() traj = np.array(x) - for i in range(1000): - u, ltraj = dwa_control(x, u, config, goal, ob) + while True: + u, ptraj = dwa_control(x, u, config, goal, ob) - x = motion(x, u, config.dt) + x = motion(x, u, config.dt) # simulate robot traj = np.vstack((traj, x)) # store state history - # print(traj) - if show_animation: plt.cla() - plt.plot(ltraj[:, 0], ltraj[:, 1], "-g") + plt.plot(ptraj[:, 0], ptraj[:, 1], "-g") plt.plot(x[0], x[1], "xr") plt.plot(goal[0], goal[1], "xb") plt.plot(ob[:, 0], ob[:, 1], "ok") @@ -207,8 +219,9 @@ def main(gx=10, gy=10): plt.grid(True) plt.pause(0.0001) - # check goal - if math.sqrt((x[0] - goal[0])**2 + (x[1] - goal[1])**2) <= config.robot_radius: + # check reaching goal + dist_to_goal = math.sqrt((x[0] - goal[0])**2 + (x[1] - goal[1])**2) + if dist_to_goal <= config.robot_radius: print("Goal!!") break diff --git a/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py b/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py index d42592a0..351232d8 100644 --- a/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py +++ b/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py @@ -161,12 +161,18 @@ def generate_roadmap(sample_x, sample_y, rr, obkdtree): def dijkstra_planning(sx, sy, gx, gy, ox, oy, rr, road_map, sample_x, sample_y): """ + sx: start x position [m] + sy: start y position [m] gx: goal x position [m] - gx: goal x position [m] + gy: goal y position [m] ox: x position list of Obstacles [m] oy: y position list of Obstacles [m] - reso: grid resolution [m] - rr: robot radius[m] + rr: robot radius [m] + road_map: ??? [m] + sample_x: ??? [m] + sample_y: ??? [m] + + @return: Two lists of path coordinates ([x1, x2, ...], [y1, y2, ...]), empty list when no path was found """ nstart = Node(sx, sy, 0.0, -1) @@ -175,9 +181,12 @@ def dijkstra_planning(sx, sy, gx, gy, ox, oy, rr, road_map, sample_x, sample_y): openset, closedset = dict(), dict() openset[len(road_map) - 2] = nstart + path_found = True + while True: if not openset: print("Cannot find path") + path_found = False break c_id = min(openset, key=lambda o: openset[o].cost) @@ -217,6 +226,9 @@ def dijkstra_planning(sx, sy, gx, gy, ox, oy, rr, road_map, sample_x, sample_y): openset[n_id].pind = c_id else: openset[n_id] = node + + if path_found is False: + return [], [] # generate final course rx, ry = [ngoal.x], [ngoal.y] @@ -249,8 +261,8 @@ def sample_points(sx, sy, gx, gy, rr, ox, oy, obkdtree): sample_x, sample_y = [], [] while len(sample_x) <= N_SAMPLE: - tx = (random.random() - minx) * (maxx - minx) - ty = (random.random() - miny) * (maxy - miny) + tx = (random.random() * (maxx - minx)) + minx + ty = (random.random() * (maxy - miny)) + miny index, dist = obkdtree.search(np.array([tx, ty]).reshape(2, 1)) diff --git a/PathTracking/pure_pursuit/pure_pursuit.py b/PathTracking/pure_pursuit/pure_pursuit.py index af953e30..38a84aff 100644 --- a/PathTracking/pure_pursuit/pure_pursuit.py +++ b/PathTracking/pure_pursuit/pure_pursuit.py @@ -9,13 +9,15 @@ import numpy as np import math import matplotlib.pyplot as plt + k = 0.1 # look forward gain -Lfc = 1.0 # look-ahead distance +Lfc = 2.0 # look-ahead distance Kp = 1.0 # speed proportional gain dt = 0.1 # [s] L = 2.9 # [m] wheel base of vehicle +old_nearest_point_index = None show_animation = True @@ -26,6 +28,8 @@ class State: self.y = y self.yaw = yaw self.v = v + self.rear_x = self.x - ((L / 2) * math.cos(self.yaw)) + self.rear_y = self.y - ((L / 2) * math.sin(self.yaw)) def update(state, a, delta): @@ -34,6 +38,8 @@ def update(state, a, delta): state.y = state.y + state.v * math.sin(state.yaw) * dt state.yaw = state.yaw + state.v / L * math.tan(delta) * dt state.v = state.v + a * dt + state.rear_x = state.x - ((L / 2) * math.cos(state.yaw)) + state.rear_y = state.y - ((L / 2) * math.sin(state.yaw)) return state @@ -59,7 +65,7 @@ def pure_pursuit_control(state, cx, cy, pind): ty = cy[-1] ind = len(cx) - 1 - alpha = math.atan2(ty - state.y, tx - state.x) - state.yaw + alpha = math.atan2(ty - state.rear_y, tx - state.rear_x) - state.yaw Lf = k * state.v + Lfc @@ -67,22 +73,43 @@ def pure_pursuit_control(state, cx, cy, pind): return delta, ind +def calc_distance(state, point_x, point_y): + + dx = state.rear_x - point_x + dy = state.rear_y - point_y + return math.sqrt(dx ** 2 + dy ** 2) + def calc_target_index(state, cx, cy): - # search nearest point index - dx = [state.x - icx for icx in cx] - dy = [state.y - icy for icy in cy] - d = [abs(math.sqrt(idx ** 2 + idy ** 2)) for (idx, idy) in zip(dx, dy)] - ind = d.index(min(d)) + global old_nearest_point_index + + if old_nearest_point_index is None: + # search nearest point index + dx = [state.rear_x - icx for icx in cx] + dy = [state.rear_y - icy for icy in cy] + d = [abs(math.sqrt(idx ** 2 + idy ** 2)) for (idx, idy) in zip(dx, dy)] + ind = d.index(min(d)) + old_nearest_point_index = ind + else: + ind = old_nearest_point_index + distance_this_index = calc_distance(state, cx[ind], cy[ind]) + while True: + ind = ind + 1 if (ind + 1) < len(cx) else ind + distance_next_index = calc_distance(state, cx[ind], cy[ind]) + if distance_this_index < distance_next_index: + break + distance_this_index = distance_next_index + old_nearest_point_index = ind + L = 0.0 Lf = k * state.v + Lfc # search look ahead target point index while Lf > L and (ind + 1) < len(cx): - dx = cx[ind] - state.x - dy = cy[ind] - state.y + dx = cx[ind] - state.rear_x + dy = cy[ind] - state.rear_y L = math.sqrt(dx ** 2 + dy ** 2) ind += 1 diff --git a/README.md b/README.md index d0f840f4..0aa7220d 100644 --- a/README.md +++ b/README.md @@ -14,6 +14,7 @@ Python codes for robotics algorithm. + # Table of Contents * [What is this?](#what-is-this) * [Requirements](#requirements) @@ -26,12 +27,13 @@ Python codes for robotics algorithm. * [Mapping](#mapping) * [Gaussian grid map](#gaussian-grid-map) * [Ray casting grid map](#ray-casting-grid-map) + * [Lidar to grid map](#lidar-to-grid-map) * [k-means object clustering](#k-means-object-clustering) * [Rectangle fitting](#rectangle-fitting) * [SLAM](#slam) * [Iterative Closest Point (ICP) Matching](#iterative-closest-point-icp-matching) * [FastSLAM 1.0](#fastslam-10) - * [Graph based SLAM](#graph-based-slam) + * [Pose Optimization SLAM](#pose-optimization-slam) * [Path Planning](#path-planning) * [Dynamic Window Approach](#dynamic-window-approach) * [Grid based search](#grid-based-search) @@ -191,6 +193,12 @@ This is a 2D ray casting grid mapping example. ![2](https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Mapping/raycasting_grid_map/animation.gif) +## Lidar to grid map + +This example shows how to convert a 2D range measurement to a grid map. + +![2](Mapping/lidar_to_grid_map/animation.gif) + ## k-means object clustering This is a 2D object clustering with k-means algorithm. @@ -242,24 +250,11 @@ Ref: - [SLAM simulations by Tim Bailey](http://www-personal.acfr.usyd.edu.au/tbailey/software/slam_simulations.htm) -## Graph based SLAM +## Pose Optimization SLAM -This is a graph based SLAM example. - -The blue line is ground truth. - -The black line is dead reckoning. - -The red line is the estimated trajectory with Graph based SLAM. - -The black stars are landmarks for graph edge generation. - -![3](https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/GraphBasedSLAM/animation.gif) - -Ref: - -- [A Tutorial on Graph-Based SLAM](http://www2.informatik.uni-freiburg.de/~stachnis/pdf/grisetti10titsmag.pdf) +This is a graph based pose optimization SLAM example. +![3](https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/PoseOptimizationSLAM/animation.gif) # Path Planning @@ -557,7 +552,11 @@ MIT # Use-case -See: [users\_comments](https://github.com/AtsushiSakai/PythonRobotics/blob/master/users_comments.md) +If this project helps your robotics project, please let me know with [![Say Thanks!](https://img.shields.io/badge/Say%20Thanks-!-1EAEDB.svg)](https://saythanks.io/to/AtsushiSakai). + +Your robot's video, which is using PythonRobotics, is very welcome!! + +This is a list of other user's comment and references:[users\_comments](https://github.com/AtsushiSakai/PythonRobotics/blob/master/users_comments.md) # Contribution @@ -609,3 +608,4 @@ This is a list: [Users comments](https://github.com/AtsushiSakai/PythonRobotics/ + diff --git a/SLAM/PoseOptimizationSLAM/README.md b/SLAM/PoseOptimizationSLAM/README.md new file mode 100644 index 00000000..612fa518 --- /dev/null +++ b/SLAM/PoseOptimizationSLAM/README.md @@ -0,0 +1,9 @@ +# How to use + +1. Download data + +>$ python data_downloader.py + +2. run SLAM + +>$ python pose_optimization_slam.py diff --git a/SLAM/PoseOptimizationSLAM/data_downloader.py b/SLAM/PoseOptimizationSLAM/data_downloader.py new file mode 100644 index 00000000..d1b8a2c2 --- /dev/null +++ b/SLAM/PoseOptimizationSLAM/data_downloader.py @@ -0,0 +1,28 @@ +""" + +Data down loader for pose optimization + +author: Atsushi Sakai + +""" + + +import subprocess +def main(): + print("start!!") + + cmd = "wget https://www.dropbox.com/s/vcz8cag7bo0zlaj/input_INTEL_g2o.g2o?dl=0 -O intel.g2o -nc" + subprocess.call(cmd, shell=True) + + cmd = "wget https://www.dropbox.com/s/d8fcn1jg1mebx8f/input_MITb_g2o.g2o?dl=0 -O mit_killian.g2o -nc" + + subprocess.call(cmd, shell=True) + cmd = "wget https://www.dropbox.com/s/gmdzo74b3tzvbrw/input_M3500_g2o.g2o?dl=0 -O manhattan3500.g2o -nc" + subprocess.call(cmd, shell=True) + + print("done!!") + + +if __name__ == '__main__': + main() + diff --git a/SLAM/PoseOptimizationSLAM/pose_optimization_slam.py b/SLAM/PoseOptimizationSLAM/pose_optimization_slam.py new file mode 100644 index 00000000..764b0f5e --- /dev/null +++ b/SLAM/PoseOptimizationSLAM/pose_optimization_slam.py @@ -0,0 +1,290 @@ +""" + +2D (x, y, yaw) pose optimization SLAM + +author: Atsushi Sakai + +Ref: +- [A Compact and Portable Implementation of Graph\-based SLAM](https://www.researchgate.net/publication/321287640_A_Compact_and_Portable_Implementation_of_Graph-based_SLAM) + +- [GitHub \- furo\-org/p2o: Single header 2D/3D graph\-based SLAM library](https://github.com/furo-org/p2o) + +""" + +import sys +import time +import math +import numpy as np +import matplotlib.pyplot as plt +from scipy import sparse +from scipy.sparse import linalg + + +class Optimizer2D: + + def __init__(self): + self.verbose = False + self.animation = False + self.p_lambda = 0.0 + self.init_w = 1e10 + self.stop_thre = 1e-3 + self.dim = 3 # state dimension + + def optimize_path(self, nodes, consts, max_iter, min_iter): + + graph_nodes = nodes[:] + prev_cost = sys.float_info.max + + for i in range(max_iter): + start = time.time() + cost, graph_nodes = self.optimize_path_one_step( + graph_nodes, consts) + elapsed = time.time() - start + if self.verbose: + print("step ", i, " cost: ", cost, " time:", elapsed, "s") + + # check convergence + if (i > min_iter) and (prev_cost - cost < self.stop_thre): + if self.verbose: + print("converged:", prev_cost + - cost, " < ", self.stop_thre) + break + prev_cost = cost + + if self.animation: + plt.cla() + plot_nodes(nodes, color="-b") + plot_nodes(graph_nodes) + plt.axis("equal") + plt.pause(1.0) + + return graph_nodes + + def optimize_path_one_step(self, graph_nodes, constraints): + + indlist = [i for i in range(self.dim)] + numnodes = len(graph_nodes) + bf = np.zeros(numnodes * self.dim) + tripletList = TripletList() + + for con in constraints: + ida = con.id1 + idb = con.id2 + assert 0 <= ida and ida < numnodes, "ida is invalid" + assert 0 <= idb and idb < numnodes, "idb is invalid" + r, Ja, Jb = self.calc_error( + graph_nodes[ida], graph_nodes[idb], con.t) + + trJaInfo = Ja.transpose() @ con.info_mat + trJaInfoJa = trJaInfo @ Ja + trJbInfo = Jb.transpose() @ con.info_mat + trJbInfoJb = trJbInfo @ Jb + trJaInfoJb = trJaInfo @ Jb + + for k in indlist: + for m in indlist: + tripletList.push_back( + ida * self.dim + k, ida * self.dim + m, trJaInfoJa[k, m]) + tripletList.push_back( + idb * self.dim + k, idb * self.dim + m, trJbInfoJb[k, m]) + tripletList.push_back( + ida * self.dim + k, idb * self.dim + m, trJaInfoJb[k, m]) + tripletList.push_back( + idb * self.dim + k, ida * self.dim + m, trJaInfoJb[m, k]) + + bf[ida * self.dim: ida * self.dim + 3] += trJaInfo @ r + bf[idb * self.dim: idb * self.dim + 3] += trJbInfo @ r + + for k in indlist: + tripletList.push_back(k, k, self.init_w) + + for i in range(self.dim * numnodes): + tripletList.push_back(i, i, self.p_lambda) + + mat = sparse.coo_matrix((tripletList.data, (tripletList.row, tripletList.col)), + shape=(numnodes * self.dim, numnodes * self.dim)) + + x = linalg.spsolve(mat.tocsr(), -bf) + + out_nodes = [] + for i in range(len(graph_nodes)): + u_i = i * self.dim + pos = Pose2D( + graph_nodes[i].x + x[u_i], + graph_nodes[i].y + x[u_i + 1], + graph_nodes[i].theta + x[u_i + 2] + ) + out_nodes.append(pos) + + cost = self.calc_global_cost(out_nodes, constraints) + + return cost, out_nodes + + def calc_global_cost(self, nodes, constraints): + cost = 0.0 + for c in constraints: + diff = self.error_func(nodes[c.id1], nodes[c.id2], c.t) + cost += diff.transpose() @ c.info_mat @ diff + + return cost + + def error_func(self, pa, pb, t): + ba = self.calc_constraint_pose(pb, pa) + error = np.array([ba.x - t.x, + ba.y - t.y, + self.pi2pi(ba.theta - t.theta)]) + return error + + def calc_constraint_pose(self, l, r): + diff = np.array([l.x - r.x, l.y - r.y, l.theta - r.theta]) + v = self.rot_mat_2d(-r.theta) @ diff + v[2] = self.pi2pi(l.theta - r.theta) + return Pose2D(v[0], v[1], v[2]) + + def rot_mat_2d(self, theta): + return np.array([[math.cos(theta), -math.sin(theta), 0.0], + [math.sin(theta), math.cos(theta), 0.0], + [0.0, 0.0, 1.0] + ]) + + def calc_error(self, pa, pb, t): + e0 = self.error_func(pa, pb, t) + dx = pb.x - pa.x + dy = pb.y - pa.y + dxdt = -math.sin(pa.theta) * dx + math.cos(pa.theta) * dy + dydt = -math.cos(pa.theta) * dx - math.sin(pa.theta) * dy + Ja = np.array([[-math.cos(pa.theta), -math.sin(pa.theta), dxdt], + [math.sin(pa.theta), -math.cos(pa.theta), dydt], + [0.0, 0.0, -1.0] + ]) + Jb = np.array([[math.cos(pa.theta), math.sin(pa.theta), 0.0], + [-math.sin(pa.theta), math.cos(pa.theta), 0.0], + [0.0, 0.0, 1.0] + ]) + return e0, Ja, Jb + + def pi2pi(self, rad): + + val = math.fmod(rad, 2.0 * math.pi) + if val > math.pi: + val -= 2.0 * math.pi + elif val < -math.pi: + val += 2.0 * math.pi + + return val + + +class TripletList: + + def __init__(self): + self.row = [] + self.col = [] + self.data = [] + + def push_back(self, irow, icol, idata): + self.row.append(irow) + self.col.append(icol) + self.data.append(idata) + + +class Pose2D: + + def __init__(self, x, y, theta): + self.x = x + self.y = y + self.theta = theta + + +class Constrant2D: + + def __init__(self, id1, id2, t, info_mat): + self.id1 = id1 + self.id2 = id2 + self.t = t + self.info_mat = info_mat + + +def plot_nodes(nodes, color ="-r", label = ""): + x, y = [], [] + for n in nodes: + x.append(n.x) + y.append(n.y) + plt.plot(x, y, color, label=label) + + +def load_data(fname): + nodes, consts = [], [] + + for line in open(fname): + sline = line.split() + tag = sline[0] + + if tag == "VERTEX_SE2": + data_id = int(sline[1]) + x = float(sline[2]) + y = float(sline[3]) + theta = float(sline[4]) + nodes.append(Pose2D(x, y, theta)) + elif tag == "EDGE_SE2": + id1 = int(sline[1]) + id2 = int(sline[2]) + x = float(sline[3]) + y = float(sline[4]) + th = float(sline[5]) + c1 = float(sline[6]) + c2 = float(sline[7]) + c3 = float(sline[8]) + c4 = float(sline[9]) + c5 = float(sline[10]) + c6 = float(sline[11]) + t = Pose2D(x, y, th) + info_mat = np.array([[c1, c2, c3], + [c2, c4, c5], + [c3, c5, c6] + ]) + consts.append(Constrant2D(id1, id2, t, info_mat)) + + print("n_nodes:", len(nodes)) + print("n_consts:", len(consts)) + + return nodes, consts + + +def main(): + print("start!!") + + fnames = ["intel.g2o", + "manhattan3500.g2o", + "mit_killian.g2o" + ] + + max_iter = 20 + min_iter = 3 + + # parameter setting + optimizer = Optimizer2D() + optimizer.p_lambda = 1e-6 + optimizer.verbose = True + optimizer.animation = True + + for f in fnames: + nodes, consts = load_data(f) + + start = time.time() + final_nodes = optimizer.optimize_path(nodes, consts, max_iter, min_iter) + print("elapsed_time", time.time() - start, "sec") + + # plotting + plt.cla() + plot_nodes(nodes, color="-b", label="before") + plot_nodes(final_nodes, label="after") + plt.axis("equal") + plt.grid(True) + plt.legend() + plt.pause(3.0) + + print("done!!") + + +if __name__ == '__main__': + main() diff --git a/users_comments.md b/users_comments.md index 0f38aef3..cf91cd13 100644 --- a/users_comments.md +++ b/users_comments.md @@ -13,6 +13,13 @@ You can check stargazer's locations of this project from: - [Stargazers location map](https://drive.google.com/open?id=1bBXS9IQmZ3Tfe1wNGvJbObRt9Htt4PGC&usp=sharing) + +# Related projects + +This is a list of related projects. + +- [onlytailei/CppRobotics: cpp implementation of robotics algorithms including localization, mapping, SLAM, path planning and control](https://github.com/onlytailei/CppRobotics) + # Individual users comments These are comments from user's using [![Say Thanks!](https://img.shields.io/badge/Say%20Thanks-!-1EAEDB.svg)](https://saythanks.io/to/AtsushiSakai) @@ -196,6 +203,42 @@ Dear AtsushiSakai,
Thank you for this great resource! I very much appreciate --Mridul Aanjaneya +--- + +Thank you for the python robotics sample code and visualizations!! This is my new favorite thing on the internet. + +--selamg@mit.edu + +--- + +Mr AtsushiSakai ..
Your work and teaching is light for me
thank you very much for giving time and effort to make it public for us + +--Karim Anass + +--- + +Thank You + +--Anonymous + +--- + +I've learned the robotics from the traditional way of solving problem through finding packages and reading papers. This amazing project is unbelievably helpful for new-comers to learn and get familiar with the algorithms. Gods know how many hours you've taken to sort all the materials and written everything into one single coherent project. I'm truly amazed and deepest appreciation. + +--Ewing Kang + +--- + +Hey, I'm a student and I just recently got into robotics, and visited your repository multiple times. Today I was super happy to find the link to Patreon! I am impressed by didactic quality of the repo, keep up the good work! + +--Carolina Bianchi + +--- + +Dear AtsushiSakai, thanks a lot for the PythonRobotics git repository. I'm a college student who is trying to make a mini autonomous robot for my final project submission, I still haven't started using your code but by the look of it I'm sure it will be of greater use. Will let you know how my project is coming up. + +--Pragdheesh + ========= # Citations @@ -212,3 +255,5 @@ URL: http://ieeexplore.ieee.org/stamp/stamp.jsp?tp=&arnumber=8516589&isnumber=85 - Autonomous Vehicle Readings https://richardkelley.io/readings +- 36 Amazing Python Open Source Projects (v.2019) – Mybridge for Professionals https://medium.mybridge.co/36-amazing-python-open-source-projects-v-2019-2fe058d79450 +