From 9c26f5ec7b8c1fc19d5bcbf19172e447b9e7ecff Mon Sep 17 00:00:00 2001 From: Vehicle Researcher Date: Tue, 23 Apr 2019 01:41:19 +0000 Subject: [PATCH] openpilot v0.5.11 release --- README.md | 4 +- RELEASES.md | 18 +- SAFETY.md | 13 + common/dbc.py | 21 +- common/ffi_wrapper.py | 6 +- common/transformations/camera.py | 68 +- common/transformations/model.py | 2 +- launch_chffrplus.sh | 2 + models/monitoring_model.dlc | Bin 427951 -> 428211 bytes requirements_openpilot.txt | 3 +- selfdrive/boardd/boardd.py | 4 +- selfdrive/can/Makefile | 56 +- selfdrive/can/packer.py | 2 +- selfdrive/can/parser.py | 10 +- selfdrive/can/plant_can_parser.py | 8 +- selfdrive/can/process_dbc.py | 117 ++-- selfdrive/car/chrysler/chryslercan.py | 6 - selfdrive/car/chrysler/chryslercan_test.py | 6 - selfdrive/car/chrysler/interface.py | 2 +- selfdrive/car/chrysler/radar_interface.py | 2 +- selfdrive/car/ford/radar_interface.py | 2 +- selfdrive/car/gm/radar_interface.py | 2 +- selfdrive/car/honda/carcontroller.py | 2 +- selfdrive/car/honda/interface.py | 4 +- selfdrive/car/honda/radar_interface.py | 2 +- selfdrive/car/honda/values.py | 5 +- selfdrive/car/hyundai/interface.py | 4 +- selfdrive/car/hyundai/radar_interface.py | 2 +- selfdrive/car/mock/radar_interface.py | 3 +- selfdrive/car/subaru/carcontroller.py | 76 +++ selfdrive/car/subaru/carstate.py | 51 +- selfdrive/car/subaru/interface.py | 42 +- selfdrive/car/subaru/radar_interface.py | 2 +- selfdrive/car/subaru/subarucan.py | 54 ++ selfdrive/car/toyota/carcontroller.py | 4 +- selfdrive/car/toyota/values.py | 10 +- selfdrive/common/touch.c | 28 + selfdrive/common/touch.h | 1 + selfdrive/common/version.h | 2 +- selfdrive/common/visionimg.cc | 18 +- selfdrive/common/visionimg.h | 5 +- selfdrive/controls/controlsd.py | 11 +- selfdrive/controls/lib/driver_monitor.py | 68 +- selfdrive/controls/lib/pathplanner.py | 8 +- selfdrive/debug/can_printer.py | 2 +- selfdrive/debug/cpu_usage_stat.py | 99 +++ selfdrive/debug/dump.py | 14 +- selfdrive/debug/get_fingerprint.py | 4 +- selfdrive/debug/getframes/getframes.py | 2 +- selfdrive/locationd/Makefile | 86 +++ selfdrive/locationd/calibrationd.py | 9 +- selfdrive/locationd/kalman/ekf_sym.py | 4 +- selfdrive/locationd/locationd_local.py | 25 +- selfdrive/locationd/test/__init__.py | 0 selfdrive/locationd/test/ci_test.py | 82 +++ selfdrive/locationd/{ => test}/ephemeris.py | 0 selfdrive/locationd/{ => test}/ublox.py | 0 selfdrive/locationd/{ => test}/ubloxd.py | 0 selfdrive/locationd/test/ubloxd_easy.py | 55 ++ selfdrive/locationd/test/ubloxd_py_test.py | 77 +++ .../locationd/test/ubloxd_regression_test.py | 96 +++ selfdrive/locationd/ublox_msg.cc | 375 +++++++++++ selfdrive/locationd/ublox_msg.h | 149 +++++ selfdrive/locationd/ubloxd.cc | 45 ++ selfdrive/locationd/ubloxd_main.cc | 113 ++++ selfdrive/locationd/ubloxd_test.cc | 103 +++ selfdrive/loggerd/loggerd | Bin 1630952 -> 1630952 bytes selfdrive/manager.py | 2 +- selfdrive/mapd/mapd.py | 2 +- selfdrive/orbd/.gitignore | 8 - selfdrive/orbd/Makefile | 105 --- selfdrive/orbd/dsp/freethedsp.c | 119 ---- selfdrive/orbd/dsp/gen/calculator.h | 39 -- selfdrive/orbd/dsp/gen/calculator_stub.c | 613 ------------------ selfdrive/orbd/dsp/gen/libcalculator_skel.so | Bin 357400 -> 0 bytes selfdrive/orbd/extractor.h | 38 -- selfdrive/orbd/orbd.cc | 191 ------ selfdrive/orbd/orbd_wrapper.sh | 13 - selfdrive/sensord/gpsd | Bin 1171544 -> 1171544 bytes selfdrive/sensord/sensord | Bin 1159016 -> 1159016 bytes selfdrive/swaglog.py | 2 +- selfdrive/test/plant/maneuver.py | 16 +- selfdrive/test/plant/plant.py | 2 +- selfdrive/test/plant/plant_ui.py | 6 +- selfdrive/test/test_fingerprints.py | 18 +- selfdrive/test/test_openpilot.py | 10 +- selfdrive/thermald.py | 10 +- selfdrive/tombstoned.py | 66 +- selfdrive/ui/Makefile | 4 +- selfdrive/ui/ui.c | 525 ++++++++++----- selfdrive/visiond/build_from_src.mk | 16 +- selfdrive/visiond/monitoring.cc | 2 +- selfdrive/visiond/monitoring.h | 4 +- selfdrive/visiond/rgb_to_yuv.c | 53 ++ selfdrive/visiond/rgb_to_yuv.cl | 127 ++++ selfdrive/visiond/rgb_to_yuv.h | 32 + selfdrive/visiond/rgb_to_yuv_test.cc | 201 ++++++ selfdrive/visiond/visiond.cc | 31 +- 98 files changed, 2744 insertions(+), 1607 deletions(-) create mode 100644 selfdrive/car/subaru/carcontroller.py create mode 100644 selfdrive/car/subaru/subarucan.py create mode 100644 selfdrive/debug/cpu_usage_stat.py create mode 100644 selfdrive/locationd/Makefile create mode 100644 selfdrive/locationd/test/__init__.py create mode 100755 selfdrive/locationd/test/ci_test.py rename selfdrive/locationd/{ => test}/ephemeris.py (100%) rename selfdrive/locationd/{ => test}/ublox.py (100%) rename selfdrive/locationd/{ => test}/ubloxd.py (100%) create mode 100755 selfdrive/locationd/test/ubloxd_easy.py create mode 100755 selfdrive/locationd/test/ubloxd_py_test.py create mode 100644 selfdrive/locationd/test/ubloxd_regression_test.py create mode 100644 selfdrive/locationd/ublox_msg.cc create mode 100644 selfdrive/locationd/ublox_msg.h create mode 100644 selfdrive/locationd/ubloxd.cc create mode 100644 selfdrive/locationd/ubloxd_main.cc create mode 100644 selfdrive/locationd/ubloxd_test.cc delete mode 100644 selfdrive/orbd/.gitignore delete mode 100644 selfdrive/orbd/Makefile delete mode 100644 selfdrive/orbd/dsp/freethedsp.c delete mode 100644 selfdrive/orbd/dsp/gen/calculator.h delete mode 100644 selfdrive/orbd/dsp/gen/calculator_stub.c delete mode 100755 selfdrive/orbd/dsp/gen/libcalculator_skel.so delete mode 100644 selfdrive/orbd/extractor.h delete mode 100644 selfdrive/orbd/orbd.cc delete mode 100755 selfdrive/orbd/orbd_wrapper.sh create mode 100644 selfdrive/visiond/rgb_to_yuv.c create mode 100644 selfdrive/visiond/rgb_to_yuv.cl create mode 100644 selfdrive/visiond/rgb_to_yuv.h create mode 100644 selfdrive/visiond/rgb_to_yuv_test.cc diff --git a/README.md b/README.md index a82b98dbc..902781b89 100644 --- a/README.md +++ b/README.md @@ -79,6 +79,7 @@ Supported Cars | Honda | CR-V 2017-18 | Honda Sensing | Yes | Stock | 0mph | 12mph | Bosch | | Honda | CR-V Hybrid 2019 | All | Yes | Stock | 0mph | 12mph | Bosch | | Honda | Odyssey 2017-19 | Honda Sensing | Yes | Yes | 25mph1| 0mph | Inverted Nidec | +| Honda | Passport 2019 | All | Yes | Yes | 25mph1| 12mph | Inverted Nidec | | Honda | Pilot 2016-18 | Honda Sensing | Yes | Yes | 25mph1| 12mph | Nidec | | Honda | Pilot 2019 | All | Yes | Yes | 25mph1| 12mph | Inverted Nidec | | Honda | Ridgeline 2017-19 | Honda Sensing | Yes | Yes | 25mph1| 12mph | Nidec | @@ -90,7 +91,8 @@ Supported Cars | Kia | Optima 2019 | SCC + LKAS | Yes | Stock | 0mph | 0mph | Custom6| | Kia | Sorento 2018 | All | Yes | Stock | 0mph | 0mph | Custom6| | Kia | Stinger 2018 | SCC + LKAS | Yes | Stock | 0mph | 0mph | Custom6| -| Lexus | RX Hybrid 2016-18 | All | Yes | Yes2| 0mph | 0mph | Toyota | +| Lexus | RX Hybrid 2016-19 | All | Yes | Yes2| 0mph | 0mph | Toyota | +| Subaru | Impreza 2019 | EyeSight | Yes | Stock | 0mph | 0mph | Subaru | | Toyota | Camry 20184 | All | Yes | Stock | 0mph5 | 0mph | Toyota | | Toyota | C-HR 2017-184 | All | Yes | Stock | 0mph | 0mph | Toyota | | Toyota | Corolla 2017-18 | All | Yes | Yes2| 20mph1| 0mph | Toyota | diff --git a/RELEASES.md b/RELEASES.md index 48e3b647d..61d905ce2 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,13 +1,25 @@ +Version 0.5.11 (2019-04-17) +======================== + * Add support for Subaru + * Reduce panda power consumption by 60% when car is off + * Fix controlsd lag every 6 minutes. This would sometimes cause disengagements + * Fix bug in controls with new angle-offset learner in MPC + * Reduce cpu consumption of ubloxd by rewriting it in C++ + * Improve driver monitoring model and face detection + * Improve performance of visiond and ui + * Honda Passport 2019 support + * Lexus RX Hybrid 2019 support thanks to schomems! + Version 0.5.10 (2019-03-19) ======================== - * Self-tuning vehicle parameters: steering offset, tires stiffness and steering ratio + * Self-tuning vehicle parameters: steering offset, tire stiffness and steering ratio * Improve longitudinal control at low speed when lead vehicle harshly decelerates * Fix panda bug going unexpectedly in DCP mode when EON is connected * Reduce white panda power consumption by 500mW when EON is disconnected by turning off WIFI * New Driver Monitoring Model * Support QR codes for login using comma connect - * Refactor comma pedal FW and use CRC-8 checksum algorithm for safety. Reflashing pedal is required. - Please see `#hw-pedal` on [discord](discord.comma.ai) for assistance updating comma pedal. + * Refactor comma pedal FW and use CRC-8 checksum algorithm for safety. Reflashing pedal is required. + Please see `#hw-pedal` on [discord](discord.comma.ai) for assistance updating comma pedal. * Additional speed limit rules for Germany thanks to arne182 * Allow negative speed limit offsets diff --git a/SAFETY.md b/SAFETY.md index b5800a0d5..3cda811e0 100644 --- a/SAFETY.md +++ b/SAFETY.md @@ -133,6 +133,19 @@ Chrysler/Jeep/Fiat (Lateral only) units above the actual EPS generated motor torque to ensure limited differences between commanded and actual torques. +Subaru (Lateral only) +------ + + - While the system is engaged, steer commands are subject to the same limits used by + the stock system. + + - Steering torque is controlled through the 0x122 CAN message and it's limited by the panda firmware and by + openpilot to a value between -255 and 255. In addition, the vehicle EPS unit will fault for + commands outside the values of -2047 and 2047. A steering torque rate limit is enforced by the panda firmware and by + openpilot, so that the commanded steering torque must rise from 0 to max value no faster than + 0.41s. Commanded steering torque is gradually limited by the panda firmware and by openpilot if the driver's + torque exceeds 60 units in the opposite dicrection to ensure limited applied torque against the + driver's will. **Extra note**: comma.ai strongly discourages the use of openpilot forks with safety code either missing or not fully meeting the above requirements. diff --git a/common/dbc.py b/common/dbc.py index 6accad43f..4acfc84ad 100755 --- a/common/dbc.py +++ b/common/dbc.py @@ -7,9 +7,9 @@ from collections import namedtuple, defaultdict def int_or_float(s): # return number, trying to maintain int format - try: - return int(s) - except ValueError: + if s.isdigit(): + return int(s, 10) + else: return float(s) DBCSignal = namedtuple( @@ -21,7 +21,7 @@ class dbc(object): def __init__(self, fn): self.name, _ = os.path.splitext(os.path.basename(fn)) with open(fn) as f: - self.txt = f.read().split("\n") + self.txt = f.readlines() self._warned_addresses = set() # regexps from https://github.com/ebroecker/canmatrix/blob/master/canmatrix/importdbc.py @@ -51,7 +51,8 @@ class dbc(object): dat = bo_regexp.match(l) if dat is None: - print "bad BO", l + print("bad BO {0}".format(l)) + name = dat.group(2) size = int(dat.group(3)) ids = int(dat.group(1), 0) # could be hex @@ -67,8 +68,9 @@ class dbc(object): if dat is None: dat = sgm_regexp.match(l) go = 1 + if dat is None: - print "bad SG", l + print("bad SG {0}".format(l)) sgname = dat.group(1) start_bit = int(dat.group(go+2)) @@ -90,7 +92,8 @@ class dbc(object): dat = val_regexp.match(l) if dat is None: - print "bad VAL", l + print("bad VAL {0}".format(l)) + ids = int(dat.group(1), 0) # could be hex sgname = dat.group(2) defvals = dat.group(3) @@ -208,7 +211,7 @@ class dbc(object): name = msg[0][0] if debug: - print name + print(name) st = x[2].ljust(8, '\x00') le, be = None, None @@ -252,7 +255,7 @@ class dbc(object): tmp = tmp * factor + offset # if debug: - # print "%40s %2d %2d %7.2f %s" % (s[0], s[1], s[2], tmp, s[-1]) + # print("%40s %2d %2d %7.2f %s" % (s[0], s[1], s[2], tmp, s[-1])) if arr is None: out[s[0]] = tmp diff --git a/common/ffi_wrapper.py b/common/ffi_wrapper.py index fd6b2bf7b..f41115d1c 100644 --- a/common/ffi_wrapper.py +++ b/common/ffi_wrapper.py @@ -4,10 +4,8 @@ import fcntl import hashlib from cffi import FFI -TMPDIR = "/tmp/ccache" - -def ffi_wrap(name, c_code, c_header, tmpdir=TMPDIR, cflags="", libraries=None): +def ffi_wrap(name, c_code, c_header, tmpdir="/tmp/ccache", cflags="", libraries=None): if libraries is None: libraries = [] @@ -24,7 +22,7 @@ def ffi_wrap(name, c_code, c_header, tmpdir=TMPDIR, cflags="", libraries=None): try: mod = __import__(cache) except Exception: - print "cache miss", cache + print("cache miss {0}".format(cache)) compile_code(cache, c_code, c_header, tmpdir, cflags, libraries) mod = __import__(cache) finally: diff --git a/common/transformations/camera.py b/common/transformations/camera.py index 367c0879a..eafd71c98 100644 --- a/common/transformations/camera.py +++ b/common/transformations/camera.py @@ -1,6 +1,7 @@ import numpy as np import common.transformations.orientation as orient import cv2 +import math FULL_FRAME_SIZE = (1164, 874) W, H = FULL_FRAME_SIZE[0], FULL_FRAME_SIZE[1] @@ -12,6 +13,17 @@ eon_intrinsics = np.array([ [ 0., FOCAL, H/2.], [ 0., 0., 1.]]) + +leon_dcam_intrinsics = np.array([ + [650, 0, 816/2], + [ 0, 650, 612/2], + [ 0, 0, 1]]) + +eon_dcam_intrinsics = np.array([ + [860, 0, 1152/2], + [ 0, 860, 864/2], + [ 0, 0, 1]]) + # aka 'K_inv' aka view_frame_from_camera_frame eon_intrinsics_inv = np.linalg.inv(eon_intrinsics) @@ -147,28 +159,44 @@ def transform_img(base_img, from_intr=eon_intrinsics, to_intr=eon_intrinsics, calib_rot_view=None, - output_size=None): - cy = from_intr[1,2] + output_size=None, + pretransform=None, + top_hacks=True): size = base_img.shape[:2] if not output_size: output_size = size[::-1] - h = 1.22 - quadrangle = np.array([[0, cy + 20], - [size[1]-1, cy + 20], - [0, size[0]-1], - [size[1]-1, size[0]-1]], dtype=np.float32) - quadrangle_norm = np.hstack((normalize(quadrangle, intrinsics=from_intr), np.ones((4,1)))) - quadrangle_world = np.column_stack((h*quadrangle_norm[:,0]/quadrangle_norm[:,1], - h*np.ones(4), - h/quadrangle_norm[:,1])) - rot = orient.rot_from_euler(augment_eulers) - if calib_rot_view is not None: - rot = calib_rot_view.dot(rot) - to_extrinsics = np.hstack((rot.T, -augment_trans[:,None])) - to_KE = to_intr.dot(to_extrinsics) - warped_quadrangle_full = np.einsum('jk,ik->ij', to_KE, np.hstack((quadrangle_world, np.ones((4,1))))) - warped_quadrangle = np.column_stack((warped_quadrangle_full[:,0]/warped_quadrangle_full[:,2], - warped_quadrangle_full[:,1]/warped_quadrangle_full[:,2])).astype(np.float32) - M = cv2.getPerspectiveTransform(quadrangle, warped_quadrangle.astype(np.float32)) + + cy = from_intr[1,2] + def get_M(h=1.22): + quadrangle = np.array([[0, cy + 20], + [size[1]-1, cy + 20], + [0, size[0]-1], + [size[1]-1, size[0]-1]], dtype=np.float32) + quadrangle_norm = np.hstack((normalize(quadrangle, intrinsics=from_intr), np.ones((4,1)))) + quadrangle_world = np.column_stack((h*quadrangle_norm[:,0]/quadrangle_norm[:,1], + h*np.ones(4), + h/quadrangle_norm[:,1])) + rot = orient.rot_from_euler(augment_eulers) + if calib_rot_view is not None: + rot = calib_rot_view.dot(rot) + to_extrinsics = np.hstack((rot.T, -augment_trans[:,None])) + to_KE = to_intr.dot(to_extrinsics) + warped_quadrangle_full = np.einsum('jk,ik->ij', to_KE, np.hstack((quadrangle_world, np.ones((4,1))))) + warped_quadrangle = np.column_stack((warped_quadrangle_full[:,0]/warped_quadrangle_full[:,2], + warped_quadrangle_full[:,1]/warped_quadrangle_full[:,2])).astype(np.float32) + M = cv2.getPerspectiveTransform(quadrangle, warped_quadrangle.astype(np.float32)) + return M + + M = get_M() + if pretransform is not None: + M = M.dot(pretransform) augmented_rgb = cv2.warpPerspective(base_img, M, output_size, borderMode=cv2.BORDER_REPLICATE) + + if top_hacks: + cyy = int(math.ceil(to_intr[1,2])) + M = get_M(1000) + if pretransform is not None: + M = M.dot(pretransform) + augmented_rgb[:cyy] = cv2.warpPerspective(base_img, M, (output_size[0], cyy), borderMode=cv2.BORDER_REPLICATE) + return augmented_rgb diff --git a/common/transformations/model.py b/common/transformations/model.py index 2d41d9ceb..0e1d5845a 100644 --- a/common/transformations/model.py +++ b/common/transformations/model.py @@ -32,7 +32,7 @@ model_intrinsics = np.array( # MED model -MEDMODEL_INPUT_SIZE = (640, 240) +MEDMODEL_INPUT_SIZE = (512, 256) MEDMODEL_YUV_SIZE = (MEDMODEL_INPUT_SIZE[0], MEDMODEL_INPUT_SIZE[1] * 3 // 2) MEDMODEL_CY = 47.6 diff --git a/launch_chffrplus.sh b/launch_chffrplus.sh index 41f8a607c..4b7c4c036 100755 --- a/launch_chffrplus.sh +++ b/launch_chffrplus.sh @@ -19,6 +19,8 @@ function launch { echo 0-3 > /dev/cpuset/foreground/cpus echo 0-3 > /dev/cpuset/android/cpus + # handle pythonpath + ln -s /data/openpilot /data/pythonpath export PYTHONPATH="$PWD" # start manager diff --git a/models/monitoring_model.dlc b/models/monitoring_model.dlc index 0b9f8060d93d92366e3b1a1b9d3a9aac2e04baed..b860a1185af126f026a22df17dc9d882202ff0dd 100644 GIT binary patch literal 428211 zcmZ^K30RF?*MGB0^Q@%OK$AvIXRjT~918Wp0Fj1elDBU6MF31u$T*=v^~WQqnu zrOY#tdFp?j@A-!JeZKF1pX;vczV}{h{mymmwa*%U+k2vMTNx$g$Bh1iHqs{$NRtL{x$xuSICmZ@nNxXVX@XBOQNEJ7Kg%Qo00PW z^HwytG;+yeup4G?Kg@QRy`8;$)RNG!Mb`f{;OH6}?CfY49O7gbVi)RU>kwieYU}74 zZf_eL6dL9*JjBt_#oj4=xV-nj;oWU?YOCBP8L_`^X%XK4Q2H0pzh3-x{n!7J|3up= zFCm&JCMK^dudpa6DmXOACNwhM%~mBzTt{3-M#o#HKwREPUOhT2HfmX1m`z-4(Bh@h zOO}TH*Ob2|=*Y+ql2`fb+u4WOjEW3eIx;l$-^NwswdLi)7A>vSd-@;`t&AlY&-wiyr<<(GZ;}Ix6x8|EArmS82R3z`A^(QW@t+3%p75X8?Ee+pKShWC ze?>*OM3(;r-QS}B3!VKx(aGtk{~J1|f13Dv!hfQ3_*ZoQ6m|apivESp{$J7kE&9LE zIs6lyl#blLp>z4CiN7cOCpyP}MfXop*Z*78Sbji!0d=g$m{%N zV`<3Jf7+0>821miB>(M|wqkDo=CPyx?P-F9tY}lJlaQ4aQxUnpp_qlQyz2jQVwF9A zdHLTiY%Bf`egBuw|E+d+KapBl30X;5aSNfByyAa)zQ_!5-K zr!JCWa47(@VJ23rPDf9x7qH{D2AvjVhn05PaDC-*7~S3tDpF5i;^IikHy$M8G7M5-%Lv4Nhu0%)=US*x8+UYoI0z=-G@v=yV?6OmT;rGo2e=LA9Nm(fgw^ z?f+ms7)=Y{%RjE++hqQr;f`^ze4-X+n5t9p$Cmt89Jvkmr>4P)*=fx#8{ z89#>hpSuOhlr``~{BJ0XQg;iVwV8HuNv?83h7P&q!Ni9IQuXH3$j&;`f;nph1G5sr zMeq^6nmNO_KQ=&vCPDZ>NqBCPi_;FPlj!GXNZwIJHt|9MXy3U4l}dxza_LscUYG`T zNwtm?pS?s9u;wfkR@#H5nzOQr;-qlXP z!!==iYM2>6uw*FRd*n2xid#XqT#=yX_&cWdDhF=eKR_q1$al+K{tyPo&*t%x+v)8K z(PT-x7dkC{05hyklGq(PaDuc7n!o=@24XqgIZK^~t@r`O(bjl#+Toh0SHgCM@U z5{IOu6Uhq(cw*R!2|E+kn{$9{dBi#7(XptaivmQM1Z=ARFu;LA(4aJdJzySw9EpY?*I zgg!E9a3ikRRsx!V8nE!qc9>yw8S1}pz=I`Q;6}`1xV7a7TvK#nV?)lv=eM#X;A$#) zaCHNy4l)sjjLQPu%nf8l)GWL;r&Ac)wo%YEO%>JVWRr-!MR5G>F_3?24i4Uf@lwo7 zlqiwpas9h7p!gtutw6Wj`BH*oo0R#852dVrUnR@_aj|;cvYV(*o1t2^oqgIdjCa0N z=O4Q@xHI;`52;Svc3YN4HJkGzmeXjDrw6wml~Das?i^MoZlEh=Dxi7s1{kFx$JaiT z1@&*P^t^*Uznp7JTb?$-^Xuk($zw5kKduZFcQt_Lf=SqSMwT3{(8j}QJK%oM3t_j~ ze&Q$iMl2MqKxsodTlKwx1T=LL?w$@TRR^C&_z|qChTVC)@V#RgCjQD~y>UtCQgR<` zX4De%s&4GqXaiqTZVM)CNW>7sC)hPipQ@iR0jt|(cyPrX7CNV$yk2)6?}uK(DCNQU zdTA4mnA}rstUMD;-QO_3_v*sLuB8~bV;GLRS+8q8yOu-UwKLVZi$+3UhZPlAFW{z!#nGo^8@O9UI))+PjhS%kjuXp=F zLHR|n9@+@n{u(S)S|47Vd(XV5HL}6JO9hs_G5GwbE0g#Wge~un;kA&P`0B|iHtFVT zHe%5Y^0e24^a*X?c*+QfcwEFX^A<9xBZja}BLY&ll##X7;?NdVg5NSL1y0{(nNh#1 z(7$jEQOt|O{6&TA_ot`u)i@ngzP=`oL%>4AA`dNY2b&*ooJl6mOZ?x zLM&Y@s()PG=2l%>K&FrEc9Y{eU|lyH6m=?a+(1iquW2XFexe92J{LsTquF<>4T1^t zzYyOI53sK6r!ZxXJXXpqqnFFa3Kniqfskn@Fjcb#oh9buq1gs}Y0zr!ut$M<`kw%E zyXVlmc``6pFCH4-kI&m+LBD=H2`nfHv#Pg&M%_tXa}>4!5KIkdla4hjQK|W zgW$I{1$rc|pnTm+IJ&r-KaiB*1_$oqa<4KpS!@K$M;>E?O1I-%S2ezBz7m}(#UWa& zMJT1*LyDZu`S*-(a943X>kb%7bDw@Cd$!HwS|capm5o_g6Vph>D7d=*_G%?{1sr`R4rLph>F@_@S(orP z?0JaTGFiZroriIY6G!PWLj!&z->Ta9aX2ZO-b{MVDDlV5@A39`P0{yW48!vUG-%U8 znsP^xt{s$*qs?8g?0_9h)D`C^WKXmEffYRQ!UeuEZUil!+eh>(R?yq)$HK3(rTEgl z2V1(eXwjSfr2k4O>UTDYKDsSOUu0?#uwLQv+_|?Uwtrs;`iTIPYc&Uf~#;yr1^k z)bPhG8~Kvk0o*I5T5yq0p>e*e`GA4t7*~~nIugplRl(QUcW*_mQgNR;UEP3wv+}sd zk~4U?!HT?7ufQOQE<9_}pHFj5Ji423|r85T}Q zPgbuXYbUxj$z6t)Hwf3ypXTLjHuBf0kFlWUEHsLx(l_O<{LB0-Sh6$=*Y$0MHib*f za%UFZ_v63$SBcIQ)o|=O@g6$)#5eAL8`1EmT)39nGTRaLUdq-qD=S z6>9HMx#^SWz}D;d;Zh%L>OT-Z|MZ81C4Mx*_ZZ$5Kf_fvsDkW(dvH_iC&nai=J$L( z`2Bzg;q<$Qp|Mgx8JXC(_0B`7$fyZrYxT8%3AG7u>(?4L1j|Md3@S!o>tYS3(eP}!Nd||^^E8Fv? z+f#U2WCOi4ShB`@cNx`~s}Fnj81T1G3-F7tL(Qj_0km}DIkfg~!()fH^Uwa?d{=xT zZ8}(q(W)OHd%r1M8Zer^c=-&CFD1a}7=QMvUYpOA9nLkpwV>H0MkpL1fxF3B9Ca-Q z9^R4S>WMNuZs!j&uK7FEohpXWd-T|$fF>B&=U;|s@?hO{ zn4TTU$}1Y!yu0#3*MtnN7OMkNf0W_+StYO?Eiqm`v3^x0YEB#9_ z$lZi)zjy?^=GoBAH9kz$PlvnAc!Ftu#&}7zPcDC$3ZD*mvS(YPsKoM^~YY`^w{h!T6+OiG~k z@B+xYrow+ThHzWM9PXod2YY7L3+s)#VPGr;)3dFxe5gN*9)_^4awVPEHj&=)K1wS# zC)2$3={&e>I4}CX5I-ed#IyZ8YbvjvWJOBn@wTQK9g;8$Uu~D9zqUN!oXj5GYTO8r8#+Ww*gb{ zH!!K{W9SGa=$={w^6e8zY{yp&Zuf_ywWZ7>^{l|$IT4E&A0kAl6IRWYp0}%GVzVTFpd`x8y5zvS_5~2hQ$#XjFlOf6Vh;|^!k|hG6wneDop1tTHpR1M z9}C>9CkGMhj*HC zOM+5Y4j64)1-jmc1nsGlSPpDqu`iS1+P5|+@{h-i;XzQNEQH>;Z)yp zCX@P})GX8I^Y)y_@NJfSd&4F$NY=r1l~Ule+XLHn g*ib+3x-O5(!oo9oeJ|l;+ zzr*S#ZEkR63QJ4M#o9BQ(YB(O>%DBI{s#v0?|-K7*+VA4w37>H+{p~0 z8V%{un|jo;;|^NGxCCm}VucHcovc+&;jOo|~%9 z1s|lT{lW<97CVrxStLo{Z`}d1m#(An2|uoQ;~_{%?x9v2Eo&ZD&*F|jcUarj;e2e0 z0&Q^Brs28oV0GkSe7(h&yW0-tN=JI3=8Og?FMoi`r{?fcdGp;~OdZC(e!XRW{uxZ( zZwP^mB6_UyY*pG)t4ZPFKMcl?i-eMH_Bt?L@1EkFh?H z!^R;(+Wss7Z|hT@u_qYsn6*;B_&D69X2KRd+6gt1w(j-HRdh$tS9E!r&EHgM@c6X{ zU`M9}-?(rbFJ7nPesW13ncjLHwN`w^7YcoJ^KNb4Hee4FUk2JDahSeUNumu&L+I0_ zbzIFm52m#3u*7{=;(wrA)Vu3OEX4o#On+9;`vs4_b*auWbk<(wANV2 zzCJXe(HT9}n&wFmbLpyKdHmR?8RAL(4=&phKar?RNJ@cAg z`vY{>H!1g^xxsXd&1T+N*^8BT<=j`j?-1ThDxgCp)p+3Aqp+S>)!4SG3QBdKkl6!P z;)EI?ijJxh&#+2Nec{nz>fEjLxD#?)u0HX1kJ%6DKDwOC?ka-j*QuCQc^T}gH^ZeL0kkV+4PI&5ihE}0 zQ}exsJWJ|6c54shruIc#=3o?^QuP$?<-9?$`|ZqvM(*ZO8TB<^q)h1#mkh2l_azOI zxxj;CKTy*-hxmNoMQ+3H&V>HHZDjQ(S=v6h629CFL8%IP{PS}pj1p^twK3oE?X_$Y zHL?benUCSug3gls)vJhha3E1tX~Z8v`Rv<@gV_JtaM-llh<-AhPUI76Sk=26!ab%# zLE8bGzEKCl!#rW?>QXc)r(9s80-4+UL-6J0up$2g4%dzcHN7gB;on0l$DV=b{((5^ zjw6YjDa5R_Ma2BwDiX4Hk6_a(&J>*znXbcjHfyjvCOp%Gg0TwRS@J2{99Imj1J{$~ zXBR;~t=l+s-E8!8N=IY!t*qv}4xVV#p@WqwnfNCanB(YyO+KoqE7~LSpC*BQR}~4i zFW{@c`U^+?5kPE{BE38H6-t>2*wCAeFe^rkk525zcl=0WFIwNAYs*AhyXZGEmm)rw zYY-gLkIaw`290B@X!+R97(339(z)29Q>s7o z9CocqMJXjUe(;bp&R22Zmb)dfr@#y?r3ltO3FJe|IlQmF3aTb&L^J zJ}n1|4Y%=)qil%sOv~zk!7BWXYC0@h)rl(`ZP`k>RH~Gf!Xq9VQiJTF^htgNjPY{h z7uOolampvi(XLydE%QiJYq^B&$MV2uu{SE$&k)rOd&q!cBVqsXYdC8i1%!uPx%c`cz6hoAw;O0SC{B_7l&Mc-o|m zdd-_n1BD;lt9P$&Vqj%*% zo|>=?we}`a;jur^K!(!}i$uP}xFo8(#e;s6 zJ%RVaWNJ3Wl~TW~XJo;YcwliBIDUQ&cwIH1f&wXbkZ>SvH?F|;4||AC(QaNcb1}cE z5=Mi^sNsX@mvCw^<<^FyF?v-T-cNJpCu0I|LDvsBGVK~R^(>&12bhwa^*dM{Xo8wx zJ6Ca;%5JpF(W)kUy4O5~Tx#>?@0Q$$^;bWkQM9{Y@fRTuYI_al+uXR7)EE-q{{xCE z4T3=vgQ(QPAE<`Y)_(T0{TaXdlo zUAyCDxqI9nQrI$qK2YmI$CRUV@hD&D8M%u4osOn+2e$Kx%JqC`|8ekIt{?YJRmGXl zZ*k@Q*4!sw94}rv$M>dvq7&7MA*NQ3`=g@!@?R&R>S-E}v>(H79++065))5piUf-- zw4ehz#9{a6qMC@D?R?SNCG@6(Ki#`a%YB>NW>HQQk2?!Saec+HXgWa%7R4zLr@n!@ z?>tIg=uGC-K!XXL@f@Z%ZZ? z?9r?~_>$1K8;)bqq&F-sT%62BGkX5Wan|a-i|yNg1P|=ABWHfAf^S?DWVo(IeQ!x# z%G9Xp;56vhw1W-39!QH7X7kF(9N2tXkNU@*fb1G$9&*fu4_d3j=NNawwK5Al8ErtD zO!UwROCc@)B3q1E-im!ZG1vCA0&|&!=I5G3Pz@@{H{@%r~Zu~dgcybRGPT2-M zS`k>?+(06?lrUtsNx-mm(AD?@rd*QccNH$uxG7S+ZfGj4kx-%Ym#*N-mNGT{@}A(M z?jSCv`3zpyS=7|t7)zh*_r>K7(Ij!w2y*|7R7|l(`H8&y=%3j-IEp&R$Ku7y&u`eH3tN1&IoYzcYhYV zyBxAaHQY%)gXx;pnXq;!!U?nOAa|!9CQ45f%1sJFJtl z8;i})hltj~0)Fo5Uid{MDLg-cVw+lt*Ov?An$K#mEX(E)dkZ$cm!U7@Ct-R&7c72S z3Bu}fY?-4@=X-(@EB$t-!Oyo;OY@=6aj)2gW zJ=kxK742S;k24EYsi%hp9a14yV>!xzr(~(qtqsT6=G-2B!CQ@{hFjC#lsV`dIF1kd zQ-(EP9C$)z5?^S4o!LkX6CPS@N&2oIp@(nx<2fN$SoEnM@M-vaw10C7zq_l0Z(V;wGrD4M` zYh*JnpDD&=M(<)Zt=m9(nHZhA-_7T9J-T1?Z%83Cncsc-9Sft~}-p2A(d# z>q;i{^|$4iG`$xyA`N+>dz@)$uB`i&->lqYYeCiF3 zk4BPrtEIqZk}h3$tcT4#uupKIw*cF17&+nKO~vfT@eW^S{<$L%vtrIcRHQX1TSj8& znNob{_!Q-z=3~=>csOhM9Q%fjL649Y=5Q;PDKw?Ry?1ZGvU51sZVBMu%gWhjX3QMk zmBYN_3&3_v9<1nVguyeP;l$cAK+B%tq+iEKL2)6Rc5H=aJ$1Uc?g?%w)q(SG&G}Su zKRBL0jJK}c#S3p((Ot)^=?eYZxMF=P4|lS{-IrZ?w(opC*M(6h?=cToxo@^oa36R0g0o7c`y&J!r%Z1;orCFWI zRMzJ*7{CbOVzCC_xh4@bKP+H%H{@aHeRDzm;4kEKK^Uk@js=_EtIXT+Ij$+wgwXf0 zf|*Tn_#`+1KPh;@^8sgIpZ-z&QM?BZSKoku`bune`9tJe3}GzD&>P&0c&QJ>H*P--f4)YSBtklcegE{@y&X?r)dxT5 zUEqsb)lykz?s`(Nuc=z{+z`C>WH-tSf^h4Tsc8BrlU)vM$9D(i=(wYcur*#(JM6rU zl3`l~CW8K;wrUV)jmUvcrSrmu^S4Nk7QyPzu4HMY3wIc$3FF;u=-^rNQFYiV`qU(i z2j0)56{0w2PU0FKbgYJ_XD!CkUIo4+^3uYOO3u=wt+|md|~Cm+rj$y6@2t49rPzGgF8}k0;5S|@EVN4 z_c`8-9~=)0CcJaA)6|0jla-0ScLjWlED;V#OLuK2h~{r^;+;|7$gTTH_&VexnTG|! zS-SnvZ(T7NWPX>WZu>2G<9AzlRQ@&jt||%TI~`b7Pd%_No7t{c=_EJNgyiSs;kyW3 z5^7{l%Jw<2Psx33zC#B#-k&7uL9b#(#XGo^v=LwSxeAVotD^I|C-AfW4O%29(5fCk9i+_o= zI*xKQqFypl$yZOhk|Lp zCAq~k`F{UN3su?i-&8aeTS>S7MG+hIKm5_Z*Td*|C>|#ze#CQZvUfd)c-*~{ckebI9W**$^RguiQ9_*8yRh!e7a~*^ilbXj5cn^ zJuRxxG7SQzNb@O&Yv8`_HV9iKM>~#;!LXYbQ9M}*r6k74X@ zSN!=POE|twfghyw~v{2Y{X z!>OCoE`dhUPICOJG8{d#8~i34(e>lK@K^98G~fJI_$1epUzoFku1U7RphKllUEU^m zU|k7o)OMqT{B!1eD4paDyh$Pws!6tOJZL!fK;3;E8g875>34Kkd*lmX)Ayr^f&?Dk zTPKu^QU;~bPoVO1QFX=s9=2jiJL`;=0P96|uuSGAId7IneD>`Z=2V_0hDDdKqQRZ* zzV}f$-DzlbZqZKAHtcbG{UIJQ*EBJby+v@aHiIZss#NcZOJc=kcVJk+YuJBf6*;!! z9BY;M14~}`g6*$z+-j)-JAZyhNtc22Ys>{);-$bn7xq#cbSfvG-FT$Z=M-G&)%@BMZHyhM!d)WcGk3?><71s2egmpnHgeE2u zSTf=Ua*b$MqpHkZB7#Un%`+4WkfLuqC%~Iu7ulS&X>c!Bnx9=2i&BQKz_ZU0G7D;m zzzIeHy$QNk4msZ)Cg?fk&YE<-q6`+#Y$FR@I@M>rfn+JG|NKL8&lFd<+HH3g<(@{s^F_$Ayl5Q zCZ!VXOlIO$VaI~K@JLJ+AE)P&E1GiL;iwqharCAj=X$H~x2Q2WGv0$6b!gFh9s0EC z`%ofZ;tj$3GqJ`w8Sfl&<GirOllT>8hgGtXVizDR+5ooBQKkXa$$XZ%ov^lR2ucjP z&&(tW@q^K0R+9dW98Af@;GOL(MIsx&SNwqLD`nWZu9oP<+~@Z;91sPF^5}S~1GIlB z^5V7mY-86~Skn{1SCk%upELfD4YkYR&VGW+dPbmoxj?GLaNbor7WR6&;v?r4+=S=ZlP53WY^X97swvO}(-SDy?+{s={~XeWCBUs~ zH-&u;8;~#XB?^fvPYSTrRrZ%9c22#`(#R9Icv3( zf>%b$P=ibBG>})v(ph}>9FX5oB8=S<1X0QyQd=Gq zh4%(<%V8Od_5VqFMh0N$fGwi_X9>Ov`v}=-yM!4-htNwKpRwZbE%EB1@o*!JaL#RikpbhiXuDVpz*x=_nD7m@5viv;m~)G?wwAYrb|%;(ViRM zXbABqe}HullKiFyMK%Q?s9M^yTB;1zP06n&+*@VfO__z@Qb;$_C} zB@^(8okAWsEg-iBtRDz<=1#b9@>4QyRyf=++DI2Kn?Mit6K6lpsA2T7PL$1WLB)WJB0}L5$S&G| zOi4MTHgvww@0q@g--7*PC!seY6Qw<5sYv^23EwoObcu=dXK5YiN{qv~@tavhs3whS*(}@;F<;O%u$x6HguD5<<_r67 z)xnP|r-^y(C}OcHwz@gGKfJzQ2#z0TR4;IT$@=&8hb4MhSUJ-H#0Q2$j^-SkcytZc z*!7_P=gD-^<~i(4!MUpRL*LxGmKwu@m`yNo$3U#JiNgFo5ed+GH(u-Hk1!C`33&x!P&0a(=8h+5z zr`n0M6Wc$V@!(h`h+kC27P%C`+F@F_^V57XX47wwZj8X|0b3zDL>tHD<_cZT?Sl1} z;pd(X-W>4{?GRDg>r^lFug`HuS>kgxH{Wd{e z$Uf4S+>d*lsDvlG9PoNnJ}iIM%I;UK6t;|+EFy~4lV9s9$&X%d;!)%Qq249LM_vf( zGg9c&=t|ISQ=!{S3WPJJ9LK0{n;<LH>y1YlDISc={k1{xEs4 z@>&lL-MwtSXAzF@(}MSW7g4MK1KAU->D#rYdR#bqGQ#T8DYh*(d5-_cK4_@jPM~{=8 zt}{+ufw<&8{N9w1+tL`F+R_{RbUIeLBN^}c;V~T?wJHagbJ}58W z2Q~g9AU`J+KQ|h2gN>1B`FSgC{G%&yd+LXEO96gLWWnO*B-a1FHWia^!nei&t=|4ra-4IeT7`=tcV2d39<6^uzd1d4E^4OQbS~^ z8gk^Vh(RuMqT>WkYHF=W_iRSjaQA-&gY0F@6k~C_W zb-FEna*rI32%w6uTwG3OtNu^7cpt-#r;T|$eL)zsvbnJ5N}g1M&>XvfH% z@Va{>6+C_i5lT52+)W`(+?Z;&pT+3ZXnHEhlKSm0fpJ;KVfB}0Y!C2)i|;d$iU@%b ztx7y1;T(oZ{z40lT-bqGVCpjyk9J;VGvy4yPoe=@Ps@@gg&#mXP>!4XdSJd(25es0 zh?;9Zz_d{sz`GJhaDeYcH&^vf zAdzeYW_6-Q+V_WOX6*qxUZ=8;y{q_p@iaJ+V#JS^ZNP8y^|v~ZO%I6 z_LLjw@2kv*O9t|($K>&jc_Fsi*~8K=JHc^YKkgH^{L6=gH#8Qo_x&s}Y>_*<_!nXH;4|d&>TZ;-7(^b+E{Dj_xioP`9&R9JIMUZ0 zWo+xgu5~i+RNn(1)WqoTi&AuSd>E{YO(P$xdr+VTJdmOHKt^)niIXH9QSez2+3&ARgF&n1A_KC+)IyW1&40q7Pt?!B9 zy*=P%Rfblp6tU`73LmjI6Y6y(>D}_tV9{;})^_Jel8B5k^X(|oqE(7^%D;uP*Gz!5 zeL8%gkuk<3>EPt8<+ytlBaOj7vE85_HOjQ1Ef4$Cmnq*d`PC%$q4^rsS@i@O<8r|= zXbK;1x&eldo(#@!p0JXV%a}Waq4djQ5n=NMo7KG@2ehr=6-GYnt4l5OpS+Cq{+UeN zj!W_rVvV})w?QH??S#gM4pfAh~T?@E%Dxt6r{zKP!_I8eNYGvtLj;OsUzbn zoVis&H`p3p66AWc5c&GOc+vJ8m>2?NTI`{Ro>$;Kxgqd9Pl#_nQXVFX@5k&{1Ft?q zh&yl&zY3lSSYk4ql~Lk-^F%R+lMWrXbUSK@h|z;9Qy?kToldyYjV~)TxpU(XuxnDF z51K6n-&*8Jp?e|TdKm{bqsHT?K_4)sOjdLNMS=%4OT(>CRam`q2*j&Chs;D>n4x?R z#mWx@oa@iqD)wXbE*;uvP=Pc+k;eWJ!ja{Gc{in@aAPu#`Z9ueW-R3GNxHlv$B0{h zx25YYFJn(G*+YBUSQ>xN33rK_;ZbTyH0F>td;RS+I4ypG1*02~#FWFIldUi-m|*M7 z`}pX=P%!9d!GJs?I^*(M$h$Kbw%+W=?H4w}$m^e&$=*f_ z7(%OUG_h{x*=B|hy~6Ow7Zp@GR|C3}J4xMu zS8T*jWxl^@7t0tf%^faPlQ$2?;$599FnXRbMiz_lQ9mb<*nX|7=A7sdq(!;Vy}p5+ zzU_zyzC3X4YS|9%GRXoW*aXT+*MMl90zDB)^5n%PrY2{^*REI(>r=#-xylmEG`U8) zK8|Ld(ZBHh3s-1e-ydZ!i4MkIm8U-^9VfEkUgRKkzk1&pn*K-4svAw!o8~TcDrt4gyV$z*~0|o#fFEdUaEAQtou} zuyPHLNxuk{QF1)n_=oV=OJDNs(MWbNz8|REoX52)W|5TmLN_magk!EQ^kRq_emY`; z!{$$ecOT7(f3*?LR9J&m7W>J>Ya=i!ZzT|x3F$*bxzp2R(V^4|xV?N0DPEa^wW0l} z-je5-GQ>$(_RP*xG1d48AJC*cA}s5He&tI zf}C690uj2i*@*XT#4^_(dLAr-?{FWUMmMruvisrI^K;2g+}I)_@g{F?yoUc3-iY#l^Pdc{%psv}d2 z?}C-i)A=3SaWu|&m#BvK9=0gW!3MW5USjMBRvuU2gwbU(f9WsQ@WTuqE^@;M4X#Y# z;zdDEz-x9fZ3zq>^n*Pcor-GFBaqw9g6b{JL`hQss~+3}&kh6rCU*(9jTyxck9mmS z4mRTY!_E*r>H+TRe*@>V)v-xCsOTU`CRVOPP^-=pJlUI%f&@`sy|w^sEI*>)NEg&r z&VWooA=J`yP}k{)LQb*#PZ1nbUk3f(4567N`gEVd6?oFpfUmqgkg6_WE+41B%n@Tr zh$)BR^9t#EQ9k~nK^1Z)djRh@nRtlWE~=q=E8UH_x<+!z5Cev zJNEJY15X`w+|PAi>v#Un)dxo{9}kbr4nRMGKEY>HE># z3cKH&+FBuk4Ugyc4Lu2J&)mQ>e;U--U*t@NorlRmH@RO%eK75XEX>|J4Y)JEK;1kS zgRG53*Z*u`U6oesQ)eYQB|U~3e<_+pwiLelB9wMqMZ2H%ICa4-&R;_O>MS06ZL>Jt zn>!&bZ#|7Y6b)lWba4li6H!_62fk_!;Tt{tvFXcQT-&S)KaC9;KR%5=-u0H#=$#Jp zvrm5G@7B!WRes+??K*i*x6YsG zrELeNdl!H|qQwPPg>XNnt_JVuIBvD^c4BuCP3YXDBHbJrr{@iKhmbxD1j=s8&RtjsFvf)Hl(iqGs z9DR+eya!R-pG!DM!I>TQXoZ;4{#@hWopi}819O&okl(8{(EMd8Uvt2Uin^>g??`j| zPRCJn*HRfSN8SKcO2;ULp)_G!J3cuJ&hBitlh+BCo-sg^QplX*v#nz6#4v9LD`6Mxf_54|a^J5rnGVbzcwwH5vF)~-V!ExUXBVa-LQWAUcPsrqg~2rIaq$DnxBZT;QIY3cyNUUrT(&pziry+ z@X~;VL`Fcj!ez8^T!2k=YRpiWVO{;ZltoXeM~yfQeho_(vcm%~!156qB&blWaOP&L zn*lZ-7gO%m_Yk#oKe)PcyuyPWBR%RNj{IxT=@O*pjty+|=851!n93N1%h(y6fT*iYI8zEodbPig7k&=DjPp)hgGM%ioi;Loia!oSC)VKB zImb}NV}qE>JHjO{e$9=2t;T{59fF-x@-fX^5px3j(5R#WSlRQLS6`9>zDau^MBNNs zmxsfjB{%Wlx@4R#9|IjS9!#=yHcRWD08Ktp%*nu*pPJeumKu8qW2SCkiwd;Z?RTbF zsC(DmDfkpB^bw=igJv#LC{gW}s>9Un@~rnx1i$)ODNae>h3Uqh(ZuK$zx%{W7`bmY zS$SvUAhq}W^xI?k4)+{97q}lk$o+<2iw?ulq8|Q$d^o9(R$$w%Ch+?s*76f4WP;89 zZ0ztoE&P6OppWfBUMk)fQ}+3>6wQrrBsUw2Pp`)zJF{R+;UZkWGaCPe9KvQd53Kv@ zg)V=!aA4{Me)YH@F8Y%rKK$GU-n+}7*J~zzl(;OL*C;t+eZ_g7_`SvP}(IW@y=%dMoBmny;GYVsT4#H$}bBMkt5cvPPF>%;Xc$GGo6>mQcMQ5h4Bolim z@4p2Hl_zq~B6XmC*xz zVx~>UNbzh2Y;=&O#J5|79N{Q;dc=Fa(Ofu>kLK}5Pmf^73tYKhn!5JQ9zn2vYdEK# zEXzWx#p0~A4DeP8!5^)<6k43fz1MZ&cI*}2|2Mrym&S?UKF5R%1`9B?_7n7ZYlBzR zQaO*sR^T4)4tJgzHZHw^Sc|ihGpUnqJ6wvt5 zB1l$Q!aGg4$myydvxB~#>(3_X--53hvdnq#74XmDSc4EprEtC6bj2Td!}45(vEfm4czYPk z)q2H+?t(M4iRR2A8?z;epIpRz;$P~Vt_DTSRZ)=Mk)KTz~(ecb{C$veOI8*-GLN$ zGK7L~qu`sG0_Dsc#EwSCpq0i&Y>RvfpC3NtKUv;`_ZJG$J^3nXhv`vNX${nT z^yM^;G>I1Xi-C-v(QKe}ESD8v!c9Bj$?5*p1$rHbsBMFsiwBE5BTLzC!Pq(92y%x^ zqj_5+1*o_Jv(2mUqR~}x-nev}2VdZ%M*vQ6TMj1po!j?#6L7ctQr)RYSReP8GjCkV zO`6?`IT>2)Tgf2yVYf9lSe}Ou>HQ)3b)9IypViPB*9nIrZg2*_Cqe27Wqe=#1eNbt z!RZ}o=zFwQ^ghoLZI?fR1Gif-diF$gvTfuW>XK1s=wD9zkrH!IQ-D(c1QcgK$9FbL zwDGY6M%@r*!&OQw*h+`0>QdRF1JNMob&A3H%gF7v!l|SG!kxBg@XT2cePs+qvv0|> zkbgo!#^E=r6olhksU$u@!GOZjhJx-SH*A{Nk9~c24Xy``N8-G@N}ui1%%{1f8$^Iqm5F z?BkqO?7l_|zh*1q&<`i@%AS4jt?Cf}pD@&`Td7>!x+wdDZZ)WR_W_DbGx_IXIr!7x zn;*1oK*j9=^0e*DM5x{DgGKB6!KNjRxbVBbpbI$0jk%YF7AyM?`hV!;{%;|g>hAvw zjrtE)-55Fh{|{ox>3=84`=2ONU)BF0nWPP+&7{UiO^})>ZBg^T7%6MZ|HerD=TGTt z|G)dh{{p7|n`Q6+9GE&>9ZP%t)^gS%(rodtHQct&+4S!2R2bdu!FS3#(-##JJT>kk zOd8r(^6{QB)AbO-(VPc(`P>rdk`w4)ZUGzFa*59kxrNnQ8~MECuUx3>0lHC5m}j7j zza}kZl|_4TW~4JeO>+kGX`0W{>V!7vvEk75ZVZl$l(4Mli4ZusmOqm&5PL-#Tyw@? zn6|Z?_fQ{8(;TLto823(Nq|2x;->Mxx3LPpUp{P4`AOg8z_SvB{8K zOr6uD{X2KSmkC30>y{BD%T?2k*n^OA;aa8Tg9!Ni$_gjVvxT9BFYsK-ZL*D92&Xdh zC~%-G*%_Z@?(tW-t3D+-yFN-3wlbCLRZ9cYNM%Y-Eutld1cSwsSWuEb$>wNZ#MxJa zmWY+m%_Ic_Mh;tAz_^mfC9^8_p*0Gh{it3ZW@24|5JZferZ=@m^LY z;X@1ByDXN5sSFkyn}4S8h_zI(;5>{xIUKdiLcva|0r(F})b?owMG6g|Q(f9@ubws) zxfHVQZ6T~@V+0F5=EMT0?1DL}(IQ^+9RI>po<2rB1_jSE*foDGnAC;QH&-Ki1>4EN za~J#Jo6j{{>>!i2WE@0JwD(^G21_h)@b^@fxG9CqT&lqTn%v16%K(88RYJ~ ziyTf1<4L0;wEO;%`KVQEolU*x4C(5COwQ<~KMOx`pNn1=!kCtbc5l+BCu#K< zmuAFLpFG0x4qmLfuK`xqIx&MwkGa_X6WF5(^Vsy?4Wh0rTk<$A1WdcK@si>~Zl9S6 zF8sntoQ$36&^}*KDXW0m7+apxkHr9^0tz_IVXmAfZSIIB@9JdMsehgho-<}!4f5&x z@9~^(RvKLHu&qeC^$$i{dob7W^O@`RV|=vGikfDV#q50pxvdSONNRHrNS_ym^*gUo z%cDgsG+LU)Jg{S%%{9nA`86D}-ADJAy@qX(H?d*ndx#u7gH3j6$0LT%VC?40_-)J% z_H>8|z5n){QfJ=hM*LgLZ~40)0=D;K$Hot5+fF^CzFvbR7bCp6EJ-u&ZIfboO_$(9 zlq2)yj0<$ehk&6W^u#TPJl1YiqvWz$gfL&1h;Zi;ECU16f5P>h}=~6sJ9bV z=Bu%fh1=-d0|kD-FGsevvK$K!M$jHZZ(M3>%Ujo+fv|CdS)a#lbW1@BmTyad{gXV& zg5SqWO|_3Z~ZqnOL+*v`yDcG5tryPVn51ff|N#?Q=C#C{n~$oIH`|Ew}BvwuK67Z0$d zS1oYqxKs%3RKmzr15sz;02qEd3?3H^;j=<*DE7!he)vE+=5R@H#9fJ{E7PY@p?e~l zem0;}`JTAA(iyV{Sld6yEa0B+SVcZsdnj(wPcjbt3(M~tv1RdH{Dt6p^b-wZFRfz* zfO9@GEpy?OwH0yi`UrNb-(gZ|x`tLq`|x+9Ti};+GMbw3T+`=aux^ni>Eva?ek&U~ z-;oKue{W&Z@l5DGREnN4A)t|ZhdZ)1nqTmCESuRl3eLv9p>;WWH1KpG*ZX}EtMq?? z6Q4fh@4vZcw|oCMe!X`P-aF64?Lsh`@NO^V{us}Wn<-Ia);K!ru0pz_)-rKw3K<$K zrv(qRF-+AAqSHO#(V4ka9ejbmon=WstIp!sSMiY0a20P`+JHp5828K=$*Q_cVAZwT zAMd@VAw$}B9f|vWa zXs-{LmFmjum#@TO2^(=*cnr+?dJD?_2B1YjBs?E60YsItaN(?oVyFG)M&CAO$4rN_ zfVwNt=@`z*L{S18o|0Kzv^2JaXdYqtZrsv>vKW{EY zfa;`<3WL4PKe4~Z6)t*1~Z!w=H@IbSXQ^L8D+ zVV^4*U%d1RPB-W`TjVLtyoial|Qa6s2F=3g3NvS>dY*G&1Tr^k}??`%2C% zr?g09;XHj1o%JV`<|6T?&@?=-UXf}qYv7}#RCcF! z8ufkIh)sQ!ne~P&Rw&#dhdlWTCr#{_byp=fMVjH-mT5Rg`a0{bnogbur*KF1Ry-oN z2R2@~Mmj2nR6fI$neIIX(I4FS$vt-17GpsjQ$E4La=`-PV8l9?oP=J%#4@;@QGs%( zNaOApuwPjSZyu?$310H#+CBo)H0ngkrhRGUtX$mHuLu8ZiK0!7Hq2S6kRD4`va-8H zuy2JBIM1oYqT128J;0E)oKc5&({A$51W?LgqBE52$l@$6RpGWVnyj~=uOxrU6z;{4 z>+Id71o4+I<5>2a%Q(a^1UddS+$?uvt168pg{_B0ky^)@(+1%`K=<%W)f~DjG{L(+ zZ-DfJ2|Uva1HZ-fT*IE9xGuSYZ&-E)Ego2KhvIipOJXY74_FJ{)-8Cs-JFX{eFd4F zI#Bxg0m?kj#h!{zsId&A8Bu#^{gP;MZdro&-ugmH<7IBN^aiFC-h*}dK`L1==O+?3%nw`ozM<7@8p7bgs^7(vO>{h6%(X*B%v9do8#!RynMS$t0j z#!2;~QN2&$frmb8d)JSttE_iu7^}Sk_>3$&Nl+ z+_hd`NF13DpIvjIx3!R6Z>s?Jry39&qf42Sp7P3rV<>UpUR>P~z@7O#fdzl6MO@9X zxnH};)-f7K?VQG99U?*X00TSEMPTeEN0q`m^uC3I*(}c(wC{0d-l|qiuI4H?Q?;Gy zcBf#pN(r;Oy@jAaU8b9+9X6;JL2ZI#F1y!twg|LX(y zJI9kiNr5$6mc zQffEeP*LUPgG2Tv!{GH6!X3ned3tYjTHIoJcPYW0-K)>P_3fb?}sPJ+%-kc&5%pbd0XmBe( z&;2f3JK)M+I6kQ|?}`trc@aaq)Lhu1{U&H#%h-#V?R;VhLBX9Xpzte|LgNRrb(8G4 zLjMAsd3g~0y{!(LGc+i!YcTVdnod$vOz^YxRlH~=58B1?lz~b3y4IB4%34D<#xt3@ z*FC7a8i_r}Eb({zZjv4DOu6T#a-a8K=7&^Gp@OvvG?Z%rjFgqgy8*N?DX{!fe zgc;q6S7g(dP9ono@=SI2LtM~!4j#q#$K$gn(9Z)4S@Ep>*l<#fhS$kT7H5{?GrM8j z#EL`A!^0Z)+*Foay6}>gT5N<9GZxc{7adUA>qGTlc(yOygFUboEMjZ>lBDoD-g2>l z89`a17fTo8rJf{=JM{q<4_kmZNR!pL=&-r1|LF9M$fq;w!+^IFD!d*} zNl7yx=dq^5eC17Xb$LJLs}qKO!yM^rS0Azbk~%0|Fq9JY`$%duw$bq%F+4U_W~r{0 zSbdD>o`a+0jYc-?Ha4fC$O^czXbU`WR%D&Y&tc+XBO3dw6v}O@AoSs8?(OG;0_+ya z+1wNCtzNrv<5y#raU~kD~sT4K4Wnj26Pi*A!qSpOqe#6nddN?k*kXL|Ax{!b9G!?Ggd%JJ3#h!D&DP^ zz?}XAS=5#jd{=!Oir*DrkYh5-rt;#=#>{V)9DOZX!uB;F|74jlrrt@0n4oFsT4_zS?}tkChBjkA zCqsC;L&S3GrD%lnLheoV7+Q5BQ#C*SUjvQ`fCDmxrk zJAcJ3UgK!khS_{_`Z-AT*ooRp1R(IIEQL%hC7H5)xU@=<*}a=jeH6qH5I>l5Tb8j| zjve^NUobny^rA^v4W=C&LBU3|_;;r1)OPzQSjEJ%mXn)kZr}!-zVa0{y&g)61y^C~ z7 z(>F;ro_c}1efz_^2};aXtr=5|^=SXkVm46D8ZA||DXeTDE4kW(Ci|6`mU@x51ALYvGp5IL+XzvaJ-@@8QteF>W=Eh4_f!Y z?_3Iv^jgQ9+N0Ts`A)R(ln%M%uA5hn=;*Wt z)Fuz%1Gd{y!?m?+g=Q&sy!Zv8^%#rLM0Z+OR&1@I;(@KRteRLm)XDo=Z+X$uhY^3{Y6)hZpDB84TsuQyn18WEu0h zK7u7Q$}@+P>JkMlDQ+8i((~d~+~V>EmSA#?>-%I6I&Yf7!hODSaY2r7dRjJJUe{M* zy6`^F{=F6radBg#1!Gw9rlD~DiZs35=1z-6Qy9IF!1huPFd4pra)xQ+l%EwiFfk0r zoV-FiijU%eFExDiCc)BIJ%cLT82mW8o!NfVr;DMswBprt*jt!OaS1MLjJqWtH&;#q zd8*`;Dklm2@dzCqQaB&Sn;4WiiFpg}Y_BIopv=@EtXVKOE({qZSz0@r(+@L(yyBSl?w)A2&dzD-a>1Q37f&6msq>_W@=)B^aM`Q^=t^A9P=RgctMrGL5zv_A359>{eY#c^67S=k*=z)6$nc zSrx=0hby9nYam$6Fy?;+yU|3a)uQ25Q}KOG3%C|J<7uvx&xp?^x5M>#VQ~kus?}nT zZ&jd*(Av*f(I3V)dePZ-M|f)B%ay(OfblOrVfD+;)IIkEs@QRGC7L zqXu7TZO88J^^?3-`(9aa)RgX@R0H3&scdyj2=IW0e8vJcuE*d3S2;di32yF>WpY++aAZ?IHj&oARio>;YimBfkuzl_ zN*Zj9pA2gmn?#R=0^h`6i^*5|3OWf}Sz5zQ(CAzMW8KLh5^QFx9L(W{W(~gdiGX## zeu8355_FIIhZij7<^!8<*>QTcolQ&^jgTe>&n;B0eRl6MDAjRsmc&zTxS z>hW~lV0wRM3^OVoOEvxl;FbCd2mdsc=(_dr4nm>Q?Ye_tr|y9r_zNyKGWdLOFjXGR z2K5BQkU_Vg<@W&^`^t;V7aEZ6@KFB2fgqg!_Ax}~@o;}jA?K8^f(0F%OhW~8cgwHm zV0iQmJUji1KAijoBMeo*?NI{zJII|j%)A3ubL+(v8-%Mj=0WG#X8y&50d)6o4KvFh zMGEzkNZTfdnXK!_wyu<;r0S2n`O_%&Tdcx*dxqjs%_0oG9L6|@819?jH{7n@%-z)A zLRBWo6p~(nMx4B8z5ECoB|nukFJ$7y?rxkIvy1nEILaTm7_a@4W?d&DsCMZMe7Gi) z9DYvaMjXCDYo-Nr+M0zhENnlsyL^u;n?U&biI8=;PR5FHHgvRZ3m&)_Lu%LGqImxf z7zyos-+5|m;eKUOvbQ3Ge%7qcbQL-`6yU)M3F%!N#@^u>JQ3!=lDM5*pmI9(j`ZO+ zn|On|&qii5^|N5v2%$Tssw`>MFR1S-q21nIq}(pcOy4l}WI!wbLFYD}nREqjzW*a+ zC*$Z}pH?UlV7LJ5AX01w?%RkW3f!zt$*)>q^HNtL62;Nu#ibDSV+PY3K7ta)o+K&fQ?P!yHG6#G1!Vo%$r5cgqw6Xq*04uR2J$U9 zDgxhj-^g%u?+U?B!GCqc} zUV-#eyBpJN^x*i^p91K%g)Q{em53hiM5~h-z+Kk?XB!u`)FFs6t4t&>OTA%aNe{1> z*#PEU5$r>+BHPj7!d`w)rP7fiI%rbE?+{gSr#??*#Rj2dchQZ$idymOv;Oc!S)YuB zJJaIleQ-u;EBsubhe7`Ov_0VgZ#FKUWiD<4kH}{JS>O*+I5~wL$4w<&&W3&N7%bjC zKnm972C@*pbwbV;&keg)g;K^gz zK^z#Ixe7_w<8aZ@Ew>0(4P7) zvZ2&f!ziWT4A{p<;>{gvD6XU(b@m+K&mZjq*Mbtfu)>!D?aYLk_b2>kFPLxEShD$} z&ht5wZ<3DVJ({em#x_P}l9$1D@M=z^c3*ocpLqwXH+L|_^|kz_e*#3)=D=jrwCR9a zDiy5!fmY3_*!RqSHe;DP%UXMw%+5qX?Bx_LT|);S|1y#+^?V1pZb1;WP?t5j1J%2% z0-d_EBI990*hYyyO}!pQ?)ICR+QwZ_G(w6B{JQYjkiBroXfV;`W^!BlhHL1RLMNV2jF7Bs%W!_%hVnKzl_ z)GLcEb1f<4Q#~Hs)WA8?FRV3+!>uxA^l{H`5gO>Tf6q?fj6O{?@xDK0D+SOyp?LhM z+K*P2W#AFpL^fzw4y*~@!=CF6#j0y(z}Mt3s;f`O%gXW+exD*OwT!~8X^mWO+MhCQ?@IhAqgEd*8+FSDMb%yakm(>sXa$GCk`1 zi=)WA`c_tg;Qj-SAqrBm3L_VKiC=NahzxdV!A{n(q-e9kOA311p)VAEPRg4}@p zEK#lmx33Sv?)Cn7d&&^zy;VUHd+i0hGgySTr>EgF-vYEX+l|}G`?9g-9(ZJNhRA!K zEseC)g!EP+%X{?=U5adQb;uqp$Zvq~S5{Oryn=K2F_zaZkAa($SBQ3;?L)Svckorb zARx%q;-n=vA<`_KQ;w?Vnr;+=wOKMDBw7KnMn?b-FjYV5ZxhXndB7qYj$r%ylc;xO7-#yi27lj}2Js=ANd40fO5M7O z0%RZJ^R`b+)hLqcM`trH3lFwo$VBolE=Ry;%p_TvW}LXoU#c@^ZAD&e&Wl?1i7(?v zkM(As1HSPqqWnbSe}hrlg&Z)#1Rj04sz zBbkxYNI9WDi_HB?E0@n>1BIW)89>^CsJR)Awf?x?}!!^1zaZgv8@!-_!%QE%z{WSK|99klTIkENpjxzh7L{ZapkFUkKGB=z4YC8z(s z{`3D&Ayxjr@Tjr>Z#+uD{=a|Le<4x-ZF}hdITH2AURV(L?>*WW`fw+i4U`*=<_zbX zf%i8RN=)1bUJ;34zjh)!c)^K&?idc&cAH~L-avM|{Tf7>XG755**Jb>4aA0}@YTf{ zba%`)-tby~Rx^4XWsWPUY#u)abB4?j{+L;?BXzi)`K=8!W8)mQ`eP(c-gKN(Jty=f zqopb7QzGa(u4Wa(4cX#~1io)YA2jX%q4Is=HcA=zQas*18|pVqrqq;Om{`)m&G+bn zwrzC)%I9Iw!Awkw594eslkNTgPNfs#PtdYpk+9sx8{S6>OEN-{Q*0kfhO6RG-fk1j zGt0*rW0wd_;vKlKa2@Aw+mDXcroo@zp?G<58ljm6OIUsYzfY8-$+lZK1HJFy9rlfn z{m~Ea-Am_lK5EkAd>6Fm-*f}Pgu z#VS4(@LuEt@tq0yC%%r$o#(>I^ep8cMSkJ&`g#0V`;#xYb_jOpk7E5hCXi}PmM}6n z%w8X#2jRL0A+u2q{qE?n%IcNWe?$qGy-j4ZmIt#mm8)#0=OZwqd8~d!1r|l6;qyd& zHtk6PKWaohcPR8Sf9`V(M)_WYJpm)Qv!)st?yJidY14_3lhG8SP=10)NtS-W?wY1_i;RlD@31QfnG9y=;j*o{Nu+O?o6Xm z`Xf25A#bsG-DxO3E=6(bP5ALV;idGOOKW00pAw7Y;zAu3{-_6;wn;b}KD3D_JEFt{~QOaNqVMqlevJd_FN- z^x}OAo!a0GTRl9XwWb2crr4pe2g6<0j2Uye4+&$#aKU!K3tnXy+xEFqJ5il9ha#6y ztd8D8{7HAncl;Y@%?9bZqw*>>VS&&nIuW@V>XWuYMS>E$bh{mY?bn0{mrh~fEkE(W z9eE}yVTg@Kh9wNuMFPa8pW1~ zs_>YxKMeoZkDdJ11P<$;Q(((ItY3M8kGV4de+3wE-LfVWlVMMWzw2P9(-AzkOdoH( zcEL}~kUjd{mu;Bz0wmd=xF3V!MvSPtR$%wjt5rarLqtBYTh)68+VZI{q5wyM-YKq%h|bhE&=6x?_j}) z>&WTzFt*nM_BGz;CM8se%F=82rU`2>bWa>iz3K^XE`Aan_ZdSmXWwC2m>YhDQIM;f z1}mkNuurlQh0lqHBfff^JUhspO(+%@7CFHj$Ca4)T?uwgK7hA3J%dMu$3(DDSk}}i zL0jeJf)A|*mnSGgV7WBpKGei5I$yb=?($65>7!Uy^FdTV96f!DK5K((mOl=I9-8_ctuM3?y^*mtr-N?u@2u_6yBR?TF z>uQx{-&S|v7VyTRTlc^r)DF)XUlh<24%e!cL2zy>-v8==W1$}njW0#>x6aIdrarx# z0c`dbOFDe81>8RlL~Zpd0i`iVbdG^#;12lJ+K0Kj zoQ1Yo=IFV*1WwG~1m>$oFy}KdoY(HnARezm(t?Yjx7HI*{psMQ{mX@g#gnjPj0}mg zZ$Q50M*9-e?eK0sa%{vR7_l)CLMAhS8fEIa-^wRP+~udIS>k+~`KUK=yGV7a34bmy zl`~N=s!-i{6nzz@p+m(g{<6hHh>aLXKO76iK`!?zE3{qd&3Yx`O)N><@;qmrx(g4E z@!_JlF);AiU>Y*dmX&pm0lp@IU#lctx#^4u9(|fjS-a&#rH?}??X4*eSY*gTMG{Q1 zUqX)2V$p7wGF-8dxSfk{@iRWX;D0=Ni8gPK@Hy>myu5CW$k^4Gro(r8<=^e7G`z==1h+|*4D(cy#thft;Jj!utT=lRwyK14bNoud zH7^HF?6_YEU+>_H!I!Z6S0)5$>fyt2a^j?=N5pVFktTw zA{GRwu#E%!(P^dy{yFgwKD^uxV?uM`UDq&DRmtVYKb%BYc6`IjzS2xfc^C;V)o7-e z&2r1X2sY^bc(0tgM>wd&Xw#?_-dH`q6lsDS5bZF z4CXwdiftJ>9L6nK%oThzV#ABS@{6A(h%nJYgAE!Rs7iAe$1-K9|L%Qh?%U0w#j<5 z@cknC^yeWaTF5}v_cwf5j~cj%lhAmS4!2!c#90t2fl~XGobT&0sHn?AMe7V+RLkR( z&{7;6W6wv8io(|`>+o}jHO)I^jj}IxabeE|B)YL5eNLZ=!9G8sSUndzs*2FH@um2C zKRFz6;VCXUCFVU>pT^aDo1o(21;(}ALgNHQcId_g)~b?6xmyIu{qgB@QD>8SlyyrZ0oQY%`xnL}goX31Xm z0!j2lQ{cq7fNIlso`E>y+qW!CZ7~OTk`? zIt&{xg8|)I%zbJnpJ#P~7dy{mCYj1?K;9B8IjaN9M+Z}?{W0#|XfL*8^gJ}J3d5rI zR`{2dhlVRo;>N6PIP2$GG+#7BoNQo6COHLcUc(!>8Xd(iov4exO>-yB_;p!0 z$*mqP|FxtEl`denP#W^SiTKsN$NAcopE15tpL}*Us=_GRL?hzG^V-oR`v(&cf<8|Y4#;rk5;%$r&aNHK(jlISGZIF z1H2X3;9E(UkZ8g$5bQi*f^6L8-H*yo9=qv4|0Enxu?!dMf2!0HCBw$SO0eQvEw0kP z&viD&!N=fo+>j#FGuC!M;UMASHNTsmX{?D2w$J%AsY~2~m`AYi;BM%+q|da|E8wbc zH_UyVh+D2lpyy-+CAweFk#< zV*;2;NE2+82`9zn*4(a#so1=GHklf$;lQC&aYRWaDs&{_3ajZ@Hd~H1{I=urf*mnX z>j*Z!dq8W;oUnA|Z(jGc1RfX_g0jmsT zg^t}d{-#_Lwnyl~Eq^_xwN9Vk_@V{1UhSsUm@G~oex7GTgQ)*y87jE9i#i&wVd#8g zcu;pw?48)36J3zT-TpiVA9JQyLt$C&#a9)$buJluPJ`0X^6VB_39|1(W;&{Jy1l9n6r=XE!lwq54k zTlc^NxgI!QuMcs0qe1Gd1zpjLg;j<@6w&(`1N?NjKZ{z#vExFxuw~P+%i%p1o*O|% z$15>0=Mam^8i0O%=fl|Ji%GrEiza6L5*_?tXZOKsF=lAgp|!IDJz9Sl#(Wep)uT&r z(#jQ-`Z=4wTK*NC01j332v;|3Wo}AwxM9(eiA!< zs)(YWjSq^fM zg%iy@`o#vrG0Qe_U~vuCxz!g=XT8F~J~5!0ss)X&ilK0W1KaXMk^3?4l(29?hD9Fp z1BrGm%1&5^ir+WG6rE2{q?-*nJws{u^F}PbD7FunqQQFz9vDf9K3-Dtr}RPH_~oz> z?jvUkaWTj8(NCf7;Wd2y)Ek||hG<#c2tjmEkndNCbu1HL%OAk}Bi&rr!Aty&;IZsx zuYj0mzXQz@LrC?C#whP1kTt!G8XIi+b=TkX)$cAsbLMi^?Gk^f`SWi4T6hN`X8jdc{G(_-1lpq=P4yqicC=%%D#VB8A>COl0qp-vqXbR z$dq{up@9ZNh|09@-&Il}Q=>`=C6Y9cn$G<^&-*^_`>u1&T4$|et-b%^w%B{^`?`MD z_xt%ofah*2QY50lbciWY;d6S_citNMB3{Wx{pV>c#u(O~y@6S8exmeJEBG?298ayN zuC17|9mEn6Xn*=`cD(mInz^-wUla2X8lNg5?WOqIqMt;b=aEz{*0Fbd9I4wxu~V%Y zbk7KpWqNWXPfvpeo{om(x`X86-`Aw`f;dSDSwTM6EGMV#^x)4oa?G}(IB1=vgoQMo zNz+MYPJbw7?o4igls8;dTLiGH5P{S!w#${p|a zLQ4M}QpO3oBwm%_jy3+!ZK#Dk2UV!}3~3tHIs~u3$Z{2;xn#|{W<2sYpLK6DWR08V z!{L-O(72%;GyAsT6-9A+dB7Mot>W0u+G<>@I+^ei_cKB(opC;s$;C{U!lT|2`Z?R2 zrY+V(p2iG3ZS)z>P6jYMM89AvFik^x-u;bh=7&>N8O;~4A^4SQ> z3R0-IO%%P}CqSnZol`==&>k+(h0OR5|J8FLvrCaFR< zYa5Z@Aq(NI{#mHJa19IsK4Qq^2_!_=j2_JP#CoShMs0KvDmK_tzfWHnr*&&U=kP6N zmhx|A>s(Kgr5uj4#IL~|ooBqR=Mng>sGA)uP($Ct>zKB!8FXXOXDo2^#8nb$016ej z@rec9^n42K=#Zx^ZF}jjonlneQWl!U-8Ox^ zZHW(Y+}T5DEAfecad{s0%>DscMXfL>$b!bd67)T1PBYuBSa~gu<9V|~ATLF+{n=ZtK`MzdC2>LiI4Nxi(&LW=Zpa2s5CU{A!& zIpMQu7CCdzjrR5pFd|zMVMVzJ5Rnfs(Or|yT(3_)(r$Pl@(W5@Maa2zC1AN?F}|J5 z$8zaXp8fT$bUrJ?2tDDk3lBNts<0Z4rKW`s8{iz5-|Ti%Is^X2$y$pX~^I!LEKf8xN`5V!hl^h}>U@zWvvEQaUM& z=WQ4AaDyxBvkU0ytTX7pWjfdwd$XsHjpFx%+`VKM$C5ts2NQAyale)>$*cUryx-l3 zYmW|N_T%*!)^Qcy{D{TbayC%){t!m#m=n?9E#Nt~pgz9Li*9Vyr=Ddw{OT#&=$Egu z{5=wv!0p{5rn-9iX0$j8mm zu#k(j|H|_x6ZeJT_vl9E>y%;sEXQsvsQL>c7QH-i zAK77ao|D(5qqub!9%&E9gS{v5*Yj0aTOozZou$$1&mqjuO`;nfUBNwE>`>Hi2D?YF z37yHGkSxf{ z^CNeDb>iT5M`G1j#M* z1N$&syBEJkx}ki%DfP>fqN%IYsn?o3ws}Va6D>TG#2(0DI_Ey1Cru7Re{&e>p**?2 zB9GWU8Nh$Ts<5GLIek5$oLyD7o`ky=VYSsPCg5;AtJY8sGv|pgz14Lf<6sD{SM8ut zIX*PtUOL=a{TM!1RAaB7C(isKLlUQy(qXRV_3NDv+gsnyswx_=Q)RD$)gc224v2wz z>I(}W{y}RgZeDbn&wfolP9IAP({Fz{CjI^xRGzqi?1~|v$}yk~Wz|s1SdO+O2H}e> z-1*&GA)0Kroy<+C!m;^xc@>3OHe`M%3QmeyBSWQNKMf!qu^QHcrJiD-id#aje&; z1+d?H317Fgh6VRG{NJgWWcZ{eP5qJ1PF_C`x7_*!2IA86#{479jHaEKGb%@SDVvgl zd#54Pf?!{L(R-n#}ML4A9&mJzhgc+(GXtReCCM`UL-?>V5bB!l6BXIy5MgySM z={U|hRm09sJHRjB#%D4|-I!ak6KP&w1OD4nj$y+oY~j;8%-z?{)L@b|9(G=a>Ko@k zjL$aQaIO>EP4%gzKpx|+`xsLze#1ZUTg>L(RyHaso~`}PU{uR^Dx@Y#0{`uyQO(!T zayX4=R=tH0GBiN*Pn&oFqw2IizZYXux6%ZQ6fm^DV)HlYH-D?>KBn>QR51K2$mTz& zVz#>1^1DT3;rUc|8vM5uGg~g8hHf)^or^#deia6VmO$hrL0Y}umNoYBL5HFhOaL8W z<=gkL(Jz*P;;=R>eH_S}y!A9Dig@9HLp6AL>#|o6pS`SfU8YHFSK5kb^Vi>C_Xdw_ze8$hF;)|w}b;VEd zlW-_`l~)bT|3o0sm_X2;CY+Zx2St2r;qUioR;aE3@)ulWj8|P_AI5%UtT*QXd)|r! zR~^AeEn{rs@K^L4_l^zi5+;Ll-C&Qb7;bp&iI;|q=$5xiWW2QkJsZ}<p7Ct|X~Aq6=SzRp_b>@&rmeXzG~&_;Ml* z9q)eU{WI3Y9d0sI?XV!7=yVx1cwQ)CRm4h{7ciYw&HTcGHolGBHmHa_hLhfy(BQyG z_Hi-`&$`awg5z`X#>+tDdk&#-@hLZ1!th>=1*9^q=F}Hca1$h`wIs9>XQ2tJh1crYc@!&j#W+ZpgY1g zF*4l$soCl>oC}SCnQE3Kw)Pj=cW`koelH&ToP+San?3h54sXgD(PJmoiPv3avZObh z&HHhThUT5dG}}7H?DR=U@GhX$91p0m@Ch^Xof-A|r9r++7E%?>i!^wpFIGO`aq--6 zY+mpJL%cqK@^(SW=?}@%g5}WJAP2IFJy>$!6H}kI5cKBuL&RB0imTS*nYBM*U48=^ zzEq+=#ng$@eSes}i*UGt1Z=TXrd>S_bkE61^ey|t%}=*dgXI%p!NNFp>wEXjA`ugT4CcnrR_46(RFK;F_D3Pao-3{3A z8(Ewy!I*h;dLA~$m1F(>d9=b!o{B2ZBn=vB^q|>2H1@ZqlQeeF=N5XTbmu9)dPXPP zHI1wNIw_OYSx2x%QI?GCI)viCmEE)09bB#qUwqplico^C4p z-Z6+{dtZj9iz!oiA{LsprxTH~ahz!W6y3j7imj8~i!&AtbL)#oFr-#N@?PyErM+wL zgJS}`8#ALj-Z$f)d_Bl}AWtSOnS`C!#z7wE7C0R837$0c!OhPmPT02I&3Qz9qdWaxdKVmT zr^0WJYutanlkxi-N^1P0@xn$~y8FC09XJ`q1Wt-456^TkvESBF%M2R~63M1%zFX+! z(IoQ3y@TQ}7g`i;Nf&H*&1_02rXQAb^}KO+xc5*3wW+$re2ouB*~7}z)`k!xelt_^ z(G$K1q{3CFr9@yzANHq}u}%j}$&A~_aMxQM5?dz?r+d^=8j%n0D$xeWvFaelVqFqT;_(Bh^fSd0H;*N#63!aD!7yz-JnN^%{(C=x{@in~{&Q0{amoD5Bn2DLOx{Cy+`0y=BF~Z* zmvlB2R$wld`uU#1kZAF@I67qq+gEiBk38|EE3Ze;sBTqyV)P}eCgp`~?_ZJ&Nz3uV zUp-oK=|03hjib$n?z29sGQ?c{1J<9bgI>m$L?`RuxgX}xobwbbTpCEy<|s_GO@$t> z037#RoD_7MlitI^q;%ywwz2gB#7OFq-v$%#%iCG(_Xj#`_--Mxx80a7FBL(^GNG-P z^NAXB3FZ}7(6qA;ph{1Wy;`6TD+QG3ZgE+1Z=nkw8RMq=RkLYE)K0t_lL)5ot3X;> zjLtK+phtE`F_-q}&_>MwC}|1DXU?lwNj$}NJS#%`+bQThGmB*`X2O41;Qn;0QNf%F z?B7&{CwDHRBi+-e*#&7B3m?L|&$m$TVm15T;|v7PO5uldyXBV4vXB@wj}FD$1gjty zwDmtgyG*2@yJRgCsK15F&n+=p`zZ8@T0@xbOc=PDj*%mo@b3F0Qmg8NH_xFVIQ31anxp2?mo!$Fr?>A%W-aa3vaAx4w0O>3MR~Hr(>eNMBmyUO}NS7x*J=_ zH{UJ9JbE+8b9Sd^^V66$Zp-MdN*E?%V~ewb4F~(A!eqvHVus&X15y4 zl8|YAHj>>5tRP497U-W%U89AF!d_3jki7ub{52z$r^?y-_CjW(b1pq8l*MSF6IoEP zgRD!-X7TfODppg)1g(ArzslC2*gP?!C;NhlZgHh61Siq!7JO9e7GUk&tWj#lYHB+n z4fCVkqS*&NzVzOVqV@r_X+|paYZRbLTO}*YP9W#o65zmvLaZp6N!k@4E zCWi{Cu5_zL0;>-8T9q@Km7Dni>d93Z02UOF8#MMl8*VsF}Ze+nKvmC|sp&E%$F+_@Q^#VcSm;O;l!kfJVizK>-iSH$dlLOR$CwVuz2`q{+yk+C2IP8_ z1bqJ{h!^5w2|MtECnZzQ)*L#^Gm>t^TEPU|uxlw<`6Ly#w%&w|zuute-dqUs8%G}x zjWUA^K0({Mb2j@6-0<$mX^<8-VYVx&lK78uIM&+*30(_dhfg}J2%p99;R_R*U5Bv? zPr_?`z^m##ge}u1gN!`v6Z*rrTnr-XN+zO6O&%0qiQsg+Q>gTLO%nT5oyzsSVXa3* zFfeN|+z2g$6umoeGGYV+(#(nDy2)gxaU>PFp+nLJ^~pk?@0g7ulqOE45uJ9-lIbB- z^}9YjF7t!QPj+Uushq=zBgP=Gdo@>pe~7i&Yxo8x>G<={WZJX{$flllc7DYGq)uMT z4xLc|#@UYCKUKl5|MmoapVeVJ)xXyzOghe!(K1KB`c(Lup~{-WE&TCK1!e8+F?0Vg zL_HQ|<$kJ?i(4lX>6$*6Q6)m2@h?H)bum&TdL1_I+RZOIS^^Hfr@?Q!0`{vu!o*LL z!F?nZhi1sKf$?gz;e#@Ln)w6kluB`m0#~LLd52MdhM{%2G`o1q5pwRR0Ntu-j>8;u zLUJ^VF8Q#A%zdLvymF_JlC$gSuH47iuvvjhXiTLVDXNU+h$N`5m18PrdXZfVyqKK( ziEQb!*Ic>q13Wf5LF3J(sY-4f%0BR=i%^Vg*3!qTt~#vFT3?)g$p|DZZRz+qJuv;P z9HVy468?rhVgfnC-Ny(e=E0+>H16&PX8V?C*3@GbP+lgSO!6Sxnm$7Ev+3+UuYK_G zOcH;t!YhbLsb=nRMC&0-&QjQQ5t+@`A*IiOJ`_H{OkHmSy6>-pk@pGkKJSXR3w99w z-IqyU*Lae~C4apPuHfI29Huqs0v_7a1#&H&&=)(4tg+$r&n?bGN_7sCf9W63t#LW3 zY~jk?oh-tvXnOKAva-4IWS3JFFU9gPg#8kxD?irrEmx&5J0|n$9J=(Nt)ZVO>J5ke zexg*yFM@n9`NsU=iVmLY()7N46%-xRqElYm!{i<}+!tE}je+5iqn*#Jzp2f7y|*Fb zO7C(25^nl1IEgvs5YK7vm8mp03GfdshSH-3MD}R_5uGapeFv<_%XC%DdaqAgswUCh z(?nohmln~zo`A9z6N&kbtGK4tf?V5|K&*1&;UIgCn_2+bTA_!J>zu%{){W}etJAm3 zthvO}AzB;x758NwAg}xk$;{6q*xs;|Tr&&A7JWtD0p>ddPP8K4+n00TG#4V|5W!a% ziDV^44)MqS{sYxj+?L;;82c8(jQ@jnb+m_r3*U)nF2>Th0~9 zMBhSwfe+Y^h(p1XMWoVgE-hG{$@B9|CSwB1WGU|@2*2c}9HpY{8KG*7n`X*vYK=hs zG6_=8StBa*b7B4v!s>@CiO=H0{;wm@79|2*E=x#waRk4>ULKZpSF*`g0kHF)J8Sda z5ZMwz$h=v`))eou0G zvhYnQF&}@eRrBYZn1J9z5WMxdf@qISuc;egT%BY z_~c6$xSKez%_r>WGncD)RsSf2Td#$Ee&c{=xewMvE5X%2&RDG&!QOduk{(-e8Wlz? z2%BgOL0md(T6h>n>s$dT?M~WJK7=K;DkR~4H|f|OhF|}&JOi09)c*SsX3PqMgnM7u zJBemgY1s$1;zc$qdNY`e{mdoqeOgq}0?5|`D)iF6QD`e0Pfw{-kp4m;#v|-BV{531 z=S0kC*5OJB(V9pLY_^jnTnpg5$4s(zmKV7kmCw6t@D^jDo0$0r)X3jBVIpH5iPzlZ zP{Kn1KLD}@RS6~wE7T}7l+7J_Y>f7NrS|#2xIdcHq#m_Cz=_n4jN_E zq}*gL`%X9+q>819YOz1#<)=+aiy98P1stcI!pGnl8SdlLpDny#P z;b4#%u+QTt$g5HNogZNQvXeM5`|Iotp_wSDu!#=;tmH>H4cI6f?ZZg>{rL0aOGf2^ zA>QWNUW(pa8K~|y7JV${Yo(j9onMdOolGW| z2ZG3f?C+-Zo(o<1nsQ35w@ z1&L;%Ct1~LM@F6 zOUW*--Jltl3mY`D>2%{M#BlU0TPJb?cdDEPvk4r?XoWV9{;)yl6hr~p4QM*%h?8b2 z)36aj-RHNn&U?ROL#q>$n6sWOb;*UkT!!3f8)H*LRM0Rf0<@&P=)G~Gi@|Ev=Y4wf*eP*|Cr&+zrFOi{M$rYHI(;gPG!X3up22(Z1j;wk02- ztFQQz^)lIvy<{hIZ=?Yi3-4sCzi(y)4ymHJ5XCJkqd-*xaZ+LtW9jYyKSVFGyOUPX zn784`UXNwv|M-ygulr%(+7NHefDc#|ni4lVhJDnmMnp^%NeEMjjX~$|?$7(UIfEe; z-y&cUT*6>-84YtB$-GYo;N2vy{W4~bmZ9ruoxdc}*d~v1R}wIIk0bY)S<5O9Tw{04 zFhZk1&RRYpgv=Sd&fDY0k*qH$6T3uffT%%^GVTL$b&}+)bQ&|>d>WKJn@W=1FR_`a zQ}NzPK8GfaXZ8gA;*6U&am7sqvNkD?Ii(yxt$pRG!`CPf95ABlItH@xdFlnA5O0HiKg@wnC!CMD2Qmdf}0{&NEXqh5a`dR_&y3KIt(HS~6 zXBjj4HX5}jh?B$L7f~IJEIiv(3%mT|$O9X3>bbIznb6+N_6Ww(A#7#u&SwF`#AwG@ zE)4usqEoI&(u2#&@l5n#8sx)=bLPL8gV|+xsp%yw9(RH3fQn!gTC^?+=%p z%xKqP3-%zo(DHbW&d%-ebnMq)T5tmSb&0dPE^@&fZvCcFeH2#SRwSOo@^sO-M#k`? zKAjg~Ozo2%L*ony`qk_S??CD=4z$37TYO0xwIh^N&W+-aZ}w(wZ@dD}qb6j#pb9m4 z$`zUO4^m^Pznq(0KyFoXtLupii#|wCtNug=TBKuHq{m0E_{RG2c4<+-T<1nO$tu`77IaNdW?DnTF*(nQq|B5hJN}jN99lDZ*hm7Sra)VS4sB0SBvRUcaL=?+c)+z?I@10ExvEIT4PtPy z$vyVjJ$rPw{K)n`FsD04W{?~`Q?@6gk-70)juuwS(J*ysVlARZT1K20VbOM+&Y4h0 zmFsYzltFRvxpb0u5&p6jCg~-6py4aQ<)5U`udo;Q9|*?KYn`zE_IZ3;Do1@THu9Vc zH0Vx;3(!gQsK_$|`aLcmRV<&g&zBd{aZi@R#VSQcvmlZQ_n!y+-7!@CU@z`2`hkBg z$Wm=f8|v3{0FB-9F{|AWU6dtpm`nG(@t;Ef!Ai1h;3ec;Zesk533buCiMz))vy%pN zpxtjgs`^P#^DX*dpt%v7?Y6-5ck#equg)}m7NCMo7f@W%l4QCP_~x*N1abF{o#OFq ziF5=Qg-)kO?Y`ie94_&Z;{mt4C-U}A{ms<&?WXnF|1kXMZjd1{#AYxRKSgkJgX#)& z&|FD`BZYY86PbIRy zc2;2XTJ`w#6{%2Ca2jVWizD(z2>_7WT~ZWcCxcN0%%Pf{u69xF}*7^_J0xeHJQUuqOcuZ;hk7UIox4 zbvm>`V-XcQ*9j-<0`QM)F-(&!W@HRFfSPtC{NYN>L;KhAny!{`U}7;6d4WrAdFCNs zI0hH+oY1Cp5t&}4K#xv8!(X)g6kJG;h1b2kknuPLU7k3C$eBJodG-P3WFDt?31@H0 zQfI_o7Q#5iDKtS)i~eb4L4q?2Drn2o0&QVBMJ5w=CLAD6^AVahDvs>eM*9DEz{wB_IzTMFG7;IBwoF@5NhZU z@}eglJ%yd&PL4g4UClv>o^&|F*P{)x9LS;jDI?NQ1L`-wqs()2vhM6mGGKZPtXukF zv@@B#m{iG*%i95qhDu?b{ux{zC`~MOIl!>)X0)vt$BU54WvtA^NKmvS7VdrlBZ9?j z`d~Mk`0^bNwA{y%!dbLv^acN5eiG~nRw71?e#H3N)!8Yjsl;S+5mP%!lGwJ^f#y;{ zl9jJS3#1pZ#^I~Tp1Kp<5qt{k?(WD|^q<27zZc|wx*CqRy3TlfiJ{e3W0~CpVa&hH zhIn9;J#F&Y%E~GI<(e2$#Ls6TJuvSCgaoy)=Z)u)1Gf9YWVi;Jt7FKQ=(WuKC3RRB z*N1l9ZZzr8=K6qiX(I9UF5~q%1g>{T(DIjkxGpgZqm2qM_Dwd`HIBjAb{TwO6Fp-6 zdJ4TPo(E=^Te!q)16J1@qHfx6K~}O4<~HqQ_TRjT--IR-t>2o=laY8_q|*bn%z3o% zdx~1NbMW1UP#=H#x#*{?H+^BYa_#;6H5F=2cq zsco#CRX5);5ixx35_S~_eX{;%MY7XJAoU#wf}OR3WQ|K8cc$%tU~V3;O>hoTsQwKb zmRDe?>QcIL*8soeL>+E-GN7mD9Y9O-bZD#S!>W>%P}WimSFWAMoz|~0#C{j8c)5;Q z@WL0=mGi0b!%TYamQy8@*FLL;x0C_X81+x?K*xT2|=$~qF>XfXC(e~Bo z)=|PpZ~Y5BB!HIc^4SSOql{c%J9N1Mot-d=mh(2y(uZX>uMC7h!)GGd&}2@m0Y;_^5|3qrE@(fR0{5D(uL5|9PzK@1CGf`&Hg=^9+1%CSq znrpv=oDiDJbWFL!wX>$7!c0kWy+s+aTPNEFIZhiI>0dbK~K3g|A>#xrX3a)OtoTeH^rys8U1qT=;AD6Q_Q^4$u1Iq2h=wR&B3@ z(1rJz$hR)wnX3+t1vaGhh5!U|4+-7r^wm~S##byRO(D3mM5WJ7D$21d}jfKbX z-8WkT%UtNmq)}|!ah@HT^%{TOh$es5%%dxGvZ-m|16Z7IMW)8iq$`g-g)31ubk5X0 zP*9h}L@(o$k_{6uJ$w#%+m_FyyGoIfig0M$Od)s9Ie5J;77mDiC)3p2L8h$(jjsU> z6PLh;QxdtEcozn$nt;L18(3y=7B9IrVDaiS>N9@^StRSjgj8x1>0oD)zA>1XZEhd~ zmiHO{+c7+-6b&J#49I7(<>cNoYkb6+cICchk*%SRaL>eeu0c^l92OL?;m_n4AF(&A z{6`(e=+aMIyr%=xBp)!c=R=t~p{2M`K!hp{=5g;!CD!Ib7n!{>p6s$6V--{RX!5AL zzSFUUPIa{>s3$#8$;0diBoX z@K#0e<~Oqc0d}128_gcFIt8s9#BG_V5@%n20FAfZ$>qvX=5pgWa%l1s7(JH_XV?A% ziB>)uo%AJEvn{w(AYl1(hOa!{8!kFz;o^b0#LTstGX$qW_}^hH%bf;F3U9zSO_3z* z6|bKj;zi4@SE0N~H*U;aj8@6FfNnbg>%WMS$}{D7%Uc&OxyjKSnepUU!7jq7yLt3a zG8}PEWsa+;(8uzPWGvhZ97axIk`ZU8JDrY38#m(e0AuQV#+lBHeZ?qy#{%^|%BA|v zsC$bZeO&he60KB8K;#1q{W!ujugYeImz*W0QzEgcAeKbh*b?_uFSz~60>~a&%YXmP zk8DrRfS!wO=y>)XfA@<^pz(YuX)zX}Kd;8nkgk(x`)C_|^z=FUN?bzOPl|LjNR)jT zxgUo7FQRr>8@@S_fTveJf*Ue&@XqcEzJKP0%SU4QE|y`qZRra3c_@L&b#i2>!6xi% z-vH4ax){*Ch)$W9j%gR7Xv8EDA~iUH;m=$KSuM6)OhE$gAC92PrC~H?p)u7_(O}n( ziV|sYijJ#xlCQod(A&j= zII|~;S-PN%_2Z-#I@ALOCbNu3*9nN3s6)b4y{PHjM63*6McUmtNYKSFW@*Y_(CCPz zN9J|lVGh*i@l28$B*l{W^Zg9%CSYF587BRvg2h`~91NRCul@^1E3+_mD1SbLxT!H3 zi#e!cyCLk69AG7kxp{9}IIZ|<28&Ik=&$iRXx*I*@+jaq3`@2$H*0KoX2}A)cNH~| zYOsbd`}U%kn=siS7KI1v1&F+k1Psi5%RY`ZB`XSCIUz|rvn*;D+aylG0#S3E_A!>| z)d%Cnd-w4nc?xW?bRxx@$ zQH%&XoMz7Jrn4(o@MyAvAvIgAOK)u-WCsdj>YeXBg3|*wB=Y7O*jY0Le_uRJUY0Q^7 ztmN)e6d%-qqe|(_$}t}_DwzNbFOo5sG>?52$_Y_^Co#OcV%S{G!`bSynduwf;dimw zv?`E7*iZtD*Agb{=@q2&)k*zjXd<5NZu=*1E!*#v(23$OO}Zf1*P~O>`lJO~J~JQzx7wIO^BiWdnxO_?fAL<8uEb>1j}Yej z4X0Qp(vPqN^(Ksg{sV4a&OwN;#3#XAcS8RK-hc(=m;^nL*{T(*jCYgvGELNB77vJ@{?trwLSzCc5+B^4!SM&%|5f?22oeGpjA z0rFF5Y}QNgzCa+u!GTsR6{pu*e!xc2Qw&pa2NFZtz>_qC-F+!i@J$;eGY`{q0h{R8 z5oh%6n?igCB=N}<1$tmyE0iytL{w|$puxBX*5LRudTnqf#kUS*33tA7WcwVv;9?4@ z{wFY>vrAVU5VNTYd5Ct#=h)|pi$VWPJ-hN{8rf?w4`1%8z-eK8%sci1L;dFw%aSfm zs-wofLoX2zN&#jstt4Gx1B0A9MLz1d7i1f{9nwl1-aM;ZBt-89L4fe)K<9ZH_OQTbKYdSKr3_ zDr?x#^k}A~?>PN0tKak|6Uf~0i%DF{6ta+8Fw&84j;E#nBjB+Ka!@U-UE2^imhOb!sVj$1%QhIdI3S%Y0)0eIYeF z@)wr;(1JA_i?O&(hAq*)#+Y!T)MM(m;XztA)Jh_XB#F@T+gTiI+(w6nSHu1z)0vtU zL7LoagxY&+k-RIwv%Nj+>q-+^R`i}H>^X_vO_;~H?v8^UW69vqUiIM_u4R+&*;LV2C5XZZe`APc}qekUr-?P0j1_q4-4}V>Q|Y z&oeo{pNko>4=;!4I4kg8c#XfmbRuyS{)OK1wzTF(3+g@)WFwbZ zeN`3&5`_gMgqH*dRZ^(lya%)HB{kqJ{aJJ+TS6Gsn{4rBIcjaBP2R+u0(wG;Y@eAA zFXwvEGk?-q^}aJWJXnXS0fO|s{Rh0FcM7bf?_p#~3vNu*WmEfiamBhu)_(Z~47!(t z_tQ9!QTzm&AoBv2e&~h`T)Zqd^)g#Ds}$B$WHN@|qv#^zV5llHgW@7-m^pPm6qd~; zyZ*?7sPit!tLnrbF?O&aU6cN7#7AJ!k?Z0@U+`0#%5sxj9YOJob+?p zp04rKqVW^xcx2HZzmu_1$epn)TuN63wUMsJGIZP#TXJmLT~e~$3@j2}kcHVCU~5Gi z><>tVloJa;^J6UalUYOV`3I8w#$zyj)Q42}7!%iwJe0li7zT=(s6b6KObqeBzrnTG zm&zTxc>Fi9Qos1s$kvF{K9N_o!u(t9wZ`^*X^qPilav-826FX=ma0`z>^Ds}sIi_=W#tODa^? zp25PmHEeV=Ct1F(Ma#Kj=Ud@cSf?vTyS}|ZiAhq_`uwUpZlPK>_*H?;@S@T=*^S@`<^Ff{nnu~(@h#uMQ{v98- z9%nl072&kK4}Dn%q%A%Q9RuHBxdL~~6fVNPzenK9Mk~%6IS-=mYvb87#G^kD!r~Q3 zS!z9-cC>^P3+jQ$1$)r%GsiuLOsG<@HXY)k9tAPAynV!^Ztb}Wu8dp2Y-^1oVwRok zFW*64Nd0GMBsn0Igo@iNcd{;HxW$ zamV5rv=2<5EyM8=(?Qs39XPp{@$@+0Rp;+kc5A^jRD2gm&5|nEYrS7_Cs!)}sI7*b z1{TcOc5X~NCQf=XLwUo~-!h-{+u-7NC9wYJNJHPh#&zvW30)HoF7Z|D&eCQ$?>>>9 zyy4Fjy{^K!ZyrOc$8}aCfWmBi5=+28X0* zCvKo}LuR}ihVG16*&{}!^D?tJD+R4)a-b81?%C5@D)^ii0|M(`qoJHR)j6MmdT(dT%$PhZAd=Jr7<(X-X1F(wRi- zo_&Cx{4Sh4s!F%>j`JT|yOWf_-NeqXn7*qkV2);=V~#x=h4fTUnsISAtG8nh&E`HA zHucpqi~dMZ_YZu?bWK6?fB;Tjo&mNx3u#o;5&RQ%36vikqvByQtnA!etg#g$kFS^D z?s|FpY!L@+QOrhTt;bMyM~gLtvk(v(4DOyv9249dclh(@X~i_Ez!f)o%n!iR`U;YI zBAg{u6Q`anX8ycVqtL_hFYvjeQpc`_bUn?8YR`+hd?vne%)2=rD~pFcw~GzR!L{W;KqmGf9x8l+sWddgQ3tArG*hmyNHs*Tde;54D2N*;ZCsv zs?yj=oF}xfquOa;!#8A@vR-&%CJY7#Hsi&~3*nW6B@u|J#3t9<@RlpAh^QtJAwfav zyx5AyjjkbAOX7F~AD^+|k(0@ioA)6^ISapC=)v9=BZ#>{a4_!%ICVF`Qj0S1mzjY& zRX>@|OR=#2&TVF-pb0){uVlB!aItCaOYF8?8Q{Tr%dU5EM|_b5`0T_th(9%(ep^2q zc9c(KhN~SRcH1l}v2_MrGWi=++Wlj^Me>k{MF~EchwNMfvdg=iJZ=fVl3+e_;ZYa+*Tx)v)(WyW-t2{Yl2bYV zqz}jBje=8R8SwhNC<*RVC)2sY{+r*rM0tTGwpKrf|BJLYkESY)`+rg9S*A>7j7Y|c zvp-)`r9y)wibgU-G^jM1B15JOMad8=UX&sl1g(*NSdX&q`U8Z?(^K|K6kBq z?^?hA*=IS<+Gl@1pZELqYVwL z?ZrKU&oM~%58i82AReoCqDoso%fFinw|&CVx9UDRagdPn^%v0S>MFGQ)5qG2%ah$E zBJ_&FC3b503Tw`0YBz z^xz8^M;z$9Ks{W%Z6WcQDvE#hM}VqMJF_5&i{c1x!DYi*w5Uavak)AlF1UJN;!-c# z$uETdLI-BqYEyb5S z!v`OEUkc6G_iBL<8KejAw!4C9pDKOIzsLMu`V)#Q%E8N`1FS~0$&7e$GF5giBOuX; zXO3kt@(PpCt)45^hhAl`a>sZD&dXbc)v(^{IMx04fW0sK8{AzRSaBH}rg8N-m@k@% zV{<~`ak3KyISX2H{}jG*l*K~+uxO$h*j|_C1e# zO!Dbxzln5pnjBf`w1E}wJdL4$jB%yjWNQCH4bvSXiOzEal6l+@w9c52P2?zjeajEr zmp5||5pMNZ#@(NpE_SP=2Mp37JQO$pts{$Zf9W*nyR{o@Tc)!^Ixb);BEdQe%Mh2J zy_hDHOPcwf^hBaOd#XksOs)*$U~mK!u~KAEvyg7Rs!DlpVvs(r1sCYS)uM*9U{NB^ z|0*|L2$3Q$N_L~fG)+?A8%~$ps>gyu;$-=8MRL+~20b;|lVtW-aJwuuvZ!Yz<7U1Q zl*6Av+?W>KQ|$wL-MIfv(kZO^n2mZ(0pzo#K3ShGMRxv`rI(`tg+e~zXRZkQai|_o z?MMdY#Si$#ZhtUvT@9!eTw^Y7l_K6M7udsmu5R(}Jly5ZW2VkB#D4f6PT60|GiiDS z*FGV8E>40t=J{aF`6uvV8V8sgt!6%k4FMeGJ^@`raCXsih)czQHJED^YOsfVqI{Em0s%1}q_GA3rPp>|4t@nVn;v*Efw73aoXF5TN`CkOqhmfFij zEOHt9?a8PfuStjYH{xbfE%r!xBW%>=z1HN5lP_-5|5jjeh<&%sxBd3O3KCqN7MJ=9w=e_r1?E8^S(f z@iS}O?)eA3)Gp$gHx7(+tq^&2c^Ug8Fobh#D)Xt(EO7O{U{m9A8@mD}@w8eT4!54g zwI5aK!w4->B<{vU&8R`!dDmF$EK3adXh`Oydj#C%giI`}bG(baoa~L? zKZ~&K{<~oNg}*p2qFd7gsC>pU5`D}YTKXL^ zp?eLTFvApSUNAmaii28umkFM0L49IoQ%+{Us_f5ze@E6+Z?WBEsonzm{PuD7jD9ow zBJVoRY>P>d*_LN8s4IP8QjZY#Ik&2!9_!MAwOs3s^wjg~-wN#ge2+ zI1i^P>(jY8X3XI!BJ}Xqqs$r^A!4yumz~zw0f8;|Q0Cwca(IwHMW!w?O_oID<1u`D z*cG(jJ!LOUcEO0IJlZ(HhmujztsQvsVLT{t zpyfucUa|2_2>3a1k(@2#iPw+=)d)V$J}OH`-IsfDD0oH~uPRhSaDO?R03%PW|z zQG$F%W`KWb=_3r{K!fjB6ykUXhF>9QLL~GL@c(qjk*If*h}38jQMu9te#R+0+$v0& ztc&0Cq#x+-=Y7&d{of<$efeE454j%VWUSJT`MCF25I-OMuW#H zFZ_lnZDGh3hH}0i12Q2=jOgWV!h=no$eR>}8&xgoxA&>UZs#UEB6kK}qvH+Z?RyXskVoOc8QOdPKGH9qIswLUNZ|CIgi4|JSL`;RW4 zTmWpnj2hKj8$%^WQ&8%_8-SJar2cjle7f}$uc`s(=kX+|y8x|sMUuy6LQuC#k*(jj znW#j~hL>Br*m>tu$eq$5d>|Z0eymcXbK_*lGIs$o%P@vpr>T>eI#W9S{X9JDYD%iT z7EygY3!HmRohW+vq3Gl|;yW&f4K5A`QM(uT(&aQ{tB8S(!#v{4sKdhkKzi+`JeoV` z@uix8lEpUgGGa0PJCm!ZEs4g^Zgu=trokHy^{{o~VmZw5BrFoE!E-0?!$d}ogY#U* z4px_|zg)qp+gilHxR4mxJZ5F;_Oq=_D}H>slWmz^2%0%kbW(W_BQ$k6@fDXKF%}15 zN9IP>v^50mK7s#04b%{B5eW;W(;u5wLR&)$o^dWQjyBW5msc=}!BFG?5u$Zb{@| zyKF7=N#^16n_0HDH&)?M!VT<;zQG@^x?y|ZItm-?M>-`3WqM{414k1w?;hu= z?AC|lLiH>sqs6i}9X$Tg1ZMr;mvDM>88a_`n3Z06l)B7GWZ&kB(J6P|viGj@+3Ew) zWV>M!TAjI#VQ2MtLbY;)r&o*?*+1ADY!Mr-m5(htXP7^A%jqqdV9fh0jIGZSaGmUJ zTy@Ndn&icz+Rb(d(lVj>mv2GnkPx>94Zwo@XgXoh2po;p15K4YI7O!th&6z|y)v}7 zJroD#?Z!3z-sI=00(#cY4SxUWgr&7}$jo&WZ0?dPXw**V_bd09DYurO{>)k!%{QUb z7HN|kL4+8_=0M*-6bwFD3)U+ZlH=Rz;e^v_DByRoKeGx^kb}5CzN3PNHjFY(2E)wM zXlH7xxtXj;SWawIj)T^Dc`{+f52(E>Nf&yZ0Tb6VIJf>OC>K5Fy-9V0x_?3t6(CNI z^h_oLM_mc~{TJ^}c?j4#MPt|l6Z%O&nBB?=B|i6y5V+jO%||?G`~+DN;l7$yALm@z zH)n#+oD5i1^9tf+#L48j>ln2Y53uV_IHuTG;ju6kTI_F$4bGPe>&tuG{UnxDUi}{MctdtXpY1%D#o6I%Hs2&yiJ45{_zjre?QLd zv#Mvz6)o7XN%M%ULJX1<;`sW!4#;zY4&iWZx+go7EIaTP#~5Kq-+YfX{!&WXy)wyj z$0P8^V+2}?8_+1=06FXLNUVGfQ9gYdxw0@3cg6TaU#KKWZd^`2&C6j1(^W|A>Mr~h zU`7rb2$Qka4xAJ41^t)mK=tJBsJ_VrE6n~PZ?Zi-#vEgJH>6OZgR=A~n!;R#Ynb0y z$N}t*qSE~FbTFw5PcWNl_^(r3q|A^AecFYx1J-oP4KC6#_7>^X4rVI{T#>A*fQ(9A z>f>C&fBDN8s;V^DgQORh?vSMg(c?k;UlnRt-Q;b$l@D&VGPwSYJ$2dbL-55>azsM`|%%`V@lcnieSE7;=JxH(J*p52s*cQqP(pcxsuuk?=LE0(Z6MIM=zf>DJ)|>r8B_g z#a*~@DIUhpi^F4;66CQjCtQfKhW+E(=w%c@`#rrx0?)(b z-e34C(TK@Tb0;sJRpa{8sw8H=K3-ZROkKyW;{CbDDCt{9PI5ICKS5#2=AXlTHFH7s z#xt-KvB!xS5+q1>9h}|3XY^-@Q_VHbOpA#Vl(x>oedVM0bJYY47f)d%`X{sb)$>4O zX$?-~QsB6uQo$@d1M^jYL9 zJZ6TLrQq`gotR=>1jS}c(PUB`X?*dGjkoLKqyUwuGEa^=PiaA3oHp5Z2ADYGt>84@ z0h$9Vz&d{zzXT+pUCb~q^h_#Sb61>LEZ3)oo%O7TSrGQm*#T+B(l8;Une%?yK*`8s zNK==lf5Tdl8L?x#EzJ1-Go_eY9o)W6J`~&+FJ`?CwV?PUUr3r*$$_L&@z2L2n5%FF z!)P6PnPg$t<%euWvUq0JZNE0+W_Ep!cQ$iqfL7 zbJi{#{uhr6m#+n1$8yY^G@s0uaAY^^t;aV$-c-1y3mW#X=kwzOn8HVTRIJyBI;uH< z*oB+mk<$WyPOYbYhW8-A83I7m*ng?^hPTvxP-xrd( z_BK?KQpRq5BOB&FRk*kP$ zb|#uLFYvBbDuyzX=q;BxR$!k9+q~ukdKSskv7pJ|w(kTUe#AlAguFO+;SAXCc7?Un zehYAK4^5Yuf~3d1Wmd%&axOp}Y}O;A5-^C4V)^(I1<39eFJc;b6f6d>+e}*!%=6^$ zWxtQSWE^fg;{lzS)Xgl7d>x+&@>};4kLTmb8g)^s9i_EOTrYEL`0by4SqD;f7=HufH`;5|{cWIMB+=nH!*$Q0|sr`P@2 zxHT5|^xl^;$*n=LZjMD;w{#?>Q_?t;Hpy}4bH8F7p} z4;P3J&DjF9UGOM8R!k#Zj>mD!-+DOu*cXnEbLLGiI}ZB`{m{oW47`W=Na2UcrbBmoVNtk6cZ3quc8eND*TM z?s91u=(7$?X0*b~(6hMdND(d>-9!{Sx-ffn6T~ij42tt5nX>PqaKPps(>lqFZrFJQ zR__XiI{q7`g!>*1_G&^knP<>-VLgfX5rsPsB;bR2sbsIgOV;aAJe6O0oe7H^Vr#3{ zVd8l~@}$v{DlJ^j7t!m%iRYVn!#2+_(tbK#_l;rymYRdn^H^fxe~Y`<6f=s0X;}PN z3Y?C~;@kbeG#E?Z`Fkgj442?fC9bmO-HlJO<*2arBQ{9r4n9j@(W3b;H}B+tl${UZ z?|Tsz&F$$cu7-S8Z4b1oufeTb$3fxAcBcBpB&K&x6|?l23pz8=@E?(=35#o~p58=k zyLK6;AG(S^Vq58B?LfMnF(zXBtwE|unVz)1ju#a)Xs>k$4er}crPk%q*Sh(1_1lSb zYM{jbj)vkWQ2&Xk`j14E%>N70>A%8K|1H1dDEVJk`OmP_|3p;<{7+Ps#s3{uC9XPw zLsiMz{`V{WPgvD|{mOs7$o~hdYQ}%hV*SSp$o#B?0?r}V04#hw3`Y>;U{Fzq%Vm)f)DhRv0htT(rDb;9eh8wo$7+Y&| zmY*7gTc?K6mIGqs!iXI;5!noG&%&r-auBZ78*P!gngaa1VTf6h%naJH_nNJouPAJAbBtSCdUzAm<{NZY(rXJC!i~*bV%KMh>ZP~qx;V<2CdBN zxcONbMrYfQwC`MiHLL|^L=?l|)5%o**&E`e6#(vn*O43zXXW<@(Kpt0a9%hcAJ#oV znyvJDhN1gfh3$e+gpSPC@Ub6z0zJ*X*J6a>o9;Cb>Yg=$g$(=qpJD`Z6&Ke%APs zO?!e7E4<*=y2*6$_alts?i;Mt{I9s|gB+dEodLyTv+>pPiKyVyz|QGPr6X4|XzAu@ zWJdL7)QUVy>Vz8L-<#)9p&~{Z&i4F3yabl2W?_@s4D#`SCRAS5B(+5cS#=jdUR2u} zjB`^XgYI>ByTz0)++5A?Z`nvQhaZ6PGkx6qqm`Yn9m=E?>hhm;Sul1f(sb%eKHl*% zq>IyDL)aP*o^R6+GjRKfvlD*#2dcBwzy=jIGaf3c5FlMRqyBq?eS<3?Q84Yf%tA! zA+#*YB&*9CP-Brgxi7d3t=1m|%_FKbEbs=*s^H3%fh))vf$z{B9LXH!Hq@KniPF`H zAJ~$rY*?yUPtvDNCavi&SUIV5yzJagwg%Y}Ie!7N>|zIVe`_R85?3cX>Qfn6@g`>O z+ZnKTl`rg7)MbSfk1=BL@??2s56f<^W~2qOTMM2x!nMCjcyC8I2U%)h6Yg(eRaF+C zsGB;(e4}uCP^0y7QyO`6aTvz^O{BUdaeV#o?c|k10dDSCi$P5fnG^qhu^Mv&$?2?8 zQdw5P)+*|fl}-yt)}KREL}eP7#9QLTuwV$eK14T+*CJmncr<6z0&4K1iGMcIoxGG9 zg_maQ16dK#YXKtI<`_ zozAYbVg6mSC+)|Uf$5ig5LC-R;ZAG1VS*<8b*+van6ZbF%hf2%X2J7w(|HqbbduaV z*_eI29-sNn$IOCK81P*{uZ-;l+5WQ}_B$0|=3|>}YyZHnb5U5YzKL|--i)Ioq1ZG2 zJ#0R}1?@YguznL6=suW%`$FzuoJ0y;H7H1CD)D3kiDC z&L+jC;Pm_t7#Lpxp2Ar;V~sfZv(rr4H?#_hW#h)Q(I)~FX{s9+vbH$%M@8N;4 z1(~ZZPop(ob5>(pVs}uE7zvc(^iW|;dv+A+BIm+yotMl|dMZ@D(V?fxG%=%T2h0!e zhNK%;m?6&;-iaRzX>;>!?Bz-uSI4+-@zV$3j>=Ykf9nWyU-TgOpPq{$q5x|&;*n1L z#aLdI#Jjf$SvL3`D~knb;*M6l7W=8!20B`1-s-&LXI%1nk=o=Sb$Y4rGKN0MP&f`&>@ary6~ zaAMVTn&W>H?%lisLyn?E_0U^1|8@}WtmuVVq4ObfsSlHSQh^*+EG1>U6(ni%Vf6H! zKvI^o=)sq#<6^~8yf_ex3SyzaRiA|Q7E*`1f5|y}4$0kD$LN&n!v1Iz{QBCREPQtZ zHLaVWAhQvSzV8B4-2xKtb`nj5E3l75kyO!sh%lBQ5B3YQzhml`tN`>;W60H;L^!r+2fUq~_W-_? znhuY1jG*?+D(GJ840RW}!T3rsyxMt!3EN?d68A#rjz@BExNidC|LtJ}mWM+ZJD<5$ zncS+BVL@jen95(Db`xxhTVO2*lxj0xPt`aSIXjLkV8?LV$D_H>-{K8+^QGCC1;Vi9 z{RZA(kQ+8UIL{c06)_g?+IU<4%pgxASHhm76Ue6nM3nx->;UH3&F&P`g+Q^NoD$JV99I9x!6@S;fg@*jibScYC@;b#K z-^85OHrC>`xeB!Kcq@9i=TSwKG8!WBf|0tlA6n*!g3%poSoQoJ%v4mvE6XO5`QJQ= zE5nlD)?kH@+gVm)LhcN;vECFsjagJf22aS3t+2W}J7hf%JAg!;QKzxKLme zEX88UxXyUYHtd2G3fpk>&NUd}0FduGCGgo5Yi6reGbo&BZ)vTTW_2^fNLo=1xUG4_ z6Wv~q_YGP0pOOZw(-WrN=u3>Acf+MU7m4AZFFjYTNfVuA*i6kX=)E`@WvgGZCPBe8 zdto2k(j8zlFV>Kz!gzGfPh=-rn)9`81kiPlWFh=Dk6f$NqW+_N5Wf3~S9B-}pKhE- z#Xi?S@JC5{H+2VdG{%vR%aNcB+PC12PbPgl?<)IPGn)?w~nLrpdMM-R}H0GK7fyhAyE+82l5MT$#?&5rf%p9bEzg8-v@AII_~uz z^=Hz&1#uug!IS2!V5n_;2Kl3qP4lltz=u!rxUEx$WeuLf*N6^pmDQGpGg+bltkYZ#(1%nhxf8H&AoMQ_{-?N~V zH{+*}j&j9_@j{yEstYFvSU+ z-cUaGEL$_iB^5dS&$8okAZvY$d+eG@o5l=@cHBk0Y+A*<(srh4hx4F+a65chlMEXR zzk+w508H`Qg?WED-H_vY2n`XZ`_+yy3tw->{tSK)Z+z#y*Av%@vVe-q*H^FjTjDA9cSkI+5A%!~VP zxqM9`xp`s*k+?peu5y{qX-W5y55m9Tr$sG}%_<=)+Z7n=7-jm|*op3ReNG<*Tt*G+ zK=#jeU7Y=%Q?kcN7n9$i~;4R$6QE zcv9IUO||j@X=_U?RSL~vC$@&O_vZ@mSNCy~2DQ0l1zUob*M-5?b&v4a4pr(lc^)aK zTY!i5^&%WfB;y4&$+gw<$&$;~l+F~Q*A9H;dvtE(KvOm#A-|X!)tiH+of>UQRD{2; zkI;qlW#G%_cz)Kpli0Vw3vY3o@0RR1NG&^wyH>9wA@$PpG>PHsUKJNnAz2cu({yC~OV#{McTgZR&4MxU50Y!l;PVk<3)ok2HB%y|Lh<*RtI z8}l$TS&4Pa%_T2pA*NqG3>A|Tp=_`hUqva>xIcx=l!td=anv2i`1^(tpKe4cn}hxr zoBTMV7<_rsYMXLIgTC3urGu`Y#`zVY5H27{@|xO__wh92FOop>KJ3SLONQXn z&e@!%Dvny$+tbQG@KbniEKTEs)+YddmuNh&$8N0IDqlcYvb0YuEpj6Cb< z#uaiGpkt;v9h`9+w6;CR4Ck+?tM`%5pXf)lIz7=>BM+}S7vqaZXGviDBru-?^o>jj zb{Q5h2T$ZMu2LgR$;bm{=~QhJsxuE}`|IE>#U1#^$b7LghhB$%p0 zm+@6`5j(~`ulb=%N8z9LO1$f95W z^5~1@3GAI*OD2LH1-_aXd!ThKX3EIX+*}c={=tE4UVIQ%y}AQ`Hs8dcX%X;s>Mz#T z^dPf%_!``t5gZ!I)?pY&b&R&p(Ls%4{Dv$ zsY!YuU7*Xs{^SF&;krF~f9JHh2B!g4RzlI@4$R-LL=`%Y(o&m8_&)LoIG839>vv`p z=8nKSW(#HZtU&FfoJN^3AWj~H6_zfbS0l2(MSV5?@S2BaedlT1m3Z2yF%_-(7cgL( zAiM~8jJ}6<@ui(uJXLQ@`)LEz_vn(n${P6M&ujLu##;Q7EJ+TftI+R#&Sb*BudHE8 z82S1p5~r^4Cb9D?xeaV4WiBS;8wG39w?K&2e$jvd?NvA}_6YX;^M$5$7g(wCy+GJk zWSxZ>sd#=D-Z+So4Kn2@;qep8gQgNC4F`JYUkMZS-@;g|iqC`PGuyy$xU+S>pEe3gcEcH^2{^IEgPZIM!CU=T%&)qG z7(a9sJ?`x!T|M&TP0n$azl_gLP}##q9ef0_qsvK!wHf&kql;zTTj)>wO7#3)jsgjJ zSav6k8jUN#o^zRa=Z%8E{qBfD4&k@GBvxw~IOpw^v4+`h%*_X#WsApO> zGbpSM(Vvtt`KvONRUf36+{TmUXK~~})>+Uu?8kif6r9T*hZRDzn2Bo=q3DSt&sNw2 zXRi$-BHR{PDCQMwT6BX=6@LZZZpQrJBc9;QshI||=TQZP-6YX25US24LFSDz2(sIQ z@t3)K^|W-JCbxl7KPf~f>15->92FePok7GGO(uh7ZRFqJNk%|tJiOeXLJTz}sXsfP zgbMl7&r^=jkeSIK-jPBN#c-gQv@R&rILz*i55QI?olJ^QC1tChv%zn=p$j!>k6S0c zei2NH-*?-te$m(mAA6hRB{hV*+Jymo~il#6CBJxsx74kkhy z>nIIYfG_U`=@SD@`mEqHUF0_c6|Y>$Iig9#+zyi22IlPJ6|&eN`jN3dGRm0VJ4`$u zdh-I!x^dFP4OBm}5ZXmngY~IvIM;d&5pZi_-4a%!*L8XHahglH;W243IY7qi7J!y{ zC=}b4;=~P`phe;poBH4+JUmuFnsXhwrpp`}YM&086-RLAeFM6>WfEcjoySj09y8fh z&tM66Kbv?{j!V6$aV?TAtT?7ao-VPXUCIGuBA-WJ5*e~*YyzA8Ee5I%MnNIhY!q4k z9bRs?C6OiT(4krl1DaZ3S$Gj(;US(%kq`M;aFw}qQ>p`Mpo=-T~j zsl9?HjNAAJiK%MyWibSGo=q@CGxJBeDFw2_Nz4soh; z7ec)clZccwrX#QdZH)KP*AwRx^Q*SRo|}ny9|@vMl1)iP%}IPNKLFaV#E9UWU~<$i z6lX6SWiE3qzA<4zJEsc;{H&9qxY0w7RNI>1pabXMi1ULLOO$AB!aUj-B}IaNDPm?u zDVu%lB_9m^FgMna)W~Mx&!I19|MesDLMwo@nv2tXo;cYw&;u7@)nH-N8WMQF9~5`} z#2L@mlD70caOuHebP7*|O&g+MdqWi8Joqn)Ox{L6zwrk1*De?(dx5cfDNdNF^Wo6* zMwl#>jY;EbNnF=ec<7N$j;#y}EDvr|^f}ZhCsIlD|>(fOjw{*na*)Q1Gu(cSS(af9Sw1}L& ze26Rws>YeuDGZu!<3bb2WbfFz%2g#1`I39 zX~Yy|5`E5}mCQGzyRP|>#Ul|^t#B(upCv@u$qD48`yeDZ4PI!~@oyx?LA28#-~H8o zQeCUZ{OuS4%@9BZ?p&8w=ZABQTF5{z2XujQ)a@yu+=q=yOZic;Spn20*NS{}9}njx zmtmK{TrQ1X%&Kg6rk0CmV8!#vH2GvZ#*c(xiP8_gq+bkO7;=Q4I8~okzdA{u8cxLE z&Gtm#^9h(|o5G%n;xwB!#T>BN4r2BVVs8$YI+mS+9*`kM(6)}#rqrvCGfvHMp`k(TlqbW!JA>}jP^CvzjLC{(HCj8Qi!uqDi1OL{@UxLS z|C>6)tRpJ)@BklHwFtu{as{moQ*meFc;4uOefUlNI7ZfK6XlO>@Fr|C$XYx=k@6eZ zI^i!|U%HYWIrIg7*IARV^QxGxmE&mNhA{lG>=rBJEI<@K=o62PgX}5|HMkfkL!K?- z06AStagNeU4v1$$Bv)@Ffyce+6X~z)Gc7Huw(=#LGKHJzUyP>9n+BN3TVL?4!EFA| zm<_N*e;wo(nBn?Qv5b05K7=|iphXAff$6(U>M+ldfA3-x-c6H$=^Ni8f3gz&WV0X7 znGD033;KMq#rxpCdMdlu!I5>xth_sMC0vX!sp@iTO$Y@T!zI66K!N@Wa1_J*nBu z9Jbp;EYtbKO5K2Nli0)_8~(>GPB?_h4VAo=D-=lJ?n%ts3^funE1JJ?aXZbNK98hy zEhnbEl^7P9N+;|;!2ukqiAJj?N&9^YUR8dDkC#)3wL=!X+iQzi*~u+WJmQGq_hO#5 zP!YC2TuoffU)zwVBr5No55G>OL%PL9_#5(sNz<=^w7+Wf@wRyOoM9>0)HqO!q)v>w zx{}`OT1_0B9>J*|(^eyS6%r7uMBTPN$Bxz#h>cuJ6_=F*8stJmKqE}i%3!r6bztV| zMMO4#D%~a`%Xk>2v|2rVgdU^rV52W*H%nfCI#oYn*@*X$F`NPhgRNA~uLQJS$#5bC zS1#o{g?O>WSQI^h1OJOtYZ6O0G?c@y?XJY`{0+Rc!+|haJbJmehUTm>v;C8`mY$Yk zA)!8=>WEk1FTH;tZ^eOJ&$WTm3{SdJ&=P8SGvJ$(JeF~g-go}?bXffg)(9V=bDxFc z_~2wx(ft9^m8>AhcL>f;p{Tvuo}7%_$sSr*1-?DH(DeKgE7urN=yaCs&ystzm4Bx`JX~*E?)OOTYIK=XuZ-ceG zC;j8;0j=kgNr&Ah#s{)sw}2e+|Fn(SFQ*BMgqDzoou_HNT|BKfx(4fOZ{x4*4b)0k#`Cmr&YXf>0HRI7o z2gu6)K0JB95r>lR!}2qLswYpdLPn;PKV=1p4i+IgCOsHcvlcz+WO`wvC+|skO+v%m*^oM~AIooOP}%#47hc)W;4odf-Q62yCB*2^ zs!xpDj1Xd^VMw)pi;;k>%W=BgdAd#d9cxs??Ka*C(%{AesQykKvxn+IM3IG^cear0 z-@fCnFWX_NyDW|15+)7hD@ohnUJx=~NS28oggI{)!|BQv(0cL%%%)8RPlvbYKU0wQ zeiX+?!i$M*|3YH-T9+6Eh@jQAC%8O!6)bjdB)fCY;EXsax@`^DkotBGry6vCUq(7u zT`h*Op;xFp-jSF}yU<(9TS(T<5;CVVh4^Ne;xZi*u-Qc!&7dP}y2l~j)X09cFQ~_^ zj-QOf@1Fpp%h-rVebAfgL^P-#2#9PU!Ane_e_A~_+Uiq{xfQrmID@zr6)}EX0>jbe z5Lp|`(E~)+lYurCJe}^~uIXp#!O6~KI75}Ji!mkVb+h4JnI5)hM6mJ}<9Vx?$+T7b z1UmI5uwG3qtVZKaR!BI8@S=AU3YfUR&UCQ_Qt#GM1c>L|MtEgds5JNY$U4=)EJ8%ywwT|oq73u&BfI2m-T z#HVhy_{o0&2RBO)o75p_y|L89!y&qg_%meLsGH zDLwN6WuzElkRi%~P#ZqzGsI2OgE*WbiEWCCWNlC$-!Xq5IdkJSrpR+UCeKq~Yn#dD zuNmZh_(CCfvpKPvC`1_PW>7h#LGJFBBVrZTu}3n9Xxw)pG3(zG3DGs6_|gH_cOPNJ z*Y|^Z{|fBBY6M~bl40#|Fne}UFzLJ72a$=~y>F2x$=wsj%GD{;KBYkVTK@)Z6^Ws~ z;Vb9}O=!)05dvrD>|)GSm*JXq+Zbld*XPU7s&ZBOp)V4y zAKr|sB?{=^R98AfVK->pS0tk^#?Yv2Jk|I$pG3A_gm!4kjKM{H96S!GnMVh^Yi3JC0@6tNO2FInLkZK&h zo5s;&c6Fw z{sUI^fBfu!Mx*|J!K!BdKLb(<{{gG|Kd<#)k*JyfE0L%-8+X8n^b42|6G&;ZCQx_Z!;FY%1!jzH=X@lS;3F$crz}q$ zi-Y~BWN5Ng4qxzg)*!RK=Oa1wL76aIa8oe)9V2g(K!VNkNPR>vtiD_f#;!g>5y&KVKmoAm@GLtj?R+ifqZBQt?b=O!d*&W^MYiGf^qn`umu0;ZKCp? zT4;G@Aqjjlk4BlDszkqSs2)2EYN}~G11I*j$1!0pVay-O@Pi_ zd6?`!Xh_#?+(7q+zF=#MpX1t3!K6bngl>Pgg>KXNghtYKaMdy#Hrm`I>Ovt9=GFwJ z7v|&H-d#)?6(h}0T8Mg!105&LAvzdgVm|Qzoz&Qe(muu{Ht7;5uAfbQU$@~#QAwa# zGM>(vQOZQ(j^n<*|8$4ovLQ9% zt~{MQ2n(U?BCf#SpGre77*KQNMR@Wn%axnLU?vAnNE}pyPW@qA;4|JXF~*jj2&u%E zQNFCQ`#$6*p)@cs&++^N^UY8ot z4H2M+qT>OYJsH!K_b@TE5{KT+#CP}ASOFSJgxBw(pO-t(S=<=pkOd!ax0{nQ^9y-i z?gqp@>?(EMa~@JJaciQ87tG^p+ez)|^)T;>C5%?8&~q>Baf+lo41JX4Yt5lde2X61 z@s~q)mn0T8|6=|Y93~3N*Fit?1c9~TV7{gXCt9h{zwc+l%#UfnGTBt*a3SL?kpMBe z@wVt`P_~F<@a`)UiY>u{}SE6>|ZO~+;#~Hxr`2;$@ZZ0jX${@oF zG-%|tbCAB&nwC#FMt?;8ggTC={E*Bf7t17Qkh4A27n?#0V)ZFuPQmq`uUQ4P8dy{8 zOEbTHz>vO5a$Nff9A7?x<*k^*nCzTLc-nkied`BL-I8N2`nZxL15Z@u&uY!@-^gnm z=S-@`HWR|vV=cH+Nc1vIY!hfq?j^dt=^p%Vq`moD z&C&bs-$W^uMp9JfXi%E;TK9@1WEL_+rb=c>h6W8vsnBR_Qi&8Al-lcF5+M{BB8ehI znaW%^uj_oyd0(G%e)ygrzJEY_SJ&R_wbr_y&&T6qvgkStwdbKB-(k^`FqoKa#@GDX zL`&2S#OTTp`e^JJ-tu8Tn_)YKnWQh}3mh_N<%99U**O=5b6@lDPpc){dQOl2a;y=Z zBoVky${K!N@dVQl5mJ}?gf;qH#>IDK=mgQ}b$^iv>M@Up=jWwGpu_^PT-nO}j#mns zo`u4%3C|^ox>dsATW0Vs$peb-AHof;7uXq}F_7&m!%NzKfWf$S3@x8WBi_4{$P4G0 zO8jG7EVCbFPp6@L|6zQ~G-e9C+9 zAEirQ&naWaio&4Z-A#P4&KNE!N`l?D^2(YgYhv`PFgoNSMymEh$yv-vBT3@BHgjZv9;5a}+( zY?Zqts@n$f>kSmbeP0l*v|-$3Wk3G?iyI&IYNQYxpTKA6{vfs8=5$nBZ!W(&fu?U8 zCT^?e!r1TEC2LBSV=3$a1)d<-h!Kd-$M2Kn+lFx`6SXacT@9n>48j5ZY^jHe$XcIJ!p(cu4f$lD6_<$L>+`GI z;rx|gX!0C{J;$CCli0~Jke+z0hr}JzZ3M z9yIQl!CD6&h%d~8q|EZGh2kFEJ4XL;IMLTT~uHK+{kJV^u+*wrtmBTLrM zSt@ZjDJT>IG;(0<#C=fryaPUcJH?!6G?j8y;_vqE6_SSqvCXUVh~Ez#5mrzL<5K$5 z&1&UrW4#EeD67F&i+0lI1rNwt$3`kQgNS}lMe=j`EdISvn+gkVfU#LWbRRODzj`lF zS#jf$;UzkPaV#l)`2`I{C(Z&La~LIG#TGqu#V6;BNd3wN?E6%g)!(VY_?PiKsY2w( zJ9?3A&L3&a#A9Iiun+&W$p`0z*J5+jN4)Lo0O!ntA-BYm_fC$LTs-&~s@_kbb#Jw4 zcG6L5F;$muH))_7-VEb$RytJitp)!T{Tf#7`YU{?m`RH-3>0HMTfn~Z4Zd>>qj#i@ z`H#PF`&T@}R@JGzRB121Up5IKq!QwSE@R;$u{`^49$Hq6Mc?05cxGFx zXcwQsECy<_n5aCm^o1MmXQoZJe+`G&KR01eqXqr`BLMQAJclu5mvK^_DK8a$ik3Nx z;YH>eI=i|b_a?S*LX6fnFFy*w!7t02ewc8pcG#@` zi7brWiGF1(__Rtx>X9tZFU>u|w-zVjk>YK1+HXCqGp@k#KOcgpO*yd%4}q@>pJ7X; z20ys}AoVuc#GOo<@SdI?82viQo5gbFw4kG8N!DI4-?o51zq$+d|8wC}4<@5h$_jiE zewzg;e}UO*dT3!N3uhI3(fM^Ecqdd?uM9i1;k0?B16}+2Al-OzA^j$O09~e@BuRQ1c0X@k6C+92 zaj-=er|rSe$JmWNFR`cR4H1U()3mMqA;_FpB@YjOCBj@w?B_R#UNr%JyKg-f{SM~M zdrq<3mJ&SOR|{i5Y^IM6OoEieo1)+6n(#eTg-$No$0w5xx$(WG(YANQ<@&iU2OYu zmx)32NNFt06TN-U+X~sR;woINHH5e?>qLG+i!80Wg;|wtY{IDscE;0^kMFI;z51L4 zUTP>99aEGXzuBuiJLwWW`J+yZm4eB}U|V>;Mi!>2l;VR|t3m$UX?WiEIu@LpOgH!Y zL>E_O2(nLC(HS+y^lTl_)?WHlYJNB!Nt9^2Y$E+5#u{D}8sN3zdAMJ6b?6mE@l`MT z^Gi=tAYfgp-7eeZ*cu#%duvrd;Y~F;e5D_*=yId0)699L#Sygs8w?klBe;fz0sZcF zk}mR<1M7GB^5^L(bzo}6^l?(A*v?P1St*7e|2uV9+%KZh3EDA5$=2>gLI z-)B*c>dpGJ;N3koYxV}XQf^GWokmiJXZ`rM$Q&M@cNzcSUTS;Ug_^sL!3k?di)-Y5 zI>rAC|GaD$hXJ?9HK8tE_eSNc&2@V)(mNS%2pn1CZwUy%fC3(c&_+aSqD{ZXZer*uW(sq~pAC8BkTcgFiEh$5%ra!k$<^ddJcm z#w~9nQNO=Q7VM3K?L{6~dD{+R#p=s%v49sk$RF3#$$@Y8R=9nUgO)p?V+KUilOx{q zCCk2pQ{5ftT67Zw?iXTG_iAuRX(Y|-vS3ot1@fy>7INF(fr+jLt>0Bn6TUVO+24O) zM|L*JwUee5${gK&#_@^aKVgeq1`V8l5?9ylgPGwQ(cq6Z^&7d3Hsu&%SMqTv*%Tp+ zS3HP07ee^EObgJ+UksZnMq-nYd=`>_Rs98k1PrA9ZP>lc7iZq6g679pQ{R?bhSg12;zlI3=#N-XV+755Hprp*H<@FX$AV%3%jN{<7e-cto@E{PDi#D26X z?gMmQx8^T)=JFbyWEi@|iA=sZi$2$_foqY+vCI4*1U;yO#dEx1--diK>LL&NqW8<> z!BteY&c*_FsAVaNx;MdTWf5z3i)>Wv<&p=m^pIFxNN@ z*K}k;zwT+}H&gGkGi)S}IFl-QQqzy)kFzAmV;C(P|B$q#&*miT1dhT!e0z5p`Q9oo z0{ZPY&JCf0)I6FEr-Yf~`qRpH56~*gj8Ex`A>TzP*x-5$VsjvpP$ z@!LaUmNjpC52aPuNa$APpG?K0Y=9Y*mwpCamvyxNMhnc4spH%8CW!DSIdt1o z&8p)^@ODsUk$#`a@(Z^>p`Q_%lGJ^ohO zCwgLsp?jwd{qu1UUz!;sIw7*Kzr>813R`gWY;BzP`UgJrJ_LKR#&J0p3pVb`TKLvt z#0PACfY+91!Bnr~xUl~Ue(T0x>^QoDj}7+2^r=dm23p~e+nb<$mMxtml}|ff*T8*Y zGj%&~nFlS&r!J>ousn|hv3x55U1?t`S9@F>!QX>BS{}6hjU69TC&xdmIzf+H+VI5q zKrS`Lf}h@V14gAMi%#KENb-}RFN(8h;;b61-4w@;I~}D#hW~KH#pie`!kNZo4W%sL z3Z82A=b2)BNGE%~q;%B|eq(1HjIQs?=e`t2lyzHqvga87msFw3@YTW)izWP%nit0Q}Dh(o6jqa=L4^4b3Juken~S*tmhozO$Be+zCwY$ zsoyS{^J6Zp^33I=wvk*`?R@r0*2;9Q+brzN&%>B^iG0!W%YB1QV?ky^HRF;y!9RLwPSlUQ}_9cW;QLdF^(X zv~CjbG_4_-+fya+qR&&;x)4@BUIL9ND_CfADsFjPCp3H>!>jmuSf!W?-yJr=!npn@ z?IC_Hr$^Aux_PL$M2)6u48TEK(!{8-674#_9$x1@Vs}3er@ho&=<;PGEdKg>Nmh=W{O2W=??! z%V$4i3u5%B;e|n<{lX61-fiMP4vFkv*Eorv zHLej}kC%l%O?j-&QVSaOMY!T>9sGGSmo)kJ;p=DF!@?*T`g=-0>NVpc?oM2Zg{FIG zR{1;dKjdU*zV!)Ek9K%f9Kdu=T0zw=Yo1V*$qNrzORm;ONPKLz@OzHwc%({ItRyXE z%T+gWpJ}G>c~6lTyLbjOHch2r9TR!aPD`dRU6uL|(u0=14^U3aktzp?rTooXsl-W- zt{RcRPxTbxPrt*EFiD5bFPX`0T>eTj{y0;gwe~bFAsC*GuY#f(RhkF4o~YYgY4&X?yvE#!DId?He+}qYu5cH$c(rs3Ay)Ga&7Q$_Q=+iS{xrp?Zf(!5?V=)yQqj!i@CzK zhF<*J$vRdZGJ>zq^&qJatp)$LGbkOC3IT?1;DS>N44!n9Kd9!&Lgcvaff$L>wE}o0 zzPAQOQ1{mx@P+(&+U*;L;RkO4@65v?)@Jm=V=h+rH0gr#O*AquitP|1B=I&@biwco zlr47z{asdc|J%bbw^fY`AyV8uLWBPc)2FjFdT{gTVSKZ65Dt$HqVg8wY52iaJi;lI zbWS;r-V1NSgbo=x&P$9AoH`G##r=sk?qV6Mt8vpBM{0aLhI(3`Cnqnz$JFgo{L=1u zT+QVhhR+t=?2s!=+|8Jyb2};zw#QKqTOs?yjq+hv`%t{oAEaE(c}ve{mL495iIYa4 zu4M!&e_usndiAg^x~A;Dj4OQ`63o(@v#~7P7dIImfSeOHup-wKV%{94Zrz_@t1jcJ z$(Cf@BYpT=_L9hD$5E4yan!L%j|`T6jcv)5G!+?qm+B!JJIC_OUjdMG;W=wkp2)BI zI#IRSV7mP0VX)aJ`jbj@>Dld;-2TyeswX0LHB(eZ~0KuY(yp;bIilEYtv(5L4QzDNAFREwoJYBneToaZybx zuJ0Jfmt`H~Y}Z~Kdi^tNN!16J7uu-!sU1r<&nN1ESK!Q(=lH{W3_oO>NL6(g(@8tW z! zidn_ZGuXDg9_udc;ig{<=~H6nbxb&3%aLvb=WXYS*laJIfsICP!&3;Sv*%iR=oo|IEzeU{WTn;O> ztt95gQheu&YH~ijH#N~4$x}+RVE(SNG`Y_=cyfGz7^%6>e`jpL`%@D@@v01;F)b0z z=|GrqD~~92i&a9_gLj7~izEA394UTJoRS@2`M^5d8afh#yjOtYA`Py0eKHzFRFe+9 zY|I3%MD?Y0ibqc)B|tL;Q3=T1kvc=;YAwixn`v%bOk2fxJ`8x~=YF^ATF zOIV#rI5yTrQl-96@P~5&&Z_xEqR+493(k5|ySL4hW(xe(u4dwTC6($uG2=CFL^s+; zv3a(z0uQWR$$k2Y-owp~Y|%4UT;BZ^eEWyWuNqGN5yL5RH2NS<7bBBvyy$m034I6evFBPUm2otiJ*RKJ;PDPO={w?Lb&_R6tJFffbI`Ejt$1Ec+{Ka ze2wRAj2mhwI*!Lfe#Hys+N47R^*`Vv5%By+lyV%HH=NgRx{v#%9cjm!0kp2Znhd!l zPs?=#+EafDr8nvF#1oO?JY1~N4pxM;w^7(GvjqMfv*y(uWq9m^8n<7+Nix9BnWN)C zt|it~9ClUPDejNuQ(QzL%hXh0>bsz_NgaA`tCftG4B++-TXAM!7IrGXk;u!4j>SK= zI1^Ul+_7gw587RR-Doo>s>)o+#*qhymE(q_PtYhjzxqy@#g4plrDM*eQF;GJkUhlh z)}H(e7Yn~&(7MTjR6#$Y%k9Z0=l$GR>N&dq(G(3|di)r^Vy{P)!4(-p{`r?k?}&(i z@1Ig7Ya$1L%ncEy>H3wFM?4|vc^OzEx0L>RGJuvDoknY?YY^4f1eKdo zP|Nr?SP9?RaB`YhfO_795BQ9ip)h`K~y;@n#J< zr#*~zM*YLfz3;+=9lmr&sTB`an$H2+Q12jF7sYC=do^JGq zG;xj+J~xN{UG)q{&+?;kYiTdBKtfEygdf`jyVV?CUbl={yKgcXu_+%HK1%lFwRO}$_m#SmCl(E&JA<* z@Iz}i>Yu+3&upioU+!31Hz$Sa-HVhgRqQ5DkN?F~)3IcW??afXZA8zW%i}AqUL&!Y zXCZQy5`DrYbs1wJ%sbIXo-{9aKcsMYsj9U7-dO_wuY ze_xN^(~SbTB}1snJPDofc9#%rQ;c?*RxD(qDS2Gzfbup0BzCp-)UH}ixYzp(aa9<^<yLX;y(AvStd*v+G4h~& z!Wc(c#zOYY3Y@k_O@xRwVjrzSnDf;Mr~EXetYacpDE}j`$LQi*Z?RrC-OIjp3WM2lLUZc9B_kI`OkOW2Sc_so|Lfes)7BY)U$Ya)wXf-3?9pxH}E%Bo1QT zdOf#Zw)THTqO$FgZ|PY>_fNf#2ea1FeJwR)%lb#)Q*n@flTE|sZvD%-*F}wk%^QB@ zQ4xj;qc7i{5WpWfNb#w<^gpmFi~qo?{woos@&AEz`cGKuzvY+y3s&_%U*&&?rT(9= zs&W4(tV(V`9}!li`CqWA|Mg1$H>~PEKk~od6!pgCEkp74F9(!8V!%J#Xp*$gE0@GB9e^t@Z(+B~`$0%X zB;J_NhFURxsHjuJ44%61tn_}qHZo=^Yg2c(S5S*%u|xs=>lntzAvui zvx`~0J;e^cFGNsD5w=b{h~_Z{5V59HI4M(L7qngpPrY=(Sh`|Egq(Gljc%R)?8 zG_zIf*TNy~Qk=iFfqmE`VnU~`rM{advR$3~*i{z8oL2{<-Eu$TlO z>tl!5xaW@r&r#~QSuC(0o2Ad)y!_B$Y&yyRl1lWlote|LLgsU?Ki(eo7yhi-j<<9E zvIT#J!FjE4iE)@JX5_`P0_P~wuuKU|kL<%IMph`8d1KVkTW{bPVGw=OYxZu%HxV5h@Xmp3dqBa%geyPmvuy7W2ThHM8qGzOg z{eJdUHX1G^S7OJthxj(c1*BLdIvo~MO^cUe0QAQtKi=5A&<#V2HG`@2;yIXo;U&xS zu9n~{V>Y1cCsVR7hK4EqQ0_@0vzmKN($smEJnNEyJN8;4$m0yD8d$}iOjyT4U>=M+ z|5>tSi9niMvY=_>Hdd6C2c=48xGyCP*t zPWy;{M-_y%h+x8tN-#~-M0_)?m2{WR7F_;Bh)CLOR9N){4$2o2RdY9(5f=rIM|O}+ zZU;$*(hg#_ycFckhe3Ir4kmWl6EA&jOs;%S2LGK5>x?-0@;HPv*;NUW-Fw02*AOt8 z@DLtfdd$*yCy~GPcI=zb53dpnC7OO)g6?aV zk?@x~aB`F*He6T_9-W&d1`+qjyczo>t5zt&S!<46Cw@wX%sYr1v}Pf6my^96$4SqS zjd-`kmY9e2h1@)O46aDGbCxKUXEYiU>CmTeC1nB`>zM!^iw+Z6i4n6q`jng&e8GRw zUPzFgD%o=V_xNUc2Z@hskO)jM2Tgy6@)aYGlk)g2WK+m+9^9SDEDCQjH;;u_bx;Nt ze9B>?gYL1=ed9@WY80D0BvYt5JXYvsZAfNyr3zab)OshZK;+I1`Mzn<^xn2xn7gx3RAYNAZBPC44{9EmX;dz>h__xN%7=m|f~7 z1sZKE{NzJ4>)#8Xd6{6uuZ3){)w}ZN3+}Nw3#Z|SNsmdw*$)D{wqI0nEEKZ10okxz z9=7YGFirh~J84SQ-( zi7{LJm`v6QcD-00IxdZ4sWlt$VY@x{PvV#nXo2tVzahc?r{JDlv=DGsk^7814c=1y z$l~bF%<2A7)EpFv0~%(a@-~KQCl%nmfevbomL@y)C7}7$heF(1J*;xDg@3*?ndwLY zDgxsq56?(Jx4u6K92PIGW4UDiE-O%IJ&hW7f|-d^jO1C)UIryq?EXF}m|{K`e>FU3 zy0%wgj`whk=h~875i$FI$ue5*vKDq)x`6he3wSQ|3(-=&3!a{uxLjcnB%7y6rkVX= z*_t|-qAJg4-*Cq-3BT-0#Ys_M%LG{W$(hwvRKrix5{SQ6a%p8!on+;SYed(_5f2>6 z!87^$n7`aYIC(8jsLF}N7|(qCYLXzbZennl{xEzx$U%I@p1`@aciDwQ-zDt>?Zkws z4a*vQ2J9w#gVWF@?4tBI)?4)g*4zq39W^O3ZS8bPVT2+^9^NDF`uCwuRyq5lyI+`l zCIyTuzvFCwRmfdA7!?N11|!=SOzpO${D^8alz))MZ_?Xwq*pEJ{-;2hayhopJxr&f z5_(A&0^Q*VTlSbih?g<^yYv~Zys*QfF9d(wK7i+|MI*Sv37o;*S;w>Ck^zhU3Hi^| z>BrjzOhfm$P#vxXS}w~_afGp?eb-gteZU?<$|8vRsa(Nv{Xx_mx*um+Ungg`w-96N z8>skZI~tAJ0~xMk;N-7$xasL_7VsjTOc|+$lGiGjpBBZGlii`XuSfYuB?q!-ad?wKd{YMtq6|;M_t8sdvF>kbRV(0dr#u@kSlOMk>Fo%PdsQ6_taj+R6 z3~80Z${Ekt*OZsS&np9j9D^SCY_JubjC;x_|F(ey(?Q^$&@G%Cq$HN+*9&`u{p2Y* zgVvq?c;ICsrkQKg8y{AXxnBrtTRTFsTxJfjo#l*ywJt2`l{X1!>CgXO(LxA`gh z(^MiidIX-%I7vS4?t+5T@kDZD9y`Bj2fJc(Urb9KM~$Cju`zHMErNR(gg> zwBr&%VtJc2{cRVNH~qD%7(5X3%S)if!-v$0XN>yn!*)AvoPgBPhww$I4Tfi!pkYM? zPV`d3hb>N`y7ZC6F>5kgwnWNy;*MiDa)dwbe-|qzc`{jY1|^kY7vR9c9k}(^Gq$TC zo>lvL3U2N?Bv(wlEMI$HWXAO7tjwbWt@B(;Xi{I(69wK69fjQ*MaM4j zc;X&{&D-abwdF%FvU&iHeIF#OR8oO?H^d^MygJ%VQ$Wi@Sr}p@#k3<5NciwKS)4Mt)on#Tn}XGr;s$+6QprdI|-9IfHSvAc(kbI1Jzi5O@j}vfz|NVG{MY3HFx8v!$JhIwxF_bnw1+DFw z`25TwI8YbO0zXfKYh7MAy-628c5sP(ps1p-RfopLsI?OIkKQ){bDJZzs# zmz3z|5SMN@IOSd-=yl(gtX=;DF0Eb$Qycxr;ytMn(_%eIyqp4gkhlw)cDxyeCV_ZI^Wj zNq+jo+xjv&waf_8Y;P0Krc|PSJq|}3$kC-sQgCSOVKV-O&iFQ?=R%p*CLCdZP)x`+ zkj*85u-zk`m5f$r_G-oCfyXX<7Gn&ZZ{|Q_MFi|w;D>+o+o5V@3)vK$4It`#yPmGLlE!M^8UD7CJ0L!Ct=XtYGJp>2V(zo6#o6WnQh!?30EIymcC-wf~=ePM4 zw)$vdSC#}&IM+eHdaheNQgyiIs4vEnfVkAlE{TC;KaJKEPBy2?A3mZ zO)5|XZ%G;U&5nYFXag7H39NMKM-C^;l0{K@%=qzOc5KWCNx_@BaO=SxCRgGD_wtL` z#eJh;>6}ZFVBs5kT(J~pFFYjaQ&^67{%v5IcjBPl&Jc}ioS3=nYuj}bD~YwoBevpw z78J<7kvzySCg-h}mk)(klIuIYNWJwf9Fmhy)MuEH=wCO9$}MqiADD7S+G zn>I=)jn;#}9Wt=ju1Sa+wyOMk%`6sh|C6L)q=X$9lfYc96tRBn9FjGw=Tg4j5{Yj= zQ5!Jd5kH57!X*PmaJL91rz%BYqWftW6fu{WJM{(q-=*w`nv5b=5aWft_Ow8IM$T# zlAZHBDh&MC7X}p_X3NL-V|UL?g2*TPV2433w0JB<)uQZSRp3BaaOV^r4GhMCw#p<$ zQy;(7iTfh&?=W(nJY?oDR$e$0&+O0#Rm~D8(=5d7S-O08TPORQf0>;RIL|ii6_bwI z$60j2SUmGn!orn*u=vF`5IQ_ZgwSh%qu~r#xqT9RP(B7llIzU%F2Mq;U?}VgBIWyE zlR+D#ga$8ncvfkR?WB|yv`&UQ24eDNk(lZ&OJbUGEAZUBFT_4ag>H;`$gWT9z%%s+ z;MR<}I8=m*y#BNSv+wvrFWD8iW_<$eIWd&&OL9c|q7A3??hC5=G1ziu1(6w|Nsno3 zqWs1aWQz4hygl3)Z+0g@%EK}EVB=w7zP1b8T$Vvp6#ZG1>0~_h@iST2G+Q`7rV@(! z_W{+acFCC&Dx~>(86#?P@UP4oCT>n6r{Al=pE^BMIG@9=s81z5rscw@1&iUwl?L|4 zrZ*Ht&j;5Pz3EKxjK4B?Jf^A3!fPzU@)OTTd3Ca!xdfx><@L=>}|8>^^os z)C^$=qD9>}_!MvrZ~k0>KeZ&FKWcWl@7e^Cxn~b*w#Sey$K63b{TvChs2~c@jxb4p z3fn)$8Kw>p+lCvrL$6p7{OPe8eOH8%g4^|AlwOR|uMLFPC5RbMMNmgH?X)W8VePFI*LsHuu33ljE@ExH&AIT|xARZ)N#^ z_M`F5{&2!i3#$UPP$vH+TlMY`Y;~|8GvyDl+>sW-wF4he@pLW(-5X z^|}IvOE!?w#H&n5^FsM$-^h>VO7>(OXZGX8-)-JOwrTxr@Ouq##8F%5=~j&Ae7q7N@gTA>ZFKH+u;4)vq6Z#hd& z9ySG=fM&__!b-{bOf~M-w->aAI*?=e<`A>Hj`)9Ff{(xM#+9Z|iF)xii1jzaqc!__U4Tj~~Y@ZA(4wqY2CRf=j&)T0{rRiU+6g{H)hM)_b}Vm0Ikdh|-c zj=7T~aB&`P=s zjsFIa`%4G%I*B0^-JQl)zidMjWk*ak+D{JHA}#o&OHk zHD6{1Pv5gO_mqJSm*LO5%1FqyFtifeF`rc@gI#JMa>Wq%qUy?GPz1t)05os<>UKATP_b% zmRh5C?lhp=ov|_KO8MM06LcJ)#+3EraO;UX80IP7FP$93rp<3>r^5cQh8#!u*v}Wo zrhkO{D|FCiYczU{3&mGaC759{x%`buBzb=5qS*3W2KSb>3H?Tf2oKL@!gA-Kn7E>b zxE}?!ed14iGFl%`Zq|g0eyYORmjfZ@sVlrraTV_agCI80mNr|D6oNLTkot}S;jMiE zW5a`q*QOkF3acgOmkxomhorzS^gbIZ9AO#J>9A480Y@GGSbi_#1n3PE2^)vvVIUkv zv#`CWW)@B~Yv(WEhKZo5Xw08{~_`mmGVvmYwhGP5v~UB#Ilt(W_z? zdRyhPEtxk+lKD5{x_TIW>Ajc~nWbWSFKM)R{goKPHQZF^16%E%!Bwj~Q0&OStj}^h zFzh8W?AVDVz4Jsp?i{jy$1CRSn}_=V?bbd92Co<8@wzYb0cn*oeGy{~>ubb_vYtTVwZryb;#<{3G*OKFpD1f{^r* zg=eO)cF9#7yPyCqGIz2D_aGLmfuP*bN*?>Yg2VaUq};2OSlKOuX}=yz%6f{KcK%A- z_{spX=X8{x30a8NxE5v#5N5Sp#JE-2_igBy=vnkrC z!lvdlmUC?;*=Qo5*;Z*d`|cJhT@;`FDn;;Hrrk=blw)gt)%z+D*Vxs+U-lE=C}KV@%r z7Zd3xe&9Vh6)Vz?;?$B{wkK{7+@G+Xsn{xDx85Z5da8)~_A9Ve*Y#nK+i)~1*ogy@ zpOa1DWASXeBUmeKBm-1}p{V2+8EtV=kcvMkrq3+k#P06$6_UNs&eP%M$;a%H<7xPH z=Lm^yoj|@TM=;ykZW7QKfupwOG6$!4GBkHD-W;V#%yul%61mY(h40=#4v`!s}J$H6Ww&a+?s<0liAZZ+`OSiI^WL3!Y zn1yZMiX@Brg$ikNcfjPo1K7C<(Qq+vEU|g@nymR0fvbKSkoZ|5$abI(sK|QaiG*C@ zr85u$zT99c$4(L1`yr?}W;z_v>dg-89Akd1BjNSTiKJi5#Ii4Gw}}076Aarjl3!Vy zZMV&ME}1Lp&LX!|NhZX<7Ch%qVL?8u#`8BS{GPdsV1yKO*7!^3Yhjm&v#$FuT2b#{ZTG=(grNv>j0s1sKEx0lLs7f&3l#aQ2SJ+_Pz7n_47D!dP#{SMRhbwO`Fk9ak95L!HS-x%|q+L?N z-6LKIvt4&Gr>JKnHuo_Jiisr$@1|k$@NcBiO#>23M-t=o`>abd4T6iK+2{NHP0ocM=?I`@a0)|P0sF@W{5u7`x|Gi+~v1D4!%m?=1aXR?lS z$%Zd-&@A4=+!~k1mQ?>C!uk%<(@u!RJ8RJL9*AR4B%+?{84_nd6Z5m~61BRcEXuWA zQs^xY!-7-ELd|}x+&q_b)T^P7eK5JVFn}B{3t>aoRkN!XvS7;LVMw&@mn#ns!tQH_ z**f)y%uUB0eZ01nc~WU2+xc8@i|mDlKSjpn)GEpCLzcpi?`o3kM@~cZRwc>jiw#&G zJRJPeWI(>*8PQzZA?WF?AR6=6VbFOgoN+E0cZH9~HseTKImi&?%oalW#R*vbLXGvE z)C*LWitE@N53Ea-#m!6Rl2yL)lI$5eSlqlBO&tv+ow?(1v285geJQS|Ujo4JwiJXX zR+V|mzL(6L-D2l5kiq=6XCx?VB@UHMB@WpJr1Qi+=3zVwZ~u8o+CM*l60@_=9Tr3W zlw2frOKm{e;{;|ooi6`#T9>^lZ(!M8rue}p88jZ+;O#4!c&zUbFn{@!nA7*{fO2g4 zdB4k&*$o4UW7$x=akie#?)*!9Gbt!^>VW6hZ7}(r0expb3LTDD;M+~6Y>ZnD>|iD+ z`*w_|6-P|{I}Cp%4@Y0Se70wMGTIEh1`@Xj@Eq@q*&PDR72($3m9Gn-wv*xI#Nm=T zHFJZwLJ%VVYNCT( zC7CX3hrN6XVb_OPNpNOA_-B6XJlaC8Q z7TFju_bND)-eM}n2n##Zp-tvAJe?3tE2WC))>lO|>$D+}pQ{Yf!O`^fA!9P#QHqp$ zOrt*MRuPlg*7V5Rd$74iju?#=0-Y?Y(5*KC(yj+XqGh4r<~&a0GPS5{d=}m5piWNI z+tIhj8_9v3VYIMpzeq>V7=8~QO#^r5&={RZ=&|-WmzQqG{+f49h!~e4zb3QPObEVG ztvdrmN0l5Ec@V=_kKs;KI-Pg#9qd(@MtiJ3f%&ykOuFt5Ln}XF^$IKUT$n!_MYQ1o zu^Bx%GoK!;4~1tBbj3+|XFzRj7(^G3A_vRmxt~taT=}s9&g0WCQN__cC}UYferq>@ zbyN~gFzB?^IQALrW`Y{JsOU=e-bKcF{nTp*Wt)l($90}u&9ozuR~OM|UegKp#f<)B8))zSRuW&ZhN^mNP#?E#SY5pg z&baxKUhOqpVE%Jh`0XhC2Uc}?#}a;TPz8UD+08%e(5i07bG!?GidQp9W)~Ey^DPTF z{vcP&Z~I(ACM2KYkIpOQ=cja1eI*fpBVg%&!>Szq7p&?(0w(SM)?fW^Dy9Fxs{Y^4 z{!eMt|0h_L%l|2m()kap>c8&w-;yYo|38wb4;$w&_w!WA9WFuiLdyXD{Hlkp+HUdX zwGnoODEYGvau)*QxV2F{Q>^g`x7n4#?%PdF;Fx}9xJ|q`xxgP29^7Ew{^h`S z)nV9?QG-)EwYZu)li^|KAz^Ja0XCGF6D_+!IH6J{s?X?#nSTc1ot4_uO5q7(ZyU#z zmb=2cfrIEc$Ago9mdB)?`3iTgsnVtPQewIJqcPG}mx;Zu%&3d9s#L8dX{Un&nf`JO ze(2f*ql(9qLSg)~f1D(ZE@{V0x)LZXp`xocv0AwoDhtHIrx@2D*;ygz~4;Q>Q zCd+l6!?-6IaM+`T5m!$Fm323mhr&2~TVXNt;Z_u38xG=!5wg@Wz@2D~AA(w=Zo)Lh z0=ydUOFoa1BHlGVbi=k=;<1_4aK^|GKdv6Zxy4+D!>2dEiS}`HyyOb8oVF^tSB$C;BNLAEhY6g7S>{xvv0^hb769+{em;KVGr{O1) zVrC=W@xzo{SM%XspH&0x0v|}vO(NI4Q^d=Ya_GtzX^@zH6$&GZ@qQSE&bBo1Rr(d) zTIk|6DO*@xcLy(;Wnugj8C=$z#(h*c1B1I4V8~TXntMBoJ3d$r!SE`&RxhBYhKsp1 zqjWIEAQwj0iXde3ByN4dd`u`8(ZG5ms_1Z!u{6+zeB)Ns-=PVec^&X>b0VC~oQg>? z<1y{CF6ql#QbpcK5!3N3C~O061zm^H{76zDbsL_{N)yK~yN0L6B;%7GmKarMPHRrq zfZX3v;NB|2fQTJ1sk96&@1Me_=|kw)Y9|a{c?cKOJQXh#uPYql%>>=_4Mx>vk|qgTopt*;NzIYx!#`aHq$OeLyq@rP$;=iqIL z6nMA&GM87Wh2bs-;B)Fa9A2(W+sB=Tx3d({Ean(8>L+ltOcUo^yOjG`BSl`i6~WCr zJLo$>^5V6{mWlph${5A&;Wk^W6B+7{gC=_shOXJgM5?R8kd{x(al3Y$Dlf>8juAA; z+$G*0mMCs{agXVrDrQ2|H5vDn4xlDv9yC0crEi?!fCyIoK3fg{IwZFhUD15|wYy%w1G@>4wyKs|n5Q@x?Fk3x-G4*b?$UUtF zrL8rb?l>=K+46;PUp2wS!Y&3BzXmX$w%KwjFDEcXxwQ~^NDtH1HxTPFmGE=mt03i3 z#KW&glS11B8nrKs%(j_MI^9XB$6pRPm& z7y=(Fo8Z-FNm_EBL#;Oks2Vi^-ZD;j=U*%2$yq_6qcU~NJOi??z46{3b@FqvE3B9? z9oMy6auuOwqSwoX)kClp)sWwbv&wauyxs?}*J37<^T`Zyh3tWe;Zbm9r#fzapz5;y z=Nr6~b`pyFJMp|F(3}g00bZqwKO`-3ne1u-`abpCI`>`7q~E>F^I{ijG|!a#uy7@o z9`J*&%~|L&Dm}&&A=7F2OCgTTrCm$T`S_V!+ybTzD{yk$+ta#`(G2lkyTA zZyU#C<)~uS!=)%=UxQEbuHn3bLMG~H0T|W9!Zi6hM&5TUwvi~bIBJR(dj;uct{g}Q zH*uz+Eu3i_hhf~tH@843EAmJ|d&ds=eKMYU`G`hLtM*H!Ew_pdXQU>?nc5YDiLoTg& zWYvgOvgA;`EXIHL;NnEc{Ij?Wmcp7YC`twkVkIxHy0;pW2U74>VXI5CeKtgrNGN(> z4gWV+$w~#R~Hw$H$Z*T1Ps}Ks;V-~6}n?@iBEKl!-$cQnA$9? z?dmq*66H#?wP4Be`)5h$hN0qDuO!H@*^QWh^)6rNbntlDP-T6?4eZ7Wqs9ta^?I8E z8IUt2Qu^L_VYMDvnIDNCZ7n&k(Whad1P|Ggb$Foe73j_|V`Wc6vN~X$R1NkI#DfDJ zM1538(>WTqaV%8f8llEWciAT%3!dae(;i&<=QTDKX;Fzo=CJ%}Eh?F5lKgx{V)OZw zNM+^~=0lzp-k!6c3{n_?DJvwH@BC31y}la@_Dly)`71O`Dhh8VkAM;5QlU3P0{z2= z)6kP?u=1V;Ns(Po=LydMQzfi|pGi_nB@NnE`wc%nQYEuH{xHWzQ%t_H4PWFuVswQS za@>{2;I~}^^L_w?)bEX_d~`r%>`f+$^(T)-r=c@Ti%Xe24{9>J8Bae6 zI&SJx9Q(_U_!;fOSBKkiTaYRF9kvVyn(rX?PJ;^vQ{n8y6WlyOVrw{%U8TP3E~6Ye zm$qqX(B`rWJgc~+9%^-+V18k5K)zwb=vIa6GuRf}7C9m#6v zKXAyY3TmgM(XzH!=IomxG{(ORl52gbRooL)@y>)tC(d!ZEu+Zp{T?)RXEg@>o=tnM zM&Tu&t61{e7;f(bvUax|{0{1a1g=Fi>S;6Hyt^LNy49(M-ZK1gcorHSnFuGXE18jV z%&_L?3I;D&VS@53G7x`_893nwqvu~hrHxNH`8|h3u}N1UYJv&G+oy8p)FsoYsK7_lleJL&fV*sOuSb^`Vg|xv?8~P7Sg|d0FG~wiGuCS+tn={mm z+nBEf=hLk5$|(=()j5PKefL>hW*v!oi*lIZ6-gZID(7b1+XojUY+;(r5NtHl6lI^R z6qlOBqU?lpCimhs82C97OQ$N5LIZsmIbtQg+j|EhTla!f#Ax80X2BW9XEc}9PqfjV%en^9ey*Go`X(Q5gFd5(4-^a4B z8AR*fHjp}hh3nEP125ZQ+|$RmL6n+-?%XT<#;P(I=_)kgofEN|Ckf^qeVmIz1I$Yb z;DT2UK=P>(oU-R?kl3EZX+(H2L+<~9(AF8a?S%kd-7ZP&>@tYf(Ll7eG@``?d62X9 z2&BAxjTr_tc-80%%<>^Iv$CNl~~&DTfW zH7mhwN*a@|6H__<=44@XVTZ#SRN!sb6#Ub37Kf)=K#Fw@j?wK9&H9vwZA&I|>7HBB z^p&$%Z2W_BoaF>!+cBKYuz%u3f4Z38e$T|^GZ}_dj6qT6U~;MZp!n8I9dg8G1hH7l z(myw2aMFz|jOq9R>ju7Z=F|7PSR~jW7kHOcT}FuB6-UP=7(kDk2tFm|;rU^=80Q(f z+=y~{dOBN*dRx^}~^H*Y+~g+;s*lrYJMI^dC32YzF3iTF0!kzl#rxcY(9>Kj_Y! zPU?2*G2;#Lxqz*jWT}lBy|z_@tXc7u8PU;!C-f^p@q#yTAJ{}2QV-zz8$WPdNT=xM zdPO>Gx)L?tWsT)0`k7rOqhVR}0Bmf(!X4Z1h0W_;;u)1>hTk`tZg97QT~l|6zb#M4 ze(Ck7G^h{*ijU$l^W)%_)r{G2f_Zk>i5X|SAHKyp(ddVr;C!$O3YB)!hj)IVQ|WPR z@&3Y<69uAKJAzjJ9tzEn#w_|+g;f@H=T@(|a!gyEi9*U=^3pE){LN|5~D#I>3H+0%w}P;O1SE5rozfejT&HbuO-0?*~lW zE0|hm%PcT>4EG$gX?ko6v#W9q#6J4Y6(k*GHaAJ&imGI63c4kp)K)FX6f&`8<6S24 zj3&HzTMT{b-e91y05r`C#ivr^AZ@TBewtK^Sv)K}evpHrahy zp1U>O3rn&G>i5bV9C#$${*?2$6ec8?p9h{&iEeFAiOvbt%k}$&bJ8M zGgp(mxxW>6I34GhpzoYxq$?_E*+TTMM!42-0Q_5vajkMX+BaLEvbO=el-!SdH}1f% zat65TMJqR}*@cE2yM-^No?-43oZzm6I>MTJE6~AdDoPdosy`OOONDWl$-^grwc!G31m_U!p9L3IaY0UgT zWiZO4>iAk_S(6Ibhh0V4SCve(=}XuZ zI9vqNri!I)3eaor5Mns@5LWXK!ExMRRQdaoaVky&bDw*R@qRtRT$MrJtDT@_J%igW zpNMrn7Px=hUPzsrfxogYR9!q8!?|ibXS$B8<0f{_rp2=!!6Q#Y_=<7jUCpDp;j*^f?p#VPelbN61wsf(BA4Ct1 z!;do>vAXnuSZmrn4!lppswascchQzEi}=VnDK8P*ogRr9GXjL1cx&1bbF)CLWio_&~QH>zP3sZf(*nT|27W^qGIO6x(AiBN zfX41e!$5Pc)ISp5=k=kfqaJ3uDA6I~CPL3*5jp$9lp2)uaO*A|!LLt(afs?6h*~y- z>3!k}u6K>X)X)vAV>}4uXA=7-O@daOxBZB8rITTsc=EAZ0d`pS^|l@jp=~K%Guj z+XW861Dr!pDD-^42JC+gY{1C0N zyMe_sPe6ReB~fe2cyZ-z`b2%&53p1|04wgqGebTL;S-;2AUwtpwpKVpp!G-WPf@~) zYivNm=L|#(vb!-$lkv~yH89i01$6Cx!}FMxaQDw$JT&7FS2xRqGwle*waY@WI`PTHW z^M?c;S!#-&Y63ud=w;?-U=tWTxrEF9j=`*ba#ZShDCp)*;8HKn#S0tFVZW{?P84Ut ziLu*Z_*!!=cbqwX?h1g>=XE)UP4~Il`$BeEP>E>I`53X&HYLvX?qXOXjz%@};m}#K zg5;l4ri1)1a_?~%YN)OUmlPg!yFZ9brVMbS`Eg)37;G2F`oN!ZU|ZIC3PDm%^-Iwms-E{CEjNbgXy4KoL~N7;<{MC1iYxgh}v6K z?EPJE#khu%Iy4DhbeS@V6HWm$`m11_a6`w4M{uGl2kv}SXKdoUantwZoHREDTy~yj zM3Jqys`54(9k+(}#vZV7)i@Hk|12bKpU?bs-c7Fe?Zr2m(qOw_0zS!|2$@E2stR6x z;dXi@p#R4_92X!9Y2WmzcKsXRj8dTbs{>qqWPlq}^YOY@EPR>t2A9Io@+*uT?1Uv6C>Hg^=rs^2O`;1&S%tj z`GAGwSFUCAC3HJb4Oib(b0SB3a?SFYNUO~O4AcFg$ixHa(OynsSQ5;5{DAwMzoF`6 zqa4bOGUE1KeFdpE>_IZ6SZo}V4V~M|nWrD(uuNw;w=Sqnyr=E}oX=L_&UG9_tvd%` zpmqmY*gYG@oYKdwMggKBch2M8^~Kx-7ay1!IRRq+ox>zqZ*umc1&sV_0h>SMLxp1% zyos^KtJ^+<_dqj*JbI5m*$hU$>oku3=S^(-TA9r+&f$AuzX#_VF0Yu@%sfA;&*V7n zWUR7Q!sL2&Xt^B^Av;TP_pgokt7#G1yS-r6Pg#w})*J=*8~IR_Ce&0-3vt8iiRkuc zH+EM!(_`0+A@2GMZhoje-Dgq?7ZfzoH_0M8a_RoOL_yQlCNc>=t$SkFv02oH2k%v_ndjoz@`IN%qf9H zw?roBRRn~sdk)+8BQ`Wq@SSm zyI9RZ0Cc}r=Iq*UaMe3Bxli@6;v#=fEPAzGY&mZTc2O3@hItp~~V?Rac`9_W-P(^GbSP?bLjQ$8oUoDFh=`d(*@T{{!s&d$N&7bW7< zfB<}Pq#hnWG{;qs{i$*H7xExmokrh22EzlS`4=+-X~={HWbZ^58eJ&j?mzj8gAQkq z?Tydivmj$(w6{awSA9C7Lu&>m0#yCzQ{snf?m;ffMaKPgKz z3Zl6KeG|}0vbSo6kgcmAUc{J;a)!D|QBGWnhtpmy?2?)@$b zZtL~Qs{{JDWK9N?4e~%{p)#)dS&TC$pI~N}$AOK_a17lQjQ5n~NSVeyvb{MFWxuOY zXDc&NkMutH?UW45+SEk*13uwq?fsbbXE+?0_zPkm%Toh!KE|e7l5{hFB072i8UKef zDyIqdktO&mv`JiLM z-QvPE1w|tD& z*N^fCw};cx2r1sJHl2OF=_P*e59M!vbYVlHqUh)+>mYgc9~!*VfYi<_M#X?q(wgLf zwqpuuk9aEYk*`Tw`fo5!(Mr6|C}Z~Uaz!>t(u?RsxdL&%M87|XhO+bX=?#7m9oe;w zcCE|Cwm+|k^$Shf@pFc#WZxN5yJsRXQ%=M0u`;~AkujTBQOJC(*-Atf0?5HwmUz}= zU{cpEx*;oq4(a*?I?~B0yGiH$z2jnzXp#}OmO|S1 zO*H(P!Tv6BBh7=qlVsJKP=0bNda2ZsY>UhIPsNy*-~ zsOOIKDf6BI3cQiEaNandhfhOINmQ5zi9u`jdTSeA^!SOx{&t8~{jdh(TLZYTUX!Ru zHB++_((K5$dujWuI%dA%b?SBhAC1zyNWxoFsqQaH(sWvrHBsG1I~S;f%7$*DSNmF` z(3H-$mR+PXwwz~6KN@3js|qh&lPoeBuRsrozEJ0F@o@araV*kKA$t3VvT6-yIcbClne`>)zQI?K6GyWMfmG@4_~Or zlHnp*T2r7*N3E#ExhI}t*Q_e|Ax-J~Fa6ZSd>FaNd?a=^Qt2VXH_+KE$+j*0O`h)^ zO$R+YOrL$v=2jYbfZY!Rdf20ss@uELGxJr5X54<*_I;}$m~J9@1{a7<*9qcQORNDAg-Ku=2>f_uaxa z=?@kgoF(e3W`RCVBM}|xSg~j?th2Xg(?Yh>Ws!!=w+ttuQf|z@_T@>w%T1<8Q;8or zph!f%IrztU0z5ufLB<#=lH+Im1T|48ZMb-ynu;We^xk85t3;0uzIKrO?oA*{hOb?` zPfnvNa0!FAT5;Nx19Y0Y1yPllLI=5Zk%_O8=@VN=`sLhFI@fFyby%$p5?NjJSMEj9 z`9q0~5~`0D(N>yTmrBZG*3cs!?gA6lOFVL$IUP}ZmaM4{r*d5){^;YYxJYUpU%hEJ zPRtWi#nUUvG?quh4khpWOL>b{`|#pB+PXP>uxlR5A62kPq)se+4H?f zRMQVk2{Pi%f>x5RV?^Y7%Tjn2Y)6l7&&H@d$LZRTR_+mI(v`#4kh>b6X;n@Ywce6O zWB)Q_U{){PliEowHY%|Pgo$hI=wi_Nm4`kPEs5UJ5hOI$2pPj%+CJBxC>JE-jmekk zAm#zM(h4%Eu96-)tRNWLvZ?)eI~+2UrM~3_^htv(krN*vf*cCQNGTIC@;hy{j)r+N zPvZFgFK8&f3+8=O@a>*M_@>DUY6g-8jB+}8BoRbCcuDr-wq7VRvL~6_E9kN-rF7rb zan#CJ8N@IWvaj62MULAb?D|94w`VBa=<}t0w`|!yKTUR()nx1noy9i$8=(9#J2Las zblRz|!Y?0vkI30-!es+P{)YZ#YT{8Rk{U6RUY0n{v@Y<0uN%gY3D*+Hr@v>>`Pvlr z0dds5T#w;m(r$m;APG{Ez&)_|d+7suWQ`po=T2!|whJ4hU z!cJT$AR$&6v7e8)^Cd5&_zv5#be-u-yyl)q%pPWe-$ETSt3HO`t)_x@#?$#fP2ser zW-GhiP?HavEz7&sD$cGj1jyy8qn^0Idc(0)}qNO}~# z_d$!E{_2m()BTvTTa&1Lg&TjdARe{+Hq%_Ua&mVWg)4i05Pw?<@;aT6A#<0CH1<3s zhbAv1p1uMWDE#GNJCawdF53TS@6N=&;LMcl?$5Ie0Mrlbm)0(X5yy`5=3`#d;*DK2 zFd|!&wtf}87qO7-q4Tn= z`9XpaS|@BMJH|qdJZNG0328Bm>aRSyY0_pA?j*xTcHbn-ASKrRmK;B|G6{lK2qw0M z2pH{YB|I02bleYF64G~q+}d7GcTBP8Lmw7#QyeV#cZ1iEl(;-BQOzLJ_1+3Fh-|vJ zG!7%S_K<10W+YZe#0Q5Iz;6MN@J+IX_-|+sqM$T*t#`)!gZ`O(?9cCX@pu9H)09Ad zbZHaK74z|Sk}?0>{4jQe?PqP5rO<-`U&z8OLui4?5_WxcFtN+`fR@H9bnP4k`uav6 zR-Ch<{$a_a?&e9@GS;8m%nGCPBY!hp3nJNJYn7P8s4di=TBt4LC` zDV4c4fxYy5CLQxhIF5e}0`FCFWccYwa`WFN!o>*+uIM~s05))Cpn{c^$bnxQZP~?E zt=z6_a&%?pd3v~A({3e zXq^x(m79BjbsS~LR!LF%JAWlRk-Vh-ZIkG@F*EojMb5nEV+V2bHECj??8D|*t)aUt z&eMIbm(ZwY9lky@lMi1uhOU~rlz;ixn+%Je#~+$Z=q1llyD{d6g4^ySpv+^kul+C0qi=<6uv&qHVE@VV}B$GAx4@BlBXst7@ZFU`A_X@;vOiLndT-An85ON) zr6Mqclz{Hv98Q$WMw2Uf7wGo5RbVydC)x631FagaPkjo#840Hg^yrLrIMy8NPf zOINxC@x29cq)lTi-=f}3GAg6l8lNBJsf#5)W(Kg;@56~iat)c~9>mY^cuijC&ZABB z@pR>i!=z{RTJq|i5&61tC?69YM<2HSVMPZn(AT(z9b6j425cNmk{bMZpRGf9qZ1GK zOY44Pmhe4$oyYOGdJWru?FOATpQDXBc6@UA7+!s^0ZHC%!Y3GChv*Pf_F>X%8oA&Y zqx7qmYAd+nIETkHamXEdWWiu)oO79W%ggZV7s-&A{u6wmZXT7JnuB!0M0OzS3n*R} zU}2SSiH(Cgd(~Hl?C#fKcMA}TE~&qwIsfiqQpIWRTc|M~Znc#>Q2jug|IK3(8ieh% z0HS#@MGjMToAO>?RoSF>cJN3^9-ZYsk~7OB_14@? z;vsbQ2|~JpchJJrMiSqxM0y4tqoT4^82`YN{M$I6F0@kR4d3@eU9*@>`<6%UeZ57W zc6bOAlaWLx`WbWm&M7+X*DUm_9-tq4Gf0W*ZmRTt6^$s{Ppm(MBRl0Tl+??@*}P=( z>uwO4YV=BoeW)hM7w^C_sYp^HoiE`26~S-SRNgIBg_npP#qZhH1v1MkXpQb0uxXpj zH%jObx$i01S}Dou$i?sjpJQ?6JV~Cd6yln{sIrRF%gLR38Q$cmIYS-2*$bu8tcV#w zuk`$cckRJ^_r=|8mbwjJB(mncD((<>p)a}WZpxd+2sL1=0`EOPkIu5*Nsbh3WcQwo zXJH9?&e}6?2U!@YwQ-N&#&SPY#Z4w>1!IKPo z^$+EKQAV4Qf#YknsPyl_)a2HPt{_?29DCg;AcAU&TRqMLpV=`{WYMaAoAmRkyGS|tEK=G2pAF~MZi z7fb5DJr#OZ*OIZZUNq!aAdX=(aI0)OT)mPG`Zb#5kJ}lr_c=R7 z_->#TOh={ChldJ?`oAigH&=-2DbTKNozTeLPn6)-1WY8S9wN`aK7^?XgZQG?BUtmU z6yC;U6@Nrqh!WK3A|ILzs$-m7=y&JIBx>3s)@rY0b&2Q-y(7fvt%T1cLiz?5E5*>kBjxCI*GO8GdlZig|J}Lg46#?b&V5Tf zMd!Ck@IFnoB)|C_#JwHCX{~o1bOgrB}~)dN#?r%s%TtH7gm%Kt?l!v*$xMO%wYZx&GmF+Zqvnw!)uYYBiuI7Nn49Wik4i9VX2Sid}*(sjxj06|h3XPi*bDkDRJo zNtKshCbugk*o1&uvNwAfopvgVo@qVV6k5_F=F`tpY!;eM<1T1KV8x zfXYta#cC(#va{3rNY%pGr0;$h- zhAclNTc`!)WcUrqN!0!pB?jY#l$$hTwkg((HyCk<=KkEl=_o4m%h!*kQls{e%QH{1 z_BmJi&~>@w%?>YKp>PPBb>5UdJ(MSaWC96$IgU7v$cHGi3#4RQ5dB!b4|Z*m{b_Wlh93#Ixt+d!;7wY!2lMfL@g#vSB3^w-MDh7sqBOpS`rQfR zO{THb?(GLm+~+_)xSLbm&Br*+$bB?I>JIs&^cUSWXFw%dP?KMgBu2`DO)@DZL)(kV zuCzq@aq?RFceMbqxFtZvMn!N2Mi;5>7a>Y%;v}qI)hBpSz6hy!iS(FVGX#yOCa%+T z*cI~kiIXs2H6BnV-{M}dio@q)5>^ObgLuD=2m*85=Z*`4IKv?o=UXaVK84qWvrmYq5- zi?$@&f`qAeVmf{ivPNBOYRWXoqMXp~vSU(D9PvfH)-xUq&x{>)($g9LZoOmESk)iK2P z&?CX6=}C@kdqra0!?5*|9xGjK!-rqJK_vsfkQ2)_D2=lu@7`XdzbcY&o5C>m&?Z}| zX|@xigE^vXBxXXLG|A{TKntHVk;LDT^g)m&-`dO!-W*LP zSVxgNi_+t(`rwe`Y4|9dlJ(Q2_#BC!2^rcpo1Jo7iwz*syn>yH>%`_J5~FvFXz$PBJ^uBRZ&}i$PwoZ(R7nG# z&Fvw7A{_W9#qRt%<6JW9-zW67Q?J@CxZf2@o3g9e<7*eF@Y|fcbR-*I$>p&HoGv{iww;D#r^2;Vk>bDMdc8n!;v$7!RYYSByr^7albt9$5 z8eBwf9xaVk5Y+9){I-)LNzssWvNd)Psr1?n(ce8tUz0!E{YZmVlz$43UN%7Rx|MYH z?f}-vUV^-hN+RD1p3#>cb~Ja137^rW33yO;>W5Sf}Z1UaBgcR9Hz~k4i&>sKq2V=L@x*mPMBI9LJo!7jfhD z7`mhV5OG^mz$T`@AhC*nK_kr{)r0hj;%f(1x}^?p);Dp%S!EDX`Ir_~^!*Qt&cmPT z?~miMl2IAiiBKse6uS4k4^q)qk))mWlBSX(DyuTejARsV= zY`6wHjP@|sm`1c*2t3_WhFtoa3FR90yfn#@S5x74>Qf4Op8|RP3vIecfY}8`okTSg zDT$TFZhFS+H*qL4>}cJLR!>nlxNXYAwho?7rO?ki3k)d%0+ zkEWvs9OK1NQm8t6I-Z{sD^9#&&)dIThRa>CBxqOxS9+tx^0ou_o7D{_g(V0^D^V`Y zlxNFjQ(SSE{M#DCH)zem=a;VHj`#u4V0+fQMW-%9FtJd2kk4B)$K6mk6cFsK`O z8=7uCVnL&vcuQOY&Hh=B3DKdvMRpm)V<4&rAHl^=)pYZ%WoWT;HWl?<=daQXc)`$V zRK(%j&}LmQ$HV9 zo>eF2RsUT8IX0JDdaq=+)2i^Fc9OVeb2%N7y$0{OUE%JQRR`&(-V$AAG}cdgJ-?!;9!oI05Hg z`rv`^ztFSo5M+J*1nx%0+`M8VcV9b+E_1%ZAFUSBFGL&v$}zLkC`btQmS=&*r_BS^U$D2lz2?GA0`TL&a_FaA7@&O?|K6r40srQ=af% z60~$5iVH4~5Pyj@n3=%eD+EMeyrJg53_MsSKoA4A;;IcUxb1W^ z(zUku{@qHv{XB`(3PUzeb9sKJ@jqDYvz+V`_HeqxcY*1lbHrLlXr26(;M%_h;t!Sb ze0XduB*+@@qumOuf080g*{&`gKE)Gp=_(u?dIJ2W+w+ml&p>s-9U)2GOhyQ5P{sEq zxNnIn8hsFCBI>_D<+UmQ;$4d0mMCzW>Tb-R~z&$slP-#Lu9=A_{ z^)Q8H-;ONRQ+|(DlL%E9DmMIEM9MYsucaIJG`FXxSBId3 z*DPG0QG*#qlTg8-79+jRu-lUYiIdYln0{v@6KQJElRclv(aAfvYi zLsjQIwzomh0FJxCJ{IU>bDtZ_IX#r0pR|aib_L<$gQ1e5z)Fe2IumwFy&m+-vQePv ziY?ykAn(q0GXqaUVjkFxw~}v&KX+%dmRYB9`~gKSiVI;@D!O>Mc^%8}+mAD2%EZOS zuS9b@-jc4IP^LaJv}EGz52QqDHFNo%h~W-W#Xt9X;#DUp?w|UF#Fp4W{o_ldY0Vh? zb>{?ba9htz*;k^xNs9h1R>OHiglDEsDA}re5N~bR&yr+JS$)EGT+yyVV$1D-Zft{` z4YwF{pTfDn?BQRqJ~j*qg?nVrwU8_Mbq5tiw=wS}^-_eFCOB<#L}H$^77SDf%vc zFdkSjin`}E!<7h6U6C-r^W6EvQTZ*1tPQ7U6^-yaQ}gW zaJ-5Gjr>mvKkobqu_fT@`f%}r81`h29{sQAqCh8cp~lyAanUzn_VesM%p5eA`tCZ8x2iADy8^^);h_|< zR9h2QsW61|qa9()#9?GpP@jnIs}~>CTtmDn7t_lMwb13H$mtL(oMdW2XRJNTGVhLn zCigU6UN4-OtIAMhR19xQcJetUWzf{|jCkhDYtLDJlcMHjq{+uX>L=c_M)3{>tKpdNSLb6nQ2p>D&8kXhl7GRFgnP{Ot zI@#;f)j63&rdR_qHSJJRy$cVY3L?`MCgZN^6>Qu95uR=fWXI(+Br|Lq*ecmT(tTMS zf5;Ew^FRM%FYIrN@;6%J;a@i5@A@a$-FPYfM%Y=et8?TpmK|r|xm(2R6^-!zf+K8o z$!KPCf=K6$dXq$Vv&m-swJgMr1f&};G6^~RU6F5%~>g4S<*oa z1Ii`ICr0puooCpmal@cgaXXM@cek@SUi@jGrj>1laB~;hox9!IRPB=hf12l zJBUuvW(ZtR2T%O+aOC@`V5{5@Tf%hcWkWT%yQm3_MwoNUFXQ3$i9vKhU^Y&8HIRpV zQo}LXE&>cN4EH!cgtL>Li>3Pp(!XXh)AP+$|qS?eE-xF?0=0Q4zuM&{sr$_<)akf{b;l-eI>Cl9S5`e8w-2zGvtd(82n{(Fn(+T z`&)IMb*`yq!P1wA{i!_IKCnzOXXgmk(L0spt<#qLQPkq8$^)Qv;C{&|*9rVh<8<=v zU$yu`2TWvT&RNVbX$fEGb{hAs&IILwdNAA23`XTD(Jvb^A!N%aI^YYX>PM|0PRLe< zbRe$PT?W71hr{6dS;A|@1mCQ&r7l(uwDM92+NgSf%4QN1`h5}VU%Vs}%w|#N z-dDu=s2&(k-N?l)!n^e*qtVL~nZt{7;_$+8bV9HSy}u`bk;BS7`+6(w{8oT!+a8mv z4qABn^h7v#=A0y`R|f6|WMQet0H_%=gR*9h=ADWnhh-NCXX!%2WC+C1YQYxjN*I zlEPx}BbsZ~@LH=G+U~6uw>&k2<*6gE*kitEPQrLRD)~+BG_J=LspW_{o@~L(Z7{z= zOOpQ39F~>c7Jqv=L6Ca^8s8Jrt%~n>w^U2=Jl>J4SDEB%xet1T&ts{=edF|4Vcsftl(p-QL+?SGiIFg0 zFl;S`z4EfS!rq;4tQbmCeVWOh9vPnL98{{ac^LV4`T_gyGl9t3Xpm=yzOX<^g#{Lr z;p(K1WUi?%ukktpV;&#DL7j*B>CRP>JJ$Vh#D)`m-||yz-RpQ*G5Ry{==ex_(x=1g zG(y*(jO6G3Z3GpWt1!UMn=V}A$HS= zvZdyC2eJ+FY548paJDHffi&IxOpHTAVVR*KUzOtm?XQdI^V3HB_C*=6-Bk!fYgB1d z=ww`6=*$=2siI#hqL}&F2l&{uAGp2R$&yQg#o;q;;A-n!yf2l>X0&Drvnge+e)X+H zwepGh+^kr*GqR8wcMs$vipJ9D@-|7~x;I#pzKbZw-xrVb^C($m)=N%!f501k#bkTy z5pm%0OZdyhgUw!%C=UBK7Kr{jGO76w^X&hb1mv`nlkNeM?=!6leySBe3g>Wc%taXg z&6+KE>kL1aMYD(ZYS{F^+Y%R#Yb+|nv-Iwh2&lU+NEi){qWO^z5}mtO$#dUd%;MfT zqPZ&vJ||m&$%e0F^}D0w*Do!Uje9IHJE_1jB5ZN#t~zFtwGo=O>cfMODC~{Y#i~4g z!pgKI=K6}@(UmUo{;7-cE9GJG9RsXNw#CxHYPhphLjJSAi2XKwVh%nE;AFlOMZ^ew zJM>X5ua1nFs*kD~GvTo?=N!DcmFb&5hF1q8P&c}Yy%^TSQV)C)<{qzb&$Nfw+92F_ z8hRvVJ%jLDRt=lEYz}qHa46ld{v2`k`%Gq-p2x1PI9k5Uj_+<5#^vKrLSUjMU9NbX zDOmKORDC}F=<5>w|F_~;rT{GhX!?9gKA2X8LGbKaTz(O8^Uk~ArEJetD+aPJtD^az z<&I^^)t4X?ec7*LPCPVn6IaP_;;ym|;Q4(e-;}9xmpf4ImNSYIbxLE zE#?iCu6#*Ii?Jw2Hfh#wk#IZIULyua2YD*iV?PqqdR|2>1B`VwGElM5ZwUd=4LzJvDLLMF82Ve6P5 z;-WuxaPeXyY_sv;M{UB`Z2LG^Yx!1mFQm3~l14H9_?3a_M;}12)P+*N@cm%)bqbZY zUksXpT+De{AiQ5tK+d|aWYKN|_^R(Wus3xxeLwgg)BPh&N}oNJR2^A|Z?4;eyWf9e z9H<7((}#g+od+B`p^tg9;$gB^8~eNNJ`Vn)#vP-wv9Y)w?rmF$+9^8Z+LSHo`2yb|hr1`$3$%EXkWa_4w%b0+Lp1$LHO@f|AQ$*!L=JKJHaD9xcftnePr^ zkuU?Siu4p2HrcVVsU2+8Hyzq={1Z!me_t|k#2d7-+fUwYJjA0v#$m5HV>@rU^4mL3 z;?glKBw2t*7lmfBomSH&a^;I*#>!ZXY*(i!fZ$gwjDU5k266>{4+i{-dW-5uEPk-&$$pX7_@ z#&VNQXPDRhHQ4&S1*Xr+$7(9 z52_%u2P;qknS@s)^PrpUU=qzVlpC)A*@HJj=jU07zQ^#}{czmQQ?b`$H9n2%WwWX# zfv>y(W;d)APihVpL^1Q&!oM20_u^01yr2uOUT-8lQmt@mVJ#aqMhRlJw4jSrvt-f? zib0-xFzUZ#G=*wGFrJ7*cPY{%xv|2`MGMUQC!puYKwLVuj$9BVothm}v10UWuu?gU zadXXKX~}P9+gFAMM;D@&=0#Z2REs{-l1PJ;9qJwr1KFed@b`V$YXxI{;rrua=CWWd zRR7n`JPpS2@YpFZ$m{|}Z}Z|(wfDilHybR|V=ytp35tasWKgCY`KTYwR82R*?4T+1 zgS|KRyfupV%-7@%$=2LT{RYjb9SsLmf|zxbIoC0}iC^EksvrOHbREo5tdmTt_zy=(AIE2^o3QNWFz}d`$Wm9omYjFCz_2MNNz)B` zX0S4x9jiOcHY_wj<;p84a@sG5Jexr7fDd{7WfJNL*}*@vE~D<@5YT*c8P>*Tkh$e{ z5*Ll#*f^}7goWzi*K5K|f3b<=m2?HB&6tS`E?*W;nEa)9;(iG+^1X)b0<=BL^b8qj zBTY-5cZe6(yWn5>7p&M(0i*@#Q_*z^c6D@*V)kji%ynmL;b<`Y@N$~W;M_sq)SW4{pvuhfA)|Z8Qy{6V>f`$>qZjWCSuw` zUdkzhO15NuU~Bq~Apfqb3UiHSa#g=Vl0Vr50+$9!EWMR6d6yBJIlqJ1Y`%jVHfzJ- zY-j9zB8&aHEQ!SMJiJ|bk(JE$M2C-8@LEF-{;YMtK0%c6^3p}}^u=@1{aTh+$8E-6 zn=&!Ycqln$BUKz_B8{ge+R^0T>kw94gom`_aY=+5Zjc{L4P=y1@?MwkA=zxq+#nty zspVOz3cTO2zf7Yk8;;x>$6cmr<7d};L6~et?~HVT_d36sVZ~RF3RUK+$INKr#5_^G zmI|+2yNgXGN_4{a_b@lHOac+TcqnK7lVY^ zwfHmfvArK#de;%m=x7-Ic`>;+ zM*)t0yTf9h3?vV>ktpN6v5GOhkEA5O!c99vGhj%b!2QlM9mY zpuIn?NC;v_bNa)}frYFju$2`|P$qF-yI^={4xXQ?0e`=q7Jb-O!B*K`CFSGdv9a|$ zOITfld$p>dXo(WX3$e(g1ikapZ^m9B` zH#{WP2A%BE{6YNf?E-)Y23+1|EsOa!Np#Waa%o`oJ+!XbNj-m`#E93s=>w?fyxAbStN^s^Wl97#f z$@k;Q81%$M^8K9#zKKf1SwRBfM{N{jt{o>i;F=A)R;P$3%WI?JSv_zrb?)ietYYMmt8l+QAeJ;|1#46mu?qKdpn+EK7s9#yWUeepfPh zWfBChw~{QD{=ighCZoshr);lNBdZ#{3Fq@laqYo-&_1~l4i%V@Api$jfaqndlk$Z13z9|ah7r|CG;xq8ecLz&=P2GI4t7iU$qqyI!!Zg!MDE9aCfeL% z`9He5|13;D-$*9c1VQdFH5wQC9|nf+gt?(YPFg9KRRkXu=oR^(-fuD=A!OM9J-kC+ zq=ez<4`SS6@(FAX3KAndf%dv~8LoSf4I>|q;@b}EqoaZxRghA{(}R8qbCe2LC-NXw z3!J!Q?PD8*DE7i+fUKaloLJM1GDSJkMVN3r#xM ziet`Xdj4s4`rALT=cT_)JmMJam^zGR+T3CHyJ}f{?%2}H>M5|v)rxmq>cK%UE~weMBP3kmZ>L zN7(rzZRGfy0BCqPniDJ8(%9`eBKu)7P*CecG}29Bi_$`9{vk*lbPh;dN9yyAffmr> zDncn8X>QuY*rSC#w;Xb=UI} z8cxqI)g&+d=Ft)ZOS-*(6nAxKgG;@pG}66{X^-Y7_q(*R6N{?g>AHJlh508?dGH9m!nR2M`VOTXO6kDL2jO`m3vNEP z8@+U7B=hgrl3%M$ar2B>IJMx2uqO=0r;+Id1qt7xlKwFF@HS?YGF;-itwr2CqE4Lg zcrUa+RpJ>nKT$(*9x5~`fWlR4GQd!uCw&jbeX(~~)25kNFz0N^6G&&8E5qP{pNFs$ ze9mlt&%#5~&%hp{%Z)r41}JUf$@}-h*xIS^&EhD(^L_z2r@O2)(B%~C-WCrsSFG{g zu!;2GMMFMnMG!n_Ekx5pdhjTF1&s6_#oLXuIZwF^Z>Ai9&mU&+XTxlS-eWE_zp4g@ zUn;z_vl;F#pF)Q$58;Io()3lg4cL{dQUP30*3(o-uhnW}b94jQXR5+>MOQ$1#0q$$ zu^8QK578TWT3meSF6iDHVBhvHkjtM?rb*}D@i`hYwE2u!wAZXZeKX3MUYn8(1$K$0 zR?Ifw0zD`wN+fFo>OtU=Le&6guG<_B&r-r!)PQc>sB#K6pOoUG&q~JeZB|25RtYjdGG-FSCf^ zx>EA~xE~uIb&s{4nTAtuTk|}X1Pr#GgGmDA?WW>(#Lhzk4Ygd7BevnSr&mZaKK)_7 z)g5ei^=Y_jG950yXk*50_gNG3V;7H3=NlCS(X(P4u8mUzI~4<5rmYGm{m#PX0sGL> zq!mVnghBGcS4?+hCRiKJ0K?U5h-d9LNuiSlUU=*{~0dzSUN^N6fcHd^}WaR0r zm%rKIV^+-Hqg2uvYQ`tsRG=)N6N|bJ2r9QO?5JjWEvzlL+&K5tAsScfIj z_nDewG<}ongdZ=gLD%U%e51@hVt3S)HXJSBa}#c{TQ0}wk_+YJaZVMku9n6(I$y;1 zRmbqxqPb$X{90VRFCG6qImVWKIS0=g4QZz4SXz9k64IhHXvKXydcylK7>`~9?cNi} zj>+k;d*B32Z`hB2Z8hl&=SULRIfs6pU{9W8mP>rkn?d}BC+vf#5viROh{|ra;aEk4 zaK}i8QYT-SOp8EVbqM6z)LHMCO7JOqE#4fUN}}J7M$uv;HfZz`;&w$9TQB^c)a}0> zx2$o2WT#qkQfWThoZKUBm5+f>D;&Z1qZArD{f0_G>~>+X3^Ttn3g_r85WVh*AsT;z zkkxO+F>$fXw#O0bW#m>|2%Q?^SzqrH^q8pz zBTo2`FT(x#*saxQwQ40AtOy0O8mcV!Gx|>vi99F`t^w#-TXjB zeBwtTnlC;i5F(d@S@~yjuvU>oEX%|plF5+2S&shm9fC&9j96xLkX!$qz-e_c;?C42Fpwui#2fF#jVjO>Vsy)aez%k3>GeO@${W{6pz{JAvnzyxZ5mCAwJrOl?SpF? zQs^!H;bn2wF=S`ZP;S0Voyxeju;`sb(DSV$D!UXwUPX}PwVxwQELRYjrp=)17k`D{ z&pO$z-)BK*-ha%d=n}k3d_*pkon{%)A!I1A!hq2eSXNjS3l+}12NsNiuC!}x{tpW_ ziuDkcidMot)ZnGi2yhNaAiQZZY{zW1dnqbF9&uuMjc&mb+?=+Im z9cHLK#oK2FAZf&tp|`;}2qzC12mW zd%)(-IB1;Mhv^`~EKg~eWgp2+`ahQpvN%l5vy`aXypdS3vr6(H?K}yLImYEO*5N@T z1c#1PRJrR@w7EX~lZF=5t*RiYwf*_LymicOjW+$LMZH~==)WOb}v&sw8wyxpx*4wh1`a@~K=P{sfyPkpOQeEVVlrV?LLfc9Jb+ZAYuTf>p z%c`B|+r^U$vgPcufgOvteJ0*xs7YRIe?~qnRFm``UWi>aC&^F^jUs9B7c%2$at&S zMA|=>Elrh1iM=#$aTzZ3{B%*gF$*<(Z)0TV8%fLWi)5jl9ZvkI!q!jSfXjN_@tIsy z>4x1}a4KoowT{?ERut%h6Y4Cu{@GXT@RVpQIr{@wJ;r-vVFdxqRPGl);V$aa^lJYt!y8YfOd^Rc* zT9U`0-GoY3y1xTMEg~dMZ-Q{?6d$}1sEFDtlJVcgN(@LTU>jbnMiSjf{%Bn)wR#yy zvZ*%ZyYowD^v)Ldq|70|zD&cp(UV12uDUa_-~?(641lfVEn6;dFt*ZoJiqT6YZGRK zHpb;lN_!V}k4=D0^XC$Yf3!HmdNY}La0q$cFp1sIiDXm8>f>qE7%(dw!kkBFvdYj- zrZzv4{5dk5S#BMTsrC^VFfm)8^o}eg8x*ltKT=X{Y|0WNi`fHHAM&+RjXc_z42yKj z*b!WsS8_%&~3@>MYz!ra9I#x7=Igcb5_>G|Q94SJdG77dyyWcbrVV zrvjV5y<^(xUgATB7cx`nf3Mchl8W`q5t#^eD!xVp0)Bj_7pwgX)_yO zaL`SXw(A0rQ0R$tcll^T+HV9iTx=uonjKIicrB!rIUH`rk|O@{cNXe#9$W&J9R=e7i)m z<}H(#ej{n0tw4|M)#0%}ze${3lZA7)o5c8Ff6VniwqrXKoUi-&=6TQGZmAv&DD!rVSj0J{MtWV?4Zxb)0|@3!h(*I$L5 z&DW$se-BC4?Ym0+bCaR``c%pJxi?u-a|ZM!k0ObifDiQWhq9bth>JM`>x0(Ptm}v2 zLh@3aIzhSg=J^S9eM=`>?n=qKvSEUE{vm8x7G;-e7X|yyRFXpdkNk3T4s_{{pz7w% zu>E*0-7n(@BW`7ogwP~*@s=D~CH2Ea%BzK5cq??z52nG-MA)*W0o)e$fyapF+;IPA zp-(rGrsQpf!6p^-{li!|OcU7I08285{t`NylQ7~(IfnGLgP!vhI@0SnDPCzzZHAP< z@0*lwlDDVX$sa-USu`v?eV%UHFAuKbRCa#z0q_jh;f`xLrVr`IHN11!>t%6tq1;-S zVkASeB7Q(=kUJhamrIp;9qIm*99UPl4xP>?6ORLoXSW|gJ)>TBeS8=d7vG&^mv;uI zuwm4C>|9LsZh=L9zr|}WNI~|KxG8_%2$PK3a+WN`lR1$!EQqpWkZB!7b{cNmaQzD#ap-)wi{;f76IcgsVG z-J$;^AC;G&*K1cit}qnmCOSaB=)VH3FcW^6>>@hSXV_E6-S9{&2A}=Zg3&HBp}$|U z1iIJpCr{3nw(eX3`33v%xs@k|Sj9@Bzg~yu^C#j&z3Gx@C3%*xD<6l?KMbv=8Th#R z0vM#f5`X`84z}G`#s5wj1oM}+iIw&#Hp z>H|>W+;Yh6GknogA)kBVV5`uZNeDavq5UqC&w?~{YG5p!ykSbW#L83A@i4rrGE(T# zwGad65Y&zR4Yo{|KfKrip8~9@r^$Bcv>d{9S}Mq}tR!ZYL9xG*A}Go^)5u#RsPV6l zk~4Z=#D4$f!Ok!RK52A4jClS8m)Q9MJ8ePV<%9~~u?#!DwL-nvk%d3Lg>|nV!jp&* zw7^!MHo|VWFl;y66uU`$o_cWgaWBEWV?O$Mza?WwmB9YjcL=L1!m$O5KxU~m{<){h zlmA{L8FE&%rP-UZq6m^Tv>w)X{(x;iM+&>}YN)$pfzIjz*Tj^N6{}pR#^V@%RLvL_ z{qMtA?Pc^;gA+TYPd!=ql;o!Kt(I_?V*p_(15s{-y4^iuz50Vnw*JA$xntb4aSE8k{oAAuA zt#I(D2-d!p;|W49FU_=@Y(B6Lo4ZvdzC*%6rr$&SHD7`=&mSU-&TWGC9UsJ*X-bfr zEu4GqBw)y{hooTrFSt6W95q7&S)oE9vF-ZHe(6NwkK7o=w1AEfp@(O7_^WAw|udy5^d|5_LiZ)}M zqB%Bq4u)8#@hr;s2YDdm!hau|jWx$+!nF^6(4?w^UB27M-RKOs(DV|wru64`ry@}t zVa%2*q~Td%SF=mBQG8WX9@^eCNxU>0iPM(n7@)32#&>^#rc4Lsng5Gz-W3K7(s}qs zxdy!z)`G%`2*|i2#r1;<(DeOIq9UsZP?q>;`39tWWFhW3Kre1e~3#iPu-E(bGTmaMk%S zthq6qwu%Pv4%;!TwsaWYrJ8h3_e?UWFqw>3nFAru{PAnhQN|2v;Aow2Ia!r~%>&v% zG-?I~o+5Z-i$G3$GH=+ahz@4Uu-}2(EK6FMl(uG*N2&6>RaTK#)&}EHTVd`VV1a)g ziO@GfhRdkcV`ifa9hmr5e0|C(m~ed?DfPC&yE)yGw0AMg`FuYR_ZRWPC%R1fp10UP z+ZP|48vvnShDes?PJ>6&)`7y-ckr*%jNW*4g++W0g|5`c?4*Y*TYAt@;2Nz3iO`pJ z)!ojPPhKi{IMM(`b)Di}CYt!^ravU4PAz%zE+2-5+0)zFIj}VHI#~UmTNoUKz9w$i z+A|b>4(r5a!Di5|8ZU7zQpBVs+n9J#0DMyTOV<3hK*hoNOjJ3TE~#^6^7Jdjn2)Eg z=AROE-nb$XO}`_`2vx+;Z6C=a!G4k`7@)4_3Uc5qJ&4G9FPUL>5m)xMGW)$hh5yM% z7HV%yA9me?wsR-(S$;k_GenN54f_NE!DcvkS)|yf#-w!cC^h_}(TLeTpUCs$sraH# z5!`=#7Cw(RWF0Z0>3-vh<%mS|idZRG{vuwi~@Mg9o+MgJ=2q7dcjxGD5r@0+_eDy36_c@{ghC9nw~^S z#SbQGzLAVuWyxepF5+JQBv{=iO|`yy@G<^#Xy`iNhZFwc{NHEU{$06zU-K^FFmf$_ zFh7JhdDY;W!#81!^K=26dl7!QC<^b#Ht4sI0#TaHcE)JZwRw-=?2;l(GC$2KV;V3w zdn3%-{hE1QPX~3k@#5;dyR3ccK=40VGil`fAl#{Q1Tq!#$&q#;1JQ7t3|VuOsHcuX z)5t=Q4gM!ioa#tw`o81y_sybN$vQZ_QWMiwHc0$!>=Bv`q5OChw5_$^@-xq{j*lKB zOi7#Fcrlpmd7lMKuJwb>N8@mybqF6@+QKBYCnYzF$BMwRo5jRWhO2UyB$Hbv)5X4a z{KU{ioc{6*>Up2RgDoFGrlAOw=2?T%M|(ax-G-kZ=7c>x7fE~7ozl$P4XnNAjQFGc zXY$DCCp=ah&u;jnvYg~ftlM_JWZ~dOq2KdBwD`|L_Tr%%@0h!nR;Ws&-J~m}uGbuF2#tG5zOuLtCYad0;KDwa3W)v;Teh>e}JcpyY>EdrYY|Mhiyzco9|8AR%S2nwVM@%(*WK-!uT*Sg6YU!=;Oo@6;t+>qfFlg+3h*tJr z!EL7!|MFU$*M)BhR;l3c;VzUHGeG}=CSwMYeZ6;p7PoRhFX}qytn>)31 z;y(A=xHxY%9UErC7c_5S7W<0vNQOLrk(0<$CR9UBNE{9ubPwKNltbP9I`roEGFEt3 zjxH#uWQ#WpBcnv~#Dm9nNxY_{vz8HmVbb-#VsAZ9&?!5JCv&{;vV}EVs$7V=it3R5 zPZsreUPGtuYjE_yY5bVzS8BPTT9Q~VON#w6SX4wb(Y^46IV=KE%N!Bh-K&FP8c=FA z>lx=8}GlAyt&#y<|UiqkB`|*?Y=Xg`?i&(l>UM0 zb$V=;UZCWUj}{CsyuywS@}SB7uW)8=GYivh!$qU6U}@e-a8fRYIqRMALhBW5KQ|v| z>W{@?vkrsK*Ay&D{lpx*rjp^e&x$tANBX4J3eWy)6OAhy%inzxq=@GvZOwal1~UwcQ%s`U=J6{nFTgwiEblgC88Q|3ePWJ`7)t6tG@=AJ6<= z!KJIhao&^}coAaYou|M$YF`Bpf8?{Q&z~jcb85g?znd)97ff=hvgl(dfsudfp>4rS zQg`wZ1}SFY;6W=<>EU5qw=sm&lrDjof>m&+e+q8C=`A_vIU54?%3*zZ89ZI-MASoE z=DygFwJcdM69~D#Lt5beG7PuH%kT|GR$z8Xfj8yur%UYI zaE{euDBC=M?fvXPQ-6)%LVS^+GJCnvD%-wor+^Ooo6t;OQXo=ciz}N z>y_luQe!fhRKcdDKP7{MEgvc;KLs*tt{?WquZDN064_v_WD-@C11FzcW_y27YTZ7b58d-j z9DX#G4RjOk?i<5#b6*Ha*s)9eI%X9fO->S<#J|AX0s3(BZUFhQe59mICx*m??F&pAebYAG7>VOZdc(5K8HLjPWs2IUfd2LuY z%L0n5-Jxbp1$q3}0uMFklKS6=@Oyj}+cs(oAFHYfKgTX0E8{G9XZ{LQFBr!j+-bvW z!Lwm|&}q0__KkdrHHXEyUSL}(hx;8auxaMU@aEG>*n96dcFuebcJW4NslJlSynj#5 zO&)_|4CS~H4<-gzg3!KE0huht^$(`dDd%rOjIeKasWF16-!=He#T_qRNTXSWhq>fe zK6?>a0Im~d_&u$8*m_ErSM^wy*36uRC&o?!jh!kWpE{VDjT*!ErACm7Pg|fzwu0<8 z@W2HR3Ls&lEF08UgJmOnNyYRmh>Zw>^yp16@!Tb#r}|Ng&xpS!&xgkL?fm3o8@7M4 zA+#@8%$~ifVM**g3{1`tT^v<{Lz-`q!08q=lssiGLS6!S@`U(=x?q4YgMQze#8&Bp zxUWqZX9?gUO{)`q2k9ven)0XDv1xc zjGNS7izm3I!TPb~?5L9tejgW09v5CDi)8lVh-*(v6BVwo+s6y=oY7C>?SF-hl39p* zA~xY9y$(`pD#mjAFj#8YOsv1;m%2Vt7is5z75^EY0am{+6Z^+&$zvCH^7h>fI22tE zT0!&ZrGiMNx}uByEPTW!d~9V=`_6&!?dwG9Wi(i)S(5T58*I&cUwSaYoitC|NR!tu zM=H$5p9UYISNglqwf>sSdhldy`yC4prSGukaVtQ#dlGaFh^JTH8o?{IS7gMq8zgmK zKkjdKl1_Z2jst3SdE|&kQ1W{upV#FCyOWN<>EnYiJ|+P37B68QD|Kkx>cf0?^+K+z za{`AgU5LAl9^e!;O`h>h7eC$WM6>WnKL6W1E_G=PU;8>1TBT*nR2st3`O8i04crB7 zU!rO5L>(HSvmQ>$KN4p)=My7W14`d7gB4TTu*ZKZG#B5)Q$`=qrbx_V1zM12>0nyc zZxDaKdp^wedW*j^Mnj=YKRiB4Ft{{sbW&-@%sw>;SZ&QNgq0Inr6Pz*ionV< z6QQ4AmzYTFVA+E*JR@YhiOeayQ96pOFX)DC-CNL7aV7L^9l*6$>EZAVLO(O{Q)%nb zC-{9}9xhUg!!9`+cyas;v;0_yRhOfg?&oW0;?ao_!~cmteIEoXh1|=Qo3*6+h5?`S z!U(+_MzLS9={RisT3p){hA*E?2E*)2xXz=1Ro#6qsyKO==tnKUSXZG`9IgWqUqV@) zQ&x#=#7DSdOIcjt4T$pXPdtQO!q25Qaenm>7_=q~jjqqbrki?H_3>n=t^CLO`Zbds zmB*N7i(tHVPsZ1?>&XYZ>&!2r6`e^N>+`9D?7kaVJ1ZBw_iQ3dbdp)&(HEeacUw}0 zCF1;B;b3hQ#V9otKQ#I>zFhbK*2`*fx3l^sCAoEKq9# z%}r&bblxLwZ@++3> zX?mg#cS7bv+K)2wc$*PAo@r-`Hq{D0AGkx_vOug+8wQ03R^#Ra@i@aX55_FWWriOH z@xJN$Fd)berTU6o8kGrro=PG)aYuz8RJtnp^Wgz|7uO%Xdu&i3~1b#ob7!$Vcp&??PsP2R`=$B@I)_y&@rZt7d zezo9zZhr=|CE^bA#|1PN&DF8_ri}e4kt|9dMeh!z_#xMvY->&BDwj5hOu*?p$-xO$ z^qk{C?#toFltIkxMJI_gX@OI#4QRODV0gWHAN;yq%9h?ggLFVHZtrW$h0WJ zuD0paTJsF+6XZxMoxIqE_1|FnDr*copU!VKejxozvRU_;6c~BwqwrNa8+zJ@z*bwfjCye7(D~3?HO}ogJ7Gr)j^95$q3hd|an;iALz*D?K zX`LNHCN6yhzvQFHd-o8$P**FOP%g7u3H^mVT5-7e-+Zb#T)Zot_CNm1N@4OBB^r_y z$-=7Q1ii->K;QE}_GND*z5VVmE~*O#g=u}UM}7(qv;B*|4hNI3yPn`u#q(6=;~_rN zW*h9-qD(g=pC_jW&%*;h6DZ#v2d2X#cuM+Udyg+V^lip+?t3VL?-^@L)AN@z>yZ;t zrtdjA@981Fq<9UjHZY|P0jAWg{4wxH627oOg(eT$OlO!R@ss(d!Sit*j`O>MZ$^%y zqkgz?kHx>q!nn51A{|PFE72jKIolU9#rN-|U47{2W7&}S^*9v1x1#0`Mv%dF8JHzL z@64(4=n(ga^eC2*nA=Y5Shx*_{tCiC*Xz)B>^Q-Pi{Q7mDfqs$AZ0=F^wqituxvyG zmK3}cjMS51|L`kp{mg!}wyYK#CP`q9r;|SLs{wdMua)fG`;xd;w&I;b zp760%PcrYhJ|u*NVS;fz3zA+A>PeLt6s9J)SV&{}9xpOjUCbsq8j}YPyCBtSsZcI5 zNAB-@fvYAjhu=ZXTrYSHd^8x3wHHninL*p(yO9*tjrxY^lL?eqOhfv&n8a_I%QlT! zPVKkZVS(3VlrC__Kd-H+>9u73<@m_^r`PL(L|z6ukXxaJ!J#9_oe4B_OAm! zo0$s($7PV-A$Ih*PB)s0^`M7S#QnHQE}W2;aLY1(XfGr*U*!Cf@(8M3+JTe#Rdm-) z#p*I8{&&A7K6A|>Q~7YX&o02#0-YYB)$~4WAmk zTH^cdC|Z5qjfx+FU}yM0N%3lXEbnVhXG#9BDR0NIVJ`$$RH_6^CJp1)s%=5W?kU+m zwjP%~bw}&ZaisG`E^&G7z`hPHg6kzxcDKe{#q-KXU|NBlfGYUTeNMjJ^T1ndp2S-B9BUFg>!nmdWShi;j@cG6bNU7% z8#f)^-n+{tw-Z7NR$=$#eB5N+4e6h<*tuLU*wpTW9ZN4^>$ovw-}nRUxP~eJu}Pms z7ypA36@QsdkQF^M=P%jZ5=2r=&H3&&UB1C5l4@?XVUL?AjHuJaL(T5kb#)LenkHrk z8^gKjux4_0Wg6XZzy-q9G$G}`Zs=9WhdqCm)4om@v05=0o+O9D9 zZzaJKMK`f>?Qpb9G-orN*2ACpLnP#&1^KBGD!C=SRcQSn1%G}P6QxW0*hxzQJ()eQ zU(A^qNnay{31(aa^T0vI5!UB;V_oATQhBWqEhnEPht=1ki&hTGCikFK;0>&fy($DX zHj+PQwFtrW7o|&@Go;SA(2jeuFPlj zQWoz}eI4*&sT2!PmXXMfd4^N(K85`r;@@aKTQMQ{64Sf>0?J-#@MTtd=vL=JCcO56 z%db-Sv!OdAC0}Qe4@NuD1wN7v!*;wBcdBo2PM zPht}y-{5x=#BZ%JhJ#D{)201x;7Z%bA972`&IYLsYOu^Fzg zc#Q79RuH>JY1*6sTyFhIe$wa~2>xjzw|F`qbro@^@>aMzH4PPX^0A~>A9Q!@r^&ic zz}k8{`mZwJN=i%U?Pc{SXL%d5r50iHt^zjc^F7Fy`M}0rC}8ecx;S=OtEBUH4qh>s z2S+BF!_)Pau-~6UQhN-`I5$u1vw89_clz+-Yt#{Y|e-3h9=!Md4QmOW%nH--rIjRvH5Zw!0eD7tn0 zu8|$@+u5`G^Kqn#*vUwB!pgbc;4S|~a=*5cINVi%9Tz8I-=?QH(PN(7xaKyIPcfR< z&7FylTx99km3?5^{;wEuHy-20yRevXsUqjno-m^yk~*(Up?QZU^bZ@2AKtFw8W%DM z7di0>ZUJ~u*A-7!wZQvzbIH8N19+;-C@vUBvHzN`Ag_4D>gMi*j8~iA(vd0+!j2Gy%Ao=6_~c(S8@0j; z#E>_CzTy?FotjRvJw+4r(^u@>q+<#9jt-p1K$9qh`VT4b=*?n1mjlRzyV*j0?pgTU2R&)>oRHL zzpjxKUw3420dkmf%@Q`3=;Hg*G#LI;7o}b)P~Q<(NoUF)aMB$PKd%|%+VguLqfCZ- z6KPBm9Ssp`BZ$eE@nm&u2kE)yL^en7VQn*=h-dF0$(_AHP#eHV;3P+Mp^OantHdz} zODdv`j*7kZb!@Q5Vir23gPAP4Bq4p}pvw3QOI|bv{m%_2M^4(|&kLoJ9lC?yY;X={ z$n=3j@h31)>JPqmFa^)nwuTLBnRx4Xs^`6dufN* zm^vj|=v&VG^2*_0t~1`7a}!rSo-bLO)IffE&&1Aaa_n$+ANYD-m&VPy!k#Zx#PTa9 zAl1Gd>$|Q9(#l7uLiq+Jf36p{e$#;UHrK^0owVfJmTS-)GD!HivmdT=_Gb=j*4q7g zJe8MO`Lfe}{)53{FV}q017=yif^JLbU>D?rL3vFT{MXQguj)N;o9A|FKJ6&D1g;>x zS`PeNV={?ubL1EPBPf)Ifa16vyfXTD#S}j;GVxv*hB&uFuC^ly=o-jx`%mOqbJgwB zJGHrKfg=y}d4qM{a$MD;5VcjeWA>)kwu2X?a-AW~d+j0atFm0^QG^W5J9g|DPf2{qY_(w>A+OApvYn z?h^mVV%GRP9@{MAY4#k7JF~_^x6FG`uU-Ui{TyNR=Xks_axOSbON6$rC{kxQmzln( zfzdxR$>WWapuXR6{8jJ}%&urb)%2w}EO#rLmVZm~=3Nn-J*i2R?o7p6NjRLE=q&jg zE#6rdP7_M45^#aV=kh5Fj*$a8m8|yq7}!|eivbg#lcoJGF}rO=q@Xa1o%yl@)-T_T z6GHDm&W;xn!=E!@YVcjVzuNH_uCthQt{W(NQ7$rlwGGTqN}4~u{}RfT4VcBfC`Ruq zGyCsW?B9xmHmxg?A#buhEvhoXNeVmQDdb}3-#|1g(q^HfC$qRwkI3K939LA-gk+yz zjKfDy!78!CP?_@$e;leOn-3R;m2c z`;;e6FNS%dL05Hf1UFr^3lnBX@D5WIzBgwv-*;Y>KNe?``(NI`+IMUDnKwyzGFz4( z7P)i})@gI>aRT$3Dm+;!8G~YK@VQD%npTnM7DdUrFX+Gx6BTS0Whb?~jtoK_Ex_d^mRSObvcD4^*$zF!?kDid~X|`~5 zmn!R%mI2vACbC;rZ3l#iQ6g{uuLSe}%cr zW3f?6?8nq=LD=(Pu+opm@Ah$U%X>GLNCku5@VDSI@c~Z!X(gBx?nT(J0DbHY_;bHN z@;Sx_>OWs%ldiY2^^cxZyvay|7da>Jgz0#$`zVs-ttpZ`o$doQ3M29NDbd$*eG4A@ zIfQAq0}N{zRrY;bH7WYF0jz%&h`I1gbia8L{z$|=Wn2%QeP9F&?|lXRPruom@rmd= zaV<@^>BN3cr*UCV5UqJ0g4J{FS!S~ZNUtqNwb9+DIGofFzmws7hJ7#i1h}*JhF8#OdOo&}zlx5-L~i1HM{1Zak~w}3qMPcp zL92TyD^FSnN}d|9aCZ#Jjx}Nr5{g;)fDG6_x*lsXBZT`~P4JNN0o=6mG)wY`#;;X_ zFhOq#YW&_rq{A zt_S49Fk28rmfQ9nJJBM=5Qg1YgHv|tf?3>JI3w3Wwv>#Av11<+CT1ZH^_hdtq7{9O zM?TuTVVl4#ddVdM0Gy-n&`(#6FW8?^;mz{ zjlQ*Rt~jyWhp#r*TH8Iv{Q(%TPIfP5 zdkv&pbDuE%-rJa{Rf}Q$W$3u;i*f54Gw8Tr2hwt%1g%>~U`NC<9KS9NhqkJ*1K+yA z<;!SxcZ)hX+Sq}|WgfAA`8w?HrZs5$*aLI|@-bFeyW56+Hd8?7Fv>wQxIO~F)g&xrO8?3_X1gL8EWma9XI6!|3Svb5wcml7P zjPf=Na-N6RT^WfrN`uxbB}{vo2_GOW#U1P&iN|X*xN~#`3p`)|i~SnG4F}LmQBpAR zYa|<@wZQKA_e_lJtzc>62U5rL68LMi7W_2F@|20=dHQK3a`DS*Sf$>FeP7LqR;?PX zIdPnRh-pLPJ2s@~WjI;8eI$HX`&Y6gPYs4Ty(6RHG|Ar_#=7GEBbILqNlSBZMfcaK z=&-v>VxO8T_T`G{Ja-ptc>10sB_zP{;ghib-Z;3mvZ`YBolS7L?|R6u7)Do^oPtLE z6i|(SFYuWHv3z$~(!BQw-7DEfHFVAp4U@g}(YgX`9yOG^tUd;RwtAp@Vg$9!c7Vx^ zE##`m?lkcl4HIiO!av1HkSBT?&aN|N7v^LM;lCHtjV-r@seOIvprUh_G9n*mx=-gR z+Zha~e+EZB!Q~K1 z;F?_2&EE$`;hVXmeYm84=TY(_YZbFjx`_EYpJC@Yf6)&D_|JYmy?_$>AS)W>+c;bG zA|7<(Hc+GH6}Wr&F?fFV0{$2z#m~M;hGD6H*m&s2jZNF&<@^#zQM|@Fv;y(Zk$H5E z&l*@AycC7FXE?A++TOUo=wBS1Kze)rvfHz5`11K{prX8j#1)2BY!Dp@zRsuMwK&LM z7CE_f)vM{(Ra9`*%lW|WcS^H~)g5g7)2iZS88!cB~fVGR%=!m;#VD_XNU?4gq zgYyTG{uZX_>6eaP4ws?e=|ieBC)7`-YD1q71;Wensl4gng?~OFVO!JZZxLUI#rMAkqSJMr%eanX)sdhtid1g{lr z&eK}bqNt4WAHBih)Iv#wbQLzZH<4Xe-lLcC3DR+{oYYF@k|FbC@%SOpW%woqhAc@G z4z;$jFAION?47TOtxhyXjQ4=Eqol-aemqmZ{ExYH_Qjc@`W3gw{2-}Ur+`hsD?Aq2 zDxB#5g|u&1<(sw_;DE=M*w<@wAbh(8uF?qtukRFor1ux*kT2XI_cGaXEr-5o(ZrJRvOMAXH-7eTH_%vRUemf6V=Df^%S^)k zv!3C2(}R3+(j;DOi99%Xh&aEtaDSa9$(I8v*se1QU0v+?n3TV4-My!F2ag89lN?1p zAkz@IeGwcL-3eFUUVzU%4Xh9T#9Y%X7`8PU2WY6lvR|d>EV4`H%-Q=MTya?#pk*Wo&VAW>lk-qq z?)3!g&Q-fNb9?JGCf|JG&MVr^C!i;V!%N1 z#&{1?Tz{R|HN69)cx}{PegOVdJcIW_8><|75Ayac!Mcs+FyYNGIM=8O2McO!6B}ls z<_TxKTXqaKoYllVyG!ult13`<6M}{w!IV$drnJvH~AfxB*vxBp-y_YU^PF4#-B?>`G{hHZ@CMf z_tnA4Moli4(5GTSttQ6k_2HlHl!8=eFWb1)3iPwvpnXOv*_o|G=UlqLcG%d9-PdIH zVa!)a10VV(_)FoBz&KsC-+L562a6U`lDUnA}gK7fsIb;zk+n z_I5ZWV@^X!lONtwdVpJu+-Odp5L_Cx3PyG>hQ~uf@#pOmSn@}S!sZbEQ7cj?eHIN# zbO1ltSjW*f6^}T1;t_+5qR-L-HeV9&MKzC8Z}A-*qC7VRdG&3kY_}Yii_Y33(p~s^L_Lsw{UnR0oMm72 z6!?zj91Kc6LNrfbkvy^9f+bt-BcAGH^UU4o{flmFV$dN}b(ZCya|hw)1&hHmVjsxs zI6``Vu@7oGlDpNrGqdbu$@5pAn3CK%Vds7~vQL?S{GA{=Hg*xlUAE@eVH~f1VT+6N z3!wR(BCPN4!d@>~2c{pQv2NrengDM|Ti1T7d=XT!3+sE9C3KHC#({ zC{@_R;;8gaA`JRN^xn+C!>$2n)IXF~&ZvR5DmOtgD+2dKUctH@`@p5RQ3&g-29155 zz^)v@*mpC@=gfO-POzz95y4R*=rlS7y7B!VCfjFL$`0 z%bWL%LDK;((0^khJ@EA^3_W=Vx(-ff|MbV;RJT+i*uYH~Uui~%H<%MGRZCoCH=R0* zJad!z+0ZyA2CII{^4d#-;m6jgIR143&9@xLuUr|(wf5Q27619--zpUxupk4x`5c;) ztII#yJf*G2I$)ebh{!ZlrdAy>yy5X9tgp=i;i?X8++xZ$)DGn9-uI<1Q+wIWf!p~i z@&0RsFT#S9|Hv3=eR?o{7(|LQzsa>AC>R;XcXv6XMS`@@`6Yv%&h{rtk9_dbsqf%s zp+{P7*>S%fDg3W-GPN9c7;P$N(*L3&z{{(fbZxeUL1y##tL0T>L{KpM&*TdY894;b zuPK-Gtz3gIz8-?;A!1ItrxMo;H=@yw;;gm%1GF2<)1!BF*}D;e@a0wkzIN22yHpgg zp-I->|62mP-28>TpHYWd?Zt3r(s7=sZj7^S!f?b9TeSNX1kD%v(TnRhq2*%HD>y}w zJ09Cj=Pl`#yup98KGFvDrhk)sA2tn}_C|r_;Bj1QPn-C8=<$obqnN>(2gLQ(eaLDE z$HPi$Q1Aa8b@usyf`ShCxOP#O*Ks&i?kKx7bRl-_{Y&=TkjLDtSXTeI7tc&;lXTs* zBZp44f#UXBHYt{hxxIS)xJ?S~m_)))Z5?VAa}-Hf7HdtMj2%Ih_#u_$^kjm1g%p$OAC?q{m=b2OfuyN&#X@~z|27iv= zzf&s2Z^mI5eIg#d95x}lCTWRISZywKZ31}{fLQorA8GH?i*ELfSUWBWj*S%g=*xiG zi>z?75Oo?g&lH^MVj)UffiHhOmD=5E#wfv$%k&O}h=!~1+e;qpsz##yr{OqV|1ut( zcpJ4g>d~#1kHJ3Y9c&az$gh8uL}5!6PO`Lt7K3|eHY1ZCIru~};P-uSSoRt=bj~A6 z`xoP&MF#Xog$yc>SxgUo>n0a=i@#5x2u4mWFj~6;KZ^U9n63ge=)A=1cB_z`D~Cc& z_*FI}?J==TcH{@0E<)f{dmOmC7(P}kAY;DVfCJkuiA;J0s*n-Lp1;$E>_x@sR(OaT zdojt%;hTlCsa@>fA8oj1`yC5c=0e;RBlJJ@n|KZ_AkQndL2R3<_**@Ssudk0b#BVw z7JZn%w|Ij~`Fp}{9ww%57BP=ArR4Ys0#EaU>9jB7NT{|Hbeu^h*$U%e@?9fpRuV*a z^y`8JQVSruGM)#;&cP9G|G;j<0m;S%jqJvqC`i=Qg*xriR5E%ZiObm}Ic3)u_RP+L zJyjx~U33oArNq;N!);;zkNMmwOdf4JjOZWp8c9^M3)YXKH09AaxS2AKCKufxhVRaS zrDYTArXjfOjXs?+Jd9@Ut)fZ(nUK3PiW|tE#&3?IH#ty_+q9LUo?9XGc3**SVxKZE z_A=RcAfAg%RB^u|SGnVdO=XtrMN-?_PNF?K_=Xq-7HJrpZM z*Q(r-EVgpoX`Z}GiMqUh&fa9L6It2!B(L)B&{W+t?z`F+Rz+rU&sl>iGbJ``(y9~e z=1vc;Tcbei+N-I>*jQm*Qx%VK>qoB?v+T#y;QpI)q0=KgQfB$BsV`L3g1 zV8d~3zGmz)7<}81L)LQa`RgKrKmEeI6Gy3=P4ls33WF{i}_oeJ- z7$P#%wx?VIqqqb}ZRF zHGWfJv(!}R_~QjjMF;$}4Zrwl^UKWW$PvCc%~#~Y9}wm?P2pB?3o8qbmQnMH>)h)5 zE%xjJYet6ejQuhn}B?o)pfuLEJ)kKfMV8)l@2<`rHN!^K#TW)B~ID zhm!TZzI>j|PdKL*Ls#7VkIWwNQM{{{qbn*7a+j?UV#hs@``B0F1j9C%(D{+aoQ|a7 zqd(%wg`2=T^Eq6}=*#m(Hm2NbDf`7mf8l0T4;ogl0j2vdaIKIgj0&#gXT(1D<3I8= zdu1MfXc|NZXNBXeyh_QsuOjdN;$pPcdr8dQ&Fp`r1=G}1Bl$!yU^Vn4tGsnocpmdgi=b|P2 z)RNIW%b#InPPRB3o45dCheUgGF$Rs2u}PV?k&OJ70}mp$NnTh)vOfzGVWysn z;P&7h-1?*{@iJ(F4{M&_fTT8Y{vQvspB9o{sn@8gG7T5KRbpz_*W%CgE*OHlaA)Tc zRL>3<4$a*zI$ky5qR}sGe~?2A<2T`#S8G7|ND@BMX=JBMX7NX#By4VgA5+|)&wljN zpl)++!JfhH!t`5;EbzNEdpM^8a&+%uLb@}qSg4A(r)g2|6JJsJdl_4y=f?L*$FR!t z<3T%l4BCuVgy;cNX^^o%>aE@iUh7;z_UuV;c>j^~DSV8dwB}%}LptqrOT>F8hu~Z* z1s)h}jUP{au9!IIBB=>72a}J9bYJ^Y*73U!>tjwKvCl~expGPLPbP^>62~FA#!WjLA-7=1$2hZ6!Tph@aKjxyq{YK ziN8LUN9qhG4^Pjr6LvnX zueuhV&Oaxz26`k;CGZqkk~e9G**Z3+L03OU>wihKbN2b}%z?)9~Qm9H!=F zj&BY3!OYB3>~w2j8#{7gndlkbXfO_jUXTN??H(i`x)BOuFQdk{SJ2-$keE(eO02$x zU_!B&B`wTg0lt?=_Y7O2sWS#A{uA)i+ea+euMVc#8Gw-OfnE#ug4%8-Ox&ghcjA&+ zfS8$|(m4P=AK8kX`?FZGjU`B|n(ekuH^f$vOYqceDq7u6g_f95v~3G!28MPJr5Fcp zvZ}BzNuL!BJ0Zvg-y_d-#Y@w)i_CmbA8c_P#BQ!GCw6T|vHypuxZd^x&g>QWJ1cIn zxLY5DyC-U(??7kxFCdgX>+fc_;G?3*8+awu9xq|uk zafpP9=exWj&qPtv3?ECKB9l+wWbGgKgPC~m&{$ju&d>5$?b*JP zm;fsnI7ykDEoy)?A%Xo_`k4i?61bO=jy)`&bh!qQzzd2j%~e-eWFm4s&*x&=OCRz` zvXe}GPFZR+fUJ%wJlz57mmxEfZV(^#j=b*A8XR`A5bA$LqtogHY%RG3k1vLy*A-)G_4^>vGQWWDb}QmY z_Y)G8?q&SjQv%~XrofwkJ@kV`6jvX#n0?4s=Tkdk!MQ?-4sAaTLsJ&e7N0rzNwx+~ zS-D`wbHWywjG%Rrj-X@|9HU28gt>^)od1S{G0_XOF^r@ zjqvL3cu8+01$+tt6366I|!7hv~=Pk-lHsuwnLiSnnN#DKie@_rfqqib*@`PqyMK z*+ddp0KmlB71{5d*U3=ZYaG@Xj4`m zGK9@DP3hH^Q{duu5C-^6=3D1+7_fK{j2s(F7HK&1XLF@+TFwt)*s$BA{|{A|I_R!Dqt58{6&krJ^_`axtRp2>S~QLzlYS^UUOVScSJyTg$E8gW$OLsGbt$TKg0m>|qcbD$N2o(h@yD6loam|ah7Z6YHCgn$)ykAR6v=1VcFaGZ!uR;-k-sxl*qh=t z81m&9u?$TipWTcxMeMFl{&<@$S@)R@eDIRwwCyIkV;#tzav7FnKLC1nsNr0vUwG?? z=tm$1=pA8*Z}(j%zg3ShwN1lOe6ZkOtb{EiE8*yy<7C7A0@8gGV2!Ue{o%56jwLY}ihS<9Qj*@bgQ&s_yk>4 z8$jW}<8mP>Js0XEfv`klEnG?6gD-6|$&P@rY~HlBq%7(@OcrPVzH9)Ub7~ZQGG;QZ zSq;31?x4#etBK)`Io$7|H}!Pf1~IoEWB0vwlJc*OP2J;0T8z%|yJJM=>?0YP`};Z$ zIR1@%Uu*})cfxVGe-QYIPQTfXE>uCc5K=0oSz*K%u=&)7)|DRwDUmPLG4mx(AF08d zHj3xoKhufx(Lg3&jwCV39hKu7*d<>@(#coTN=JPdy+U-n2+JYp>NIF^Q>U*b9bjUo zfF1p|Fp}>s?DXBu4vPJSWuX>0SzVsixMz!J;Ut!DDuw(z*eo$}Kg=6W`bb`uSF!-V zW@_+oqh#cQ1T6Y02l@~%*|qluS!S&Re|!|U{w;SZ9kme-cRQiUw%1I4>SZBpVjLcv z8%N$NOS5c=GPRDqA*mG|BW`Q&!mJ5qB)VTe`2OEw_UhpX{&a~d7;QX8QukMtFJ2kR zE^jGjALsNJyMXm<*VjeDL!H2|OFj-1I`R=s^dGa}NTkQ$z7~+z_^4c^X?=rAsR;*S5E z9+|50jl6rD0y|8C$=2VB3|Hi#v8ER;S*6ZZr+I+$kRNb-@IG97BN|n{Q#czif_ZDa z!)L1H=v+U6%WXMC=UfY+%b#m&xP6i2$IGiYeW@WU@hfM+TP}k9Qx(Wd z@B$s}Bw^+N@!DMi2)*s4k=c>?- zi?t+wa2Q!&nIX){P{*epNzC)Y6tY`-D{k2RkKK*%V|9I}Volw7;Y?StP~*a(UAY~m zRUbn0J_Y1QQUF=4Sqf+Tg5jBKoy2&q1fKn9ljvEgNgmBu&TNOCVaaDy*qKt`0AD{js0^9f|&?B+(D~3tn~wv;M~}qnXPMZ0~m%T}od-zbOKy$Q-3F zBW38MUh&|X-hu0n?1GZ)7#3tdfd_v)#Z^_`M#CNzA1h@|3JH3o?$-;kRtz{8-D`vnN>3R~c z+6a2pAK4Q!9^yyoz_7PB$%*Zc;X`3MzVFBf<**9!&&(3W=8E6%o7RHWbVK-5eGE^} zJp#c#1%i^in1w3zAkuDzRBhBow)b=x{1$U@hK5IYsZ$WRcYi0aFu*ABiR1oNq&EZ*4!FHGjidy6D9x6Fay7q;-t z)DbhkXwg5msgka{|FI#48W8BHfcv$R$y*%?wmmDXlBfQf$1;z4V?gn}nZ3mH47pqcL;pTHYFB$2CXZr3bsbc&0%tp8gz+ z83W_EqYCH0!?kJ1egPKy?uGQSK>nig7Tjn#2`yW5#8sph{gWFH6&g{(iRu6tdu1&s zIe!*5mW-F!PtoV9>r~<1)M5x)6#zxaw?(ezPIxgp0bGB3z{+kLt z0|U_akqS+jw15qZ*$xjIzAzj8o#Z1}~K9zq>_=~G7{lEl_ zNa;_*6g^>K;{v=cWkuHezZE)OH{wTNLHb^@A(CpX#?7Zwd(ruYXF0bsz=l0Hm zh@Y{Ttf&VThcA=R8GY#eC;FISc2yGAun6XhJ*2wk*O+&~86G{#p*5`%$o z-DoMij^EDIuS)pjrV5uQR^jSa(E&UBF=PlWP!gPkub1b; z0<&whdihM)a=sjP$IKFvy1htme}B>|BjFzF{x>UV^yzc2sOS!e^vhgDcOzVNhWoiCoW4o_Vtx zH=DX~zvFtm`tWIzIaP)l1#jWof2YBtTm7KEK8>1o$wi%zf0n?KF8h#G?M4PYoTpz zANbrj0n{JG!?w?TFz=28ypC$kM+_j6GL_ww@c5{@#S=j{=ljtpWKBoV1p2 zg85HpqDz<;F2f&qwg3N7bS8c^eO(+D6-9HTC<&EHgi77L_BCayh$s>nN<^rTDN?C4 zX;7i00i_~D)7@)VNJ&vBN|Y#5_!*P&J?~#|Klj{o&slq|?|PnrR5=sK?FZ{1dRqo~ ze+`9#1}kW<@g{?XUdQu6^DxnK9iGZt4MDx{$onB>L}r^8Hn?9Dd35dKwdgoYQ=V7Bz9P&b6Yf11X0>!#ZbMl!e~l%#bUf>DGW7y^mUNjd7sS z&s#t$vRK%spN@?y1ZUa3T(Y-gH@7GZp^Y`=uxd*tjC@RKp_zN-N>lbm1z3ho!1Mfk1g5Zb?c zft^XKV1L~{*kGyx#zqoicR3%+_us+P+v+g==pHnG>Ps4rSi!0L-E387BYSW;5tmk% z!hEwBHYRx!UVR|!a5Nnv<97dKo~_py1qSr&v@yJRN-{}$5F|NuU=zNs zSccEvUXf%yEe9hZretz(9d6nBoh=gHw>M;8;<`i&m|Q?`QjUSZ>v00NkbS7DtIZ7( zQ{Y`_5z3_0l2-+gmy5AqkiD^IB1ieH|9QGIO?nOXVqY<09 zxry~?co2>Gnbyk!HSypffWA#T`Jp;zD6ALwfkK9}zvdivvL#R?YvReIVpoa!#@}Y& z?#_mrC+DycVk7jdIn7>WEdZT?C1`(4fkxb%#O2NI3B2z#xLWlO9A}Qg!4JAg?B^=H zF})oR#mn;SM;=fXx`N)8TaMMr#$>lY(9$;vWq%|ElHz}<+@^03Z7em0O^e3UTEP{4 zA?*QN9hHQoU4!WCTeDfA-hAACb~dlP8_TyQRf1<_7N2_35j;OgaOv>PFlzES{%ySh zOL1R>;CPD-_xnkn^n{Vkntwzgwp`S9xd^_kJTD0-h`~MOV{xD1JvM#l6rxix4-<|A zGq18AsAc>MRJREE4U+}1WR@54eWwi4&c`J_?bhh^^8}n)Md8Qo2MCvq$g>M4$;mJE zk^^C0rN7dxFk|3#eDh{3%dV8+cO9QY#HxDMd-*8nFFQeMa!#Q4f`0Ug&@(7`5s$NP z^h#E0&wxfbfuZ`@0hT><#c6qq1vYdn^A#oGw8o!cxTBUi&VK^&jrYl=T}z0A<{bL1 zY$ct3eiZMVLa;hp_-|eQj;(KJ!I+dZ?C()23HX)Fs?IN#bdFCES?Q?a<(^YQ-QFLK zUK}HOi}dN%u2kB!fbbtT$Kk{~X5O%rHrL7W#MVC0+A|3kgw3ZD zRqtb@O`wo=L2h$x5ZzVzk?I}O;@68ES-|r|zSZ#w%`JVzKQ1V+2KB8pdgXhz)^9AG z7##~K878!C?t2U~KL=~AuL@bVPaqeygb%&{0(MTn&JHFeif-$Rae>t=-t01pcI|q` zA76Ea^Ar2w38pPD4A1ZxtFNHRyoEUbr9bhmts~p2JfYO)H3UD(BES9Bpw;3GjExeL z1Cs+m@>`W3=qi%jA29;dWUFyq%>cf?WeT+T^fCVfkzl`6Lp1Do0xvNE%fJ%H%aZ|r zJaKVnj3`S}mD>NSN6Z-vJ1c_N%e+_RIcFudX8rgJ5!CX(~0A< zWQ@|>jjA6s`F`7x*1pjnAZt%5F8XB#_gt%iT$kX>`Uc79rz*Ih${zxQ=ioRu2kX#; z_h2wQi0t{a8Vv{B!p?ht(JUgLoxd@XuG0{5uBid+z=&HQBQR?tGVO`dZ$lhhE1ZFS zJaPHt0q|AsBz*sE4na4U693QrdD1|2erZ4nxQ#cb2byzm;GjCm{bB{W<7T43#_0!N zh9%;FY6 zR+_529HK6jlc;sGE$`R;7f<$0h5l3equOFESl}LrAx6cZV6_)V346j5zfFNPA6zkD zWiS*cslaEgdU#N&iGkaFP{qq0bka6q)c9L`&)~!G^@}dQrc(r~gy*{6&vT@FNDP`) ztsvX?J|n3t7@9^NgREvDmy^95b3%J13h%>UVrLkatQy8w?(Kt9Ex%E9?Q@V`r42dn zg*xipZ8lokjD>c`lh2XIh1}dWxH^0k+^|c*ZT%cs^BP9JJ)DMTGjFnyiC4fNpcKR0 z$I_F5y5M!K3BPMxXAjd4<7sb4;u{bJGu)<%e!f0UJba{4yUG~b&Mbgf^)g|1qMf+! zvy+UuVvd;)=hDxs2EwcQF6_T#CJu~HUNoY?PCL#@(sl<98TV{(5hnbYLayaKBGR7EAc? zlrF(D{{q4TcHn~9azuAyAvyb8L8#lGz{JM&{7}*nl&hZs-@Kb3mkUm_oNBUoK^irZ zHR3^=m1xtBHPmKA9Qxk90V7;qFt_)#q)tq?-G@#W-a>wrmS~-sAyDvY7E0bTs zPT?I~-lIyh4ytgyaYxzqo%IlLTn;u#XR_ywmUNR+5j&&v4Xx-<^2Ev=2Iz0VxfMsi z{;@9~TA%(3zv z?hO(d$SS!O zRG8ktdP9}?!L~eb8Fh zMKBH`HfiG&k0#bomjaz5M(~gk2U)-FBP2=D7AICJ@z0?6e?AtxFOsL0rEl1_&{~Pl z{(dN%oXTdNKLL{IG5E>gvS?OMIF#*SWazh{tS67-NT*AZMQTI1l7A&}s`7&i(Y92_ z(hCoSlrn4SD7LN5gCq%T&F!w^@O1ZdB%cz%^XCG*kl4r)@>IEF>IT6Pmx2*v(%8Dx z7%+>yNF6@q;hI6)(J?a>4w=q^QIE3mWI-q4K{WygUzV=C*q8@r)@`Ay`8Lh+B$K$ za#t;FpQ2@5E^AWWaacqAadr@2{vexoPu@+8F2t25S9Q?Xb*svYyEcj2r-qBKUq~uf z+%ru4)#U~+o_UE*Id_$>cimk+z_>~*yKF{zk4mptE%*-i`Wy`V2g#Q^-ASVM0}u0? zx^u*#M|8wn)CZMkzf}^qB|DdYtNTqGR`n~FRh?M=%8Rh+hcRY`ybrnqT=nW zdQ%Z=7^_T&U7b(g2M!mX+gL*uMbrcTS>K(?*Fo3koH=7sqQJ=^5HaM^g(pmEA)uY z??UB54Q?#-_1>JVqDOKr@rgn`E8W#eceSnpOR$gXf1u(BMSjb1)tGo z3%;cO$+SJNC z^Z)fZn{?_l_jz5)e`veX9u-q;eX<7kujs`OOV0B2KSAQOQyP$&G=j!3YdYrqvht&j zKTx&Qi|#N;rS8Ya(!;xBsnrk>ed&9oJXiS`OeCRHVyg(ZZyqhr9DI(7H#G2un@W77 z<~q8ie4M!O=SsTW;Tl(6T8TT@KTvc%#-lVf#Dnxlmn%ojLho(2`2o*vYH;QQ+jn>l zvD-M2u8O)#Q?impS)W1N`SvWea5myhTc20|Q9_Gd9enPVtMufyY(Br~K4$!Qh_049 zXf;!SO|NP zDa8XD&0*p?Z|-A12{bi~XwB36;O2BvWbrBrI-hQ)A8|O#9~l8>mYw1os1Q`&4O~s* zCr-VSOfOs2pmE1~Y<-@8&fPP35A_}k3NEcNKG6$wm#^Imo`}LkE$3q@AH&ne=~Uj>Q>2tAa8^9~)8n~%JmlDRuC!8`-XHZDx-WcX7XN}EI*#zS z`&{9Vu@)~^vZs9`e{*&9EchJ1oNBGqg6`#FdR*fvEInw8`fo$<&aV;F@|hI)yK3X9 zrrET0<9t3f$Bjm=Ur3L-%8N7QtLZ|+K{#o8d-?JCzy2=<~xC z^lQo#@v+7*asvm8_Xo&{je920m);G7jyT4Ok9rb!sX46n zQx(^)(qL1}eq+Xp6{u4bh(}_sv4LAhWB+kNjk#+ED7WUJI9r9kc6ciCn`2EMbY_)y zYW#w&0{|^%>v2C9Yxp#HCOFBvb@YDWATy|5BOABYx_Z}|Xd(3f^ z-5APZoGs{^<1$oX>=#_M_@n5V-zRG(^mg`nM3VD2jQN_n%V4=sMN*$Ugog&3b7}KP zRBJrTo2LaKGdzb8&J*c4zqQP8U^Pz>2MgyF6{hEEM_ackGMNo)`RUtp=t`w@U;|Px zU1KTtJ8Q+0Cfaf-`{7*S!X&P|dKeXUGWl#R=khzrdm)FZqo`J%o?ju2@1|_$?~?ye z2PJnJ{>YXNt&ry)(~Zk7Y#$84HS%2app@U>Vbs<>m(CD&h6=35a2u<7Dl7O27aD|@ z-3mF6b1sz9=p~`_?W32Z_4iuwg(gqlH>DIO?;0)EuxRGf$10Nn3#94U_!jK=e1Z7i z98a%EDe#)rZoKLHF{vElg$_@haLe)o3?&FN(S^v4rvFJ(GC&ka^I_M;9<=drNC zgK@^QD6ms@hqhiIajp}fdBX(un?93{+@t{WEp*tMifDFavLk4m+XK5UYEsF@g)r&AZb`|54@_(! zI5n0kFj)r&`0&jFm8SUP{yY&(3cX4zdQ?d0hr4Xh=Z$2kcQG+Jqy>p;s?<9Dj^t4F z5UkyAi>DKX_mfOJ)3xw~kd}uy(qa>J?<(V`&=6Ky(nTut->yn(kG^SHxLe# zo&z56i7l`C#cTvuRqZW3noT2dxsX%p^iINa-@g;}mMvx8eum;pjXPnEtP6e@czjaA zZ0FB|V7RgN7znd}+)_LfB=4-TDz+Kck2-_4QF1)(%X74URYyLre#=I8Oc0;`y^ne% z8S&;BvHZb^^?dKlWa_RUBd}8yxz`kFT6HED6Q)gpPeMLK>heDBdDmHZCTmfL1Mxg0 z^9S#mRfz^}*?4C8T1a&h+-kN*ackpLeC78BAMVnWL>3I<#@vaHKDL3+(cwHuF@x9N zTnclK3ckr<3gEWu3$__fE;qB5#}yu%=trAVe2d_NdlnVQZ;)j?Mv}uj^dFb5N$cPT zg@eTQphW!BXeSwRaS9!Gts44dR?vGRRdLn!ma=)%)5&S$I8<#r1J$#qp-ig=w;wF9 zP|P1m=Da(Il7iWIKTb^S7v2C%4?B`pat3-|R*rh{Nsf;`n?ypkt_6j+HIi2jdKlC@24q4m zND?-7OAHE+;Hl07L|kkHn=Rw8^W_CBnRc74bZo`8kA`gc##ub_>nN}pwI8R?_))6S zI}oc1&wyB7$jBuI5T8^-KDf3=vOZ=ad!ly)-ZiM=(3uC&&|M!7UI~GlZkO=%uH9fg z(oJ**1^1FT5GJqsLu4PFXMeOO6OTP&zA?lEJQoyVcK&!=yE%p|Fpp#lKF#O7qyu(F z_Crg@A1vu!D>+^hF0pQy#=9Q>g$Y|L(PQ>Jp6e6OPu8kYn+a?9h%_mB93U{|2V%xnh;WY{b{n@Y?hMA0n&E|LCltW|^%}AZ3E9b8fhu;#-l&iVeDJ+9SWY+>K48OYgDp=hhQeL1eq875eU>t_f;|~F9Xuc8 zKLm8a zjA!lvUNB*T3$#r0z}0&9z;d|_JL93qT8I-Ky5`Dshm7R+pJl^ImvPV&>H_1nHn8s9 zy5KEtB!OF;Xu~CaZpjY9qyEvv*-jT8jv30+R8GT@ynJ-KJC{~gE`;UbiJbaR=daf$ zlWYqIo)ByXbqz1!PRn>4rlm&RzgDm{V{J(BzzlqEnT4m{{T1nT`+>V*lPINmAzg7i zjOW}*;-5OLsPq*bUTGKr$=<)oa_?^l0a~Qx@ezK0cbKrBnF^1u#9@_2EGSKig!L`K zJUjRb*lS;4x+6@{cFbxJfVnK-l_K@Rb^Oc4Vm@10j&&&qlAWiI@!IGybi=f?(ai9Df+lfQ|I}PiL51~zRFgcx3!ZQ1PVMA`U zN!m=)(Oyyr<(YEy+N@V(_8cuzyLBw28Lxm&3olSxq`(upHx(bcFcq9kOL0qr2(xOH zpwIpW8RlsRx0a~!tF1*aWSWsk#{U89x5x%8y97kqjubL8;se|{x|U5@mX8}H1E4qG zp4V>Mhmv=~Y)L_ub!1YgU8affxfAnRufoN!dS-I`Ji4n&qm|4n_O<^P*eL9Ch~5TE zYRt1in+#%UBUfN7&5+#n7%Dg=mcXkDTa0sZ#SxG069peBcu}XsE!O2ShZPT4Z;BHA zjn;Ik%6`aPUkl2qwsgtMQld1VhPpCo9?y@H<~S2bTy&YGoL$3>E*XM*^GN>0*Ou=8 zJWA-jUgQH!FY%)$+hN+Wa!jwWq|Oyh7}l7D*7#2FPz2F|-c}@6G?~6KnGZ@A-SG3# z!QiFZhCX5`dS~WC9B(zU{LkoAI^8Bg$oa>Ex#>9mrnr!IPTtIV?UJ}^&|}oou%$b4 z$}lHu1lUSADcseER-f;ILE2rkaEZYeVVz{yh!}jC6GJBj)Zvooe&rYDN8>V|(`D{Y z^SNWZF|8V325#$2Nrz(-yyzbbqe7)1*<=y+`w#|GDi|r*A1T;#uMTZ7)aC&^6mA;T zLZntFUYgw{Fjc3pNeh>h@yl-T-8X~|G9ys!$soyGzH9r|CY21 zhp3=xVLmt#etkM9O4&J1$jn=lj_bCtzc8F-9#x_)XU>3ZR~Rb2JdEz0^-!|e5FYk^ zFI&0)9Etfmk0$gig^IIt@oQ-qUfMR7Zb}SsVS>}x zc0N}hEQec49^lIAbv$gvKW0?hL)t>au~-zxL(lBypO=J!!L~wtQB=wuc8rBPorkE` zj}X4K1z~2JDS9Spfa&1xta+LRUz92Ezb-D~j%7MLd5AoYfys2ePao#ae~bG{lzHWs zP;47)PH#XqF^6%qBlo%xU+72cW6Rm;sn(!L2~VA_3}@#q#^a-1srP^? z@#Vltfi`v}j^|^-1o!vAM_^qrPT+4Ir3W9Wz){Pc5YxLGN?g)NVQw(!A36u0v~=n7 zv5#P>khO5FJI!^3?+O~n# zyqJMklma9r=L~RL{RwjEZ85LgJ(_Qv{2w-Zsq>FY3RFs}41M(G(%HX!X@J5ra&vnt zvhQwqeCl9&J);&=vaNW(&CPJ=K`vMii5IPUdw_dFDBfNY$ZPtR&}`Lzu=7X_e5{^K zZ*14YYVRaI@90XnWABgpj{_weCm-XH3-3YwD;Zj$Z%bcIG2;Canwag$ApZT?Y}#ZQ zPo>&c;6p>8ojT|EwhejQ*J+x-Y&wH)7n;(srdxQQw?Do-oJZ}yEP>jJ`=}U3aD?V} zj7vO3+n1lBojwPc%lltIbj$eOCSU$$El>-a!&ssu5!^P;yl?L{Jae;)npq1jnEG^# zdcOnN_Bd{LB!xb|y_WX7IE63XzYpt@P5Ft}%3RY(hr3Oii6p*Aa(%@k9MUt08fE5T zSj|k{P-{ge^r_KjpJMo!sB^qzUL*f&!#<2+}x5H+yJvg@YFqgSA4wH9H#hY(E zggHnF+%u8lZo+JEr*Z?^PM!}a5IoIq zNRF!kFJH-VnZLkolD6YgUPYL2SLl7KzJ;GY+eD_m_aT05A^W%P39Q#_hGd;s?(tWe z&Oa8%)2=>cFJU}?>-Yk_!Z*WZ#e5!Q-;WDS6|CrZ1irIJkv7w5ba8bE{B7w#mq&4! z{wI#>=xf4AqnZ4M-wS+bBIHV3F7bKYDez_eKU|Wwjt8@2B!71yBo++7X$MlM_~t%Q z?}>w0_4^j{U3L$3cP~V{b(dfi+lhW#R!iROapHcigCU21C9`IH#L$YVX!_v=$Q+0g zm7cpsFOD>YpuBMK)Oafy6@CXp=wxm`{sAfOamS4f4ge*6SUrE9Bw|N67 zsZ^)=8uJCG-UJf0)__K1CJoRKgF*iR^pe0*`!)7FeI-7`bBN%q4j0kDy&EBD^Gx#o zR2CE|MuGRGdMGsWg&xw2b&;RJTQ8S-ntovs*JP-!3CBHA&QvVF6ociP`G>UqyzuE& zblm%wFEfjvJLh@Rlp;s|+f)x?x8>6B=BZ%S6wPvTmrxD+Thx8NCF$8XjLz6pi_2<9 z^Ty+)e5sKcvkpDL?Dl_QKa&R0bi9HGBNZ6gY(_pGSwvUQy8vrnyTYqSE_7zK;69nr z51kEH@~)FhFx*axmvql5wQarxHv7eV#K1R#zEy`8O2wDGKdlNRDhAeXAIhYgQgP?B zeENL$EmHntIoC9`<{2fIB^T2S(A2CLhU{4fSJGbM`zz1!_6;%jNX`&)x^vk!^-N4` zjU&gs6uH?zC8}ih7t966W}D`DtU26B*2bu^P=)cdO#BHee#zmHh20?ErNjrH(c>+> z#bj4!1IkVs!fsGm9=+%~e0t(cs|5F6+Z$nCQ4mh8b}s@I(=U*dREiebkI4OvGw9&9K0$vcDwQ!Zg%d#DF+tNXfq|A=KKp6n|x*} zMRpL?w26h>Ya;&{#iCAdFm-n^riR}VKt0)sJ~b2ZofkIHrOJc3?U(DNAO4ikm`i1R zTirccbj6M=*H(b|4@G?a=Dpk|>?jX%KFbF69H-y>fAA^erNkDc(t_Y&4t^~oe5+mv zw_LT9&fIIn9g>F92Y;f$Gf0D;=nUp_2482UyKhUHYpn24)@#B}JYtW66{thK2Ca~i z!_^r-KzWff|L$UorGf)^&%y_2xg!zs+nWWaNH9;WJxli8+KN=Zi)7h4;NFf-{G}2_ zdWGlM!CU6sWT6plyW)?p1fOs2``I`uJPosAjp&*6Jve|m^M-dT>Bk4Pm>DJ9yZS>w z>-j+LZ>0=lme$~c$ho}ABaV&!pu*kT)8T|BA>U7hlf3W(@blE?`YmEUM=q7_AHGuH zoqUIN|7`##oXTBgj)7f^EEybDjKf~#gZ^AQj5l**|JJUcMu)6QZPhhECNKw^E?RN% z$3v9#1WFngx|3`3215M1BmAw^ZHV+^km&OW-;C*j<$+J3P}2h5y>p{8OCpKf@}c14 z?F-UH?KuAWQ2N_-3hX}VjlngMlA}`!xf1mPYj=Gbkr#)f&f4PLLPAeWy$A7@^7Kx! z283CyrmwXcC3~kt@CJcBthM40*p_YNWB1mB*n2#mr4$Y-53HztwiQmVp3I$B+0$3E z?!qTgHtQ?AKtH?LQ=iu>ao?HSJm+yZIByCEGT;Y^5PazEKeO=eps(1!dpymL`$uZ4 zcko5o!PKxIpT3G&hn4}aF(TiFYNrgKZ9@Nj(5x^n|Ls1X)PEfPHE|40PWnnJl`erl zkppw`8k{RrM2a_uQID?8u!cwC(YG(LaQQ%fV6Po)Paa5%+LGDUoD4EVZzQhYS3>I2 zav;~hgQIpW2{X4sy~lH@y0Ho$Kg|+49!~+dZUA6x?~g0bG*rAiVN`9=pndiPp@S1+gR+9zD*W6dr0;V zoQ869kR4w9tjv3^4MZC$gSW5`{NdIM%o!g9^;PTPWnnNM*yD(m#s)l3!&PF=f8y|Q ziEwYW;NZJ@6nE5ZLM6YlIDNY%POL~k^HSh=-SE$IJ1l`1_>f!j~ z`ef3vQE&@OMG09F8JG~$2=o3b^2@6(vFZso;B}+=v|lpknbm)FxZ_JUq?}J-IjSLi z)d^!(F+>Z;3ZKz+#=GRF+7)6Mx0x=`tt4vi1nz#559nTh2FJD)k@nBOaA5IPz9rd! zI$fNN%9+_byikfZe(NUgN-xOf)$w$?Mk*HTOa`SjJL$%c=irBD0NybEhlW2#!?^G7 zAocKgs9d#xsP3wVVsR7rtxCihi-%Lo_x;$rS%Tg}%x`h8*jF0~Lt{d87rpoF4o zO_-q`O8nL4NkkhoVY9$BGRt0!7JC$6^0GA1cey59HR=v3H@JiGGigXj-NnNFf>`%o zH+<2&1V0~264m{xAU`hklJ4hTD1F`yLdIw^vjYt*DmhWI<>n#wN?>}q+iexam#LuX z!>Rn~(lt0cxIaJA8-PV~Co#3J>XJ{}Yk-8eVClYMMUSgZiXJF4%1-xpThPG1M!Fc`|_@~y7RKGfo4%OrFAP%LEYE0Rp zB0ov}EISgfr%7D8?BLLUZI~eLVFTU#aPx>~u=UtPDEjyxdGKf^^Rb!_g;~4!_3L>! zV8b=4XkQ6CT`Vzj%08I)@f5WG8%5asf~z5( zy%h`0%-$*V%|Q<|OfVsz)m9Rf#UmiiL5iq2=VPtsJYo|R&P1#9_>5N{t!ECpL0ayM zaQz%ry8l}w1pRKokh@oiP1qpRx2PcfTBKOoq=~R2;UKD|y9w{VQV74cS#(=_C!T!S z#QqGjfFZq#v{GsZTNb_@&nv3%t;x&avTO{y5j`3FC+T3>4KH$1aS)sf*o1krE))MA zPj+zBL|j{+3ym{Ypx&)c7%$97<2R?G*xd(}M{7anzf9)s@{ZlyGLOXegy7b%_eCmU zo>oy^$5``$Qa1dkKmLn~2LB&-(fr?G7_jySp01>Lc;Y$Hk6rET<-9xO#_6v_tDibP z8NLcN+V3@n6Sg_myW=>duWdCKOG=qm=fBI_UFpoTC~SJh?$sNV(SH8PKUu8OnT(b z`)284l-m>R{Uf5QTh~jZKRWOmPOBu&(Q84a|2Oc9lLpy@Jc(b-T9UYL3`(WF#(a|- zf|sb5t<$bxqYr3tIfGb%g{us+8uQsqftlW>r;gXQ$fL#*f9Q2MK?aqmV59GB@;21>4m!PjmXNbo<; zcv~xzWXIszb~%Chy_%V?n}qAt{;@sx69{A+mNfD_)Ofocp9ZAk<{hr^!tWK9Ml2C> zXu~9f_llu9P#W92KA>KmIYb$jv0szQ@%PD(`2AQ1`OuSrKF6(jMe%i<*{Y6k`zTD- zn#JvAF9aGl9&$~?By(MS$#okkp0Mo)Bx&WFx~A-w$L zJrs>P4N{{A!S^+(^igdk9&}g$3sxQ=>8bxvE^VT?)AT04OC9-*`{TvYslwj+_i9{V z+RgNQ$MP9d4S3nc3P?PmO&1=&M@Jgm#f^c=yheXIsQeA21;?Z4g)uXEkJ}<{JYlGK z!>fJFoNtw&Wwmf!%J7%*d&!*dN6GDfGIZ!XYuXS*>7(2I=@YFE5LwKl>JzrY%O#Ce zzw9{~t$G$N)*3@`fDQWk7U7z*8R!`l$iudLlRP??hx_jgMT@TDvKG4!s8X{VAGU3P zKl}Qi{oq)7ZqF{RFep&6pdwFVTv*4_;#1)Awh<^jTG*|r?~v?UG6Kn;&ye4fz^0Aa zKt4Kp@r7rj(B9|?I7<0~RIe$vNYYr%`VJO+&4ZZSRhAsFc#RWP?@9hks0F+I;bcOB z6#I2xGfug<89tfyLV*25yuIt2sB``!A`~6?$Xx{&nkM7P_A8KnE*7J8Ef60}Bfh2&{dntFwbSXz$F_K|sE%Fq+)90hl_9@85w_L( zGF|6^{GnDXbnH29eSQ4^{@!(l#8+bxzr3rD=maH8{`);0@;->E+8_gn+T6o5GMr$I z_zVu)Xh27X%d*gvAE>VRk<@?nWw*~~4C7Y>)}5iiMfBHsj_%-TEo)Kpf3v|N@HSxoIR@C{AR5rE!m3SI3ACs24Z2S#fUo%m`` zezBmp(X`uJOR`{?JwI)mk6UcBtUq^76*A9${GIK5BGvN|l1^7kvMq=6=W>E`$1wzx z9~shy0h;uTkcpjRX3U?Q5_-cM#__k~Od$A1Azc2Qg+`n0*qq#(Bxt)XSJ=0gTK47e z-A7uXYtki5JfMxgw->_TcW?2_2}8c!NR~=VRijI)F0Q{7jE8*wz!URx*i|I-t~>Q; z#bs?6Hg-85v{Q?612ul-i7G7a2m_fgZ6ty(N@s5<8Rh+<%szM(%G8hJQ9D!MaAY%l znc>I!1cy@Nib9Da1_&I{Akm#%Wgc^GE?jH-4rQxW;jU3L@cwrv$&sdth6EH>Xt(HAzfOmeH5dM4X~>AGCZpi<}n(=ZrZWWWXOw|sAM&PI;^jhJjqB$ z_j4YSWzL6i&=x0LyF!?e2)Vk%@^XkdaE07fc0_A!h6)RYqRRcx?D6pDtgGuDI;4Ci zY_vT4b!#wh7Wf2V8tQobmLi_-Q|Ii#QkGb%PBJb`q15yb{%UsM4#UQQ=V%!?amJ9V z#NEW_eew8Yitw%;R)RY7jU=M}8gy-#4Q8er^8of36}_g?bTc1n7q7!-ZrBaZ_f3U; z-Dk{IsvN`K58_J~>u}|9B6{YR4PExZgr6FFlN0L(Dtj8x(O4eH;i)w0$wT3+5D38oyochAl$2vw%vGye0{= zbJORQF4>ZMH($Z2EsWihze65PN|Z!|TqGGMqu8y;p%B9Uk+B^?xHRDzZuGOoWo|7v ziY;bm?Z!Ze?@3{w-3(9uCri^;NJzgiQ;63>bM{n021W-`QR8eiI5f(Q$gMe!vD$A~ z&gv-1BSU}Y?s*L}bSv1a_R+9%i!a)>`@`Up5p?|4@wmQwG-mw?g1MHh_`FhI68wA& zRS1d4<=ZAhx8fJchuk94|LJ@*GF!>imCl3ijD-w*r(?n7PSSQuPnge~#EiTQsM?Xu zGVijoLH!$ujq5o6`_vussm_NKbp3!2k!|d0TrRsCe2N`?V@5XB1mlVZTYg>V7#sV` zhc#ZEC#uk0jDa0FP&h)ENhYfC^dcQFb#x%cvbW*P7Zq+eO{ljXFJW;z4#3mf%G@s9 zl-HTJ6VVL8RWbG!PF;EvH_DtQR_AL`UiS;j8cJc)E+;gu5%K7ZOg7w2c$TC{(c!D3 ztjW1@)@~RI{LcwAFp;8_Dq~U4;STP~Kg?$cd#P_nWz*)_y8K~ME7u_-xz5hvqD_Sz zWc|zkP{r4i$Lk#7sm_PVhKOvK@1HX4G1??)f|PDfJS(Q1e)GcPh`P8^PsbG*9Tagr6_00r#Ot z`TSG2MFT#!NU9ARt#i`fU|)$l1izk!0b7Ug1Bvp?Ch#rWxgiyAR22{n??ed7S;$-B zpTfM^!d`{D3_oUI3i#zdv-%wYb-7EJiXMj%rteYhZ$5rJa1y%~VlLClrNXJK6&5$|FP+&w3#^L)lsQtT6GS%}0+WVwKYv65&rD`zs%yeEfAp+CX zUclmE`*7Rp3idF`i`*Kj$roREOq|;_xqkaqXqp-XC0^H9>NCb{JaRyG`))Sn1|_@H zx1ilz3%D@mDWH!MmJc+8qa%-#!H#n#Z%_oJ6QzPb?|iI~r}XbZFV8 z;qcmy!6UVK=%uVdr`841eJSm*^6+)IA9@uEhAv?x2Aa&~!!}9LnZeZb!bEB`YYQ6_ zGzynQt%kuN_k~+OiNw5_j4qq|(bADSsr|FZu%#>#b}np!S@qSpK~9<4t~trvQ%d03 z#e5!_s4g}M%ID>_NBFk3k=!}yDhc&GjGYg}bX%Adt*A-HTVp&y>d|m<=kJNM^Ne)4 zPMSF{?e~sk2=&-||8q3!@gzyj(zj_U!6o$-EyD0C74= zqT?r`yS%XDHr4^_eRtqHtJy*pT><j{O+LAly}EjfxR*}=y^P~vQKX2+8~xcA z1%Dy;(JPYw9D(a5+$G|eHDuC`Sp0h}2Fexm_=pdQ=q0y@3Xnv!>}Ss#9?HX;!Lp>~ zkU8sg&y_s5nT+P4k&vxA9Ct+|()6qIAbZK^^3U;au(nBtw=H|dna(MCEB7I~L`UMF z`ptaI#bD;-y^HR;c$ycW6YMB$;@4|7KCg5_qR;pcXQf#VAF5-;bOwaoK1o2 z=iJb~bubUEJA=cwd!XM2ZOor>nz!XyfcE=9UaFu#=~@RM*Au>b*jSN?@7Wc1z@j%z?wwV{m}>I-w7&FXYtngdRc^#5R3|BMkxY zP&pem9It`oWkyV{JXl0dgkpAhZkej~G&ba8KP=Zc1ll=aEN!g;z8c{M+Ph+j``%hG zOYnhdZF8Z*SdQrLu7NQRHnO|N{*V{{uBI(ubW&1ao03+@2Xc0ANcJY7 z=W3OR*X%>#Q^5;Nk+mY78}`DzqRCjV&_bR@UBl;>$3ei?`)INFG@F>I4!)-!iF`%l zX{NCVU#{KA_nQ{uuMsjd%dik%Zd?p|+WLcTt07N0YR`LqK7va-lfkKYC~xO)_=R7} z?B~rXcvy6XdYyU!;t7nms|K+Gn^}C^;LEJbW-1*reX7gdOwI zpJC~`HqdT;&)zTDjJ+YJB{6p6F?Omf6pW6+tFHuqOQ-{z5_*G_wDjYtS50Zr&^2&j z;eEDF;feLLSLQI!tqSsLv_N{^QP?`?4E8NLfpc%B!o{C!iTKSNXmM1)YZ0r^>Q)4f z^*;oDm4_gVI?|OsVc;V;cKvknz&SXXINS+@_Ma*^T>25__HPE$I~kDSCO7-t)T!RvLB+m3@Ee)nie;F<}T^hye*S6zj} zv42R)wNtq5%uja1@Fx-II`rR$d{}I51KG)^t-Ds5!=~2}czB2#Q(74abKmS?3u8Cn z2L~e3tIrSxn>0vjMqk1I>`$|M&*q}F%5ku(l^5;Zu%E1}6SLt?LbmO-6Gq&QVa6(Q z(0Zgl_U8S^_Ic#PEYFQ>fW<=+ze<=FdYI5zQ}Pbi z#7S-M%ki+FKpb%kTS`kR&S7H-vEQ$x-C9_5ps($eXO} z*N8es6S<3=BK;S!kKX>z7@V&>CSQ(jp{ae^4&^tyuzN%&|0f@V-4hUZ{1?gp^jSiR zn-PzWe~+hvp5lR$R(w9ziw+&F>ad8)N#;HK#-@tp>E#9|hwj|3*tpP|r`Gj{!_~#? zb6hfC{xEIX7NDcm82U6p%fVsSB*siq#pMc?OkvGa zdUHiN8Sr~8F1w+QX+an0yZfX0@oS~<(aqZbO0-4)oDM& z2@dg77qfs}mxz7jZqbNKr&zd<{e0TB0`I*WR09s_4xQ==aM4-;M2#bP#MFT}yhfSI z2@nI1owI59A#I1uFkycvdLTYSX291M5%zuRiPU!OA9SA{R1+S@9d5q+2tJoqv%Txa z^QhJZk{$aG(CuqFLCd3x&U)8E_b=7~b(an{`DYLuteGUtL$=efjx1E)wyoyxn_Uit z)syJSYE8VRD?I0914Ltoy`thbiNv>3+Cj4>mD-NU!kcqW&}i69hEH;$Jx&(fdT}vK z5OPVIqyFOYkA^kx2l|Wiex2Yg;v9&?g=9ll7rx8*Kx}L4$ibX`G;q)diDl^lnDR)- zcc^?vxtQCaX+4}P3%!)e6N_pT$PZ!@IiMzf{vl{lx-B`@Wn6B|SN=d~g*$U+Gm-a_bEY{32J=?{FSO#G6Q3=HItJ|4J7p z?=&W+Ki{wqzr@&Ww1_lpj|czD#yoI-IVe_^;b4VAoVjOs&8Ox@ke|}b?Hn9o{nHp2 z8GlomX#ONW*4~6Ukv_26?*_K}T)~LkMEG|49!f=gVPB7YkQ^15e*ab- z=bFCqyUH#?zX+)F;m(JVtmuIdEpk`r@q3UHl z%zr1t%aqjYr_NWQnmQTy@t>AM-Zx+J=(Q0<+b+gP-$eF6b0f@AO(R}$Pr)J~oM}am zqM|@G^e!3#hZYZ^fwT6*>;7{IIr~x6drZn9@<1|l)fW-}qmJx&sycp2n#<(7tk}A< zlb}KOjO5y$+c2Trj<2tH4e#}b(#MTbG{jFH$0VJBwDhYqE=~m&g|(0`n=i0F7k3Dk zw#73mX0uA^kuY>X1G$&!OFpD-=bKHkM19V?;h>`|#HM|e^zCqgvd`zKbg4Q_5j(=; z!wqcutQ%y=kZpt0FGzDAYx*<8Jo$Eb?^=KG8FSALf%dQuJ{888R+V1TP-V?!|xOk;Cph z_HPGM8C=DJ-2KU$`0)t7k+un=KQ=w?xk&Kkv)qX4ldh8S1kC>r}S76C%vDN89R4lZ{mKUX)+hG zr!U1ZUUNZa*)X_0;S3Lvxgwq;olcH47tzv}w*2_|tM)6}W2k;= z4-88m%3Bt`h3Zd9WVY7_Y)JN}ae=DLX=WA5dz@r%n=9#_TT=z^NiPro5<}aC{8pt{ z$l#LoX1Id+xCKkb4X%NSYc8;(uR}m}iM!*C#;5))>(GauqB-&qK8;6Nd!d zOOhQ62k_mpU*Oy8HMn}}eOz!X1lEl8gV39Pm^~+edM(UhuMbe#1clHfEd>*%3=wjJ zQIZj#A5!0G7Vtj*B)+PSV51tgvgmL7@Xdk%7*%)%Ot=+}nm>tlKhehOKj|=Y#2Zi_ zCc{LpO{w{7ZT94r7d>>#4g3cWvOCg#1g|SBf-SDY@Xx_i+;(U#IRRPh%cQU1QPjmw zJsg5^c^v=)rMdnVc^aIr3Uw0&NBHL;u>Z10a!tJv*PPOalU;-G!rvBj`XF!-AIqZM zo)@rG%^M$X^1*)%X|OBSl{=N`P(QB&ptmQSB?x}gw96YM?fVS)_@pq>JN5zFD0oN{ zw6EZmBYW|jX$Oc!4MLArmj|_HlG$mYe7KY`ZFXD-hDmieSzseKCzT2N8pcO_`3yTg z4JIL>a=gVu!mYnVvjZ0<(%Y+!qS^g^TncpP38PZJU}%4w@zRZ+8ut(NR-rh5#6o7N zdPw5!;L5fAFGI=3V_a{aP{Pc-C#jM*q(QgN@{|BC9(=zDFDtzvf$r1ka8o~?vw8?` zbUQ{GpGD)txsyO8ES68bl><9r44+x_3L}gQ@L1;-KHYNzJClEm%Pv%hp<4~vwa^SW zAD4`WY-7>j?nSYDQa3JBU&WLo7I4!sVv)1I4#pYk@tk!HP;~1tUY@NA)qj_9_qYZU zdCV0w&2B?R`Crk9CIz~4b|jQZ55lE43sL7vALhJOk}O`MgId~Zyk+wfs89XPE<~Rf zJ9*6J0l}3l`11%@v2Pw6N)x!w+oh>juo3-hAjf}1yhCHPvy%UUeZWobBzASg^3H!+ zbWYG+k*T^AR{Bq6XPn$IPj4>jX9dFfA4YWe{5lXnAIXNh`0|o#i8x6u69Oz{Xt3^l zs2Wv-uC1HkcSN2<^T{AyH?JB#3|Yg6w7g+r;ddUWH-tV(J^=II|0doWH}F^A=5pu2 zMCcuLlsyd6pjC}gEbjA8=x(T&IDgRRio3&55ll}xBg)53cbr!%ME=`iSw55KW$6sT;z4WH{MIHoy6d~OJ} zSvdpDrbna8-fXnHGmtvIypJ7vn(%d+6U~mFOM14+^L)obc=3HXY@|ZgE!u(hRIlQ0 zvgJHaFP&B%ok8!rJmYgakAjTQ!&MpcpUAO&9zPk9%io37kQ>9p_@`60LZ(^h1^r7y zgBUyBq4brcyJ*1ATO+vfRWqKjK-wWj(GE*KcVU5zir_%56-~AYW{)6Ren~{|D^ReRaJaThcD|y(j9IwD& z+;H?go7s6?Qu0Xfp1)T^&(vP*?a`wLKMv-FcPb=_-%SNx`8`SC%>new*ksYCDaT3P zhAi0NJd!!>nk;aD1TS#fJ#y_^EVUdbjkCS2v9Dh-tXN^iQDB&NMs{H0V<(vDBSp1? zC!kw>z38QRBnGRhGr3_(m^@Do^uyF)`1fVhHp`qVTXo{LfI#ru*#y6B??Cj_M%Fax z7D&vE=ytg<=o9;L={HGyqO&}gTf*s@Cxv8B(^JXl%gShz87|sg`Udf4A$iyE74@9f z!V_WkI4*lO<}Av<#!q+2o$we~o2-lHcA9d{f2O=3dmw&N8cjRLsllHensjGt7Fnk& z4+a*Uc(mD-Z29~^^k(2im>F6}9vS$;r+9tXICnd@`{p6($;~F~Hr$mMTx@0HG&!!g zHJ|*DI*zuBOlZy3 z36fcp_KTbj6pY~5IWY^!VQ}~D43`LY}Ev!?;>Pq*R3H^chvZT zyjUFP*$Lx?`ia2?U7?ehk5kMp!K=T8qEtUj`Do%s|Lvba1Tf%HbE6 z%JbZT+Po)Q@V9TA3%$D4m^MoA#LFp(zXX4U*RwEy=DkV>3jqYjTCxyQ4~aG z59Zz>M%-;qFz>x9Ff1#_W1h(%e$zsMZ!k81t1EXx{Ud#r+Psg>eAX)R%Q^xZa$1P{ z*gHf%>;;LuV}Vm#c0r4k1E~03g=3>jVeGTD{PJBndeKZDW}lo&JwJ>2?ynhK>TWHK z%5mW3T$S!{)8S*^$ciLVyP;slcgfIm0T7}!2y)uq*bnHsgP#xX0A>AHGE&|drg)si zO+)qRubW@MD4JtU`UpNuqm21G{lfFbRA^4@VK$jhnfo(!rk%Y2eMe>Ck01Y$#gjAP zfMb8^lKB`V5(C;C^%H`-X5c<~MZSgvl0?D5Fx6ofk-B?BRDHQxByYW6)LlFSUi7bJ zfuj;gx6rrq%hDk}`o>((A_kf=F2nZ+>&ZuUg3z8ei1zY?(I)=PhwQP>a?%6!ZO)Pf z)2!&Qz<$tfBS*9+$uK zH59;n$x&96twy)|Es_`?a1k%^SD}W3`$KSz1;2MoIL{9Wl0@Ci7uz_}Ild*g&VFS&abw_0XAnye^4SW7W{~hQnrO=$;st5_Bsyq;e4Z9Bt+CX6UXK8C%Rauv?6^g+G7dCYLuCcfcT3XTas zDcStP4p#2@kJ4Lj&~dpg{1e3Dn~U%9bC3FCZMrgd)*Z&X)E#J}ay_cet7Oqf&k5W& zUmkRS7yo{|9$dZ+qRU>?VB`5Yd}UQAwVSGpF|vp4B3q2v?S+5Y^}Va;^tw7s$g$)f zqZROU?k%{eZ^1XOwB+jsKZ57cXZiNT8ju>f05XQR3O>$dxT;*2Og2A(<2+hGeBeD8 z6iwrvKW1>JJEmN}RR`8+&&A`pzI^qea}c2)0u?t$(WA3eu=CXz(XvWp&-_la8Dn?j zr@xlC_02B!YkjKZ!JKVa;p|24X&(XKpAOixd@kF+Ws79anbEYTfy1VO7g@;*89IAH zIx|wPMCpDjak2LSvZU7;u5>GqzQv2#Z~aslUM%bjHmpQfOH~XyIueICrO-dNx#Col zeK0pvijF)!iT$aPA?LQN#tlm=pzEU%1RXAB`U!qukTVI!r}RQ#a4~M{`@uF>yMRGm z1eJb%Rk~+&VIfkbPcEgMdnfU0&Uhujh^v#n`;qpm0 z(fmJeDA_uj7Hn{(Lp$`~+7~~tId2E!RnJN8jJCyfla$5T`6GGbheL28&zughxex!P z>Cx5U3ZOsu75?~}M87?-q1koH)LJ18n&-ZTd_!w)SoujZTg!%)YIxJAqcZ%Qb{sxw z%4H3co#>CFz<0U^(FrClyi)rX&R?X+AH~h)aedvaYo{9*tYkd#LlVuZ6IihGgniPP zNdiOGn2FvcLV?u>vEDLOI&p&qnOXH43;Pe|4x`lQ=Ot2@Y$YbD3rBEGnY*Ifdq&cz zo^bd#dmRLK2;73|Pxf*~d(ce32qjOPxb;?V5L){zFvA9oFFl8baf;*v5qt^9rt^uL zSFsqW^CXblfOO_3HZ|Oiwfzodk5*f8!xS|^h^KG7s)vV6Vdsl3!{RL+pKWC-SQ^0fkbi8w50$+N)4keyfFng>asQk($ zhAL8IF>~hcdK2-~kPVq^j)0{zZ!1 zI78U;KbV6}>%YT|^J93X#RC%75ejW#r(wDLAokj>mTf2T_|P>GqW#h# zR@VW&TaEaD_>W*U@iZwJ5>C|}Ch_G}1z|%XKmJGd($`4 z-&0dKhB@L7Ghcq-iHMJ!p9regIWsYtL&KGZ@GY$lTxNYLiI(!`HI@lHBTE4z*NovV z?FXQwav0o*w!vNYn<4O~BkP*~lf-E*g)K+az&QCiOjp`PtmG&1ce`Y%XHT_`z81fZw}^p<<~#j=VBKG%z(7tfs9b-g$|{ByuZW zUosGV8Y+Q39DsvoQ0`}V30}{6N8+lUL6X80J~1L4el4qkTdNn7(Q}$eLDX*+5*xs` zBoBpeCHu)Sb>O<2epP>-U4mzCF5!1um%(tKf5g^c67|&T#QDo7fZRrj#y4v3R62t z-I%G=(L9-b`k}#>P;K<7mcf||W#LSI8M=)+OU4a74qLs-1=r7DW;{a|R%JxP(90Pt zK`9;jYs&M?xr^v=ei7~;OyWBSkD=$?^Kp=kF8vxI58~clOc|So>%Wi1wE`31*npdY z=cJiUKJJ5o+gw?0qy;wJiANcWYEic9BJ5auf;*wm71_2B^iNjM(wQU z8KcGZ$5oKYORTBQ@v*F?)0j_Gk)>5Pr^4!ACnWD@$8pn=X|z1>4>K>UXN~KhNiGy7 zgY1nXFfK%gk4ZQp`4_qoR>Cz@&X6Kk+jOWy%qn*N-Xw8&`xAkq*-oYpT|k|0UqTDd zU^2V*AS+Bcjt>g%k=g(${B++CH>WDX&T&fo05OC9sY9rWuc6Q{FC%tW81por3|~Kr zXlu`6s8_Z@$HE3^|Es}$ly>r_wEd`McbDluFyqm!#ke&j3Y!;KLrO<8L_H{#%pS0g zNWS*itJ>Jp@L5qbA!sC@Zc+nRuB70K*H-+pwfKpX|&%vY)nBo>JftnR;*x`PNoPv40)*fF9r&Q{n?EJ z?{RZx8ov9p9nM9@2y))DqUeN7bSirSv#wUsT^XafT!S2tuPTyDrZGg4R0#VEcVVfn zGI{j#CDS%qgbQmfFf-k!?BUOu5VtH4X-+EM%2wuE-Cj^Qn8L@~x3Vqi$06j9Dt|ld z6g)Gy&(~eeK(=Ez1f0sntER`GSmch)`O?(HBA5GX3CxUwc2>RD4ITSZ@Q8#{e?( zZ7%AK=?`lsTw()aEO5t`GN!*n;AZU*liHi=FlnRQy%DqBwUE(CUs24-p=gP2< zbC>Y3jX&bpVhEnA28%NcnN5BRtbUY1u3sC9{dBDH!5w3Wy)c4@Ppl%D!S-s8=2V>29QR(9>BD-!7|9&)r1piQ>y^W59RjK0XXD#TZ zm`?Xw4#k;2+Q2JmK3>+l#M)l3B`X@PLXN*O%-EkHZg_A48U~f%-@lE-8iv55my@BX zXAZ8`vE<+PCDU)O^!e4Nq4a}M9u!R70?ik?Sn?caYW86;Dt^kQZH{H|C)*0ed=0D3 zUWcB-_jtMIEdJBK3;zv|q?fY8`05{%sdw)Vh?V^c`Spr)SXDQTU;LVVV3~r)cN#DD z9D@%kKJnriThVm#c7Dp=g`0<~V(g(j+%wUfuN8Qz@7xRNo7d~Pw)<&*&&EFh&#_e5@<>kP0cgLZ< zoF}(9{t(5^|KCYn?(K z=5ND?cU%~IH$(F0TqY|~m0;7#{_Oj!uVilW7qV~OH;Ia$BN#u*l>AH^gBRWwfYxty zOn7)5lbptq7txjQDoY<4j69A=x^V07+n zQgXtUH)tJ}WapF<>l0O?w<#J(w~vOi2Ye`LodPi(L#RuCS-h_J2to@^vehQ7vOCtLyovjU)1}Bve@E+bL$qczop4e%T|MFr<{lZhsrz8+P z+`o}OPqJXQag-vc3Autixgr#c!n0S_jX!6$*LSedw(yhy9bxLH zmwD;X3E$k|{pEdZ-J&g!Fzg6BR-n$|qY()+ehKk!4-&u2z@iHi*`BG^C^N#88a;GJ z)n+N?(PYLIS}I|Vqb6OE@Pl3N(S%a5Cn~7`o9}x>(*J@j?N$%RqNhfnSzbmWmd?e5 z)L<%WosUI@=ZJZo77s440{nOuj+AW$n_D+Ueq5P3Y}pUgaRB(XUxY{UeK@1xs6=1? zboJS#HsZL12#8H@aYOJHqfv*1-0 zVb4pAz?F9K|!Etl1^oG%7v# z3>jstgFDVxkcF~Q)V}H>v^X`wWW`jvwb^$T$8qU_KA;oDX35UwHKciyG0ZMKjztlE zBCfolx;AVbQ@OVo1BA{$FFuFWqbRCw(1c>WShn~?C9}*l#8oe+ibnUPFm~`LD-5h7 zNuMr|(YH5%+MeSe89D`TTC76ZfnA_-e=^y|*O3zS5uzFWFOm+mRj8Qa#@|0R!lMG~ zVd`gPiCp6zc1^w(`$?~*y88^M`qE$M#kF8t(=-|ySp;z&BcM@N=y}arOk>W*zy+CN z;_NJixBnjDx}Wm+#S`g#v%NQ^4gNUyM>%iJY=z*Eg_2v!QG7s^KhJE}hGxq+kZoGc zD??ZFx(`X*rsy6|nXk?ZcFm_fPXqaP+xazCeVh5v&YS%CyEuL~)sio;om2Ds)(_hD z{w!zdJIQ$CT-dVJ2;|kyL3P73mi~PPuHNU)dmbLa6%P$)!IVk3XRI8Fvk9c_*FwQi z<{uj=>S8~C93=@BX)G#kAh%R-$L~!gxaIqO*0yOi%)NF>$Sh5uw*8)y!A>2LVvll> z*YAU5)J|<;Hm8iJN)Kag9gm3hawq6mQH0B~tjOno<8Y9yEBe1#266-MWA>pI676Y) z&!0wt*O^esj+Ff*edjEe(AC2jAF>K`FsIX+HyDq= z>M~dG^r^6qj%mYLS35=D*SkTeG$Vnb@yy`a9X7?UKd`S4FmvMvmVPoy62|w!-SOoT z3wtXVPmYLl{@oRckNrX40|Fl`BAaI$9+u4BlPh`>@c^&=*Cz38m~fHJ8U@~-*ip1_Rel>&Q*e6i3{MQ(GG0BFcKub-ylq8 zJBEzn?ER|oyinl2x!5fs{e&z@!4iAnJmmon_Y-m3jwd*xPH>|Pe~JcPEBLkwBRY8N zdUpJ=4gULA4^IW|fV=W#uCZ+b&#P$WD-tZRR$hZgy?MiL=%~^b!(9GbDGMuqnDb3# zQ)ypY693vbfo7dBqoGBE`04B)C}+2y)bIYwhsw<6d#+tZztF)BTWh1ZhF$`15EtN! zykH^5uT^6ow1oGy2+y*)R;X&!#6{0^X?M0V&G8dUJcl-bbE6ivX!x_8@057k17$w2 zM}~I#heKSdBT2g6pYH!Sl+P%)gy9;);NPMCbeDDp6n-qj5pSDV|7FjZ=hNZ%xkwlK zcfPN(8>LB2-<@Qv&In7>{z`V#PQlwz2g#r(wWzu-9=2qUMNyqJ?BmL~Ze2C=-XbH3 zdMD4lt`-pef_==aMwjO(YNOrmg`m87BAyd)aW^@0+3ofj?66eXL~MW(bf_T{5__bc|6j`se=E*U`-7+OdlYryD1G;Ys9$7 zP7Q;nj>5~)AK3mkVeqF>Al}O)vd(3LKyUFToH^P_Tp!nh0YeI*W&9&Z%^OP(cDupM zhcDrDT_GNhUq#lOJx-)-Mq}_@Pnz&Nk7R3!*|M(Tuyyf6!XGQJm-jQEc}*KC_zc0T znrc*g+XnojyxmQM+lxE!p^d=gbS~g9O$p{N*~=5kKf#LIar|?MJS{mHL${4Sh54;+ z)HQjNowQ=U#C4W7uh4Boul72y8hS|b&uJ*!+^0(wTl#UMZ!gHERR8PXMrC| zT?IDxZArL^G{$7@7auK1C$6m#?C7u*=&txfjEbki8kNChaIGue5FZ5EZh=x!jrhY+ zAE&>lAX9#t@dHB7U?~fM7jaR6bgU6%PdOwy?+E>FEJ?rSsUbo35gp_J!m*mu5Ao zC0PEqAHAmYUT^~`Q-eigsC@BV*dhUzSHR%25mvoT?GKWqY}=DIJD z4n0YzzNJ*%I)OHEdnlG{gRHMUbp6Jm z)ZX8d%Pty3XT>Oy=Gu6^?YXSOA_(UL?p{T+^bCB_Kb&v-{TN2?J+l>+A8zZF z!h0+9=xu?q^GmcAH2$t57hmlq+9VuOxgn3P|44Ku8iMSEX?&<=Es6FYMrXahQC+!D z9$I75A$N%jt^ZGjZI9C8XNHB);X5qI%J=zffL|1uC_P!!J4hcz7Y~AW!)vl?(E!Pa zQ#q1{Yn;fvOO>dun~v^3Rj8@SEs3hOH#TbL!l+q^MDuzP%s zYUx&3)Ot!Z0UK{)#7{ExQPNrMsh>o9tdikfrlcgopQ-1)y`WQu` zS6HDp%Y)6^BH8?WUltswL_=C0k(Y(nNc4QVHzTf$=zTudHa3*=6jfM&W|iUpC?HCRo143X^{8N}4py$g13EsG4en zN`2)(&xYcE<|-Iozlzk}vcO;FcfsmSG0}9^M)fVjXwu3ZXj9^Y2NW~J>AiygTU*F# zIZY$ZJ*g6-(tdp1ou@F$(I4Io`h{!1SW&B4{rQ<6s;r?Xnr}aBfiG9+((~UF=wPW> zXdZ40|D{KPuWlPI+^WGX_MN2amv+IBk_=&&dI}!zm6yy(Hsz<+R6*T#y_$&K0rcbA z{V?Nh7O#pi=ap?y`t02lwmGqk_9Pdvm8-S5!H!I57xMfqF|xcTNdtSL!}x(C z>EPqx$rJ2<;kRqM=#N(>^!Se-SS`Hw$}TDk+_faQk~12IEWVCo~gqLou#Z-X>p5S6Yz0WISL})*%|F;$^C)~tq=jXvq`5%&VbH7zb z^(Mlt7p4Lmb0RX)eD16_3-@1L#Lu`XanGha_&7(Kc5f@e9FaVA95R^g8@ZI9E^LFQ zaebu7wjN%+D}`*;>6rP)6m8sU(Ozo~2IWk{6q89Ikne&!p99;d1#klt3@yspg7L_CH7ha(2)7OysX+E9hl!3LM ze!=S=IV!VOPx8j84SwvDqN;YLbcFi{7{cQ4x4@+A&G?2Ff9*r7cV47>MH@aDuSX9V z4yO^*PGVHtOe!5^N{2bTV5=h9!1nJ+IwPVAC-r56={Gf8$a3+wV*n4EsK`G(Q0FtZ z2lCM$C(w;eeWZ5z3!JJ}LbdP2(4BMkNp|kf$CsTesqUQwKGtU{&ns5rE=D>u*fg6z zt@=z>xgCVsKvmwqb|6)ZltwSr&yvfFwsSX?WWKc`nM(bY=7$1h@xPUEsF-^f2gsl1 zu|G(BJpt)Zj1SlBZynK6duR(?k1;F;V5jPSIQ7o^O8jdwLw&?eZ1 z&N05ryo9_%_>^8Wci+!;BxJEOFVjH7Uxqu|y@yHr?}FxQRX%dWH}t>ajz$63pj3Ab z`hIx>%;6s#4z{2*Ckm)>YkwXv!IDS#b>TvPHTtCZ42RqpYMP_Ocj?=bYs1p`!`V*! z!_xcw*A!iPHETcrI_Dx>Od1WFGerDsPpsXx1^rQzZ$v(0yqH~$!PE7na8~gY8#^%r zZktx1=Z1Ss;nHyaH|7QOODrMz4kEZ(AQ1&yU166G6%wa^as1A`bNEY5h5in);vN6i z!(@+llAnh^!t2zh_Jh}66SaS>$3n9-SX`CI&OJR3t{W!Uzoz}zo0rce*)pa)>eVi` z>fKLRT#`dd_CA#SR91o)R==U_)t~CnRuyvib~T>woD8cM41+jf{=a68;9VbPz(O5H z;;ju2F{JD|>#!(>)tlnjQh5gyhX$d_A1Qh>XO(a#v1HCNwfJk6CcDvZE!fu;i$e$P zfm3dYl6B^Sx6WCH%l6!2@wz&AMC*uHZmlU^i%{YxaujLewNo(8a2B3lA?ytsn()(? zUXs53fZ$y1CF_H|pddqoA4`6LW^wK~?LS{U{qi7&-Pt0s@?OVXYGmoN=X(h~^8>xd zXR|fG6#1r~C6eO1#W2Zw63de{m&CuF#&^$E#V@lP$RM>0EV;TCgN7$Vx&Li`EzyqF zP4~nav;KUJp9xgVbm3PX9w*(!TJ)YmF@7Ca4bFj`*j6&#PSnqkDrIW%Z*whBdd+nB zcCd|){q0EaDi`5+b#=b+%q3xuX~SJT8ezqCXUfZ;3;wGm)a{cpFCB9WnX4I9kUxcM zBmZI23Vk~2*mSgt`G~<|+gNl@9Gbs0M+Z|=ZvOf_F3n#87eA=839a&cm5m3tx61~b zV=rJY)?n43vuL=Z4eu16g`X8EF#YT$81P98_PJjde~>;z9?tKSEPmh#%Fokq(YM2* zrFZQ3td?zHT62YrarLG?H4EUnz!CBE@TLFcFF{MkDR>^728#Yi$T+DtWSmM1u`>M+ z?yp{juN?gC!@5i`h$TY`xMEnmJ)QpkGiaRufI}mJ9&-Hz>mR2uwUm1>Z5JnjBe%iW zthHck(M9}6yupLp;z{_Lqxhq#jBGlYiDnOf!CU#=F#e62khK#2_t%_&(UoSHbxn^N zjXVJ1Fa5}ie(})raERzydOdm_SVcz7_rSTrj@10`2DZ)cF>&5<08+NKpoP&=a8%vG zrW_oJ-qxRC>iq?5hd*bTs;1QCwJcAm4H0F2=%Ghe ztj0n8#yD*E5ze>ownEvJW3arl8dnEUzFVdYDi`(;&o8NbiPZ$j>tk9xNY0V&zRvKh zVmeXvF{4T39=5j6f|7wztTuchnfoLd&TZ`?74EO_@LGYN@Zm7r7Tli`&u+kE1$8cy zwikM1yP5NIS5$7;1UqMRp^DTEw*N^f1gL4U>(>87Yu?4PhuPopbX7jld^3YatL;S9 z_)jcP=7g|kng^c2`-yqsRy_7|HGG`ag!OOlz~Q_dr0Llsl2c`jZeP!!rE?VXH3?z0 z*1M^DdMX;XRfDX@cv_l~4;!bQBka2d4lKQo-xd#mFrhy{7dOGC-deWvcNY$MWhGg8 z<~G39E3MiZZl6@UF znO{7YiFOY)dEksYD5tGWmp_r^O{?F+phfo7ZizZMYJHGKdxh|YW`;G6r_*Uw?{>+M zkN`S1$d)U&B=P{OAvEpzQ}jP{19QWc(VA)JdAVahTJUBlP4(J?3;)J|Y3=ZunhPUn zn|Km&t)D~fj1+kHdkL&pOJyS##1oBmd2oG~A&m{W1Q&wS;dP7~S^KV;H%}Rj&pX`- zw<+OHCx%fguVK&?*1_yHmf_k1LY}2Imh|n+hP1nxklH>K#@2b`kGyTP>X|Am4>#u* zxBp??R(=1U74uzY_n>5=(7}0RLdNULU>V7VsFw?1Pm%#CS5t(j5(4@}$#%ArwguAkX2dcac4`vL8$J`hx=n*M zYNK(6T_?nMv_Yq^Pd@3Lh~;7fqMfh`>QYamk5w{O2sz19OH)Dj$w1PrSVH=mM?v-y zCH$o54X2Zg`F@4}(DGR#Y<{D{AK$nPQv(~}-%>*`x*&x^`?X?aSvXG^Hk3|yy#>|B zFqrD=&-VWqj4>Wsu-x5|pODrRau2cWpY8>c?sgv1Z5u(qrWP*mL($2-C3y0SLQRlY z8;QLQX#6ss>Ygyh^$&*geX)1p^TM5Ycb5QtH~b@+^(P+M;zTfFc^rnwR*5l76EZW> zVOXdOd(~2p_fvgA)pjvm*T}t+U3|~b zv(O%IiZU0cbMCc}tyo`xe*2G-$#!yFDYOKuyxtMHlmFrFFg3}>h|PSqlLMsRx5Q)B zGBpy8jBY9imr2t6!?6Ky^{p+w{!_)=Kik-Q^)DfG z!FY1ARB*&jlw)&3AEIJMJeUdT-T-tj(}5!V89V)wxx z+jO||r-#N+!JFAH88uG=9pz$3%bq1p`7{L{7tP_vr~VN+ z&3Xw({Jr7fe-)5zX@(9$Ut&AmgMLERSnbI={$;%}OrBjR9joNfv54_Tk*-aGd>d z9FOdkK*+1f{ANxvbPpYi!HzQUyr~;p2Sj6atru6dJw$3|6*H|%C&4Wx0-r5YKqJ2> zw)mtk9-{P{4a6P_MO-sJp#JR_Dha$66PPWepviWMPlfe ziN*nzxFFSt9`pK+vRmIvdgIdYMf6MJ_ZZosLC&{#cLp*u#4v0^8hT+5H99CFv?Y^J{gjIsk^Ps*3;f&#DxHK(ImXO1uHwS$jUwZ^t>me#E-KA?!MZc zp_85m*k3#eb(S@7Vfj!jx@txt^)Wg{u&J?>?J8Q4ia4o%tbmAsf5@rRpEEaicBS$s>b%JP<8QnnQ*PPR8GYOQ3Jcd9Z$Qm$>Bkk?KNQ+*@fz?+?%< zpI)6M=W~Pj)zvzvw7nePFHOV0_mps9?J1(s{(=o&qC$s1n?`i3b`x23IU4!Y0UEYk z#(ejAs2cN~Ozj`fLabZKp}nPSqQx~lI@FriKZs+a=Y1vGNgX7pFPRP#9P>4EpJ8EF z3oMV(rz32f@R?#B?Af>!7VpmG(^{@@Ykn49jLzp?!(;iD3N27Szm?~Csd8hVMP#4O z5?-%Aj>?v_@=kpt8s^^vpUV#51-mNYRU?A9z6oUB4@>%Rpdy`cMw_ROFUR)LQK)=o zDUVPu;ws&$h)c92TgF`$<}J&?dZ`}t{Qi!mu7@G~PK@v@aV5(J72@|bDdapYXKAI& z;J)6H|50?_aW%eg98cOqQfbR5MKT(wb6-!2G$fQLe3R@V*^wyiiPF%bG&B?{s^`A$ zLsmOmU7On1*v;?7~=!befBKoyt#_o&t*f-B4Zp+cLFxIk~l*@c5A#CbZ?Bu25k-W zeJc+k0RjWGD;GD$SQGy$?s2|mxt?fB>OL?~UY#P^r7G=+`%Llio+1lWweZkW{v*DXxLmZ*q0;vHdl&Q9;SVA&v@ogONabS z;=aGhr#FIg*s4@5Xwb;S(Zvh7_5?*#$$5Ve&HU{_s`Ulqkz(e|Dhz z3%5eA2Z7*Ot{@fj0ZuM$r`_jAL)PJR$Uiuq+u<9EK0!vjKG zP>CT^mXflsRq!}%F&vQ`&n*e5f}*PHA~iKdHt}jH@9$=dYolvK=J(@q&-o$f9(xdL zUrmP;Sr2?0aDds*E9J)8eu9iL2VB~6h9zuP#Rk_Y|M=)-2c~(EtL?r{`6`$YiXwBgwUPwIyam%c%{btZyIrRQD@-!K5LBqyN3;W z1h5jlp_nQ-iyr43WNSxqEJn8sc^@q<@3Ac2f0|E6ntAX)a}#mp4SU|wp`Kc*>oJX8 z_xO27wy=+h!@yS916K(j`o8qy9Bqe7uoh5fb zyZ9uzK6?!3nQMY#ucFy9b$za*-JI@hlAs;39sI0VW%}7;BkFaPqfzQNUgBCj)U|EK zEuH^ib@Lly?j2djJ$Vby=Y^uaa5j6Ruz_T4+fGHt#<0o5<%x07F|1qBjZG&?u`}=x zh^6S$&O~LrSX;w89~vgIyXK5j`hS7l765Vk_PVC(nb2`m6$8E2(mqLL!Eu*?`X?+< ze7`M=thZv19iNDr->icb?Gf}-?;-R$N@&x7B_z{PaMyPz%A9tCc*|w*;;I|eNfpKzM#Sg(aFDLIC#9--u61=gLB zf#KWkus2VX*t&BH+-b}AFj{&A`&aJ7S_AfQ{ZrjpL5LDl8CQgv+XgYUPmRRFQg%xs z0{Tpy*I!L%YRs1p20`k7F!*+R|kt*D)_NIi@#*;0L1hs*sMswqu<|(#tUAB+b8nL z_l1Ya*C{D9Nc9EugeUQGu4B;H))TEhw2|L&qv7sDJ(v>yL)5IW5&S*x!saj6=1iesX`?f%f`Uq`-X9pgKUZHS6r z9^K>ewV@Dn_fUmrq%I)b zb=J=15(+DE^UaZPJ=_I;u2ZbHo-mgEJ*va5{um1`lPlTJg4?)1>5=e!PlJ;U2nX-dnmW^?+-r5t$-wNS%Oc# z8NpuZrPSz~9oU``!%4)kLp21!cFiy zSxiC(f@qwt5q8|yz`quXqK$^5u*R()7StR@z3G!Uv#q01YKI{`+@nUl4{Qhhn;foM zQ4BAaJA+hMDPLewM;{!m$0;#!aQ0(4?;uxC_tv;^nUbwM|9u{3H&Y4r-+D^SGE;F% z#9`Rpb)C*@mKCgE)*^MsM0)H{HQlFvLtqJ%@%lz7^up^kIG~XZl2<(O+8TXspNuk` zS#D2?TE5Z+#oOSLNe&$qAi;G@3;y~?8&D!ahf``S!~2P87;9ZeReNmkUAr_1D3XBO zp(-@ycruJLs=)O*l_WySA7;GC*C zq=-9Y_K&vTyG_r09)x!-opesgPPpGPKs6-F>DApPq|CR29R2iy%-5I>+4mZ#wM+{i z99m0v_$%R%yvZEr=f*z^`i3$lN*sI?(aup*q4?xMT=UL{W@cU{mMV9M{>2&aNx}+d z_~z5GvjoOgOCj0a5sMJfL-I8Uovo%obS_VaAu}J-_}K}>`KAiK^6$2szA6U3jqIRn z{Ayt0k!Vu0?u=;9i;d6)>M-`xR$e{hH@S1%MU<7F%`dsXhi|&6NgQ9CB{>JjQ^}An z3PPs)l*&9TK63$#<6QCmi6f}IbPm~SUyWYf*=`Uw_Y^X7Yaw6Qb$<-h!ix)4xUGj>;jWVcH!|58Clp(=X~7B5 zwyzBr`6l7%!=o{0g$8$BwhfLC^f1-(5N^kiiS%2)7%5-YgY-d=NauqghL4P(stbzo z-NNDZJ5FVAnq|gZ-cDOqd8CT7j$Xqa8kcic4h>{t|0PVkdYT(KJ&Qk)wHppx_(QL^ zWTRL4LTHlP!^(^1vj?|gIs1ri@_udtHLV-V^oQk4xrf9LS8K>B%_xJOq=`tqUfQz@NsUK;HMf3=Qi47x{oiJ;?PV!gCE!TSB{ zEVL2W*ty)uIj^aiS^|G9I05y$?qbZDG2FqJ!^|jk2lq8{iJnTx+uLCM(5<9SAPRU*>*B6;BtX~TnPTs^83bCvD6kce*1yYex&v*o1aV5KQrW&ai`K&w7*=S*kZ z0l`hbh**Uo+1FNsn~qoEYm}|e8#0yq?Js7%AH{0;udG(Hjz3k=&q1mfsLoW!&IvYbWdsjF zqh{jJ^o3Z*j$Jzv!UxP9md&mX%a-T?Vi!nC8u)$*WD3oc;!(j@l+{+LT*!ONV zFY6g2WG}jDg<&M_6IfZ+?;qlf(EG5!XAOY1&;c~{fhVu}`Q@FZ^vt_NocB5n+_yBr zdzW;a+3}vwAFF}4wF7Y4m>P2Ki5SdbLU(!bGrT5hgdjylVm?CPhM&*|&sX87q>+kZ zNh_deofj?oKAu@iCSb9YABtNrDzowg?6=-UoNQV^TEh{=ub0s78@2F3;~_8Z9|5t8 zXR<%1lZf`#F;;rTTB6$Ic`VvzAGJ!N#7PMC*|fRgjCXqU>C--#kzpiSIcp|v-uVyU zqz2bvaT3l+OlCDGy4BN6lL#A$O^2G0DlfZQ7FqT4ii+_&cr+`Xa&)o-=f1^)>C z=E_RQ{CJ&~`eyLep%S#aP=jhNPr#{FDMB*n0JLoAL#4Vl;%nYUG$yp6hWc(e`EUs~ z9;rZs;vt0NZCH}bGCD0a2yV~Q!-9Ypbcgc@_Q^DkTqqyTt-SjP$9!82+fc9e+Z*cRj^N!~T#St0Qo^&W1G>=TSd}>-5NOA$RmzmpjcJ5O#b@+=y}RF#V5>O3p!RY<-mQt? z9%WyuTN-m6j%*EufJ_mrZ+uU7Pk9U;JC(`AExx3tSB@4OF&1rl8wu++j$#oCS@c)f zD$=2;jq?@t;Me2F-A9mG&to9J__)m>fD9gu-e;M+Nr4#0@xd)+Ld-=@{V>Qr`rP5@C8g35|fXUbWkJ98G|}Ms9-Y^0K zumU`pC))3|5H0QR2h|S=7_R>m?kkUH+OvN{hN&jh-5LvV=ilJF8BXXpN{V%DawALf z=8*?tt`L+ehqb@#`3F&of6FUybZI3Y`^w4r=4ia{9e`sK zm00o4&5+P?0BesW!OPm00A;(VYMc!{e|iC|&$}b)2=oK@??`GZt3ftbUt}@=0A1lF zjn+*+&|^@M?WkD-rVqbhmZ1ixzfNFays?8#>lTxl?UEv=b>kuDUKZ86k_?aBOX!#F zW1w2k0-BYxur~WG4c{iq8T-W$Goy`6;Y2B1@y-J}?Hq6k^Pn~NA>Q}g%+>#Hp~m*x zxJjN1*i-XK?DfxV@?~TlYglT;EfJVD6Q|d~^71g8kQ7K)|0jn|vLH%pJ^??bj%VwP z-eOFXke__e4EQ@)^tHYk$2y;YmKg@@oHGxOp2MMVlR1Vt)X;r}kEs|aUNMM-Yfp+w_h5x*=;q{3tATBqByl8lYZ@WtHfV~T> zPx63Asdl{5=X!Fk-CuNP^$RlH=oiUGRnBDE4UC|yDHijsD{3!yrI(#AL0TcIprRObI@q+8Ecu)c2-7Ij77#x^vq587_g`^5_)M8a1lZ$ zv*!wiF8Bt28e;^nUn?HkI~u2q+K7XD8PrSqVwch|R^XwEec}ILOvfB_=-ycuxT_ha z^ZVhdgD?~M@fKA_>u~fw^L|> z(Q8sj4}iPkQE+*-2TwgS^?RKv-^6;?}G=?c6d9D-!z)+5wn61>dD;xOUI$3p$KPZu1353 z4rUta!&TX7a;IAJsKxV-ltw;4+hxGC3$DQKJF1*(VFDX2B?AqL?%cb71;D$xvHf30 zpz-G@A~STEsQz^tt}t|C3I_VzBws^T?w-WGt2Sl($W};s@e?(plj+7?QJm+ScozCe znrrhnVi#uj)R_-aXUn^*@Tb2EUY3#IB-v(G|M@;D?h0j1LN8POYdW!b0xW0F4zBFf zZw$>Uvs$irSV;0qihVR;YZ26Nro)!xdQt=Zv;e{M&f?oEtuOD&z8pA!*|mj z;^pz5=%4R@u-w=aF8VyePEAYtHnxpas%L`#I0>scLk;<_Q_tcJf&Kj?#RJC59YwWG ze#}U?+r}@R%qEtVzzn=h_3hkXi@+8ztE-`JW+;$GElGOvM%>_~H)iNEpg4{pupY>&wA;%0Y7Im=qLMjAIXOJjdN!GJMpP zgXjy7;p4zskXBP;`XU9E`=kksSwcG@@L(1b*ZIOU#PJ zx{E^BJ1LO+aM*&gDBlOxW6$EM`QE7gb0jf7{Fs+3io&4eWvnyI3jF3Sz;$23(KII; zOP6)iWY=M$JAcYapO-eL-B$&DrY4{yc?!N-nBrN#RJ?CB84R>K`8$G}bN}N~(SebZkhFSaZOyyLTE3p#dy@Nq_AQ?3-A0+cU%(#m-nJo0%dFo>I9uIuT!LP}) zSf@w~rdBKP7k89F4Xr@)g?G@PQ3-yD*)mzTNWSSwpp~kc!0kNJN$Q`R);P`rPXk0*Dstqd@^gMyxcy8EYhTA1fIjRSbNS-k`^69 ztL+w$vyGZ4`Wg&d_NSrmMFqj@{gO`ckR_cp0@Loc1H|0@gk#QahfUo;J{u*2l%+Jg z%a4aTzG9_u-~DF<2_hljT>day$K3!^n(Ey01KniQU}|y*(T{ z+z!UBO9fcG*qvQnn?vfgqUfw;6S?otj$^Zw5&CEOqgb)P$X(qnv_e<$ehDPR|z9w^C2?uBeFypJa;$-A2~KtCrAf}g}!i6aEC7LeM3@w z&eMsb?Wl&cBD9nzp}`14__j^xPNjF@pLzRn5Q`))Ubc)x})fw$Gp; z?ADAjhVcte%W%i$CchhTOhzA#&7DH`4o|Lg*k*t; zC#X?l!@aaiFBHZ-n}?zM$6!f^8A<A%I_fpB~Gf?t#9K`GBLzZz21mCwLPA=>5qL>-C)pHIPTDKK$2|c%! z8#XX6UvGG{K#ILr{R-isd${;zbJ_PYDY)Nf!or4xq2H?Kuvcz5xz!uaOt#5!KZk#y zcNVXMAqz@S>ts1jt;?)y^p<7jDXJ*TO=s@Yeql%EJv?|)=n$`EF$+Ggdfv|0taW_DNd4G?5Iqp zjcuk?o&v9B@F;O=KMsxG(y-U@1YU2|B#CkM2y(j6{WS@9nMBb&TRO;_E%9J_!<6sp z_zyDtIV=*`8iJ=090l*fWbyZOR-Zh3wq*|YeLsbyp0`jpV;nBCN&9HC$I8OVK6gtvv~vT#T)Ttbh;AfAyo^feXVb|<4ZhYD^6iKB6YZ)H z!9Tj3lwkxBEx6BX8yP@U!D&*|+X-*x&VU?}gs)Hk#KRXp(T$I^xr#FZ5Gptv=k)sH z1*wU6%%%Y-Hw+vH&GG!BNP(Rx@aI3r(vzcAIbE$uu*#;BKQ}G|H;&a2+@puMzjzRy z%^Au@$Bk#v=HUW(yI~qJ~Hk(!@4y$9tp|VAqjnp5_mGz8ur-A4 zy^uqL`i8(+gGky`$3xr7ao`vbNQ@(jVDTO|T>9RNeuS@w7^ z{FuuATz#Yfmc}{kgh(Cq{9VBE!b(z}HWn1juaSZ~-Jm>wHuU{i27i5?VvhB2Zm6)wd?oD4 z*KH4nWHnjNZ-)k%{rIj2F-aON79EA$342RBjht21E;Y)r7IpCF!HCHt#=5+<%agY8=P&}8!{?(*<* z%ceh5*|=@>Jl7t`D@bj{@=HF#j8KkqIk_DF?NEbj;Wwb=bsYWg>NvJms{{(E&~e`| zgS{^J3}Xdm@h@u~CfhH}8Y}=uJ$y?mI)(`y=m1J4I-*0rBH{EEfJh9%owuSzJsSj8 zP1t#>BZjHy()t>vx|EYj`VQ}o-GDKU$pRxWi|9;~hp|ab7@TVca>Lic#ilXr_po>z z=&gV;yPkg?|l^#58*+|C+t zN6O{Nh|P9vQ}bo0P1_P~{{H zzTrXd4mYhs*OSz4`YDhXPZjNXA4=toYppJrwei-H3ux~3DhN`)1Weh27JnFq795w}C@^Q_*a_YFIH_ej8QyY%E}eVx zy0960Ro-D_;6^m31 za_}&>dt;fUE&l;Cwd!!cq=9Ht#ZSCH)=Stw*TDXr?##<0i@(=@6qL>U@S931TVxq3 zI%SZFzW0LZg}1)kgNVHQbYn7Oj==f>VAp;LoUz37U~co4 z8hc5xGgXgBrCA;yyf7GL3onw>ttP~9*#I3|nSqYk*K2PTc#w!M4^h0+h0F?0!_V;_ z=~c0G=!l8H+$TcGjVpXjx@rl?mr3k&C+fd;1Jy)8E#{O|4<_HHfYtB+r?gJtt)KyLvHt`kBs_`OyB1WQ zY=Ae43Se#8De!pX%9Z^c55W<4scEra!VaSE^ zD&Q2LOsy#ldOuu>Ep4 zq}y(T`M*wLBk`M!hom51SG#ZY?hr4|iw z9>STHA4fgcUo<=L9kH{LXGP>ZZvQ9_y{8)awts3O`xgq}7d4N*ER=+osunQxSQy?;dYJDW-ju;nf2bn_-+N3bHf!1BYy}^sTrJ|R0r9tM!Z;K{soG2H$K7LE4 z9<3GW^JAIGxe>y=vyX&Cmy#tQ_*4p#AneB_xcT84UE4Mv4{xi54!uGg_Fy~oh1OBE z+3}Qo9R-~eE9)lTHD#h3S&)221Y%!Cp?;_$v-2>6sz7b-!CFm>Ra?*2%=*n0FIY@- z{z%fLJ_WcZv5(x=N})??BuVn<6mSds3Ea{XR_Wtr6O+tIyr=SU-nVZJXLaa0EgF59 zO;1eYrb&K;#OC3|V`M1)Xl)>RHyuHk^TV&1Ik5F&kw7P0fO1V<^i7K&Exus~!_Mb$ zx4ho*7Juzo>y;SJsY91J4W`nb#R+)DEeFRQAHfA{-6V-gFGY4~LdMKna6)yp(K%+n zNoVF2B6jE=-1QrVf2JCVCZyYNw==TH^k-A8`tH00m21C%`!a)jKA(d%KIgDx&p0-E z{1~io83Xel6ysh)6PkW1gyhYufa{76MJuvj3Y*bVn31}QyEa0KOSvVuFwNV+{_ZQ7 zbyt-O?zd$>gN3e&r5E>Nc0Ok-qstD@I}X9`+~8Dr9%+qV3cn}4VG2)k;6%R`vp9Q@ zYVZ0;k46g&I_^19|2hi;S93J3&rP&$(GbojG7(LbhB8=^05{+N0p+v~virak=Kfh6 zcPMnzW7fxO2RA>Z7U2pI{qzoWq^Yoy4~6_ZjZ64RsuteVO~qkv_z6{Qzy>Y#;br)cc>|Z*g&xJZ%=;PJ<4xy*&3X$Qk7@V{G1l$jq zA#f z`GXwwsDR43%3K3`3C*WW$jks^E-Yai8U`vrqqYJIUDAhGCBu2T4WX=x;>s;{IO%yQ zS!$Or+V@`zZ7?`U=9oF6g6>90y=94G^i<$($w;dpm2)88aE6?m=}iY#dcY0&5ir=- zLNxlt*o`DL5>_>dWV?PBnLOFYYq;ChD#~8K&26t~s)RJzcTA}M;3%&;!78zw(B;H4))``1ESFAiUqDQapd-0p8~V%{pihyCJoQzdj?I$XU|pt;_wCF$eJycf6Os8cPxc z*TjyI%>1*6L@KO>^dDg`chnTjwDBOR9_b*a`x6)Gw8O-fJXr8LlN4pG0q?dKaHx6` zY#*M4Lp`=J$0SF=FYpBt;)_8pdNFf~lx11!Bk1C48KPmsa8185r?P1$%$*fT?|I!P zr+OpN_IDOjn4ttK6vqi!!;9!y=*X(Fx3dRc=J2{78%+iL$$=0mb zW$T;|av_h8(<|r zYOpdD89bZRLa%F=)BoZgz)t@>%GpF>;ox*O-(Wp8)UJhk)f*!DIfZoa+%DL>7re-hSquo`CbBf&Y*b6H{r)xv2V!LRf z(DzJ{*#~j4>ZI@VPO|5xum=u}pd;^0ha4>fHs@jumK{M5S8!(6zOBJm+;@7Rpn^Z> z`h$$LX%$U=A@r^$M02HA!XRI2qG&C#>1&#pdZPpnJZAmh;m%QcQ( zjjBhzxfUx2y6r$DQ<=4um28z|!#yr=NlIzl{NK^cVYNPsEq{tmOC89F9kICi{t?#S zwuf!$%tj5ZAXcg=10QE(3p;3Qmh8KRDPHZyJtl8p#jz4P*<>~ZEZ)Li=mqg|bK+rO z_FDKGyAy0(9qVUn6cCW@V0!?lJ^!IKafBUmhWa^ zPbFdF@BsRD%?)n1ks4PB@0m`IG0i#efUAZLXId4Cc%yI({wiO`+0;KoXf!$(W@9gr6zG#+n$Kr&&TH)`-FA8Jgr( z^(y}5;tzCp#A;Hn)=!K2{?YoKV=*N6DTI9sgB{Al1h4NDI5Ito91SC27;je)~oQ~5B-O0w4DiRi8F5s1-!L87crk{02d=zOA_04P9^yZe{&}bf+51-JsKP3lCncbsrZ^E7TYMp`v2@P3#hr3pouQ}NH@|QWBTxh>jb!W;1eGhHHnj*qzE{uK>5UUb zA2{FehK%wwre^n!(J!M^=#_8lNZN!Nk{J4;_U!&Ba-eN7x$iPS3L8>+lLJ5Lri?Ir zcK!t|X)z;zlU~Bxt;X;!*^@5XaznIrk}`=n=p$PCK!r%gbVFymD%8dAhaRU+fxGsL zNc3mXuhui@8zCpQ=(Ut6D6A58?}{MrYl`u4)N#QFV@?0Pxi7l*a2z=+_mj-jG=#Og zMv_z6veYs#&B|9IpNh^~*DcU>B>jFmRJZ6Di2mFncf{hbPpkq)?fF2t4UXW|b%R`= ze8cK?%R7>^FP3y)dq({a%W!+DuHw4e+c?FCr^(2Wr+myQBQ9ieF4~h(IBk3nv5^?g zQd>9BD9QckR_KaTdyW#n^J&=SRZWJ`8VwuiENM5Zwa}lzlC90o5mosJ; zcbq`j`X5+aK8)P>Ss-=z7;MVsf$3Voh3gApipD}_GwB6C;Mzmu&q-RleYc~de|cc3 z@c)KHexi>|&#|alVV-bzB^bzdK)=y(7F2YaV%pzC|N)tAUPntDJYTyO( zlZ+q*X?Y|qZxe1S+9I60!YNlU1{NPSg|?5M2x4a4K8owfQrkT81c*<(}g>Zi7L{~bg`4U+wVN8bn_nK~LFeiC^ zH!l+_fv^u>GtoSI(4R zdD}Q#cq{{lJdm}n5xAXur@O#JOMh;Hr#cqsr?Z?@Ke74WF?evf2O|GOu~Apf^516? zP%T&Dy7$DBy=I}j#M*WIc-?mL^ok^`$Q;hb2U>B;GuUuq9;2+|jVovz?^5 zKSh7H`Q-f4dbrdwnnZV7QyHmp>K~X*Hhi4Ojc?3F3Dn^asUHv-gJ^k~%Lr89^8s-@S87h;!(EcRDr^FDjZM5Yg0>uw&9 zCq37G5oN0e5gVxDjhrqMO*>Uy^q->Ow$QC}nP5S7d?>J7d*={6lIo7p+s_INRw+0? za|^xSx{%Bk&4BdK4BjOz8>b|;z zgTC`(RDCs?%N6F>KT^I5zoogT%XHY=&nvkJ&$a8lp zP3AbWnY`ZlmL|<~CSgK$E9Ojp?V6qjkzTblln+#proctGRME1=zo5*fKLZjkfJB=@j}2|C^G*9vg2-mbNV`5_GT@Pc;f`GyAJ{;rjd$|CrE9a z33qCrKD!n=0=-7O zxd|txi$MB!V{NF4JT;$|4i_{gz~59x-=wP3y}ORmMcec^`Jgu-)YHJ`OBb0ESOgA( zPB7z9KlwbN8eYq;rh89(rfro|xU~W|%Qk-`e8Crc*)03;KX;aO}CG7x4(2Tv5X~* zllg#0HVzYct$Qcf7*l5eC=$-Pp z?%h^^^ssc?s4Q?rm;MI_v%d2tZO-(hm^k;uW*%4LCvY;(TCk`aD{$I@Lr`+U1o_1> zto=KnT}CwdprAS@+=tKO7&Q2X@JF~4s3ev{&kKKlVAE0npJJ%)8MrXX z^$hG<$dex%HQ~SD-ze*j^f0qv)!SEy&Qwd_KHC?>lIy|r5p|?Szm3n8TaM8;|J2n< zcR=_y4$5UJ;3!!Lx3-u=o6R`X`6^8UrHpY<*t;&6TSCM?#nY|F`q4ak6{uP&;oTt@ zusgN`rG`!AOpmFxY$6E683`aZb}{8psQ0(tF=$p?~&i_~!W%t_riLGMh$N8gIy& z9mg_zzFc6e3hc*iyXpQibJo7g7dAOcgWBHd@ajrC$fQ~0k|}y@zk0L4RnccMRVm=4 z_YSU%%Vhyhi_vYwJnrFz^=x&%A2U6k!(C08$-?%=vQ1LM>L32eg6!8y%tt;DrLPNf zr;DFNw>LZBlm%WyrwY*D{v;#@Pr^Q(Q`Gt2HGxZP%#6)$6ZM%lDAArd!yx+*XZd`b4PC473B0yXw=Asek$ifnp~AlJS^ z^!T_qs6BClgGGp_^^;z9pAUhSr|Hcj&RFPp43)_-^6mqvvpw;|>S575GPbgqUWq(N z6jp}7zuF;KudG0dCGuczzya)3G{q24j*Ig9&YKT6LT{<W ztD_8YY{6^NGb)8PXzJ59|KsSqG-lnIZ zsW%;mFUnz3l0)d=NN>!SHpB0;ok-`JlVCotU-VDu9?r8%AkQUpMegBU?3~3BoEz3j zQmYF{@WJWyKcVvq^FA>re+!!bVh9{^{m9-964n;XOBrG zM)H5LH~fVtr$PlrZybjoMyFx%jbM?N{4PpH9f77r4a_|HIr=Sm4OcBTvJvrvZ7-0w zFy5K+7b-S*>Ean|q9Q!#Fk0;4a0`FJBkFnraI!=a_Q}VC`JIt=TkPEV<{VY}*>|el zkDXGbtxM;F&7K;XR2+vRpKH^l0h}L+3#D&5#^LsDF4XaEBcv4T(oL!_#Fu+0$a#j+ z#iz|+Tv#tuI3%Oe#~jg-hEH(!p9LNM(1p$uEAz3PBl)E$Sy-mmEgC-DnO@Hp!@t!V z#fwM8llN=SlT9%$)T@6PK3gD5o@$xUnyIBEeTTMq`nfYWrNflZPW8eYxn86{PJy|4 zEu^3K#lp3=?_#`r#-=28240!g45Viw|9a^hnR|IDwfe3M((xs1#jJdkayR5AuiWu> z*aLRE;t3d+%F)SdUc%JHE5WE~Ap88@17%uTn7+kH@+D9LL**Ayl^@CA4lD55?*evz z`ztgb*e{wB(ry!T?GJqV=1pdp--piSA+SwXp7qu?5`)urxN6vUvZrznI@FJam1?a( zf|rPgb_J1pW~0zbSzx)g1(NvRCXi>e4Rgljf^S_g6sg@3?Y$rYzlI+t-4Pi?`+1AN z?wk&D3VuO=shEi`7}9V1Ps9Amv#jj=Tk>*aIrz#2p}F82vE4rw+zyD?_Qwc2KLrVF zW&?3-=6~FIwkjAk+=I@9eo}lwUtk$s0E2AdZ+Ycs(bMOV5UV7Im+cgY$B-**Ms*NQ zZ<<17*A_AyQ;j)7US7)Q6@GHB!BCM3jT82guLeF6HNTjO_Wr=f6fdKv*KZd6>Pn{< z>WcZH<A;b#`E11l@yI!J)Exh(uJqD^znp4I_i&?CYRP81A~s6uy&gy?Z2CWRnx8E`Wj;pAP>AXerf=WuK$W60@cnIrTSW~>vt~kC`(t8%_#BhZkB1sFAffA$NNa8v zGZA`kGunniOXN2;?c@iD*An={Pd4CvcqvXQ74`5C*aGU#gOG{_fR747f+1^3lA z@NG*)`t}OQo;?P7Lkr<&U>Sz(eT*$dqj-IR;2o>a7wvv_4wN($d9>F#$eWo?`H07O zWLFC7U)D?&HZP{yt+n8AE`_^yY6LYFP49{84TZUGyUd zuGpvJwmNzK_=+ySe{~pb_CL+8_SLb1fF>dlu8phJR=|eex5QKK9VF8hB(W8jZ;>^h zGeEPq%J%z$OmaRXi(H>P8{$gSSfb){&}sjV&^O(h-&0;I5Tq1qp4|pEb<`SOjIC0lmc6VPD)T=cM)roUBX2wUdYt$U;NP*9B z<`+P0z$A44FHyA7%m~{Czhj9i3&5^gV0DZ(ByTqLuszogK>Im0dU}vF@wdDwYLC$n zEpSt0)-&a3(2^w5KdYG;1l%W^7795Z&v^VWPYEvQ#6Y8G1z9la4SDe}3wjP-0;8Yh zwwgJPM3k!yi_dIe$#2gv-^>MYP<$RXtkqyX<7#23O)HbD_r%OC@^rwtIMVK@2j8?O zvcQcOA+y<-bR7#u$o>yb6myK<|BZF#7|?cwBDOxf4wY2zfJyab)^sio^D8x|p41}f zy?++#?QXM@wjyXfKMf8|Sj;?h7L$!Djvah)%pttj zWd<$Tt3aQu3&wko%wehXd%QK}6n{It4Nh+#LgiLR!kE#&@#iKZzH8iLT$H7Wt5Z@? zK}!i;d!jMCsS9FWh?&cd;mp3r;CS>Bt4j|Bd7WQuit0>y zez-N=`7j5DrVH-I(Yf?&lNr^qUXO2tkJ;n*0N1ITbGg@ca7bk<@oZ8;_t$C6Dc%vC zq&6~b4_o$WSe?kAcZsCy)@cAY88N%uJ5u zk;3X#B>83{jz6)MEjsa+y>1k^{^z^dm)HnAWJIy#tT8)ntx8_Gj^yOaWu|Fg1JKlh zZ~aQig)?`-jQf?$+9Jmj&u=a;>N83ix=T1uGWbwi(j!fcNHV9tSG z#9EtH!Q*2Ou&d-d>Apch^NyrAHP#eg1cnQ&@Yy&vte7lb7f2HHt}w^X>db%G)ROzf zPx0qwE#4Xs1m~s(Qd#9l;XK-eak_`d(d82S`3enwddgh7`FFWE@+X4>W;LjMAqVzm zHVJtUfj(DjO=F|1xL@@J7;H&ta8W*Uk?to3Q85DVwGWr8FXCpZfm}o2Rn1Kk{wG&z zQ)fdno4mH$qDx+J;>~wvZ`K#Bk$7&YykI{uquht5gj{x$w=_BbI zrwV~W&p|`Z2yPbj6Ulx{cGO}Vw9gsL^QPSe#iVRp^2|*n3Ms{nCtj2EA#a&=vMpaF za~*30Hqxmh;jHXXi^#ZpD_JMK2;>xo;YWoRV#8qrdG4xyv75?6{P^i8`ze;;ZGIZ4 zyX!YI@)*WtmzRO@h+@cJrh_J#dH9@PK--EGyk1iyun9EDz?p|}hmh^!4>Pc#4=^KV z1rLi4#vO0s1O`YvUbi-uvXk%ESVf17 zD#AdM+ptqNfTvDZBn|a<;Dz2(toeF?TKyE*SicXG=K`1h*OxFjpL`CdtS^LPI_J<{ z;}kDkvyM4u?dD0Z{RHm3Ay1hphm9>$`O>ye7(L-5gb%txZ|N$LhL;cd9@!W!S>yv5 z8=QF8_aox`-(7s)&RA;E9)RoKHKNMa%jhzrfml~D{5owKE>rtu>)WVFy%e9Jzw`)p zT0^~bM5+mRhjn0Xs~pvw?8v|G(FV(DwRrQM9nNTUMK}GaFst2zPhY9a$6Qz9N4pHD zyY&++m@ppRsh;NQ5zeH8JY{d67*m}|&(U}OZir0?1(9PNtH0P!bXM+$)~|$5sCkHb z8bdKHGZJb8?eIiuCT?41z}I>*c12eMEC(4t*!EJ)jC=_C`3vb+x4+Q7v;zwMgu-4! zbJ(;m4+9VHVYbsfS%s4lS)&<-;j+icdLv7IyW$uu%)Aa+dgt-?t6GrT+5~y8rRl6U z`_Uz(h9oWg2oLXeGYnVYr^I*A-R~NC(L5DyB4}nUMSSEUrhnC29Qn^aH$d#tx!rm&}7pyU?>}FwdXA^+GWK%>Q?cmdh@Ve=x?d$caVSo zZbH;gKe7F~P(E(&Fbv(DD`cj|kmY&{c*(Du)KVt_^HZAP@w@H3utJmDq8lGK)tu@^ z-b0Hox>);FmV9|yORUPnIoHgkEz?edPv0;uchU^(W;fFxY3tF@ON9>1wBoP!W#i1z zru?eoPf^n6$$U@jCYWtmEz(-HojopIN5Y>N(2eVcQ{VS9F6c0FU+Q5SUXMo@tA&m72ig2t+fgn0Bk+{_(2*r6K9i+{MEN1L z*F6Fk_hgGbmU!``o}0K{xM$n&>=i35I|#a|7JOdr0(Mwh3&%fmV=run&}rvYG5EkI zQR0WGu6hY zO7br^C`3IVX58$OcU~89><=bc?Qt!{*kokbtMe>@Q`%6452wfK5_6j zNxC`A5`8XJqPN5q-Z$71q8CxF!Qx@K=p88-ppRGEC$KlSWvOR}6IEaIgbZnxp{ue= z!Dp#Do$fOoK-v)Zp4p1){EYecl_IA2>M9oOlB0HJE!Z97hwED}g2Q2b(tl(W{86qI zOMS71X{`m2(f=717HGhZG1B~?TRFa85rjGWBANf@wqvAv zaS7Jpf0SnNpeu*aIn$ah(Y_1M2dlx%8{^pWSL(byU?-`$xRSNkWigFd!J&9C8@q3n z7wKjotQ4nz*Bkas`qv7A}rJ||6OHsjX zEIiIQf_8IDg^XPi95qQqLzPnqX1?gM<}U2J?m=buw4jDzF-)laO8N_J*jJ|m@WNM$ zKS-UyxNaD}XtBj}WxJSOk_hPLG5pH|6S{eL89pgo3lhiMKxug{zYdY;EqViwasttP zoesU^pA2cEE)&^`QX8i!qwoarXKh2O$(WcJ{;qjET{58#U)R16?U$@62{>6Lu;!bI zo%IQ}Ikf}+HqYb%6aR_FESbX}{aAt0lhf(P9mb_oH#gzN(lhj)*pd2Mon?3CyyV}7 zJ<`~UF?`IeCp6Tf9$0r1qG1i@r|FXYDxaIUxH;x z$oee&yeCq;K3a}WTQgVmKFyToyedPVbAMax9u3PjC&BMezQz`xYz>LxBW!X#ALp7DTBOfW8ReE$22_*c;4V~Jnm;MkFXJ(X6GAmnzvMGXjd~# zx|hS1e2;?Pr=7ei-jN;OceD>1W}u{O4RRcJ5Ib^3fWR0N-}KvU`s_CsAZ0z zgEyar)LAR}^N&tkx3QiT?H)xn$51w}z!y(z%VJdX33^T76fD@6g?Y;cQ;qSe&_@*L zXftmJ|G0)`Eqe{#q4`9ejpuW^CP2%sNqj`E1??Ljg>hr8$ZRmAS7W95=aKQC{bw`; zw5XGjbBpOX1;Lv!Y9&pzQ^dNxN9e*u|Im6!Ir?a=<)wulG<)q|e3?3sJoqM@(VoA+ zWQPS9J-0+ag{xC1&qnID@RZm&V>FK}n8v1A=<~RR+FU9vkDI(#;@P|0u&Hx5p8uOf zbB?d!J7Sl>R4c+(>neh)tSmR(zlyI^pD8~6rUye6$M6lG4#AWdPiQLg<7WitM!bAG zbiAGbei6d6d*f87!FOz2si!FSaS%CH=10o|^LcsUJ`#Pofue&spBd$e*Xv99v9{rO z$>pKYeYy&|m8mdvp9=3&>qFm?k9eYJ47^>ql`bmyK$3qt^AEZMcvws-EmvQMquX|J z#mQrNt3w=DvQC7-8&%mr?P&aQJ`2)dyjX)Nv3{g`q6!Vzx16^bhLf|?C*U8`S@`?*JZ^MZf-A3}d{(T8 zUJ7Z(A>pUU&9h5sn(bkDa!ZxSme|u7ywKOIwXi}!`^}Ap%hx2Y6sr8J>akWTQ+cO5Zk0J^n~4<@lsA4Os?^RY)w7! z`7^q_g*}9}vGG{el|k~Eq$t0R(%<`B>0AF0y!hoj>c!XL^P`%4XX|QGKX3+4e->^V z(tMB^rBISgR5jfHzH({fEFmH&6;7`AogR6Q1#FxsEe7FNDr5DKM z2WC`U6^b8sxbmSvd+3V(09bizA?&m$rinYxV(C$trh%kGQ7>(N(q6y_P}<*yb#Ttlv_K93O?~8MU?=5wrkOTMJ35Iuu^8f9gvs=H4Uc@+2|8 zSES4rD+J;Ap(FU1(VM_{=486rs0(G^OH%j8z2LYeTuhDx3Y}+LD6=)7&3c#FzSMO3 zN$6I#4R%NMzJKhpcof&|FeESToF{)-Fg9?W&eBw8I9%;N5Jvh<+CaFoV;Ul&Tp?4SThXuI>{9fl_H2RPOcLipsT$&nvsgZ+| zD-yVs)IA)&RT7_o2U;ae!`!2DX^U$fxE>lv=X8#wKZPBMTHrni8uW_qw)LQ?@-aMS z(LHnskfLRu?r^oD8dS)a;)5#ZiU#LL^1T;F^3PL8@U$~ez~S0XX#EgPP35~wz6g0L zKOHSvk+p*FzB7uuy-?u8PUrCrT7oB4c+VQInZcQxA2aN|jUT4}As>Gk(K$Zyo2ZKqT}2!k^HxIJW%7iE>AMzA&8>cQVhaIkrlz?gNl;HmqS|7g+Y`4^=5*;WgDbL|>fC^@q6)e@*s zlnXV7k5Tivjp(o;l#kMqqw2_o^eGIl-oz7PqQPmW8-H*hkcd6I z(FHGZ$JpU`wLSxb)xFvB`XM0rS?Q^L-n=uS1ttIKL(a(MFnic1%qbee^}k&uvce9w zsWJ7&O^ZE*YL;<5cfj6?1?-lwBOY=dKqk!1pbwVW@|SLVP$GH?Z0Qwtww;5yyfE`u z*z2Og%?j%2+W@QOtKp#PUtXgld@p+7vHU+OKmI`^?AE-p8qEbUBu6Td7PJ z?hZtk=Orw0e;hVl+Q5hQi-~s8Jf8Y6oV!;{vBN8iY2U89G~7tK)J*RM+V{EAHxK3D zz2sc*=#-@F{To!)lEGK_OJrsp$k%OcA+N^G<8>=Uyr*KQotmt`C%>OXUESNbzWNc) zmEX~;^#SO6;}q=ZKSAx=2jLgP zt_U?enOi85Svm&?e>LRJcjuET_aXGXQ!6ej&k*e{Yqxcmvcwbp?`*5NJz0>a#)nqw z@=N_QxW_a-s{UmS=p{C?L;sG8-gxD*?{aV9(Jl`f=GTRrzDd|Bwp;s~!E(wtG%w2~LJ-(0pe++AHs+nKu@qx8z>%TGkBT zj85a486{9xl`GyR?Zn+jy}+Y=>$#?z1?aSuz{~<6M|4AQOir)@GuM*>yK52^C*H&- zOD@5@RVp+y`2w1RsL?QmpCohmC_YH)7gk>{#w|L2EZSY2YWPNj{cdllS^kOCr(Y!U zqHAzVL&!r(pCEUo|H1RCr5L!V0mgq{4Pz(C^C7prd8u~_4ELDEC&cK({MuvWS+6hX zw|HUI@~^B(Q<`4Aah{!bzlh&F4$|0&aGbk(KFGdtqf%d5P-d5i#|vx+-yt_qTG%_u ze5ceQU^zJTYN%)1@?Cj;TOD4!Wlzvdg%0QZmBW?#9g0R&Od1oSHyF_fU$i4 z){~^5L@e|iG^yzh8QSwXj=YHuXI1wrpjPFcIOv@Y9lGT#+vKPTi?=_=!Ihf4;J7}I zU!4v&D@Z^jvItMZ}zS@Fc5{<{xg-QuYdf<#)r)yRVRYL zs^of9j8g!MDNJ+K;`Ptd4{FYKW$Xz$zGZg>QExtjaBb{;7`Yx>5}rd?r$5oW zoJLe?cEZ4MNpSpZrr>T$_-0Lmi6cFS5pU zP2#=N8$f@;GP-50B;PRpx{aBK11m~OM9VJ+;i-uhn0aWy5|xp3PEoz+)n7wgB%cU< zyHz36Fo-LDR2FqxD)G4^^Xar_^I#iZz@kVc(f);+v^H4|euQb@s^fj4&l|gixmb-i zraXa%Z| z{{#&Plo$GfGkyr}pc2feDk9cRf?M`M8V>hR;PT}*=x|~@lwDy*qz!%G zbQr&9ULyt*rC?0E0(-K%(bga$hYcUtL&DpC5@}s~oUFVNmz?^*96P4alptYdy>tp? zCp98IR-}!A9i)F_t~g$J)|gI}hs~;0tbXAS(#3~}Z`rlNpK(WV=z(6Q*eQo6-x*V% zi3>&TYn8D(UJY%A`~ioTvT(#<3AW0f5YAm$EX%l>y&P!@4f49MGj0%7E%ag2PDrz( z+XX&y^Jl0mwug0xm#{I4w{Txv8_10=2P=IsrU~~0+3tn-ebQdC;hK#2-mD^``Lq%e z&(?u~8Y3rlQ&98DKsY|;D!DaCisxYzO7*;iCGu8u`lat!_d}JA$#B3+sgFf{t3JZE zKY5rldj!0cJ_$?A6@;^(1&03`C-4*!pvx`+%x)D!v+_U~ANmxwuDS=u^L1dDhTyF+ z$>aN?=h29N4`5~8HeTNg7;||e-aX__hvq*oQSDyDhnXDZE6b(OYy1G7d+-*ia`oVz z!gJ=Oy*i(`{|Txlw35Jti(qoQ094FwF%7$SWcrT@DDQZRl)(s*gUSW0nsE=cen(;t zF!7`_1Z5ghpul!DjL~|9$DWTTRyN1knGtt!)7gE*RX>IuZ=C^B(-xD{X4P9|iG97{F=YNHr&B{cBWkIPxp zmx{_3_=qAq}brL%#A#b`)AFKK#guA;*V#@(S)^wvgUaPS~|840Y_2wMOI@gKE z6%^T=&+{=(e!fV~M4gW4jTX4k5%6%d4t$izfs2QQY>?Lt{4?MWZwcz}@q$IfJ%yJpv+?c4TJh(ep;S4ph#Y+NRn-1q z6u-Pt8xQ8rf-P*IX!nbM+1?eWs3<%SQ?VZ|xCmiioAFjpHUO*>3SUC#uX zZBF|KEh3lw$I-9z)cBxgRr)jmQIpB z?+Yn(`b{>@`NnJgK^%206PG0XBeONaF;F*#tQof#%h#J?RG1!+M|R=^8^bYw&8h+yDF|`|K%-=Q^<-^K)#)^4Cm#wGkM^?_%q{ zQ}Bv-v#4y#7$yLU$bJ)3E+bJ*j;tBLWzCkNefMtcy#5wX$LV87_+so)Z6%IYL6H4y zCUKE=WS9Fkp_7**u`AuodjF`GXiG*hw+_L3)E)}%+x(cXXBvhS92E~2xJ1g!{t>1UKW{Q*$qZsFDNj2VJ|#6wf!URI~om%ht+YzoG38d=uH!ZEV}YuT^P1Sf|xxM z7~!Afse5BL)MFc7#gVx9!z;LMlaEIIJ!9D9fdpKdVL)&(DEZKN|~sdJA~KmPGPzadfDxfZseD;q*!Ww2$|QJLZ)U1 zp#HT6xHs`K`Qr42=#EGbl_hJj%Wezl{c|<=sV;yupO@k%mkhw^pBqJ$S+KJimi9D|_6;d0Q8kBDKB^{( z$;L$XHKLZ@2uz)S4t92ELwvg>bIQ}F%WbV--eX@JNVef3uba47rWNT7B`Uvj7WxU@ zq4Hh*kZ|{s_|UW6*io58EML8X?dow5bSeRxD}x0G`+BMztR=o%XAiSaHWAZxrYu!p zb{_qe2))y;lDKEjK<^6Iz{>ydnzvsvM?iBEkCxE}7`~ds59OtGp z-jRu_+vqi;NbXV<%@56fPe02P@XYQ)-WK6Tf-A&y#-!n_cBLBq_f~?L-TDnH*?I6D z`xH-AYlG;*CFVRrALj(j7yM^Kc)Rly`ZLN);6I5WF;Ieb`%L1!^fenaz6NfuzDsVW zjir)Jr`Z0YA{J%jL)R3~!OdM3(C}#p8TrwSb}SnJrPk`yB{PoNACmz;kq0mTw-P5R zXOPa2aMGlD1diASFr&}H{1QOfbosd~%47yCp#G?vIvJJL41-4+A>@O;57CRvL$yEy ze6qqhy4ka#5!4_;B8W#G)CA*$Vgq`3V!$L50_x> zzAufYPE_K)&xdkH>DLhMYDCBG9zq`si=mH~?!&8fHem60g3wF9!~biUO6?nj+=csM z%+=MV1{vpZ7(=XBd`8HPB=N_Md+5m@Q$TT)BsV!EIFdtZSeM2^vFSB0+_DP!PHYEe zu0Wganc~RLLF{k+Fn&YtAAeZf!)}jv!M1E2^vmUJ#+z(Df14$!Dn!!s^j=~#-hh{N zsqvI2N8s1~PqbD&A0DPTkX=>9_(}d054|rzQJeJ4v#^LA|hk zkia0G=*1TcdE>rO99-p0!EWs|=xG>jt8DiGrBp}YpIBkPvBnX!R7Ya|3uEz1@>d{0`m5V`*2hqpY4tJ*^WPpGw938@fe#=gnEd zxna!V(O6i<^>Fd*-*Cm}9BPHU!IT>aBI})$7Hwc@{>ETmyoTqT68uvU9?aTRk}jM5 zK$P_0C7D0O5#C#9p~@#InlbUN$Y~A7+ec%0Ui~_%_f8LP?nq+#V;_jOTO{%N3t{-{ z&sw(9sgS&R;=nAY41@`}Kj3uL6x93P2jjL_;Pt5h_ifd=r|&{C^M{|PHgXK6M;*mG zTlR5_C#o!PpCM~_6bJA9cEc)r2E9=#bh&CR25$EO>$(W^|C3AZugGIQ=A1}`He%pj z34As7HA-YiF_);Ta8ckgN=?flQ$F0_TmBl--zV3~9L294 zhk5_JY~qqRnOA-ZVQ%qp$n^3+UN;n-B_=|nz&bduRtMWd=A-ODH9j@K8|n=2fTFbE zE8efcA12)4?%A>EzFT0yDW~AY;VZdD-A^2;mdR!90&i?e_{&zC9U~VE?jT#9gx`9W zlw6G-LVfT6|EGV1D9noICO*fQ|BIJY>GK)UZ(}chvdM-=H9qBDCGWxZiq#FN6D#po zOE%`JjimwiZ83DF0sE*R$tC98#qvsbbR9Gny8H5|vd>nswCOZ@c=lnn{aGGw_knat zI)Xphk5n-M$s9#mczP%*eZ7be|7wXUw$|I$xt(LBo5dv2LCAfNJ&gaBhLdaL9&2a_ z;dk81Ze*yriZA=WW!}$aZC5VaDOUco0&FF=pu2>(t!1AEOc|mHH96B*S=}?Znsf@3 zx-UXR<1S{iJ{|8@z6Lq{5oA=puQ+zT7L?jZqT~WUdS%W)T;W{G=4w7*xiyk>td|YB zXxs@3R=-5vGk%ilMG-i@U<|FWF`7eIpXCK4*lbd&VU*t}2MY2iM7kQ}>8aBa1b z&O_HpYsnF^p~~L&Pev>h37;)dtrw@w^{4MnGHCj+5S}@%hYLe3VPvxx8+va&SVf!T z$5kD0U2hDoo1jHU3<|@0Gw#BLqpsX*$sL?oFUM!nF*_YRHz)--w>0Mf)vcF51~(P2^*Zk8GJ*< zCnl6(@ke?UsN2h9x%xcJ+SQNO{3g;4*HWC_Jc6qYRmG&8(wJ@N3RhOIhO8ONygm3P ztGcSl*RQ`PxQkO!&+V3wDW4;jX`X=6Du40Wv23u?D8Q*f@_cCZC30Cs=#-U2;LK$; zkX)aM?~We9BURNne76>Ex+DDT`T);P*F`Ot_>!uHZ7A38135J$!q@@B~!+BH&M&3GDw`iE67kJg_pOk`MH8);V`Bed-Loe|IYV5hXA~-AtKC zS_+Sy9wBPFpNH-Sp-|xd1XRZy!VR1Lkylg}XMeMzPnrhurGw>5?Pi_iBcCL~Fhd_7bd~u12->sy<#|3ZT6`o~idtPFMKH!ex?s^W4?d6Y-?Ixob;UNc^vx)Z+aloV;2NJG*gfUJINet%se ztZx!BP0xSfF0D{9+W7*`@+rdsH*|4mnj@wi;NmD3-IF#Oy9cUMClt?QM zdea~FH|Zb$5^-r&^bM5<+WdfSH=i_T3%&NBpDV06O+)tTLBw%6!IhvcFAog2ok6+2p(@gtc@a4AY~GFis*ZJBno zKpcaGeOIyYhAIEuJ)74#Ee7kZ2#%HO=)?glxzDiin7&aR3a5@LwXU5i+Lg0W;AU4s zu=Hu(@$eWe4_U!8TpvKn*Bp>KD#1&1N0E{{75u)B@XmZagev#giWTN;LK=`iuPA)m?Y9vO&;?ZXlkd2CIN=9Sl@ z$a zgIV3$%HEI4Epbj60pKW$X++rlgfzh9^8$NVvk`I^-2ttHceeVX2vD2i#k{A^66w0# zhS8Iw#ErQDYD#u$H9f z2)mO7gXk$?58L_*Aw}rrXjRObsf#-z3`CY4Mm)$Hr_P;mam0`%Y zB(&iAq{pnS%7P^sMBwIK1Nq%wCft6$ISteZ;4eOeawUt8(BOE2FY${JAGf-L+M5~P zFVO?X>KWYE?>I_X4W_2Qji_#4EeRYu7p`o{LdV!n8oB!u#?0!#rNiE!am`k~*zG(n zQuC+TuETh9;ti}Hv6RnssNsK`5ieUU#qr0>`PDlDBl-9^9uT&XUjFC}(K5~ub>uXQ z3mOSM0Sj2y4HcBJyoXybnV`x#C>s@QJL6y;Nhw&0)q^5IQs|Hw{qY9XcP~T^3mR~z z=0y_NH4Fc>M$&`#OYyz%e2M$-AbxvMEq=bel^8`zfl7iAoA^qBRj$kw@2jL7-#m%c zM-j>LSE}xC;CcX;Eu5444dbsKs3PUwss$iZ5pf3W=XCumiBPJSyM!{_6Vut=gvtos=Ty_Dd0MSe`>Zz)Wl z=?x}-%s^o^vW|5_aPjINWcQ;&_II5&HOrHQKReQy?`(IdK4y&r97eJ!E{l0@^fo?z zTOfQ%N~U`^l`!9``_SS%hz^=vN%qTrBOO!aX>#3D5PK)VJ1PtPoeQ|6Yz5}Q3;fy_ z0Y)oFahuFvaR1E%2>w*X{z**YmYBfCIhK;?=*S;jo`Y^Zci_qM5v5a?AK_X>bufS9 zC9beMkYBzx4z_+#g{@Jy$#o-HTBCg(n~qk1kD4m@ZMXoL>m>Nkh~->QZ4s5d6(i(- z)Y-#zmmxXyJt~ee;dS!`5$4i(kzxy?1pA}r))<3i)5>XJF%E47trHWHAsnM#f2?9aK4WR>X@m*Zt-Up z_hSqegiQv=;0~g>Op-^9mc%KeB4CL7QL(bJA~VUcfRA$v;kUaBQ=0x1b7O9b)n7~D zw6{87pJIwC4o9(pZ30WLsrcaAFrKG(0aQP&MPIx~v}hj6ZVe)T%p|Fbu2Ibj8)^HHR|J3Ketm?mzCfUa3TQ6pN73)B9`d{)jtC;>B zI}9CK?8)34w`?W-!g;y)g4pZ*cGBGHOr?HF(xpl=e0@nGRF!*jnY1o+PLif4mPf19~HeroKDHGe4Z7Upm5Ig4;E^ zSLg>!cx%N2o^GOUimtr;rW(}=Riia8rFmq?MQ#{UK?BQWOK(gJ2Hm*9d~V-;PUV*I zQ->0HN_Z2u9(a(KysU#HAs=s`YztHK-{Z6pZMaer2;)plN$9{)wo@(DpyFFIaq>41 zya-Li!d&p#C*C45rs1TaCm8zXycV+QRoJ)dENb${BKf!au%+=8Ol-+#RjX@=0Wkxc z70N{W2_aUFJ7N1F3HrC|E!&oF03WBtgIebz+!@8OTu%zje-z*#$wG*gc?gQd3qbRl zG?Qr`fYrmw;Eky)#?Cc|0bkCs0he#FMH_F69kScR!-q=pgUe6Cnui@^&Ba(O5QVcl z>4CJ_;U;KpQpL5$*OQmI{!sqhMzpZAfL$9ZWYK%;u<+Y4QsoQq)%O_MuC{{0Kts4! zRDdc@$!tvbZaDBKmSo=FWs?uV*6VC1z{ehacD894kB_gyokvXQnCoMBe93ar`&&_{ zSGawL@&8eD=HXO*Z5R$AL`o8+(Nt8T z6nnjkqKFig6q+=tNTsAXLZQr*S)sv{C}OX78Pb48X`)hTo_@`xq;G%!pX*%bI@dXS z@AbaVbKlhJ=r(@)@Coj;K>-YVO{SjRdN|X5HaqM)g65CTph~NILCfQ6=>OyzIWA*7 zY1W*lTy4uysMvN0^HvwZwreHy!uI|6vsD(~9xq^qQYYblkQ!b6z>6t+zaTsP=g^*J z9vEZ)Lz;a?NnK4_uH{}N6!uGJiYxjMgZ_>*X?{4jiAu*0&99itfHJl_)SFCPU0Ss-W%!$qo*0$slRxLAuAfb!=&a#AEZ|?(9TM7w&Z*XPmT^8)!UveZg z;QBE({A+L>v(}M*oB1mE$mIaEDV<_rw->^-t?Mx8O9Z_)ejd?GJIe0FZiU5%)uj&W zd$zj99BYQxH zrqn=K54fUo9()+EjfCyGhcmVegbRn7(apGv7(YyfKpQ#O%J$>DxhI9qRw{TT@Vu0* zyG#aDN0WCKbD?2f0amcTWS_eq1m2HlZ#$|nixrW}v7fNt>zPzb@doV9I)c+b=Rwsd zbMCdw0o^iG=~PpHsPa2TcA`_+=%3~qh3pw8>K&N{> zTA%oeC4-&lk;UWxpNoYjU4hUt!V@a0u0vJ0E1y~Y29A|4rOM-~;ic9AGHs?M?RM%# zhb@kW5tH-qeeY3R*7zJ;EWXNXZx0|NH4npqDCG-98^t3tZ31&K|bNv;}H2~!;6 z*yY_b@OpzDjInjZH!kVqKWT5R(XIipYX;HHY1MGisgX=61qj&iitVYh#;rT$D0>+M zn|Eu$ofi|Z(53>roHW^+W zh%}#GMGGD}!H~OWVUEPJzmPBz4!K*S<@VWp(Okq>tsDGes4R)?7zt{7{mGbxqd;kc z5!YBh5UL~|24`-J`AfnzX&>VeLY7x)@7wJdUTQ-Vz`N~(_}%gYOz%USuzu+}qA58`%vR07*h}Zge@`#Kd7Ui~_}CS1Z5=G_h8Mt! zfg1dex-WAixp4OJR-$zK7-r?m!L!IRw!TA+?(<*4ikO`lqMSS(o0S3?bjII$6n2h2)2)})!>b=)vP}_eDBdQC5 z_cQ^YNrmjkkQAX=eGRzxP=}B2Zo}%0y0EWDy0CssBGKxh&hyIW!9AN4lHuMDWt+O; zv%UlBDwdLc*Ey+qUB6A3sarGoBXRe2H zKv|P@UMfdaIXWsuMga18+ zFWWoVgC7T}%&YS_ru99#oYtdOGRExQf)n(rnG49Y%9COD0NhOdBzN!z?(4l0RR7K7 zrPF%B{nutyJ1n`s;x>#hwuhP(yTJQaEqr<7!RO9=gWBD@;ic;tGW+Oa z>Hn-&rK)N{()MOx;oN8v^Y%X3v115*+rxsF%A92?-$sJh;U{o5zn*Pbei{>otip3m z&&aSDzOX8`i*!Gh0o5@D605G3CnZ-f&k-%ey>cWZUM|N^6F#x`_dbdldDn>HWg@P7 zcbUxAtRgcTZ$hP%Z+4mfoajI9#uN6+tnv3oX)dlqN1c;pFTL}~#{njg*7+F6NSo;$ z-yRCecFSPes8m$V>x7hwKV;IY@2FvtA;eZ%VMcC~P_XPGSS1=^kJ;wrQ=JUVA6`!~ z$H%f#HAVjUmjd+5=?U6o0G221fVem#ZA#Rm329b@sl#9;Y02gqbQzd?zu*%jVK}YJfggr)Wv7 ze7^8dQSuwhJQ3-e(N@e@5mO9~F|Dp(?)o5KoV&79^qTltXb!RE;o+*dCRP^yezg%2 ztCr*ZLB{xGb0NvvH+d@OSvh@tDQU_?zCe|32hTCdn+wdBVyG41yoT%f0b z_r)FX&hmk9-)=8%<}U_@ViSv8Of{uI;GHNBpianGSGW1>KD|VR zZ@L}G9ir^u=I=(R2|Pg_lv~5HQ)PI?rUj-KaHin(iaB&j8878T68!z8nClZEE}Jxyh1CZMU!!Kg zQSrL?@6ADQ+il34XKW@1H*6BDR(Z03$0vwv*c|2=bVvNy5=c~?7qJ;Tj*u~(bFe`F z3oAAph&^hblNGf;h)i)PGlAj6=kQMQar+SF(epXW?G6Pj9El+x#zEWTV6s19r+E7> z!F#v;g|s0tY;TPM(jp!5ORj_XNX!GJZ$YeX&_FArdGX@t6NUJ;_z<+T-(s?0o@RC5VO}voV8c&s5#*!jkSp)J1%9yi@?6ZvyZ`&gLn&U8`4FRpIsJWqtju| zjAZ=e{SjuRA7syuNICqVV^|(C3IhE7@p{KJ>zcL_QgXlt$9YPg5TkCCZ72sTmn`UO zitNk8{b23yglo5c1DoNy+0M&$w0QAxY|ac5jqk{!e&#{z^4aEKa%?4E{|k|io5!mdmyneu*YQR1PKEhQc)?Abm(C9vaXA%Qj%D!8m^3 zAeE)n2hkTv<1p`}68j*pezlGEnOu$fFn`O4)ieD!hebjFR^JI#TqhQV<4_;WGn zWdPj$VuarBr5#m!CPutb6q!r|*9Ei@eRMZjm{SmBol zaj7&X3v4)nYf^WzuWm0$TH`kOaJC-ZwVe2fx@@>!a=fb3E`kKUcZTEMYoT*f0Cs=8 zBrGq{#CG++WbK$YMAt1C{bxCozte(Y_h<*$FuN7E33+(H_&>Pv@{ASlyMmcX+)h?7 z3>1rQvL|nUkXZK+_A2@vS##hw+maE9^K_>(EB!B`<^WANUo3H`^G~96?IJqvO$u91 zUGT#NU9qk^o4h-AiP%I*d&8g$RUgutr5u0;TE20@1Jmvk*IkzQ?4G;OHaUbj+wEml zMmMSZURBJIa``*O5^EWUJ*wXK?qd%|}>pD~Ycww)T} zMvWq#ez|1aACX3k8G;(0DKF@igW0>1+55MEY3~!*3+;B{z|VH3K0OIuSd@|FDubv) zOsnJ}^oPx+F{EC97SyWjr&C)p@aKdILN!addBjF+`YdH6Tq{YdfGJy+3-7#V`)Mg>hI9AwjHZOXYRgDq9#q`$DSRAobGdM`p77%w@8y0 zeeEU-Sc)((UW+!yR>7{CWMVUZ02MmB$e`Y9`RmK7^mkPkN#F4v)_6*chSzVwZ)#ub zx{S~C#^!VkNSVsMnJB>m+57D5nNLEPAE8=iYow=sdm*V{pyR3H*@3bn4xA8$Z4DIhr^4qeZcz-q} z2HuBZN8Di88COJ(@K5;khz|XgsYv&Jvx5Gc*J7d6**qidJ^D;?27UWqbmXz)aJhIO zzu9Xl-Z(yw$Rtjq7wR1-i~EB`tM#E>R+{%@51O{Kx^+@U!IgVFWE7GYl%Jk!&L9k8B4ZjLwFg8es_Ftre z6*~RIb$iFMoQw{1ccC!US_KTe_E4=Y$H8Rjbr`)UkCddnWw}*5SxnbERudjf%=JR} z;;XN5*p{zV9`UDON|gmqD{dB=8iJ@tqXutwy8zicCg8uhbxiM)DK_Xz&b@GHKl@Hw zFj0Jt0dh`!B0{pJj<0eKr)HGOn?wViBb=gM19wAKQP&qx^GlpnN{+Azj z9zbk}I$zam9ldd87`;8YAC+5kj2d6P&aaJ&;zrJ%{OX=NJk21OcdSrBzqW8*q|t^& z%8PNygX6sY_&|uxXalnY4WN8f8N!xd!p#=(v`O-U+}{BFP}f!VNp~gb(cqJPRne;=n%m#>=PmyLSMQo5^v^J(Jv>$Uz-Ot%^+PTxXM@$wuvAY%qFlq2+*)QQb^RT zL-n6u_!YAX$cYvV4^j25 z5p?^%A~N>&Zj2wYmVN$vj4$(;#+R8M#AGBcFB(oUlgvhLf^`w4+GTd{;Ml9jc7FiwW*Gv$g47Scx<8XQsCD6$ zNoKUyUk8bGe;aO%@S<6>rG0j8AMW{Q9Cdn7h3^M{25s|banBibn*Ved9idf@d;iV= zPnmGssZq(yV-AQ{I(%uLT~TbvUma_M7)9%oyZkUeW z)Zx}I7IS+NHIZhI))%i}^@?+(>})hm-*go(^f04O4F_@)`&z;DR4#eUtYFHl*|2VR z3{8vE<3^(+X!nKQ!k>Y$bnGo{*mUSQ{+Hy8frB1XMdzic^z${$*S(1=ms#QEKzlgt zEMn4$SLEQ@Qug4qAG)^=r(?xR`r9)f`dr-saf9xm%;ah&H0q#coIDLF>5ZKilxY0% z|fhKqGk3eI)=P*X* zENCdsXL(1*gGQM@(Oq&1hW@u-P;MK~{0`BB^0jZ4?CuR0)cvSr z{V#kLY<9jU>O1s7t?C0YtM3D)x$)%R^8>qL|L)*v6Wj-1)JpS*RG@>^3= zNkC3E8Id20s&Dh*#vxTu`FWoV^VmvcWZb~?{dxTCbDhOJ=wN1-*WHL>tY{oPgqxXtZLf#|HNdMC?+HICl9^&D@5~~_^nKt+zOGw=oKO4`36Po zzA3}rw+5s2wEftmb&4dlPA9Dk?O^D7b%~=RhewQ#vVq2Cl+Evhj#)Xlp!fut7OW^v zpBe_siaz1)twGGy#0NK;W@B}^0o!B0h0I*3OcOdzL#x~@X7q9<4qniU(r`6=-t|^2 z46{VPid)P@m_e6^tVF{)0e?&`CL8LlNO$o;;b37Z+!8(EQq~Z#`8Nq&=LN7!$KEoV zd|RB?k^^ny?4aJi1YFksX2*7Rku7~M!7S%p*c$So@@Cd_Ub*8i_FMKAcW(B@-pdlv zMQ$n|n3o|y@6%YhM~==ic}kARx`OTu1CZIU9Xi8W$QQ}~K4MlU8}9AN3=5VMFRu}p z6&cQ#5kqj#-Uo?vE?=jA1Rw6a1QV0SLj2pMq`>zgd9>?l)wg~x*p#!^$c_cdqVbri z!nbOH=y~=hy1Tr2hsH<?D!}6sFS~P$#SMxQUgoYRy=&UpMB5m+;gUqOHII;MMVFXQ zU?W>=KN5GAO~y%)`-JWEhd9Z)kJYcqL9mZx@hL4MFv{f_JLC0`)%-Vs-LLgwJ|pi7 zaqmaKy^nh_z!uo2BNNd?^9lZPo6mC3ogfw!ankd523-C+j$f{P!RlUwvJjg#EAuDY z$rTkZ^cZMD0_<;+-uJ3-TUkF?(GkZUG-&feCpYj?j1c>p#tQpx46rKCS&4UMPQ`)e zMzLvbN8#?c4`fNFAEJ^9jH>Ai3r==n*7c!i)4hbf@fyUREg_)zxRn_{nhw=58(9nY zfDgV6!lm3EQvcNe&W`kB%3(9DB1r;t>nw*!+QWI4NhgbT`b}<_hoi?(0y%0f81C?w zgf>qg{vX;Q!*wqXuYWIEiEpfWr*|;5&Kt0LY&e!*`^m1i-^8G^gWyNmdU`jtTsWnh zQ1#8@GVZLiW|uXK@Ve1(?lyfJPgG51O&+^h|DpK=GRINMdx@N6r2MWIxVpAY6NjuD@z7HngD)Hv3&Qpe`5ExEYLsc1goYDW>43K!jNbS zc2~YPdafRTZz5)qPofrM#ASbx#7&>i&9Ws-lD$QhvtchZ# z;@hK6z=W|rP~j3^)zDXkbf#|=rzrPlFQ-NeN|h$~Ym<%8X{L-$-QoPsrQ2*-p)s+_ zTZT*PRtkHRBXMDDIq{iU05i#5F<5&X$9YQ?xw(ySlXs$ZTiJ!aKhV$=O&-;UHLm2zDGZJRJ*nqocFJaLSHJxD5xjE=~MblGoZ5K z?avf$65R{BzL&wCtG4j&f+NCE2jrHI`7{W+m``6g(MKg1lzeq<}X7V_4g7bO@4!TKOPzkG=z|hBWF=mZSUP-SAP>H2 zNxC~~I5}mD0oQtf^||eQvYX@|9o3CPuZ^JxT-xyQA<1!htC*~5S0}M;=dh^vIrRBG z5*4qW!p&7*&?YsDUz%GX&_($aZ%la!`)6Jtt3ODuxA-e{1A4QQHLs!eMJ+pV=M;?1 zT0}R?=|kFD2cA$7idzOgCY?jBqQwtu;kE8D=^FAAcGOnEwi}hi^KoyU+~kV0o{wau z%l?s4wPh@9TNV`-#<23_msPPJ`ZKmX60}Rpn3dskW_Ecq-}pll)+n8Wh|kW@H%SfF zB~HTA0nc%$b2zj)HVfm=QYwGI4e5+taQNb2DzE<{rW)TD)7^COq9<=*C5t_V=ApLJU&W!uPJd;0=PmX7?EO-_C ztJRQptkH1rW*D(~*$BdhLA++=RNl{HBP@FV2|YXaQaIUv1o%!bs-?MlY`F3Io z>`Dwn6R`F_sXn(PO#-I_5jQ7#$)an5f19TwX&Lh7D5kxac7``Q;hvc5xUUQyfHRN1tTVOFj{=vYGtNZ+U+9ry<9L9#l|lMt#8+LSxqP z-ieiLNU{tL4H`#I$VP~>u#nFFJ%n<*I^1gXS=`wpha4Ct%RlF=#vgI}QSZWTSSdeL zu={WfLR%yF6?bpc-tq(O{TrFMD-)W1_S4p^AZR_U zcu<0c7oCCMg@y2R`v|^}soYoJ zYZs%uksl`hNf++!&Le%^Um*np(lE>P)ZP39c5;$LHdG;d%Bb5W4|;Chdifd(uFwk0NTAwPVpr zHRhqO1tltJIBZxJoIBJH)~U&Y;;>cNcY!PHOnra_kE_{w?EncDv=e9cR)w%)$q(Y% zNxc2TxqL}GJR2Vdu_lB0c54^tyr#*rrF*FOS&r}1ab;^}zd_TXUffjU3}12QH$GhE z&sT20!gD5S@)7#qI9T|@kun9^ds;bvq325P-Dspw#!jK{zhA>CgNCtQpNdGuFmvAS z?ZS;>?798iHlg~-8oa;Jm`1waWpRloPC#-EMVv}Sw;mDYW@H(nh;=tU;3X@&J z_#|T}TB9o(1)O8|8;@gWuq>aga0;~Bl3+l=4Pm}lD%+HMm}D+=X9jt%*qdt+@bY~D z@%@#~{EYR%bh#4kbkq~C_0z=ILql+WKrA!3wGAd)pMilSRLuT!Q2Z0p8$WyAW_QLN zCMG7qWagzxmRivS>mTHhw~2amp~ZMuq*=#Wdqu&&ImgJTg(+YdwUNkevcVeQ}Y$F9d~YU`_a9G`@X6V&YW7k@jH{OY~5r>ciJYc?_S`dcukzzA*|S7H0M-mpkv z4P4_>;kAXn#O(3}!y5t6q?3eY+WUC6^$OM$J)ru);ZZa%w3tR}r18}&cTx3-eCXWa zN3Sl~2wRB;-XGe+_S#uX-Q(kU?dlaQbmMKAFr(pT4r9fO zA~CCe5~*!=pqWz%oL(`G-+od>2KVes7cOYSJKnBB_R(7;y;~VH^!2El%OHBzPnBK? zK%yiYE3}ND=rZgs8{10>m+xN-BL+EP!yY|+T&GHv7W=Z<4h~YcArs#1Rf3zvt)Q@e z2AzBO7doh&uUfh{o-B@&XScMv$*fr~F?+!l@u1^gR2&o`>W6aZJUSGW8V958y-Y#p z!dLP>F%`m2N@v|@EpGVKLZGz)Y)8&J@q17mn_U-!zuzHSzb+Vjs^VaUUk`W~+9ZUw z*%PA#5lZs&grIzp-1YVVhwKRadh;bTOWcC~5`$!VuMQ%gcK|1?t3)jqB|64D zBJ=w9#^RQR?A_UTV*O|a+3L|G=>C>CUBk!0nX(jeF-C+Dy+yE0EhcskBtPr*8{*7; zEuhtuM}BJm6Pi~Suq_wQvw(Y#aC%Lm_|@YxBkDPVc)EZXPwNSFnhq%JKM$7w^r?PZ z6E^=fW2Cx-z3942ehfr>dE^|(y}O0BkCRb0B@tE)cjucPoMfgAL2zoR5SHX#Fc4yeq1LcjhbM)rmB?m0t`j+myeuvE#d4-s88hWn@B<8jaeKz+Zk^z}3w2 z7;S8V(AZLLD}NiGOI^17_sR5_`*BSBO{FfFD=HQEU`LLfG&>wlzHGCT-q(+&Hpqzq z!`-n$;%e}PRp)P0ZMy5QyX3U1uG)2Z3!T+8kKrE;y4Pe3mKb>B_umJkS(r5pbJWK3 z#|%lus7)|+^r@;fC1&id_au@(W(p)txs1OK^~D#-&E(96OkB8F4|0?lc`BykY3&6Krj+Ha2Q9=#?UaYYoCBmx%*0-*gD+ojs)e zuVbwKRsKTR-*cF=uMRhz;bRpTu%A`0oJ`^<;O4G)_SGtg;i?&s-fsb#StsLYpZ)AD zc}VOJ7-DV7EpfHk33MK230uDUq3Q1=oHQ*IdKQk2fhrbFY$v#`S8Clvi04AE_&?EE5zQ_PFW==o~o`pswLYg?w6)b9~DYw9A~WYXA> z^nTXMmZZV*hj+0)!i+9xWay-Qo{ua4EA5Sc;_cI`XyElMUh-oMe5z8TPj=5|iw}Mg z;Nn_w%!ccNN~ST|M>JQ>c)S)3dIhlrIf?s`tA~~CK6s_ciCDk92ayu*<(G>g#DCNT z^{Ll|c_*t##k23E5Di-et$GjLKUl#Kr;eZMiNZ0rr)=HIKPd@De;f#0#Yejn+qEh2}v9}~^`4TD0{-=x)J zEtD4Ypp{#V&}H;}HoPNJ;(8dO!-&3k$xTw-DZ67*%WAf`WS_)e>B~yGS3&JIPd+)m zPEa?WD@MI;XPkK)+=eoFa&R7<0I-XzMnSyO`;gw-U zw(NMho+N8ezr^v{SK;)ZX?#)`L#-il7mEr4Ra*f=lUcCWBk*$jOLkazG22feuziRO`VDVprJC1qY|$vV zuCI&zp4ziil})&}NP(|?t%FIiOR#p66}%4Vi+}bi<1hDRFk?$8#Dp6OX;(L+($#z9 z<|;M5n2!R;-ot!(GCni7D;}~*!95pVv!R}Ote1v1n5>WKASHKIm!xGeqjyOxjb#G7xbrHgivGs60(||XsO~u~U2WTHl9q#ozn?0YM1hz`~;L=r( z7RF8xbxngOnRa3XEG8#R=JWd|CfsV5|aVSpmM z*^&vK))T=l-h^F@mf<%dGf3vCGlEYK2mT{}5ICuf!Lu&oS>oxQ)XF@7TpY8Xs$>*m zh{7{czH2K`_ipxP{C98(I*0p8^6_3UgPyBJ(RzI@hhJv!XO$sFAM=9n6p1(76bW&D zK2+Us3VXcz93*+)fcQg6+|y(>J=&SY*aTTrpFR;Tm#RTk&Q(^~wilew8sR{pQ2Ih7 z2h8bQINqlkhLOu)qgM?-jx*>CG2|{255rGA0SC`qiLrKr*{;Abu(&V^FGL1HzST@2 zuQ&!Isum&l7KxzEo{>G(N8RiRFRvP_vFRy4oJs^mM_Zs%U7=u7jsT zw0Qrj!F1EdJT`L8DPc*|ax&0pFLr#6VXp=WH12&Hx=mUu)=WJ|oZ@9zWW{tGF~kyM zf~MoNA_tn?YZ5jpoS^!%)0ojA4T$niXGVfI`5}K7*5!St(`}B3Rd_w~2stWoHPXjx;>BGC zaP{^P@vLfp!JlVx-x<${*VI$|%Ux%pF;ADY_Bu$SmTbm=@AVjfzT}Bnki=RoXLXX7 z_i4Zd%SzpI!jE5VWUt|UGO9C?M?A<7p5|mD`6y0mP^jK7UHe~;EfD`Gk3{R+AvkJz zI=Ak4E&Qi>8P;i7(}O97$l7$oL|ZSCu`>#lZEP^hFB%MTgJJkXo9c42V`9t-CD6^* zBu|7HIKzAmzb`rbI^>4Z@?weW5bBP7R%yV4jH_&sO`TXoBU#X=d1Qlf0*q6cT%CK@ zkzEOS4h?-5^63>*@RX6{SGs-(6=Ygz*7+Pf=WBp{``gl%X(6QZ=5(%G+{%<}H^G3t zWe_?dnofyMg#mI|#A~87EBo+(EtDG#zhwu3fBHT)T0LFjyj~+%IT4Qfs({J%Bx&|% zVDV!1W2qMxMfz7=qNYhV$;98XFlS+#;I#UQ=rTASvWjBaDn)4? zy`E<)HM%^&qfZgMRM24sQYK-?Iz{#=XdBvA4YD>Jz7IQ=N3qEb6kcO6>wozI#P}DU zzg}|`j&1EnnomWdZApR9V%!hx@01F`=DpEwFtTr(-?Lw>eXZ9JbIGZv%UwRClm73% zu@wQk;6SPl8Ma{}L@sb8!&XRqtdUp9_tihdr#HWfX&rsA&-&ra{l;f@t?M3D{&?6@ zC+G|xu6(JBKFBV`l|K%OrFwg@-%Mj(b^e!_*WUw+W*ui^ z9)^jVCJthl@tl0kP^U-2q_g06mFmmiJ=xRuhnY>pPv)(mgzD8Isr{3Jk-v2$&UY%_ zo~Vz82EFi9Pcln$V76gUm6pE^>w0|?zJDGEKjJb#!DBs%yJQRc`o&~$WEd&waHnB`S;El& z;;>Wer|?kffDCrDAetApQ_BY~K=)YVi0!^$(9;fZ#wsgoO+ykW6A2{K6$Y3+5=$I1 z;L@=<`0bDr?v9UyX%6$*0J@6YG0mV&?oPssB7fYoP8Let(3@1GgiZ zfOq;pU}aD6{gjLSTl~;6uK|KyMu>$!nwh@=p*3^IW2e?uOT6M#0&jDRAmT86KAFCT`xl&|f_QXIey3dzt;{F*}m?)G}p0uC65VV;n}^ z3xk^*zJpFbd#l^#E1^E@9$WIUMQn@sifhrV7tLe~7t-RpRe|sY2zM&DYMPlT=ioxGi@fkQm!Q1N`iz>Pe+j{vqSKlYY*P~K-%*Lts-5iy13{+ zb?m96$`>CqrLU8(o$)FdzCCXYH;-0w6@G0!GTRkfJO`#7|DVaoqTjf3Y8 zvSYwSp1Hfs1S!Pi-PsftV{&OejG4)5-Zbql1O<{c3%?yiOLpVkW5v&z`&;pI56 zJ_KW*J_h^6Td`H@5k{?DiDplJR6XxmNVT2&qoH4aJRr>qCUz_XExB#*--vYB-D?0b z`e?$Q$7JAN(@Vmse`lbN^lTmQY_r%h>LQ!SkmTh>)AH*@Ofk6_-(V*8oZ<|hZchUn zDW4iPe=K~?2p64RXJbu^5;^lb3I`gQFnZUI{2Hr^OKh!Sxb}Yfr$HOP+$xdomn*pa z{#vVp^|G|w! zB_VLf(~P&IUWI2)I+V&qbFDq~u=Ue>PO&e9GjDk4Q^7~2o*`BJ^1*$~06yUEGZ^?m z>cQxpqGBKc89Pxp6m}3J@)w{%r6t>xcL?S_ctG^_ z-UGgFIaetPqx1Y)g=g2kqlc$-hITXH&v*5J9r+5#q)Qq}joN z7;p~zem56X0oH!Imo@#0ySu(Toj%!s&b9zFrD@W;dGnD};;R9qZVo48}&z`T|EB zwJCSM3df8k_C@q2@?rlXarT1em>hDD&X}+P4gaoWjhVS{xAYvC#r+igUKr7s@pIAt z^JIQH*N=uyHxo`i_osaeSMrfRTp|9j%q515B6c>?Wl48!}9f8mL98yYD~+$8fWOjb^w&-YJ+!HZ(}(e@VB zZ&zPlx^b*@hR@>)2eRmosJ%SWCrRqI24k=2-Ej7I0(;v3KI)(B7OT9aJ#E}FD056j zC7aXItihTU{8x#o=W@xAJ}P+dvX4-om5gyu8^BUSp4T^(!>&h*`6)6K6$~TMxIBue zwERKhEitGD+$V=_+oARdIn=1=L3@1d2}A#_BJzSN4y+tazaAdPbDPKGi6M=+^vw;c z!{>p|tePji&s+QuQ%!~sKLT=N(9gyP} zhGFeU($G>Wql_dPs_#6fL_$QQ6iW5W4A}}Pl?DwB+8I%VhSB)WbBq>AA}X6G8IhH& z{NDfjr@pWEJ?DAu`?{Pi-6wlpI*Ik@#JeH5Cc>qRj3RKZ$IF9!c*l7bJpi^lRFQ~{MGhZj*v_Cb> zWWy8KD4g44eU;E{?J#P(cNrucaVERH-r+LEGtJ!}(~$wPJMW!@(_ZcBd&w zKF-1mLkCft5e(|g=VD!S4~ah71FZwou&2656kH<1j-)HW%cPNXoI)&Kb==FV0vFMT zQxcJS6+mK)CV#9^$#CLKdTGpClDRSxq^}&HkK%%O!2RjirXLS7mlCl)_X*6i8(8^Z zNGY_fyi8Y|yU(v(G=$;c&U1wOZ~3Z&^uTC6{{DD0oo-)6-Sx}3?bT4;ysQ9GDG2wI z@wChA5-*#VMoS%3F~_hTJKU-SzU?q11y^Cf^jX~f?{t39JD$%;xdz?s(fpalbh^f2 z45Wjhlz^^OE{k1}vB`G(MZ1l7N$0SnQgA7)gS z_qrvDUtJqc;cpDp>li?Xohu^8cR0f%CmZpT+YfPN=Y2MyGZe3fMS{cXgJjl#*`kox zM3~*V3Zfq5!AzC?Fw^P^jD`y0+4>llhtI+}x+_sd-xK@ukEd&aP~4#x|I(XjwNIJ{=KBlEuM_-Nfg<;7lDa^BDeidg`c|- z26Ja$#8ZdfbnPa&X?ANtn^=%_^+;==!e0hySuQ##> zQkmTVTtg3TY?=t==W5{3w_ET);T=Bdu49(pzKWi$>&4s`#TYB_Lmo^{X0x(5 z+rGdMKAw}uT{qP*BB2?!k9Z+UQnZFAtur8ViU;gFzM0prTg|8JkD*8UyU}NS2`m=h4o@ zMkIeukH>8`=5fMY!p@h#{h*Jl633O9f7QMgLpm7FD>KQhU*{)?=?WIu=vb3rCpNL)#4qIgj# zCU|DB;E*8dKDM>OEHH-nrYAwUL~KRJ(VNh_!UO7m$Fbl}12DC*$EmL$;1EMws5+I# zK14OJYIiYg2$3MJYrIM4;e7Vt%m~t!<_U|>t*6Q^22kVB4HW^h;PKHI>m$Fj0pByB z^;fz0__3idbWs`e>No*D@4WXwfN+`C-JluqqE2rn*?Yt9|;RneW`(W zC<X@(L%niOLdv*8 zY^;+PcB})z<(41jpS}hA*AHjUA3q@BFQQ@je={)ZQ7Tg@JtNkYSELRooQr}Cshi$6 zkbBijrpe!CQ9I{jxc6xK;m`>F-^@d>xcZOH^RZ#*T{BP2{P$s=#}W8_^od}A@}cVM z8*$`2ADb2<2NvL2!bTrkj=TS9pwx%4bd%FwRLYIPCZ|v2ey*{=$3fgN>^qw|x`EVb z9$+@(`{688g6%z~lb&3WC2-3e#;HJg-ZSw`RbOy*bR`D<)x_)HFxpi( z6lK-NLEvFI^ynPMIm(sr$6x&>M7>78cm zp77n8I%}BVx39zf7hl`l>6YP}+~ldtEothucsO5jYbNR}94v}nw2?_9C!w$K^DBPq zqW^$*FeY;}Jv!W0yxEY zM2la@c`$e1D6k)S07iF7fSpSueDCOj6$%0D)x2D+y*>-2y>jrqwyXG>uw(Ii_XJAx z=A$k#fXhM+JMqC~cIfg7(7zfE_CjxUvXE)t?9c+6ibr9Wc_=>I6v0Mzc%ngsBpg~e zobUeer&9l2G5MV)3%X7h#dKer_{uy9xJS>ExBa_d#$qQJCy@bhX_0Jh#7i=6_c`kk zxnuEqTnxxvo(ZX2Gs*om{UkVaKNugHjNe{YlB>y5=sxBMj0XhrV7}MSeNEKuvcnEb6Le+0GZq*?wPWv8^S~WZa0eg)!fqH zBV>m{VX4wrazL2R*=84s&*;uT@t*Ud-2O38c}#^GyeME7Y@d*|KL?Q#(MfW~0A7CNS?;LGvt;!W{KKt+2NJAHc#R9#O- zix7M8owE;=H|W!1aRs|RScMJ0rB3sPE##->S2F$L0^)b7mG#g5hngX-puF2d$ao}R zMC4HR_(m5te9vY_$LLbqdRKa)P#fQTAB9H~DGj#>=cdwD>~gF#jN4&#eWdeE}J9`{GgrZUwdsOE%zOu33qM^Jh2@9s<0cqypQqG%g?}j)fDXd zb%D>GH;VQR(BuXKhS+KhYUj}3$D5s$X)=xEW-yut%?jh}i5uPc{5!t3OlEb|nVHRDz*9^*zR^jTu zGjL*-BmRuf#cu@->~__8eAhe?CL9?D5*@F_@)C|1{a`G<3)h27?fGaF;0*(kn&Co& z8$0$#ktb&QqRjdTv>o{w6_#{}d`>8!=Mx>uzug4GoOZVR;$^nJL>eZ$g}}VHKVC{CGOQ~s0k41KsbsMa_1Qj$4(^NQ1xGUA*r!S8Y+DC6 zYbBu2?E!9IvyRp!c;o0#r5I`LjNbx(W9Ima;AWCR&n5q)K8GEtN^d;%{dI>MrRdRD zW7DumQ46BqXThX-2U)4=61vIlC0gz*x6-rU!pHoX%TJk4r&5n(ZL^XUY!!dnP>;9( zN^I`&xU=s?#`6T1n2=B1ywC$QT;rQ#PV$VeWDUa=F$*gexl)YvL6$it0)u;S%*#s*6RfnfoCxWJ577cb6 z952@r(6C{NAIe;$A>jj~Kz;<74rp_u=AdFIBppZ^KPor%nPx2GiVOmG^>iq`Z2a7%aZD(w26%b z8ClywX=qWM2pbNJz|-gUReaX`RdIbN7atz!$XDI8;4iN^pvtX>tSNdd>8t7yNe;B6 zYcn(;cYze%&4?hb?-cnfw`;6APskTOo`x%5CxXRdClW4u5sy3w=HV9xqM@U(i`$Lp zt1^=9a&xA-yVrop-q-B)#1Z79iveD+_#=3B;xWC@6DI9?gIE0ONwh_$&7FN_yl8SJ z?rT4Yqu$?S1Crt^4J^OF1ep*pz1F}?sw2Q%Zw|PBIf>2^E#Quq$?hLx_)c95+_&c- z^Ea5un}ofltkeNfUQ7vcw<4o;*jblW{z1!Beq{g96`elmaC;_hOTw zHLq`e0&xe%kittQfk1>>=9ssEz_$PbJ<728*_%G;BIcEH!_a%scqdX z#AO&vIW~}A(o5i@3q5$g)>;0_CyKs1Hj{^q9LU2mIhg%ThmkW=m|<@sxpAtN_(_(q zE@vd$ZcpSL*SF%F3kmGbU2|@I{wO9qokFyhc%Vi5n_tX}bbXX$3NtYYih@L)oL3^DB3)j3J`h6j1vYfa^ns!c9waCiOZW7MAsj z?Bn->bYU(V;%J1QJ8yu(O%YFuOorse!+`AE!;+mpVr%+bXjretA|))uCzE1u-L+Cu z;B^9&9(Rx#9^c8Y!>KT+`7A0ojDvp3(^z)n4NP(>!Tl=_GQP|S{lN^FZ@cJKO)yh3 zZpW|#`DE&pJ+Su6e!M&N6VoyUFcdPaANLPKr<94fd|Wh45=oNrfp_tpRxR5;ZaWHn zNO+U55#L_V!Zas!kUp~qeFyJG3%m8Wa+D?Ri~I&>Oz&anL|gJjK@AeUkFeK)&(L>= zIo>_~2Dc1o$Nt48MDap8vx*x)hud55&ho8jy5j;n`)dv}J^PuxPaDbQZI6+MWs|Au zzgZal;Ux=^bcazld*QRwZitJ!iV0boa3ds~9WE;X%jH?(1(%B>)*5p?H%JYV} z=xY(W*{=dS^A@tiRp68xTi`$aA(SrHrE^Z+A)&ErVao6(qI7NswVM{oCtvHtP{}u} zE3J)7jkmN-REpq=-*o7LB*8`Pc8LGn;lP!n^5N>-J^b5|H`FWorQ6 zYorARoB~}PUJ9Si&c#=zfX8KmKy%jnmdznDrgSohYDebi&+ZGER%A`zm4~|5Wu6AapvW&ExsKAzhD0XvHIca`y zg2lCj@Sroccxr$qHVIi3Q+`);?)FpS)iDq}3iCl)=$-p3{>5X9tZ>iuM3Q3NA|9ce z&J?B)oN;lFNU2zw>zn>$K{kuI@s(FNthxZ-c0M8RBWhvUSYJ?ds~4Y*s=)1YMqtqo z5nDb&6IZ3o7EPQ|%v8gsi8k#zfPGm_Frz>o7C&7=+5^>4+I%XM&o3eCR!350qlI9! zs1fIMoWs=I`}kUFKizibB^CtR!Gx2C>7~osbVlZ8yuB=l`sv&kPQKZ=?X@X9a~?_$ zNGploz50ujr>0_!R~^bndE;0)Y1*0Hil40hfmzZ)VtP@B=S8}*x@I*D3U%V5`8iZ3 z;w{<<%xTYWX9Q}BHWjx$!E`Sxki6nZE}e-dVLxfa5jVw3UuqcE6sGZV~i z{UwnnIVtc+Aw%1?un-c7be;q`QudVTJopdxoOuA&En`G4BJ0`wH^MAut}hvovJsmr|hHsLs=!BlXK)!r}VY`DcYv5F_%7$Tiy(}x6A4;~0LgAr~Py-h{82cVP zC#4s^u-K8=K>I3fM)l|msJ&`gmuG6=`biDtg5yx^Ig;28Q(8FmN0 zfIst%z<6sqi~SJKzF$a(petFTOR`3IvwkA>E_wuJESwD~8N%Dg^^2cLU&3O^X*5>X z71|W-iOEWH>JgSj-o*>Mw@XoIapSw#D8!kDpOC`RQ>pxM{s&MNnAwx7xADi@9mH$5 z3!9dA^^n|S5AoMq!7Q(gwhHmpQtv-7f0q`!V(^hf{F=nqq-d}?Y6HRj`wL8$K8XQa z+IX;z7T<8W6Lo`in9kbS=$ZPG)OZf2YMz66Ip|@K+V;vH|231Sf$li{gBUKEZx_F^ zkww$>?^x#!2PnOtL8=Zlu_~+SAbTQ#xW7Fw4lFyvKD^0A$pA>hLoiKqH^i*|D-!Rw1*cJ?A;ZfJ{H||f^_>gx-_Ezh zz^|Fr$)02XKKvF5q-D`*jfYsYQU&TS{9?{`S7GCbtIQ);TeK~44Ep9C7H!*_4tEpI z2{4z_Xicmjsl1Q1c^JUq7p9IpgRaIV*tXvb zln3sBr^VJN(mud6J^DpC(~m;H$T-N=p25GYm<%#KYtU-oLVD|X3x0i;z)rtMSW>3U zH|o`~psqx486hHrC;cILvwGNNi$9{B>UY4-wGhM4rtw-;V_NQ8AzJop3``)8;`Q?wo{D=4UY1>mc5IDM?-8ui!5ED849gAC{ZQHO)g$K6`dOR!wWd|PaAhX9>9FVD3!~`y($jqLXDeupi-bixb8zRY9%f~G zLA>+lKGD(E9Ogei1HKtcTy8XejH+=-Y(;SylQGL;Qk5naJkS1c+n z{(&x!6>+1{aZ&YL3%1ewC%Hd#9N96i26H!5;HnL&>`UzdHhwnZVfD8nH+N-xC?HWj z+)RX#0bf|V(|X)yTEgyc>R{dH?z5+^tG-`Z}#mZnuoVBZ6oSP*H16z}^x4Tw6 zqeO;pKDh{>atc-3YDMm}9mFxIn^F9J6|PragU2@*!L<>JTsP+sro6sSI#$()Uydrp zIFim%BCN@hjovwDp+qzEXcfafsDPQ=*ssm(5Pq-w`MWW z;=7vIO?`oT(>mGoNjYRwi6o!efh_!}KArYP@DKfc%(C>fp)jWrRO>dQhr%8zJ6DUZ z-h7uWdZt8&tW}^;w;vZ&MiQ@a=iqtk9NzRnpWX3}g+?nMnyqxHVn>q#NIY(Z`5tZ9 zz0ifqs~+U36*pn2$cO&h>`AkGr1_b-L-76edhy364R~eSBrI(bcJY44>AIYI=%ZVQ z&hn$Ew~qtPEk6ZsepjQb^kaDV(4M-*CeWK+J9(TDWhRsDG2?d$ws!Riy8~r34XA2NXaYL~^Q--R>rp;yB9XQIf-Ya$n&3?*NkkF#MH zW{S>N#fi0@&f)DKM`AQ#7pSTL&Fao)9^P^QCl8)Dg*pEdYFQj)Lu z8xFbu$zs%~IJo}O1kQS##a1Z}#r1C?KRb}NkBGro&jVud@ybf_^8^kuYhgYr>#_Bq_A7$6j=n1Xm@b@QdzXvu zFFi=D{FlM<=r(*&uo{b3-oQg~&*%@^2u_I_J-_`UwLQIux8F*DF9PT2nAU8Lfr~IlDvFfqOQZT>P5d@Wo_`u*$IL~I zYR!m-Di;AL41LA^6b>!1Lr&+TJ|U5~-|uMbQ-bRF{2PUEC&hnS;XJch;_V$wV- zd|6{o?sTpI=rp1~Pc9)XYwnUfhneDoo!dagY$=-@a2D)SOv#SK0Yd-969-M|K=o8p zaz0cVI?Z3;xNf08z1a{z@d$Zv{|oVX=RkgbXl0TE77~?jg>Xq@3QX)UBPwZ?M7*+= zY|N2m?)9!P@LL*chHV$i-~3Ce<_pj4n2qg6t|p#Cq${aO#w!G*Be*;3&1ros&4CUIDZG)~p~#~nW|pbgWEuKfFaoWIHV zgM*6w=-*pqyt`~5*Vq<7+sS|q4W>~Haj@gGEL+Mz@);4LJtd5+S*`r++Ce_C;O z3ckvYA^#m4hutaraMA8%Xs(?jmXuuvH9HGM-*@Ws<>Q0INw@w33)f8Xyz3RH*LVt> z$7PE5pS%c5+Z^~Fzb3XcR}(FN-(}9`57}ugMXJINv&Umb;JU497}+ND%!CZu#C%z% zyYyN`O0Pb8H(Y|3McG6*IF$@cxyI5z%fPh1GVspP7(I(bG|s*e9zk$3TSP6libW3+`tf*r$xN3*~E6;<8R!uAbusJFEnA1!}HPRkjSjAx#BQJetQOS`PcoXEl= zffZV|N|r=EuV;QXLue5hZgZHtfjO~LZTwmuV|7Ui7OS+N`VJ3tX_BE|O3t(CcEa4( zOu&y{wW8}DtMNV?KmIUH{YtF5JKgpDDmM@Q3sYMU(K9K{ydZJ}DQUP3kCrR*ll{B! z*U)cRFy}0!oJpqUmrkOF;#jJEW*z)k2tK?a1F^X>7LU%0#V-zeg5zNge%y7M zx8?i8po0@>&MJ96)xiM+lwx^;VkXH548Rp_`XY79KDMj06;GZ11d^N1v$n1-V))?< zDKSt6mM(*11ed(QITbD$aDqK)8P1lpzL82{q)%4vQ;Fq#*KtD7Lt{pl|bcaJ#6N)K}Suv+nPwhCZlH1)0+l! zou=X0?<0sNJS8dJ0oWCE2Hb*`Q6YOKd(u}(l9oiFf#wEu{nIVD-9LkjruwG=urR-eC00 zi+`*6CYs|g9522TX2CgOOy{yXeoN>l(*s>#>SRZJ^ePCqKMV!jJCEeqE7GkKgwIG; z8kNi*k`W)2A(AIm{#$3;(Zb^gVC~>+8Z>GxzjfW6ZfUrPO)(NzmOHf3&cNq9^1ceKQR-yfpR;*G zoBc^``xF68Rz-`Vcie=sQU6t{o0l!oXW;tQM~fmifT_?V%?Kp~pl85~Wg3jCL8 z@%vGBfi8%PhQY}#wmX?$X~65cA zlkmLnd+v|j!?)0#;v(`T;XIose2*rM4THlXed>@Xia9;E*&!7KV@RM!*m_|B6HgUC{PMkO~5}rmEVR=Cu z-n*fT+qNix&g0dPy>tqGSf|a044Te8rhXTRyd*%pX(`te%W&^oQ|LqI3Vft|9aK`= z$nmXlq`5%_-mad-lKC0P7kUNRs*5mc#YpIJO~bzJ2jGuXA~t5#u$kqDMDC}$@z|bY zSdqU#+j3evc)r(8tybxwvsqBE3 zFq;}F&8vOt;Gv{4eRnTU zjMC>3`Pn3OKpOGr8Hiz>C2Xx(2|S)=hEFoD*_=+R1+#x;tjG5{DtU(EP_h}9%=d>= z!e=wMdp{P8)#C0!=|pkX7qZl00ouKg5T+hmsiEZ;_9kKopB1{0>f{s>C)aK4N&F^^ zfnGck8Oet|T*7{tInuvo^8Cf%JXmxymT6>JVXurMGf*mk%)#|+n3p=Q0CT>5q$TyY zAItx~eu$|LYw%xiFG~)$!P_OtFmKypJijTHly-f=(U%pu=q=a7E~99k*JHZ1i?v zj~_z3dRj#bl=8{IgXb9!&Li8k>czVDQJA)?j#xx#62J8w?CZCEfcrMEJ8H%3+*d=Q z(7jwNTdB*}eb>Y>PD`lYrgYJCbu+Tf|12CiZX_CVYKY*VYJ^c@S;*Gf4|h|K;;9+h z#AxhcT-1Dsd^}qwFcGDA{`)z2^oSj;R2{@?l}3PSN;i0x+!Ym#YbH~lY=o>OM@g%A z3bg`ne*fToket5=<_cNSCtK2lyX{MS^kFR~FWXOoI_>z2S_`K0`y%{H>bHqFkqw{! zNQ3Fdb(rCO7#>La@Y%wS!RYl(GH&%>9Cuxqrz~?4QHv|=*UF8genTFHtUQ5A-Z|vx z9YwbO*H{SMsz$1(o72g+l&QSB1wT+w1KXC%vifKSi&Mjp@!K-7wiy#G{KIv*D=|&~mjCZ?QiN{ZoL>h{?tr zxjJFCbP^`b4drK)&*8#*r+M&nWg0J%K$UL_JpNT9{(A1iuTL6Jy*-PF%JF!p41Nro z%Jx&A7HR5!ryi1e??cO*QV6RZj5?dV__NWGVu^9#Si9srwr>xD%{wId*oTVnV4@EG zdKQI&)d5iO$%uab+=LNIN?hM^0QFed00y5lK}%JgTTRTxzfPw}oW*NV`On+1Q1vMJ zP~OeH&TkCShINNn49UK&{R{WR! zlPnoi$7HYHCd)(R$;#_UR;}(6%^Pq`Pfz*F$-I42XKS!K_9Jt~FkvBI%6>J&2>WOmH>pvr|)*A^E>Qlt2RX!wUA#m&4r`ezPj}d}zlb-ok zanIZ7P-Hs~BBunh-{u3!lF)y*_&t(!{JrCf~6fmiIkDHtN#VODF ziC@$eqE}&v?^heM>+35aX_67{%9~8$v`@j0pSQp@vJ0*xC!lRV0hRd*;L~}UbPxKA zfvV}~ImeoxPOO0u{k`npVncExP!4>{i&&Pd7Sy(Ef-2*^wC;E_O!n!`I0y zt<5OWdliG0mO_5eTeehZDAvr~0I_u+Nd3d@-1>Pm?Woa*M}NM8@}*JyNRNoBHd^xX zQ8!@WtW#|DyiSm?JWI`PrlJ{$!LCP#hDD`|ZPNna@U(NdaeWMq8=1-2kRsOH9)rVW ztzfa;H}-F&6IlKpNl(~M;)?7f{ZDw-f1PEAe+~(Z<3c?UKk5WK`6D=P@-$dZtZ;mf z2DomxAog0452ly1nbVa)EI@k(F>76jKi>%Ryla{e;IBvKsSktfIitu3vpekTg;fxG zY6|UZ;qbt5DcNW7kT|;txeUXn;`61~n0kvC{3m@DhpM^a&>83O+=WIM{rVT^bXP!I zz&#>UG?1=-YC!wFtDsr`D?Bk94GRA4MC)t|_8V&pj$&_ESl%l-b>=SqNj}2JdKa>9 z$4A(o=L-8S-WJ;)JqR<+mqDt=D!BQ^6w;+6c*e|uP}TevHBx#>cV7tZl5ob0OCGRE z=L=ZIqe#?G8wYb%BoYhD6=J0ZEpg}UAEKal;UsU{aZLR82d~WcXFnhoR~nrVT@bG6 z+h(+h=mZCR7CsmoKX?+2kBQ`o_64@!iyAZ8k<8kDo@UF$dIHGk8EQ_R1xd|@I0v_* z(aV0(mS9H~w91q?imZ9(PZJ*XDjf%mw}EHZvsq-l9r3*9kDDWIi>%mP>`V2;cd91v z@st{x3M_@2gB9p(pGVBP{v5t|V}_45C6b^DXG#X@QnGXb+qp~+J8beHK{|~0mL&6| z3OT}VHVfwb3ZO6dSAv`4F+MIJ81^L$;%BRTKv_agC{~@OhHsf?B!DXqf&X?s2eF)uX`lnHf zzh5<+f4$oQx)ayIbsNF^yH#rHyy`XhduA1Ad7Z)1DGpfjp;nwS_9FYbO2qwdcc4LH z97+6_0QD((MC+6cmz|ddy*a9MoOw1jYz-w&D|weVuPB26?=fV3uLN$6dCi=v!om8X z1`gYInGE!~3vy-FczaJOdmL;fq{9K@=lZjmH}mk(&3>@Z_{QRd>?T=PLQW4cL1`mJ z>_{#IsUKnB^`{Cp56Xvk{~ZvOcxYLVlDbOdNB;*UL3U6uSO#tj-I-?vi?DQYFqsB3 zQ0{907DxBtg3)t9OUi-?77p~~i{{?jP5*nb51a$- zN%^p1%xEZP7SWNg##jN$y^Bfh=Xl=!SC*>JdCduY;W0L-4#rn?5f!g&TuERNTnzC%=T8>FF5C9?E1g z$8rUXe6$evYHuecgXfAyNCrTj_#i627*DA3FpxEG22du|&4{lg9n~tcy zL6$r0Vz%R5&|nW?UH)n0+!kFly-c`RcXtKD-HW_yGjp5(qq-go7cW{r(^Eb_N=;UF7Q@3hAMDBQo zf7BDirR@{B*<^D#S z>FRfl;;>nhiO!(?q6@p?VT;9J{w2YH50N@eFB;~+f72UT#)qBw^maP-M_6IJq!wGU z{5-nY+(kH-OSH^a&FbKMSdzsy$YB z8RFFia=2mhJbZoYJ}Es`37V_6i@j17lR2R-WUh-fX1(7DOY9%Bgzgb=?WY`P&%mpGI)ob5n4%#$+5Pe-$Tpe-N(~ z6=U|Y&!Y-Wc|qrYA?kU5iT$SRWvthKP?H^xn$xt(S$agu^5{Hzyq0B`Wa7 zlp!E_OqIKRRp%QtkK(MrwRl_Ek==P{NF*db34GN{>|oeYs4QCm)AsA};1`Z~FLg3~ zWS~HYl)l8XZ2~(X&yYLowPKd^Bz`aDD*jfxiRBkhvxn{RY;}Y+Ezh|FhWGJ3 z;4$Qi-Q!}q<75Tb^vY)^x*WLDs#NQ+nwfOb6hAub2gBi$rtsHFQnnh}Np$7HLUwfE zZ3y)ku%%Yxu+Tt>&U#Ve6C%B^EQlfvhc(Cw5V zPLnvyf4mH0(b3akn29X^x8(%7CKZa7sU{Jtcz>a1b`CyIRbVD-ldx;=E_}Xa1q6hh zBahV=K}gnY(sC<+Ck&a0sx>HXy&!OxJXW*iSxC|^ek9qU%f$XQy)dUThnd9>Mg7yN zEU9rI1i3DND_ae)v0EQLp&eh>rVgJ?;!sh}5z}R6qH^Ucu$=etSu|YcX=)3mlD*uf0#a9(vXIoAqTiXlBFMZM#JbamAGc!ck+7Y zKfFH}=4oq-(3C{|jU$d;b7E_M|61<{JH2;$Uu9{l{>eaWw2<2&w(7o#Oy2`d4TS~vYtb+AlJK^il5_VN_ zFh61~VG|lTkEQz*!_d*+S@nw*Xr4b3PD|F2V_!A6V%Hq{dg~D}%T9$qlP<#C7m0X8 zc_+N-HUrthFg`l@0PZ+t3Z}O2;ZjZvj<9oKhlITUAaN?@1&!fb<XIXFk-?PqHP<8L3`t{Q`j*}-YpV^Gzs0NP$^tK`;T~Z-(_eve-1Y#t@(2vOYW|X zXEAwGV9?wYE}FRu4>u1GJ6U|h0R}O6q2@ox{+e$ydz%zpa;*p&fB2FrVP@#-=S9!j z_TmMj1I&+|N8JKN81LPR4Wdx|vrrnd*4`kqGY(;UdhSg=wL8~*ME6_b&Wq`Q#jR-8n)ntN#YY7MC03*coDLG)DRJur?jLZvMU z&}vv}v!~RUNdHnt^~sFpXPsh-ntHr{xgP)gIuf#jKeI8ln!M0jV116A&bOI2!uiR< zOJTuaoOgUAPL6$z`eU}jVfRR;J@2r%>wXBt`G=#Ktrx#D`6Pby&KAG%9>z5#4${r0 zOL>MyHCtPuB_TfQ%-$+T*4)d&ZN|%>b(=c9wm67i+I9uKn}_4C zmBrXMHiBNfasX>~r{eHwpIGok;kk8DgPTbgFx(jo&^03ue>&X{WKa z+8qx>u7iMG_pOY~TOh0LGQJMZf}MwUAWIu7vYL{IjplVkB{Y+j|J{NygN%8Wjx=9o zISG6FdPR_7sSg z_KiZne=>Z-{hhdO{1DLjB!_c1w}R7(Y8Mu&YV|7ykRDTEOGZV-^v>^YRR8_QTWK!lgGc-q9|TZ7LMFax7Eo}QOIY^ zaTCLeWAo?<=>bf4>=Sm#u?_l^iP!C)( zq(spp-;%cvWx?x}J{>*U4p;4uVkh=YhUrefV4~*%Ds@ASC#Wkj#r4_Hefl7MaI9H; zNO3DRT{467FURxSex}r7LL`KWt;Ne!2I1sAO8j1zIpDM~_>;sp8qEAuB#vL@%J=JOl2SGw_g|5N#;bcFCiI=C z@U9QIG@N1P->*Vw(|i0Hb5`&qRzRl36^u;vL)}q%WctLd%v_c5s@52?>$1Rebx(xa zKZ?+k7Dh%t2obnEpIOHHcW{>e!Ko8s(OKXeY|1KQu~FY}_C-TcK)0p1txS_wom`Gh z3$#(%N0BZ(b_A>!rlFd01{^t+EmrD#3f+CxWX+jiQZf24#4na(iBFH?zekeLCsl&+ z*+0;J{wgfM8|e0;5tbfMWY<@&!Mwb|He5dqbJK6K?-i5CoE#&8BQX|_ zGztu(`M2?))ZPC%IuA##zWKXf z1f$0u=X+#R*qn#Ou;}bpGJMPrMt;y>3p`X=<{o|aa#I#f>b#9F22{bs`z*vCUI+;v z(~xzEGrweG?w80G+?tTjVvdG$7o=kG)uj%6Z_xx+zxexP$Pt+PL59wKznzPEQwCLM zc0Hshlcrkz5a zwxJ(d!_YUn2BJ+an5LF!!x6(tMBmmI$3zBT_+Ne0KkEoyi!89~sJhVPy*T^UpNcNe z9l4r^ZO}5BKP$F>q-ia*Iwb&c*RC{rv*b7aDkw%*pG#n(vJ)>1gb+(*AEAcQL7chh z8%AG{$0^FwiR)G=u5H{dv{QHrhL2X`d7YVP^0WYqW?jL!>4r=*$CcYzw*#*)v_{#a zNI1(oFKK=#D(SB`t(7|@xHY89RZdQX%CIS5Y_%VGfDLu}RZj?ePY*YKLJg@4kefdw z40qa$t=e;8o0T}zPdCK8PnYSLK6x%%$(@@Nwj7StjAR{eZ7_dlCY|KR^ZG6+^XKmA z>|5Il;jC4kAaURh4wTBFXRsBsGEb%sX?wu4@-b8|I>3$UTu*P9tFy6MdAKw9BzQtWpFgy+DnS(=L++sVW~@xg#B*jn z_%OwQ4H-yqKZ~VUr_8nU&qKMdHK$a+k!x9gkp`Oi^7*?BSf;k0 z9((tUz7pGsQI$<7vwDWmuKN@|oe_e!)q-H~%@yL+AujMYNi$8=+z#<&nnIaKX{zD~+k>{H2;Fh(aq7`1Y*fA} zD2)jrWp&Yls-81gKJKxpxI+VoEsiF3=e_aL-<`s-r$@3(@z?ZoMG@U$u!bE~>?b83 ztyt*O6FBFM65N|zEQ~VM7PhZCLj!+}Vs6>1x!hZ|g6$W*vE|wl^h-a2#6b!VHyonf zD{YuX&2c(ylq*XY{fd(wo14BXa%JW>`m0nXY=b6nVHTHdxnmH99=)o>C9fD|XWgO6 zsatWGK?fZ(rxo3_a!~wtGiDmdu!qYXR+#UIw=Y=g3(7E1&vQUVXSJB@S_U9Ltkox#@9~6f{bNAUwk4> zNp`qvoId${OdZy)K97~#cxRmAA7qis!D?9}d9*i$+RBXO-Fw+MM%x+vn>Wzcddf$Q14v;5-Lf?c*S=39Hg67MvX=p_*;*^en5~SjnK(|^ zRY+x2La;lC_Yhe85=(>~q0yF7P#qHq`}&Ydf01Dhno;;* zX99e0^COn&lbQIHYlw5z+0!q1ST7NX2R~L|;wKGI9qxwGSCZ^YUJPe?GK<*XvLQ>B z-p5*-$58ZM+?2ZO!JNhJPbb#?{+;$ z{P&5_b-7r$X*bwMPr}bG2e_?cLIj8HUAWB5XQ=KmptPbadNfERGduMoJp60T=H-?=Xv7JgoBNwS^!T!{ZCxMMPx`J|PSEgQq2uS$>m z*Jg-=JMHPD+!I`}*;3)=@v1PcyoXq%E+ixE?h>J45^cY2Pqn|lBNa=fan$M=crNyW z(2&f8X{!Y2T^S%0zEH=DoeSws#ivB+=U@EfNr@!igBb4-LxP%@k(f;yxZ(DGdU9C| z&ONV=FXsP8udZ7NIzQ&pSY<}v>@h)y#=#n9yBySaK1Mg52V1>Jgo!^_#RSI{kalzp z_N1kw@!zpH*nErxc>krMC;=M%5@i2to&|EZnmqH~3r!!!!QLx*xPNU8WNjSAZ`pRH zUiwSnsOtpSy!{BSFrJM8CR6DCDQD@*c?a;EX*FH^?HAcOzXU`#oTbh@hjNdb0zS5j zgILA$c#FH@sizpTy_wejkrb4lFBYmNeuhKI8aTq< z7b~V-B&$~jkzv=_=qahlvrzTWB-0hFjZV|V&Ew$YZd1B`{RhFxb<-eiwG!=HpGRNM zO9U_7@z|z%T=-nw6n_1DNXLrs@5~(w;l`a1Xqga44F>Mg7qo>ed2WLtLIEm0;@QgD z`DD7b4f(n4B~<9RlP~7+=qn=5?G9Uu=Z2dw>UukL|I_BouZ?6%s#;3VDSXgRYJ7@yzYCVdW~8wpqx>p}1Mj~FNsiz_Rx zfR&stYiOCnyY5_Y(dGhNGd&w?q&tNxJl=!dKpOT%&V?~o57O`Mhw$6(ZD4GwC2(v5 zG`k%`WlL_839@o@V85Qg*D@5!6edH~LVk95?_#xm%oMo8y8%u2d(+3~<(R*=P*9vc z86Gdp5y~A36BP1{)X$Cuc;a+A)Q@;BJQo-R0mYegV+Eg&FJ2Bsu9s0pZ5533zK*-3 zHAAu6E` zRWk;#^0_Se_j69oXaxiK5*`lgR(8-!tIy#x?;RxdzzkG$%|V&GStyr1is_n)Ag$`f zpQM9?PtAr$z5X~opXZ#Yy2FA^;X;{(S;Cw$Z_J&Pi~`|X;#n#IK`~jlJGh8`zQ*wN zBRT9A zrq;Ty-Vx76|zVj)Xc0$v@MB#L|@6=3F3P!XpXD57DaF-s2K(^#ZQlycI1A+1I zVQeQBhv{*>>E$>}d7fb6>{(pByAOu^`(2~-$PgbCRN%#j8R&3j8H=_7PE#};?>UaZ z(e@5Z^_3Xpn*P8CbL6?s%Y1&c)&$Dc;z1?S9`7!hg$7?!glcNN#5c4X|NXcFazQTi zb=4&dO&fvw9TU){Y(MOAKaPj5jO8?IcLA6Ciudt+6nZb!#QM~!Snw;3khP8icX2kJDn#Z%tw9@EBU)+h6@=OgHI?m*B1+DTJxpl(?85&&ht-Vd_Ydux7p* zREAH4f}->E_zg`M><%WKu^%u%5Dx+2-8HMjB52gtYjmsT1^Ci&1H3;_cpMuqm=bj# zuX^$9EnyJ6+<2Y*2+F|Mt%@M>dnxYQcmnqtU8At5xOMG2?1sd|e1Wm6yVM zy>(;DtO^RM>8^A?_6nmP-e z!g6rE#3Inu%7Q>WZ&F&h7faWslk*nx_)aZ}u8eks1)L4~jTs>jgeI?+>d7ZxO@!gt#g9 zkxee+$m*;kn4~oc9i!v$&*&e*%ocZGYo@}0YagvU)=%0@q`{$i5`FTx2%}z(hJ>C4HV)lR04p|8lku5z>d7hd^f{?FP;{^3!O?Xg<0f5AkUHCBvx8~6e~7>8|!5ir(0 zn1+3KqDyq0Vd_jzGBeqeSi7cy>dT$@@5p$x8|O;yn2Z87hhKEs*<&>G{d6d@odId; zHgxu(ZPk&JJTW0J2ux;wfot2PaJamYjregI%7e#a~f%x`BF%}P~j}6 z@sPJ?3P|O7VMSy;s5~oz*ioSZ;}K7>?8tJGw^fCE5fe;)jJrS@|855}Q33O>_NK4b zh_DI7kO|`w1!fahp?a7D=M&5`g}tJoOe&s)ZwtYQb2eCO6AH;=*5L!6O0d-3j?*4$ zp;2HuycnLtBsyF$>fKy!a}eTzH(K26p3yk5z=9&B^x;q_9_jjq7ZUhgikCWb-4PEg zK#pmL1!Mb^D$LdK5KJE)q#D{KFy?49GM!PJMiJjjg-q2X2Qsr2O$T$jLEFz6|YVNnJsrZI%G z0~Vp{)E9K(9b1$?5Dsw}&2Zu39X@&`E-V<|Kn&_PLh{>q&}ve|RZG4=_N|q)W8GrR z*<6CLc0DxMOrFem&G!4QkM%d z%g)lw5hLK>P#yMb%qKh4N~p+YON_nSNNv-kYerlYkgOq1w!rv2dB5sDl*S!}&N1x&NJaco+1c_l7RrC;h+ViM&y$8+xeH%9pjEBpYoQRm$D{@W74qbXjLh#v4 z{yQ>@eBIg%?WYs*Y-JWHvbqod_}R+gwWWN=`2tx(iv%lXh_I?dE+D&Q8T8y(4cDxS zu{0tUcD}BJvX~0GnD?aR*MeAr}jwVe=Ce2@>?8t+wdt-*u8*LvppnqbFQEU+FHaR{4^R2 z-X}%_i5PL}kuZ9z9ed#rkL~|PGwObVN#$(A?B8wh#jKNRt7n7y&DXH7rG$Kxh=8M6 z!(_^{5iD%cEl^SkqV74OY<=}&wvS!JALJ-rwyQ^?~q_avD2c5`h70 ze~`2NS)di6%uQKr#NF_p177ci5Zm5M@8t5k$}{c6*{~VMFXs7@OVfn)m*mN)VgZN@ z+F^*hEiTlH!H}*p(-p;iaO=enSbjkR(#Pe4&Vo3|i~Neh)BlKeP(5C>_)V3U`M|Op zJvG+ZFJS%0O(bhpHafg&z!~!=;d@CwKXp}tTXcLb=<4J`$+MmC&G`(zvD*Rzo@dd$ zQR&58z%mg5d3=u~A25Sk&ix3P zO59uh6x4Y+kv*Tp=WEU-lea?-_&!!l5z_l~x<_%6_zQ^m6`PC~sW!xY5WryPac1bW5W2uFfh`B)4yoQq`s@Noi|3ZngxBr%X3}nii`QIGb@fY&x>HC zi_O_meh;f2U5~n(6Y!Ib5qI0emnr>Gh3@# zchLveTTrlZAA4vb#DDK5vW$?W?33gq_GId3m{V7We{D)J#^541c0oEkQ*|Kod1lil z(#%%g(B{G{jsqoUM^#mzyyr{c?%JD78mW}Sk4<}utq=QbEB z4&#EO=5wK$8=2!_O%gaZm(5H(!R)UMc1#p*$;H1MYJh!|Kt2@TC1KS=`?gGzU zB*k>AaWd1|wx5fz*vfp|rI?k{B5LNM!cIpY6m0wv0lpWXqQTUBjM%kE@a9Gx>C)*# zqlIsxa21E_f%qeFUNtqRVH)Z^9((oB~a3!%cS_3$()pv_#({<$4x(j>+iS2 zuk!!c0^uP2F8vofJSD+n<0Nnt-ozDglbKq2Hv6}L=L}B!fc~Qouo*|Axm$s^u|HUX zeQ->~xtCJNhczwCQsphREc*1NHl zAGb`v;Kqq`mDmrsXmyE7|NM<1qmnT8c`dyEq0OEh9Hw5ar=aUZGwm;~X1x{9@Lr)6 z9Cwgl^QyfdA!aK2$M<0Gicom4vkJv{hsBU_2=`320RPL0!6Uw_S^Qfc+~{!|7sg#+ zmCqOAr)dkgvhrOpJ|GSH%I0$4Rf5Sd)Pmdmi}1qVkgW&P9jnQhT( zHpsrwu&)}BAUlm|T2*1ONdyS2otUP@HCC(L#WkuP!HI?^*sRs>glAj%`<1i|t9p{a zc86-Bd`K7QRjIKlmY=YD%?s{H>Sf$BeGT1Tzl%+&7|9ka(KXXujj(ck9nO9IRai4q zk&fu-#5;x8v2$Bp&E!4uJi~M{>l!k`{ePmkf{Q$RA|w*s3?2$%RgIbB8OmKdvWjb} z-N6oI6_d-Ms)B_@4{6|u_c&Hrjcr{ifV0kHnTuL5@Wmhq?fifcxCom)7C?#KEp$N> zPB&SH3u$buuK1}+!9B2%8qN!8~zUW3A|KS*0P%@4)|8_ul zuC^6M#w1$Jn=X08Fdg%4W9)rdSVWCYE(l#Yl^n4pT;*?JNGZwLH zskywWQW2deXtMOv7qR=7B3m+}5T2x8G%cHE0%HcUNr}-s++-}rYOqh3lV^xi_VQdO z!voCaa~IY%m4k(z0+-t9&qm61Qum)ZBq&*lD;p^060_cb>JG))h)e5mTa&8rg#T^M zc&$H%sn39?cgwk_X~x|AJsNOk@RR9X!vN0HO~>q>>;_;vk@wGf;O(MJS}?l|ZZ_r6PuoUtd?AAKR=Q0`o;Bj4!hfQV z*&^6baE+UXG!DAP6p>w% zwYU`ReD0v`ccR-pOh+vp!<;gbc@Ovy?8tivdNYK$&U^=WnOL)cyl6J#We+=?(nQKG z2b1~d<+x?sM*3ihsM(wrDxf%|6G5WB8GcTu%ez z9(9+qp42+@E9aRn=azBfm0sfRN0zJ~RoR6-Iq385AoFl*riU{(vjh6PU*1|4WA|Ax z{coL+w(uxq?n=j|-%SRXUM3VnB3bR(JbLThSqQwDy z*!J|KV0uToAhA{orkiiaP6Io7H|I6P9+PF$1}#y;PZkbsISC3&Kho7w?%=W73rUyAbb7*4XPBUQjb32ipRg`{D%vv^6!JZ6Kfpz<*x$D z^@tL!+mkWiMWgV*&@SFdvKS*H0Ak zRdgH1I`DfFHzTl9lth1o#nZRkFsbH z%XbKPFXeKxU=lh>OK^F52FUd06O`bY4*NYx@Cz#%HR~4ox=&*ZR$U@)mS^$q-wU+4 z^$$d}Jf`B+Pr>y`3JKqEP;e=40}k1DgL!%s_tdL}laigyb)Jjhyu4)b;H5h7{4cej%pZ)FMAx zB~UD7I%)iJ6}MY1g8JD3P`Te;cq(!UT`|x=mU#UonM<$Irw?<5yY+O)xYC{lZ70sb z{1-CN>OD(%b*miH>fq<4ua08E*k+j2tVte@oq*0_OUd4}skAdf8Ai@si`9p+$%2EG zL`zi+9fsCHJ(SXD&3F)dt-^LMTn?QcW!N<~9m2N+3j`C~5i^w_r)@8ESt<%HdbVI! z(n$C&y%o0UJ;nW9y3jgB6kjNtar2DEFkQ6}aNJ{#1Gl9hTi1x$Xcg1-*LOm)UolCs zN+LEq2PpWzGNIAABv|$E8TE+yEm(GX4(S$K#x3fXX0L|B;g!t=8hpPDJUj<*lc6Q9 zuD#FGW^Pj@L*7$d--tha%hBS?eRA_mJKd(lcX_*8YZQNqafwgTuztgPVs*vbsKT7U%Ro7oBzX>(c9Vbw{7fR`53dM^HvC( zJqy^x0Y$9+ECQDk$8*c$$APs8|NPmS0IXL+`&9;l`-97Iw*#MH$h=9!MqFX%en@b| zo)TuwqqEtD+hb|Mi~uOuHI>Cmt^mL8b|SGkRq$f+Y>@1VhTaPuBTogTb^ItEWt*)gcg%32eEdx1eOF?tbfogPHi ziaZ2SPKHGrohIqVR^5DvqdyP#4DkH56Kg^8WhN)Ka26Ah zIfNNsv#H^9zQ^pd9Gl8#g7>u1(6(YK6M4J|f_}{xe3&+mlBwI^;#?iB+$ov&PT}VLFvconm;S2FqP{Wgi8bT{C9+&+Moru`n%!4 z(;gIGk^ttLlAt2~8^^Wo%ucLMEaVhT3No@tl`{k*CJol^<6)Lm5dfe%5R-O^8J|kss9J6W^b{)5h-z#UWb4 zjM?WdW(QsJQO9Z{l=>ecXUde=V^7}QbeW$Uev&6|3}wLioi(l;ar|ftP`xn|(s{qd%LZvEZKx!f z>-Gxu&k8WxU70)ly_9G@SHa+{)!c~M0CGnDE?)M^g{iV?OxAc3mZwC)IEx7GWzKU@ z6z?H7eNTZ1c}J>aUtrvlRL*|Df;a}9rT=1&ar>tY3pHAbaQT)euy1M(8qBK4_O0>N zFN+p(+R3F5*y9PtGV##4b_=Lnn#f#NKj$-%>QoEXQXi)Z4(6RDckb-Nxsl&t&q;Im z7Uju`9hTx1uTW6f?ZM~7d6%iUHH^2PN{=a@!7mrHIDaC-oDQs~;;ornb@+Aov^@|f zrSmx<30*E&;vY)H*V5*59$>rW5kzh<;QG!^C*HBVvqe;iy=KOobaEPtT6L^ucRX!uAuq}zMz&dk_i{xW}l97tTDot3Hmd@P-+~L^*llg zw-___Vh1PZo`Vy087M}SbJ{P9Fjhi|GYZhaYme{4_{I|9iKmx9RXh=QE2lDFzt?2R zq6S=IHkSFRi^1#>HBeAx!{Xhhu<#>$ct*x*eED%Jq>ofaL2n2QZjj@io{?bD#))va zGfr4oxCB(q=aUQJUvQLR6uzrSM2!{8*zv87=x@XCKa?-x>%2AWC7<^R&6^0#)2_gp zsT>OQ69g6$w+rU)_UF_r2)E&6FisSfVmkkBS!6z$l}Y*G>`VzJEZfDRM&6@Klbi6T zQV5(Oim-dKH!6JTAl%+C_$>`w&GNI{eX+6Z$c$hV6eeTd?-2GeJDalXx?x$BjCxv%X4uCQ+jOVXAWdO7={qi__PaAZI* zHOr&sbAAnLS+$&Yy}kxPnv+?9^B9Pk@EggzKuvg(*LkIn?%LQ9JS=`M+er zhK^vWwsUHYl4lFdTq44D_>2Kxorf@baS;0z6vJfQ-EqC#Gr_+S2kyn#udvxupF7l` z$@GpXa@|`V;ya03p#MHi==*X6XD<4HxRYoo^j}K~lS|n=_p$8LTn#49yNyT6Q*Ma? zKNo#t%q5sqvR$MLlseY2?`Qr&yw7bEdl}8WEzXAi{D1g$#Z$N!tHyTtDzY)-r?a0= zZwcq}dA#3)p6pOT5ImZ+0z$5KVYK~pv%Y=v@npIJx6t(lDP-D z%9v5`W}G&fu9W8PJ>16{%*HY8=qRiT87*MTI-pKV72{f_p!N?boTI9PO~#G5<)teo z-f@J*x8tFH+g$Vw=%Sm04+yhmi?Ld277J_9oAF;w_E46%UP@9ze0$7}z}SGWwhOl9tWY#OawUw?ado9+2=t zgW^K6Oc=_Hp4_F4op-S&@EMM7JBGEM;wUv>2yc8IfuZk@|# z?xBGWJFm8Zsqa|J%~iP#Y5%$6_v$hr8DUs6TZYM>{=qgzl)=Hj3vfHh!m;Wf@O;{G z>=>7|z{F-Ho=edHDK&YHg{+4S^@q8EjyYJ<NbQoR;mgkd|J`YC>l$zOSAc@eVB1z2E91&7AzD*;d_GwH}kv>Sca@J9V-mRi_Sv4 z%l9>w-cN+n8%~mQ*G~&m&z7QpzYHsT^Bdo%YvWOcCd?u~z~H?So%Ko^Y-aVrIjK!V zrZbBk4!pxNLKc%NLpspWwgCiTf9U&8dHmvThi{lZitheUy}RWZM!ul%IzI?ikBOtq z)dt?}y%JXGMq*yQ5XJ~qFm1^rq1`2C^1Q;2svh)2rJowYDGdoYtniIo8QzISOo1~o z`$~=4LWNuJ$HVnsN?cn+8g|OI!_1na_%ej=&uK^T`OsP;QOKI}&bo9J+megVJy?7auJKobVh|Z4U;yEfyqh z+F@9KvkmXK%*Jm2XLv|-Iacz$qkqn!^!3))=wfjlg)g?SwLeo$<(5@Jy5?!75E_g+ zbPEgBJj>N86|yv$F=htay4m?US*GNq!8zmyGQIN)aq8kf&=V5}PQ6l0?oJq+^+AVo z6JG-b(XRw$d>(sR!5ezxy$Eie>xcb>!=-A5+&cbe{4mlF()m8>>xxIh-AUcx(DR5a z4>^KzIo1%T=>YdrJn*Cw3O&SAk&M;hSoRtS^<7IRZ~p-k6yAfe@qDoQUWjMBC&Ryz zF5Wpg8z-z?jgEt|5a4Bp`wh}+r?f{#I4=%M}<7%)jl`hUAZ zSzsToSEt0_);$cmBSu^IWs?+{Ch#+zPs09M!I}}*$g|j|4+{G5Mq>eB+Q_+F+N4+pG{5k&Z*hlZ3 zw#CoW1T1-3E?yO%!Nzx81pn3?X_fnw)ARUO$x3vr>YQQOj7z2@BZ!E|j~d zqR;LeJ%X}y6bouJ=b7IIT-}TmB7WEdG?Oo&Z(=Roq0Zk!R9C~M`;UZsZ|k$-fGB)w zHxf`UpFVzGMxS1*!yD@;4y?<7!crGbCVUMzH>feUsSbGJ{B-=JKL@Avug5dD`JK~; zw-{lm1$S$GXhR>Of?*h1|6&+Y@LcGT_86uOTfn{b$&}qI%_eoU6&0UErrXmXe#+8hbVjy2k|ef`L3xnm(v(PRnxzs*?}X} zFH{m{G_Am;t9nekbn_u{^G9O0qmrfshcN>uF5V=H`@79ds09Ao!32`+Khv>3wzKammjxDJcu2 ze=h=4OlC&>nK-GzgsZ=?i)ETKu<=Pm`GNvwwM&%UN!6lHzQvH^VrN*6GXLzI3d5$w z#A~{LrIwWHw>;h$uO7v3xpnsWUja7 zbC)07fb8=~J(9}N>(y%-M-JlI`Msp!6Ht-Nc`X8;M}ySWa9=WzV)chu&n2cFoN4{<{| zY<-I!n^$xKZ*7s__Rdn_3J!jx5hm$4+Ld9yT`-1K50m0?su1$78PAQ=#0jrB7@2vA zR<8(y3!5`o`gg!j;*-H$;x3GKtpa)fDQwiy^;qmVoAOArZ|o#YGXL@eZHCy2t&3q029cW?~nJ z=s&`(8?(qIo~pC|dX8LKOt0t*Yx*~hIzxbVIx#1(a;?*PyDNKS&I-G{N{ z@Huw;j}Qt)Rf+s`QM2q)1MWfIJAQ8&06!0n;RGV<;BjSv&?m+Z{@&fj1uQ=<(7ZbX ze#!bVs>z{B;$gN)E{kX$%!P_sO|ZCtW0F701^Yh8zrxm3`=#hkfETRMb$8xP567jx#xd z&p1u=J}iYcd)|ZJ@$+n)DbIc6bMd7UpO6tP*FZXK8eP#TO%G%hQeEXJ^jq6ot+!eg zZDMl~RS~w4Sb>*;ke~n5g412XI$!jH-*6kByQ~8L-(TT;(j_!Hf0%l|3?&{5cL=`J zpCdXWRN&3*)y(6YGAFg*139@wR`@f20?NdT)4n5oIQPX_GL_Gr#`kFxm#bHB?iD4t zZRh3hJV(aC%+h&Ifnt#_+oz+ac=R-53? zgH?vnpXA9_2Y))%A+`6hT;dn<|`3ddRL1@LnEKdicY4>X+1 zaFXA8tZMB?-ApI4_R(?Dd1W?gX1QR_B}bO0JO&nO@r>pzMm)p791kD@4F-Zo3gE7#+2y zlr_#)hLkraA=Ao~96zIsVwz{@qEe9+?7bWpjvE8&+#& zazpdyai>rI!zWh*m_|q_GvvR6uV#d!WiP+OD#?M`uZ~Pf_89cf%?0UtBl`V4MO($E zurkh$TK*~{(PuO0W(8X=TyucQ56fkSEVge0iVReyzdjTUuzN3(sP0dcnfPo`B@u5nSPq2D0LWGOISYiRGySaKUI0 zhdyd>kUNI}TWC8BOAThhlcnD123?1vdq=@p;~L8t$A!>YZ$H&59@-@$dwsON@cJU-RIi z2=6+sECKCnSs1-(0zlm?+;?9dpY5+8KW&n!lDrPyPpATO!_hn^<1^kKs{r+Clc0T8 z!@SgpJ7AV9#Y&s^aH%}=t9oviP*m?EUa*~jdp3**Yqw7rEbV|%HLLh}rUHDmI0QED zR>2XYHNp>L@`Nfyr@0VEDP}o7klUVT%V9u1cAT+fahLy)FEXpRA?*^3FH&HAFZtQ% z|Mk8nTmzd4)wsI6mv*sw?D#Pq^p9=F^1MG(-*+~Rsw~JyS>xvvFpG zJyWV^hUyzjL1#bD&BsWxY1|UHc%J|LT^$EIPqjg6qY2h*ehhwt|G>d;KVEkILn6nY z!TsH$m@-KNWj&{G%gsIL?**|q?fy5oy2=yU!N3AA| zP4M=uEW2XC z`&st4L;j2kX!8sO+n#waw`&i&xy%6X{wX9vb~A=9@r3aYPv8mHVsdm^Il6b<#)qqU z_tY(UCbn)L3Ha|Onnu(^{|QabaOFb!KH)v>3zo&j0TQr%;$n}Gs$eua+9wt zM!9<-Wd5vu?AhiJc6U)QcJrB!)A>I5Va^Kneu^kpog5E$mhsH|Im?J@nji7;t|9Tn zj?5|8#WMOQu;upGsNu$T{OWJO$zA_QU+$`*bsrVk!Z1&4)N^Ik1>)>!%TWfZ6R7$A zqx==T6ZB^{Ryz*(^XdC;>ezl5hF+fqecdwRn-mT^Y(i1d#GRD<`$FD4`$mcbZE!CU z7cP5T42M&#P$l~gHXgY`TbuJydr~mZi<$~0141}>=n2VgYJjBJA*vG{OO`mSC#koh zNZaCj__)asBc)G*lLesU`w5Kpt6{Q5CK{Nf(&841UtwBD4i)?A!`WR6g*HnUI=UjA z?g~05EIFVK2hU~0q-1&ca>3r$t@uAS@}3BHbw&d3jcb8b_CEMvkFFqg<3!jXy#qaax4_Hc?euq`Ei503<@;lY zF)lHfay_f4vdAkC+5a3xHY@;t)48C1I+4~Yw@~US&W;C#f|JbNd3iImVR!g-I_v!u zm>8zYe)TJ%UV9R_+n3_DFXx5wm!w#JjUDRjJuNu={vMy(;TIkz-*AR}IS!0)WB;ip zQ`4F{>}cqsqGgio{*5!j$BHxA_d;zhSvV1e>67U?{=E9D^`2l-;bnNfk_du#O@y)U zi_!X-kWSuVNCKz3(no)f2t$hH@!##Wh{IZ6?_y$ zl|Iq@v=%tml~YqU9YE_I&j+&0B6iVx$+AmTLc`GeP_NoZgI9#p2giPrQ9UB0wn7=p z9{eGVlfR&)sUF!WcHi5hr<=}QGVp(mQ8waani)uYgQ<0YQc(u`+x z$8n)+LgAR{2E6oa0=p`bL~=XsG3K_LfubR0;-| zdf^qH8q5gv;O_Ruv3nTKT^<+(RYMOj`0Yi3TEttpe5C?CG#E!cp2!E;xiY|`S?OKrI}n>xI` zWCN$$&xq*gR8*F1qFWCw5U%6T8>1TEqMxfKCYl$+8v8~JTfB&KDl#JB3d_kl$!jzt zJ%%3H=tWF^Z>QhxC&62{9$f0}i<6!n#h?8WRJ^tUJoc`Gr6bRx+>jQD(tiYlC8BIu zg%(-(YATj(u*A#>e&mN}2oyiMfIH^YP>%DYA9vPMpNUi1vIF|yU7SjzwqL=AKH;#X ze*ye>n@FxasiYHK#-iF+O~I?t56EX3Mt4lSMz=iwO&UUsQS9u<8kd0({Cci}_?17R z)*bgrM)?l7y+#$pUQESxg=1(-rvct{ECg z>&rLf?XV{P%><(J#2i%qMhcoPCgI~kzUT6$9?P6sA;vlu4DOa=nB_-7$i^jDFm5E? z3e2E`qHBdSP6WVBxmrB*xQVFG*hdF*#u9nMP59~jE$sC#$HdNyP@LLJN>W0wqOp{$ zJAIfQUp)>b?O)O(Wo))U4@TB7Zm0i=4!5IsFm~oJ~1(%`iN2DHZq6 zSFXK4L^-`BDz$P}Y2YT*VM*UwIs6|*=iyJ~`^Isi%n-6i!>Xhd8RxlfJ4D)PXh>=A zs8lL5vxHK1G?0p@IL~!ysEE?|5|xysA*4N2zvuT4@N%4UKliz=&*%NVBxavRH)G%Z z2K?`EAx#}n&c-W-IC$-(=iP)$Iu3g!Ly*nBmd(2b**I*!d0 zm%;eY1vtDXA3SH);2j}j$D zauUZ#g5)JPX6`tb&-Qe~#rOUb}oKAv7N1Ra%7h! zLSTsN0F3H-%^#cbnl~D;hW#kt57pn6Q+9M2ybCxugG_dCL4uJCW<`ub3WFPhCYCbh6hG zjju;g&Q2YcVCaPD z_TL8`dXSoeWy8Y3wNVW7UUq=i%yzx8qnI9^zziqw z^fJJRBCUdj?EMO=s{X_uH?P5s#gnPY?-@TPw*o^|ok(Iqi^y>B8!+1xM=HM8L2E=J zzoOZR{a#VbwH4IkW1G#K+No3GxmgqO>Qyx~+@nfKPi_Hu4W*R7RwD7nO_csc7rISv z+s?MmV%)cOTynt#*E)RT?0l6`YO@TLSgnVsvR9+TGJovr2+)yuTxS--*L#Zi~+lqH-Y7?^k>%Ah1ixe4TkPL4JR`! z*<#0qq>xCYEa`t%$8DBnyzy*hz*3mu** z$KQ($T}-)0(aTtnVyyiVgcQns^nrqlBVfg(ZeBalgL!w&rj4~%L>Cr( z;CIec#kdMdYD+zjy;CYhInVM$b^WVJVa-0AKc)^|^lac><3}7ZB$9pR{=kz@V_A=z zBwut^g6{qO!)2Kv?h`m;J;hb%_%{v%s;}~W3uH+AC4)aYXD6xQN_iL9>!cB3~?|OxR`%6qA{pt1H9a?L8rZ{ zftSi*7q<+ons8T(J-=NCY}`_g+pkRbtE%yI%W?79&MNj{!x~m%{exXEegdW@Lhd;= zoqbAuj8`SH!075O9O62H4t;TB2aAT&;XVSzS9vp*D{)o>&k}P?v_>k zMYrk6zGtAXeg%6zZpB5GZDc)pFur`(Nom`*ILK$7#815(%?xOuL*;ox*!$RlG@JDu zJhBZ*W4s^Z*N^1378YUsBr*R!bP|O~Euvdj1>bPfG{^`@MboYTCR`Ue3%Lty$L}RD zYPvi>YkMxU5$-+jU4mHXw0d|P;lr(w+yy^GLBz{n<^S{bVZYAJr2Ff}kWFI^Tcwo( z@M|PWW$ojNl|5kTy-m#f_+S3v++kENQv&k!?{S66Q~RxljL5xAaHLfz!>u>6qMy$V z=+KCBZ0^f3wE4kzy!1XB<_vIQ2fxZNjS@rgo}`_$E-4!(l$X=#|5^nmf-y;~6$|@d z2`F)22h89FB+4@uy+cI973xt%Pmwf<39T*<2lK zHriz)^NS2-H9-#KE474W%ua{(9%;PHNImxIO%w)J>9b3=ZX|ask>zXVa0?Hg!_B5! zQT*D6N)>YWakt&^e(7!8Y#dDOOAT3O>}Q(WXGOgMPeDFwCog+c@L&oVP^-C*xUQ`` zNPoF1nv_nb#32Rvd7K+f$cUzPJ2l#S(+jn4_(A9RvlROy0ro^K6_~ZMEG&N-Jp5XK z4gP_!FC>&?O>e>Wh0!DAhWFhU`3C`4z{Xpj&Hg%svmKYqW<;8iieVOYJn3=zducxCn+QxLBL)J$PKHtIZ$in<9O3up;<1B9!h7K) zr9QL6^X2bYmx%;jTfPNVqb6{TUn}w1mnd*L{}f%MZ{wr}A9iX_Gx)^t`00ZkYbf-l z*=9eXxA+c8Iy%D~qql64Mq*{!?12=yZX9d(Jck?B|ALYqx1ot{!4H9peRFsejcynY zkt%A~8mdfTQ~O{h*^y|(Z*X55PqI1%;_9;l$o|j>_A%%Y^*uAdVX5Bi*YBrd1<7~# zygrdOR3z~GrpVFkBqy5nX9eCceJ>7O=}jlk;bExO+5%e6H2(=x+N$X4FmKGb_-!p?= z?A(uE5{A;9I2mRZmO*hZL#ZlY5iL5hp347Qij$WpfM)Q0yg73cz8toR4<9)hFRDD} zrC)}@>EmX2zDmS4c@^WQtuCPXb~rtl#?iw%32N-OqGgHNtZmRs(FF|~-fx#BOF5Uz zb%k%j6FVxg!15lfYD>m!P(1a-R9@73502{` z#-%3L;NXV@*tj%=pR_`T9zr+QVB9SJqBnpw$DhMPnc4h}fzSB(UlDB3ja%^ff;0GJ zY~d7doZx~B+xWW=g&ReKi*g9n{&Z zx0i8^hCV!O5O{iv$BRGiEv7}uNBD&nN;JhFjM=FQGgu+_b8uD{6i+PU;{&sav}EW> zhv1uf@66<^`_bUD0oP<$K%+NIqbSjg%B~hU~Q^6s&@g(n+W=H$wvc{eQ2-KAe?t0TX)KxxvXg zqVn(Rn7wfTZQD=|1LE3onExoU(NdtloN%A|l7RP|*HFtQBQDBAojlLldq@B6p(& zLO--~4QdUP8l*@+O97Q{n(^|wPH=KcI2|04g36gz%s9UrMzkcH~CDkit#cv=nb zJ#`=*HqxP?9jDQ0X$s~9YGW)@1i+ZaTJIZcI@b&Q_CMlZI%>2y zOC7!{O~nP@EAZaq0sPN3!hJ2k2P&5mW-C9zde8AJV~!nP_I@%tdMV`V8*R zsuF&g?D_O|AXb1z)0t3Y zG?Q(3d6vs*KLvACl4+?|4K%68aK&YB#Cs=8L!IkL>Nym`M*5q=tKZp}a#9Xz0yN-8 zPdBJo%dxWhT-MCbg~?B6Gs73cvnJ#Mr#?;x9hYap)nUzC?B!HSaJ6HqLmzMjcZZSh z9A&uBPy!2v>9MJQ2C*6chB3_#xo~XwDiD>#pvGBw=J~7`9|WF-@9VyBlk*cP)6k4T z>|t0oTAwrrZiXw$Qi5Ynjd=}7VG|}UU;$ex0>MSUSE3TBXFM<@8urtl3~X$3~(@;C}x!y0Foc4vpdI5P)cMRXe2pd zxnVdt2y@g|%U998ZdW$qs0Vu;^9T7#Mq195SiEB`vt9g?*6!Gc8TJ#|;s$-H&`w7~ zKVxQO=fS%4DkyH66dZA0MKkVXvdTV1hXogM>5t+@;E*3OiXg$fPuo?QU6{ee(3a}H}nH9=xUM9SVro;<@9Y{36z}d0h7^+^m6|N z=DB4Nc?~mx=iNe&dC51v?%FhwYi%MMA9)M7*VAa(yn$pBqa+Gwy-rVM$I_VYJN%Q0 zMr^(3XiCv6XL)^5LXU0|$Aw?#wqy^$U)J|=`(R;aHdbH+XdlFV*D5gJNDp*!In*R8 zN%J}cF4fA3OdnLsZGtr9*e; zaz9k!>9gSctXD0i^*dj12ekGv`vpRFaDNze{K~>x(xWNjwj?|J`wfm8EkR1d*OPrq z4pW{OPeTRIu4UI(lsxf|@v~P@>YE*;ASK75=R`xzkz&4o&_3p`c*AkHSlfsVS&&M}KPn(YcpbK$Is+XU?|2E* z6ZC9l8vA=OnVnscKw155ptxI#HMD;rZGIGeb_?dZmU$9x&x2*D0mMD>#$RKM*y_e? zcI84G|D`|)dg|@j9+g524ZcC==Dx>-{5(+Ul&NxvNG5IHL>zp{g4Sg|!P54jG?^bn z+aK}J81oV~Op6BFd*Q5P!KPPv{6K>k`k_^UgAEfg<5~he z%E`u|=0j+_oh%)TI}Mxe+c64sW@hSx;k^7#3c6~{29L_cgD#KJbZ88VnUI55WFPUK zYi3c1UltDW*Mj#;Hd2JY2Wn_(K&EFR%g$WEE`3{q_Ln=URJ#~Fg}#niL7)RD}$BaiC0 z#4xjYdCWlUMK;__Ce>#^{;nP<*)kbEs`|pejY_oW?^jeBltnN0jiSR(x1nmR7yJ44 zKJ5OWf>X=}F`3OLm}dGk>M4t$ZKVOUYO54`xqJrQ(;I+i+-^fxbvN`^r&9R1n~=XS z2QDfPp@x4Y`02NX(4jgCQ^w`9hub^h$c$7RIBx{mcphM>m^`Ly8t2%pWa3+}391#@(XT82M|KN0x0OQ|WKQ{4Kt z8fDU!;l7n!yi9%@R^A^&X2uHS6`98WGuNW(J7XxOu?*Zy%SH2M?BfUMr{K?FBIcR1 znhpf$;mRS$`Dt#i&`5m_O5BOTkj8V^C^;SF4~F55K3xcToJEm?=Tj6{C+h3|2_f}y zmEM9YK|@P;RtDWewK?;JuE-iH@&Zr|br-3eI*Z*4mhnw1CGlBQ3VaglE(+N%MK+@DJ*@T>c#d_)VAC;mQQ*Gw zd{2=D^NA2VIoHz|`}P6adxtQaS5s+F?F>{KT#s=ZBpFG4{;YMe{ylQq;Fp%ncRd`BwI5Fr+Z6~^?F~*i|!QIppRke z=2&>Kv5iZWK7}t|$m8C#Rk${BB^hi`X1+W6`SYt!^76j<+M%a6?MY}m}FK^R|@LBDnlK!sJwFmg=+MlV>ymhaY}iNB24 z$m|ay-DgGUxgwTwEq2i9hejqJAyUzZ^TK`SD4e5D%MaG z39_3raO+tGF#TuBEbU5YMC*F?-+n2!c1j-WGmd4Ke_KJ~=LnV{=R_O)Z*i~Q1n?^s z_wjd6tYuTb-{k(obZ+TQRZ@GofLo=X2=}3^>5zPH67&Yj#t_~`^*0+{KBbc(vL?;)0EH;B@R~ zQOu4f6-BXSTx*^wKh67#X!g4`aLv34KUU|0ZTT1+{Od6O47to(^R--IZa%)=v;vc? z?gINgnEm|`itW0(s5Y<|-us;3Y*l>wYr;2b&z1{A-3$y2s<2hQJMNfCV;WbX$bqF%#J!d z;>$uZu;P#o2E0xndmja6fAS5eFF#MUf$Dgt{|N2*hnf^lB8#V(Pz01M!PbJmb=%8U^6KA(43WLQi?5(pQ<+z3j zxrA2k7k6JgZgwQ=;yws`KpQN1J%~lh&ZS^geKxmNgZ0D=s(P{i9x4sg6q#KPB7KXW z@TFN3TW;C2zrvkUfBj&R)P06#Opj)SDBy83cM>Zq@}G1SS&_PsMJyXmYnMh-vYS53 zvr@p+x=?PQ*#qucO&A;U?6JVtlA)=#(ztzq4X>G6Q>jPNbjwo6-PS(hZhY^C;hU8) zDtaHe)X(P?j*Mj7MsHa3@E{c5n+YGAh?7s3M$;K*G1X=&cS3B;Yeo2S_V=_oSubzc zpd`(Kk`*3$x0ozqOyQ16Dkr@x6)xQl=fXzb=8u=`MxT+sqKg-!u*vrlce(c_hTjXc zcaM$Y2Ue(K`O$~`+^wCsw+wrweDFNe6wXCqfvQGMJu6!j>uIczYpIWxHY*yp^1S_;osj-p`^d(hLp1D^@cjJb7Jz`y4YeqM7F zKRuU))lFdX(uoy zH^`MT_O{@&clPXR{&hOP@*4hI_!1|d+`$h^uZR1>cbavD$3S=E7yPL=kixE=Km*qh z;ViDE`gEbkynZNY>^*{CT;;gytI|bF$6B!=TDf?(S4yn@a}rc;wSdxne&D%sFveag z#`C66M0UZs{0SzURdsT-AYe2pZ_R;>8WScu2JDrUNKl zvE_n7dbxd{z4_7MCZHa&1NTI3!%TLU3m*Q1yX|qFA0chQ3KEy`Q?>26lVdf}UG_d7 z{q8nDNBWw;$48h^cW zE2!HDwa>uw80fZC^z8)$4a;KO&suQBDp^`6u%G|)H~(A{?8rOGp2)M>abaU0*OOa;S(?T=w?6X zH^xt5eQG0UN6uX2UIWb(STZX)Z()X$M^_ef!mGH+lzX%juGpN$$8XEAd4djo@HoJi zJ-WoDPmsr(=ccmvYAa~XQ-2(&d=MwD9>iWeT}#(LZ=<}u6Ig;oGR+DMW^RkqA-QNf zxxD#|cAjPUeY_Kzdat5aqPt8+Ux^M{_2b&WiMYYxDNaAZC{#Iw1{e0?R^?izbvT9Y z`uyQe7e8P+s=Mfc+8p}xIF6MThmqFSfplSTJPg=X#14i|WHpA;bpPrA-tO^hZ0S$n zZXJ|o7lbodravFdGD4w#Q$KfO-8{k3T!>zZ@9^xY2fWMp84zw%hQZTp;TfHTsowMP z#WTUpk-UrVo)`%pkt%HaB7qgPYa2d08pI2WBnsCcS}#A8)g4M;*TY4FW!f` z=lfuA?m(twse?YQ8c?-z5cexr9#UHu(YO_XIMsN#z@)#--&((2U^biZtBxO_D2MIr z=$}At_J?7RHqMyY>E*+ODc8_bRU0o?S0GlkiJO;uQ|aKhBKg(!oTXnpNA3zF8z9X! zUrD8}(TACVz6(TnUKG{3Si`<4`?=CLcGw=;jNcDmN4BWw>G z)m5c;EjRhQPg>~m!4I${Zn;>YW;SQ)@5I&Z{e@l|1KE4YVpEVh zc|SE}XOo7LS-A-tUeN&OA|8^8!a_WnGO+6X*Po)6mUD39@oIAZa-A*M7)0Fn6U?mT zgTPmQ3Omit@f-e3B^~9J@U(0fg&8fNXVNFxC;52NQr^Jl&ss@)kKKh6e(n@jpjdS@ z_A`{9v*0dl_e5ELeYn$f13pi$CZj?-c7K{b4NaLvo2JUsm*^tui8#mk$MoY>{jDs# zD1>A_Gx)a1g;|8DFn;7)(WF*uzQs3!^Vfby7w;CMo1{6t?TMz`p$AY~?J)g!(gM~d zw%{CXGxqbP3SDcw4?!{;*!U1>di7limlyrxE0w~*<=Atye72C}$Jk)k-Tm~F2P|6K zgIBC8!CpHYf2)mQ_u{3?^Yd^r>-1ZEX4YY)rgCFot3KMA5dMDfx z8B5X|&ae*ON>D$Z#th#d7y1tWp|ykr+tIj+=7-C(OPkVJgJUejov~$hNkX4<@>z_T zcYr_LYQgS%718Vo_t>@fXQ5p7FPmU&M(GoQBr|l`_Ue~3ElH2vS|7zKTGW_phHy46 z_`xZv@HBIizA%>@?{NL?FN|8(Pa#1Qs}A<4poY9eRjrWqKRVzp)9jO_RhJ%8&5ZkK zL4zH%hj_79Qv0dz`+Anp^%(!s1++SoLIu%*RMvKe5;O!4UWWqJpPEdj|1E_>CgG@U z*MLj33+e8Id6f4z8AOHqX#Ib>?8v7g>@qsZD~x%8B|=8?y0$lsSCfXm)E-RGmqmX= zUg-FE3$D09P#<~{;%=Y7gnK1?jKz2|UL}V4txr%@a(gLgK7PaJ{p#WUm4&W&(H>qiQi186u}6~)rywn_9QojMh{_J;FPOLE%}!x1 zVEWN+osm6v)bJBmrt+Q-_pKG{*R}KAk}tV&4Qa@4ab)?oUtnvbGGv!Uq3j zP_5;Rl9h=le|#paS?kL0@QcC$y&E{uDs8?h(Hz~EUw~snvbez|hoNIa6juK(;H%?! zfm1()tvK(^J-zS|QleFb9M~cZy&^8Ja48J!d8ILoS5bCI&U z@${yn@YJIX)wH%?@M9~Rn*#S)&g>8+U7gBaUbdjxbNz5X$&x?*YlBE{tPy*pB*zV_ zR>LP(kHMvYadai?8@wrP5RKB3$8!78_@UbhrAuS6Z{uhP{@(&HaaF#tY;jL~YM@|ReinlJ#?QFqe;|6jevIaEh(K1l+KFZCX zTFpo883jeJCPR+J1}OCmr^idS!)m@qtmOKUyXBS4=@y-V1x-K21zTp&^1CLm{nBwX zeB#Xhwgo!M=mDvx|;n-JfL+iy>EbH(pXq>kSowI|9RjRO1$1ct>$eQlk z&V!}#u@IkV2nRY=V270%t4-OCT8A=0#)#qU32(S~I)}A6RDPCHgmZIIQ%rrYfHrc%XC(PV-;6-Gwdi zuX`Z*O5Vr)E|-|iIYJjr0lsj_ln=7fy*$dxmtu{F7mWUfjxv22jXRJtB=REqV9>wCQ&-{Z>WxUqck6GD| zkQ=?1{TZReY9B1di^(TIZC5P>e=foMCPttuu>L=5G;t^EjJOvX9+cqu4-Mw^p}gRc zTOV_b?oJ$slj;|<$tw0t(O3uH;Z)9a%V&7qr$mi!oS4LMFYf2T#jNP|Q1FaCP29a; zyrE-DuOe2mj}Haz_fdiUm8#ByJHJ3fAX8VnrU2HTIHqbZkk9F#WYqTgdz zCbMWCRXSH->z8YIx;=*Sv4#)JI4$OP6=DuAOOdfFNv6Y;GR2MpETxUx=$!-lF92F{lyx76Vr()Au=}sD4oj-Z`L5Ru>(s77KU#W0LPd z`a~CO-K9vkJe4qTO$3%#a?DXT0X&00;c%pBO06b$3!--%;&Y9aqhJ)Z;_Ad_&IlY4O=dge~#SL{{B*427+ z*St)e<28qk`ga)|KQ&@OPcf_tYJ@9w3EXgu7iXTo0rB73!FlpIE>~g~#78SLw}Fn_ zR_%*;cS$R@I3D1qg`{xjA8WE&@qO$Za2L2KlbEaZX4v#)5Wiz@9VEo0L(G~I9OCpE zmRjut@KoTRyN{t+j=ebcuen%JL4vj2$>3r}oWb=Y~{iv`6O^X==S@J!7R2-1zEQA);S;221Y7hBQq9WPMIb{&n|`5dPl z>VQ|%wP0tMkaya@OPEDWq!h&)?DhI^oaZJBg|S!FzMlMDn2beKb61 zEyukUy|_5Qj;}23fm0vN*tC}tRZoPT)4T2Y+?ik2+`F&{FrQ=rOr=kPv=FX;umy`?j#hs(0kfC6aNX=UOfuUh zYX7OtPZ%!EFPuvdRec$n#KDkWa+?qHoI;+DD)FXmDDN1n$wq&ygPvkV5>=GKA#DS0 z?zj?g-8%~lR-40Oa)!rGgIIbka^GdILz>-wsQ9K&H+A+wjQ26VW8MT@T{i~a9jn1b ze#ZO^6KOK~Js)aBU3f`-ET&7FLWgs$;F!tgcN9d@Fp3G?(e#CF>s$`*H4of13QEs*|m3=G6Kl9H*u+cS8Jv*LlsqYr@XMq&%--y=# zY{+WCOT3&kl?E=#qd^BX*xIIZu;Jtc{`ovh+B!tIlT=M(A8nTM(PKNfsp>~TMm}Bi zM7>yaq%mF8B`Y|RMz*2kI}S#?%A|UUKA67I6Lw!&Y?m?oFUpPch5a~z_wjaQ%D+E} z+oep{frUme_KdOE_We}&9-~c@w4}M)Y!s8s+Cg%& z$U!)Rhuf3YmORcTa2}L{KXmUuh!HZwxztjz_(WbUEI%3pTRz|BwG8tpeCs3b&gx9= z(O^dkm6L_By_2c&n*&KEXX6BW91Z_S=qU6($35>11iT zn`X+29!?h(FOjO6d88JbuIi#}v;lP;`%IGx=Y#4_D?IWjIT`(EPw5A)!e*JJ2EWlwr-kKv|)G^Q%V;&FKe7&Lw` zSoo{5zaed)w(tR_ELg&%_7250Q_{G;?!DYDO`(tdVhGD0bVww#Pa8wzGQsR-Af|6| z1XSCG%WY*@$mV=eoq;1u{yvB5SO&YVe~05o=ZdQr1;P9~=aE&-VoRSS@k`2wVd!Uo zqd&*cv8*$=dzLz1ZI=VH^%Tic`IXq$(gY3s9ohZ3bhPM;>o@)xaN;c%1bLeOOx zHaIEK@GtlHuLpnO=%##3zci4PPt?HTorgqkcQy03d*^_$&UQHR`X7eNtH8IzTlt+P z*U-!)ADo5U+in{mp*@dlA3VUd9ftVpkv7HLodiGq3ZWxL0#Er^!l@IJu;q;}_D9ul zu0Bot%lzm3Y}I`J{Gkqh&u1$VwI0TYo*B42=%LtVz5$xlXkyNQbKIV7vE10u`5>-% zk72Ke!UR_{jDKu`$M%$S%{3}y7tqV6RsR+`SbE~n<_!Eavk_zlPl9DxZT!(AoB0cd zi@~v4;Fc5#UBJ#x9B%FaW*k0Rtqx~Z7HoZoStvm06E^O?BdWwe7N6$G!|}zs;wetG^L)!MI%WjxG5>4pRq1mw}*an`sq>?p1Z3*tV=4}m0^ zedz9^%pX^jNBz2={N*P}XuVf(d2*TD=Q}I;t*76j-o8$5sryp#`mZ9in0tqBx;lvN ziHu?6`e$6g;k%SuKaIldA_bITEG~U|U&yzP;locvbBEWa=h{V} z(%N^}tBLH%8;;AH4ttRB9RyW|wXojvgzn(A8M?_78K zJ~14&39q^3TNie9@)y3;I)#tD@eLR7m3Z-XzIacf2F-6d!hh{hC+kbv?9--coP$pu z+$>wjRxVc*{N>lkDN>)sMa^YpY(J~a)+P7rn^AG64%_af$JQ&o#*Q^|r#(!$FpEO|8;8x;GTA9oU?%(4R@NRX#DxBTF=qcmA1=);e!jaU)n#?2}} z!x;{=r0>rf?CRn*vHJW(C_N$Ynd_CXbKo%02$4b=iG`$?HAif5>#yKkH^r749{lb2 z3%F*c5{ZO78TVr#)E~3LFEdT?xx_cV((()EzN-#ul5%;!?4cw;FzHV~5v=~Z5SkOO zVX@gvxb8ie9+h<9IZGKD7M{!>ySIQVlaED7aXQX2jR2k7B3SQT!Wrd^N0|quI4}%Y zNzfSdODV>Y(p$GFprP%(xIO;RW4$0P~muu z+v#t`jnMAqy;ljmvtLV?%awH2**k#EIQ&PX{m_Cj^RIlxv;8D@vIY{g)#=#|XK?$h zj+K`ixc8OwFef7l7mP393eF}`?XKNi?!zT$&j7#3-4{p4 zKjn&bqA+Ie1kNmC5ZiO`G;RnP54X2jb7iZn$RPAP_s1g?Ya(iR(>Z!@@2LbOzBvFA z8Q1ycU9+I|L?mu`uS~~x$BH%=PJ(~V1F%5K0B*-!gAXf* z+V&Uu4IBs4{}X-L;|wcbJ`nBOZ!y6#l1Ugv?}SOdG!2UcgQJDh1~*^oa+`>(c2r2F$qdJ{SM;33T~XaJNDqz^l*> zzG!ed%*r#NMbB2_JtbGxlwQRx7CM&v!NoYm{taeNc*932%hQ%Mrnk}bsqDMUa}xB<;6bd z%hQU61Ng1h5DN3>z%L;m({R8WD!?gi1p-pOpKTNSrYJ{#)V_lsm?1K6g=H~FTE zvHXVvuUXN{wRlE3Pv|2V(!Nb9G%D&g*LJ}inw4zP@!xY+rEbM8HvNVUm+>fJ63pHY zm?oYbD9JiXveDwxMQm%Az{rUe@Gof?x~Ps5JbhXe(pt~GeDtrP;GjGBeDTCJ&ix{b z&IkOY%aO2U&?)};%E3(H*(}`Iq(ZY_EP`3>j=X%225TDkjvMCr6&0Qv!jn6h+?Z*T zai!v6`}nFTykaZl3r%mM?WFBIiyp^K-#rZaq8H%1ENjTml%jK?<^oG<5?(tLz<-_n zi!%#Qo@NM*gUYaL_ZZM! zs{&7K>;>0*so*K z)WCTqJc8-v=l-7w<^A@dYiIi5-ONMc*yS;BZGbMRHmgy6 z#(8q-$|Q542P-x{#Kt-Ofi3V&th11K6aA6+E%TRnO0OoBSxV4}+wb_~lOrMGqcp3` z)uw~akzBG?F716VivG<~WL>um*tGelSW5O_mIfK32UZ?5dA%HNS{H?L7A~N$6`k;C z!3%72ImPAPyu+RDIRzSHg`HHq1}XmciZzDBlmE^z^7=ERYR0Zo)*FAFGVl{-kYbvG@^Chrq0 z*?)@OzxhAJU=}^v_M5I>IZjg7!o`h#7y0pFsq~=g57guntv}kxqMJ8CR;DnzkY9ur z!HY!~mxn`_p$sRo5cmMrW8q@Te!k$HMU{`>^{U^n50x8?!OGKx`7YZg(oYh&va3%) zckM&i>^~lZCc9u=+Y3?J>B-hUSN4!A4m*=(`aG7fuetF~<2Y z>gfge<}(6MJAUBow*3&_?vkMgAFDCxZ#n8e*#Ih!6ma3^w|tX=8Trr+s2k5g_{|NX z_}4RWY^wrpnI(pjOH;8Tb^{+*83&8gk7Lb^ER+^@-rX7rFyzoqS|RMuxA#e7hRPZH zYHc0(e)TmMzT}Fi_k-~HeklpMy9beWlNo&Lva|hhvPyhKxcjZ$6oA%^x9pG3i>AjR z^?c&XU--jh0&ckJCp;&!1?E>FR0XPFt-FV~A!so&V^?-^&ud;;wONcVHe{hQ%KnIl z0e>{K2Zwv@;3uX$#1*Y0P)WZ9m9Ofsm_x(ahPhwFAMF2#k1Rh0qxUakda83dr{5Lg zkWqqPW@;VSe+lAFwg;2O5DPT*|Ht3$szlMe?exTUHam7q7UNT6`0v9EnDe<_8gQ$g zjQou0rg}N}Rd3>6DW$MsLstXsxK2}krjb>xh<#D{0FAygxcCh-X`Qo-!*?NT@?2Wr zY;JKSBM7IbI;Yv8x+anhe2%kre#esgg*0WtLH<_sEy_Dmg%y6f)O__0|J~o8_>K^= zU7${0<^qSrBtziMUqqX=cVOI>Iq2~5GdEvx5QfGM!-S|(&i(5OjJ_aK)#~>F-J}xW zTI5*q?qF&5LP7!5=TyLXnFCNc6Zm@FNM0^d;J+0GLQrjh_{{QuTunq791_bBQ;ViS zr%qtD@gdk9@lL#EdLXW{*$%Pm6XEZd<#iC|bl(45zF!6d_v8NIeP8#v z&N;8=bJ!egU+)IqBdu92jqI;y)IvbZy|3&U?li_`KhqFb|_T=XYPu4oRglrUFtFw1j z3rWM0(4zVP+>ss5R}JvP#2-bHomnAR-KI{jI9|r)34<9k|AFsCx3ukeQy4jUxg;q< z1@0Pd2I16jai%|mwGSu(wexCxS*ZnHHFjhf&_MGfb?HRk8e;$S_l0M~8f$4RU^~ zF>lih3J?7GbtiL4&-+bi5Z{c3dn&>0PJgocV=uo>YXtpC!DLBQ4F1sbg{o%9o-h8ybjQTepCn31`_4tb{#tFUL}P~}`0;Fg8IJsuNTTX~+k=La+nT!>8p zWvFfzE-6}_;!rI*P0uu2fX3z5=!g5@Q=fWR?qkX9zo^hlE`#Wa!XC1IQ;T3Y#+|F@ zZlswjhCxnH7_(h6QJB%S2e%ht{mZ zxprr;?C30B=ez@~4U*~85h4@TAc#+CH=wC(Cv_QU%byO;1BIm%`GSwpbZ=Kbe&Kg7 zSo-Mk>(;j1>E|?Bpx-W>sz`eHF1x;+7Z zJ2!G06+fIjAdL8YiNS`7-^iM`(tqPy$hAQwxTyUYcD$3|+dvndX?jHD)gDCByB8mA zu*X=*Wyi%wl5z6iM)6#=12^&fPO%(5c!JmqSEN)61#I$}!%c&J$f9U`|sZ-~31{>fub0s>ZNJ}v3?~Ym3P3+oR z#%wa@fX22e^5f7!!DYz}JauXS3|RaO4p!e_QsD!sdY`wFG#Rlrr+(=AFB>dIPNF^* zzL30dJQ=tx4Q_rCT`>QRqj#n-ym7J@m)};Rck^FEf4?vY>+VZO_~zB9%+cjXt~yFS zf3v5T$OVU3PGr7!_XmeH9vRUJ6o;?x1rx5F|di zpqJqYk@6LgYXJc4slPO}U7y@fDfSv<<5l>frn6Fv*`Ma+uz+8+#Ov!f2xkao=|#j9s>m z(ChNzq_-C=WaSjUev6-QIznp?wKXi~|NdxmQ%`l8 zJMIY6`Ww!M_zt0Vvu!xJD@Uh2xCkAK(y{NJ9`I%2?^(rAnXiLLe(NwC=Qf2;+iZkq zKm8+7o>QPoDiD-vdWbnW2rc%~a7RxSzCO06O?yf(rrek0C?0}$(ZTTKtPYvuu$0~3 zVurOd)gW?D16y!W8ZNh%l6havp>4r-)G7)jrhjKZ__YehF707V{qjeQ544u(pYkPx zd&e>VjCjfVq3NXgd^s$+H5wPbHWQ4N9VOMtwXA9LSN5(^nMF+c$z*Qq!Q!>Huzz24YH4M{Jh8zH`V^Gxpp}kCwoo;|L3|ugB}AY@;!&6(a`&5c8nOS2%dlYUTQ>6ADV*}-B3xI^2j3h`x-cgYd4fJ)A)`;}x#8%% z<`7(dkP1Pcm4zf1hnl8K#iZbk4t6pQ8?M|Fx^@{ud#ElPNo|6f8V{D|e?#d1ERF0t zH4OTyE0GT$>(FuFLa@y^is>t-NDeOA&R#^ks$MXjzmT^^!l^<7t-S@<^Q?rES zEma^7MvnzSpUyEUW2{99FFJQZm2qX#9A^it1tkz8#$^d93U}CLg`eTw9;x2+!R3eXDk z)&!sFA0}POZFttR7;6hA&>-_wH2aVzxn6!1&N_W(Pj8>V&Z>Bra*35CZ+ z^0d(9B%bj&z*_>3LI7PX8N1U8@78+3=%9hP5@wQD2b+o0z;vAFqC%BCSK@;e0^V+O zf#zj}Q2#0!$Q${Zh5p+3#$BL&4Teds{_Q1m7j!}Fr88)JBuA2w70SMQ1l2ry{Syw! z$70NVE%;UQp6HK$NUkbofS0lj+<8?DGB?jb_0V5L%Ep|Xs;`5rlk3F2f<=sao#QANX9krSvZic zo7_x1-x5C8x0?j*ILsu2F0pS+mncpVgtm9b1P|?tL_wTWR+@dryOz3OICnHk z8$NZ-HCFd?7uE8A0IS~aqc7H_lEiPL=(<}U&|l*OXnxTZ-M9OB=aFq$=IP^!&*>xY1%rf7(Pa_1Sxv)J-Kmab*-AzaWIn zbn6gnwQY1|Yd2f}Jp{2b79Q^p<&EO*s#In;&C)ZapS(P9q4FBcjZMO1)uX7Tg)^UX zrw6dik8IsG0T*tYgq`Mvtl^C!Yn&AaZ`F0^cM()szc^Z`=+^`PiuSWRPo-g00HuNV z`th3WX)vI7AzZ$pkM@tNV4>GcuvGqtqwYAtoPV_t&@O@L-=g@hQ3RQN54A=f$Tfk!8g z#ln+u)mqBVn4(reQkQmtko=f!QR_yzr~nvLcY-;pJi`9d)cB(DdF03n890%-8#|wW z!}#s@u)fb_G}K^1zv@0X$;A%aM>nzo{Y)|R=26__7s0%?E|I+YXv9yL=yMz6lQq%- z77#wuhHLGP!~^};VR!RZJZ2XQ7cY#(?JLB(Fd`QJoylYS+jkM2t8!fV@N>2%M}aGC zj*+Yyn2$TF<-~gHKBi`C;eM^}OmFI0hIgZct)AsfdxFLcnTV^6&yo{A| zONie*U157ArCM8;ki~k2P+`3Y2dEsx_&!ejw98wypEQmR2rvMx_`~q#*(DOcTZ*pF zNnvl=Rk%f8ZJ4`BWY@?63pMwKb#2+;J7foLT>OEp6y(v_w34}OK9Al;b7<*}xhVI< zs`9FtFR1nPfDuMf_@`wGAq@#Irt%c4R!kSXJnukd`vcTFqe!g&6$t*Ho!C^*f7t&) z895jd&t}FAp|vd*Frf5^Aa(E*TRydpC1h-a5h*gz_;omc_b8W~{7#J^TfH+LK zb5yc*ls-<~jkpp)_2A$)))+5K!EyP~m9DAZ2Gle>3; z`+}p`Co78$OS#EZCFT$neGw*4zk|Q8DB=9edsymd1IYWj0)CcJNN>Nu%;&nJa-9SG zIPr{aw@!q6f&1a6x2>>yy(d|H<1lDOO5pssdYI8)6E7aqCJR>CK(Mw8tkdo#BOcGj zH%|tkcYYqe>dqqG%dWvPy)&%7`wjXz{=mZq8t`Q9MM&Z`pptou?SH8Vo!bwSld_|z z*UKd_`cd+Du0L(83l>>niOlT5=bGqsI=pXbFpg~xK-I=5 zen$T%(77|ofENjp)pn-z#jt+-Pi8CezqOCNAF>ceWya%}>C<7?gLVZqbYk~<@e)aPG1Z1 z?`&X#%k!G9oOR+%=Mg)0fHpbNHqxtq7 za3*pf9@L)#AHqjsY~CjJa-u+7R~wPmik-M=x*nt`RtVW8Ti70yW{DmTB`20DyWIzS9Stnoqz@&m)4{>sWEV(H~x$AI5VX7jbse0Sy0hMzSeY70-{i zLZK&#TqROes;7q?dvA)<6thS~_8-zOpTegaKOD4tqPTB@lI}H zd!zqjGrYE8z`0gz81WVMPc%Wx40{&Hq)7Or3ozAI2iQknoOwG3`~5mk+y_Up(!-zN zNB9{w-k_3Q)3<`fzC*EJ*izn5`4FlOce3pk{h(arRqUy3z}R!{5M-sxjnb!LQ+EaY z2Wx0dpOrAQzzH^QsVDt^&ZfVfs>AFQMq;Y!i2S<{u5#y<=;$frO0!i_YU^DZbm%&& z7*D}3Q9Idokq2fl$eyqGMfke9LK@O+thw<-~!Ss4)IR2dx%fB}U(86zl-0#nDY%o%W$15mb zL=+{T_Wor*Yj=``UcbqY@#oOhat7V6>qMPTxAFJ>>u8*vD|CNY2+O|Kk&O=@!{VmR z7^_)GChoO`j!QL2#ax8%lFMYM^-D7U8-d@GTZNCuBhhH^17?5a2)vzMLwwaY!~M;& zRF;p0W;G>z7`Yp7?i&gv9|>&loC&R(Hf&{(JK4}wikG!bpm?sxFKzasSK{Z8C+SA~ zZfFHLd{l<^6|bcck+qc!9%yl3$!jBXbognWwjO5bC zZQ%L2_2}v}1Y+Ks!?@Q8?3lM6ocn$hwU+e9#PSLZS4P4v^=B8N6L7Vq85DUe#SPZC z*zYsPasTS`=;|f*|4q}N>iaa(FY_o%dpVmuo?4CF>xZ)prRUfYC{2fo44kCR{rTdE zk?>P>5=(z1gHyya*u-KqEi*Nsr)w3V?xrDxyAHL ze@W)DU$}fkFnX69qV?=HA11Y#^v>E;JG|~IHGMJAX~Y@h+UAxaPD7R+;MIlB^y=8- zLQrE7pRr!bX?{^??TvY@GT z*9pCJ&$pD?L%;0lGg%3)(pGUy@G7p2E{>rOJ`JjsjjX6Wal(|&zy7y2cgQoCUip$2 z+aIAf{t~_@YCn%Zz252VoZ4DJWGxK(n~AoAA0uCMo6j9Hn@2rM<>l}FYt?=JlHT@` zT8BDKSooM=zvYus7r2*xL7aJfIK4i_3_g1dppzcPaDT;mct59z-WZ^Vm%E=!dd41v zBI|IjA$^TXE|s%+FH_mpsnd~IpQFJSqxrl4kL3bJ)-Et~rE<%RYTx|5kF6`}Y4iwr zN|$BumvS{!FJ}#1EN0dE-Q7bL#(e;p`6qZ?hIDP)h&33#VH($ptmh-rGFWp&5=(u% zo%bylsFQpFu1!dwp+U28&uD}%g)exU%1s`#PtHm9)D51xqJdA_BwM?~{1!f{e1e_Q zDxmDQ7bn%9;M*5|g{CKpd`3ty7)HFJDjGkDcl2DYeeNvgLN7hOF_;J1m2$mQ~Whr>bG0;FkJ0w1E;MD;&>!ap15 z@$HxAbM548R`B{R?ABAJQ|1}-W4m)|dU|~zQDqdrDza(v`vy_@3%iM9=tW{JnaBqZ zx2MZba&}qP9Ur_}%a;ajqOD8+z>CaoFtZBh=p6}kyA$0v!5Wilb}}D>66!bbEE_I# z2#;&U{p{=(@EM+i?JE*V&&7N`c8NQkpY96_E38Gw5Xbqemyvr5LMRSh#gOYncJ&-52vV5TW1OvCsbDwA|n-jjxv17vE;(w@_Op|Rlkq(AIT>ja!K zo4#M6MeRz)QTxZ5?6cx&%sJzPt4IeEAJe?7H2GK2t?+QuQi6^z2o9touNmqdW1vjtYG0a6h88WC0DB z`3e8p_pcpO?L{-+FXS1sylBSXBCK}E!7l$Mn0tE=x3M(C^i4JBd&ZXQ=)Qx2*RPTD z{rsVWdHmG4U)O2hSm_%GOt3Oz?)M#MQh`~EH_C3fKp^M$mU zuZO+XSHS1Y4>J0z4pm&Z8nE3wjYb2>Vo&xs+rTNUT!QvhJF@9cI z#wu2vLys5(oMcsrBO+b7!{guVgVR#z{P7ovQXcxI_dr_5IPB-#Ld=~jpvu68J1$5? z#qmmxjp3ik2<;MeBzQSOG$8aWf5dQdi1nNS| z$W<+Up0)QbxQ&*Fb*U=kL7WU#nY)T_vCyGEr~2?6`@`_)!zjr5Q^L;g{f2Z|1t_gJ zfF4=mnO_?LTQg%t=HLgga4`mh`8#pmw-dxfaXWuyVF`8z9r@6d!{D)LPmP^M2rBwb z;Jd!&pu3=jgJPojlMa1)u&9EM9MJ{Wl{WH2tseYniBav~&I2^G$D+1hyB^gQ&9>t% zZ{tHvk4S#8Ewp{!0kE@6V!JXru;*O_3~rJo6GM_gDP0--=EvY*aOT+t9`v@`7dE+R5?23m z9!`{bRipG!kzR~Q#Bw1N`b55g8oz#c%XSotPgzTUMZ`d&rW*QrKEe~eCGfAQ3ViP# zV>jF1u?@X7m{_SwoZG8G(l;6Po0h_|+~efyqoJrjT?W@4tfq_mJtHMO&md*?BGG$p z2On-{!0S?Xc-kI^XDci5qP8=;i+9z3|A(h6TZqD#fr5R35QN<*GTZr!$icZ5uFwNfBn(JNm zPNr8jf^`Yv-rRR+SY?O{4mZK2yf$*^$Wc`Nr$pSJl)&X<#&9j5fw&D7x%PJq`5*N$ z7-H@MPo?agZg{_9iSd(o{3TC5;!7I#io2ErALTLQUSkgbl@ss3VG`@=1Gp-;0rsvG znO_Tw`GBE@?AuL4uDO3{?W&CRym>$d{4p=!wL`yw^8X$6bsTC$PS~!*2_Tz8s2@~N znZF6Mtq2Jx-p&d4D-75-mHH5>Cnpw+o8aM12j^`&Q# zCWW^KIOyD?^18ooS|95daX^#I6S2C2y z`M1MhqJ;-+cq+lnI6d04kTy=JaQx4-ccy!EpaU>QYOol2<}7{n6^qTeI%4*ZbO`Enor-SZYG|`JLvAS`KlOf?qJGPd2E_ zOyC+*dWed*}@2`ol63#(2Y6JiR@*_f*?92LcU zu7MP2^IaFxJmZ66(;8IMQ~IzBiPeHZ5eM zw^qRI;I-JNYXq!ui6yotO^^lUk)R(-_`kz0lA?)q%=p_qly(>hdm9T_KdU~(#mAZs zks60tpRFV(j$1*H#2(_tbc5T2IN{YJk*93kDope;L%X$`ncHa@EcVC&$AuDDE?mcc z6^9+0kGP`i?r2u@z!ki2^hy>fnu1j1aOV15nx>ewW2V(2GGE$`W;Uh4J3VoqR@Rk9 zg|3HbAyeqHcenBE#c(v6`2wG$H&9)zt$5x;1Izng0^|BpdgbdVZnLEYGz%*6bzwG0 ztuA1XoLBMHr^WBeoKBqjwiK2gIS)F@PRPpY ze|-sN-TuQiiFI|{mw_;NYBF7%w2U?n7BK8y89q>a0}uU-ab;B(_FDAdz@lItkbVyg zGOV!d$8yqt&P3eqSi=-Eo0eC zgA4FJXfLFn-o}!Y`iR+gDV*hC3VItd@JC1i!6I)M+8i$lGF&EPS0rN9zDv~|T1S8` ztjE_ezJf=N48DE295N;^Ml;1ozI^Nt67@zArgu&vlU^JmRxFwoub4{$55x&Ej^+3` z-5R1>gV@xtE5tM4CoyOZhSFIIkTPA9ACZA`3KB@i4hm;m_#%CnEmKP52emrEHT7#K2vRubF6<Y5bHRXE9_tv$ue*lt*uQ%{NlHK?k`T&THMjqY!N zUs;HB_v4FTFYfxcy9C1AUsgQll0eqke1R&>x%g#l6YhO>hFP@g;;|=UW+c2n9g^ut z_YLkvFXPp)!EiiX|0N8Jyrf0$jw@YTJ^}77Nu&d-b?LQhg>YH18I|^VLs9oar?b+o z{Aj@zF4w5T4K}<0!vP8WuiR8v;w{focMe9gvH2|E@ge+DwUO>NnT)SHHe+OPH*9|` z{Lh_+c=XMt=wA}^ zUkgd!Vgtz1Rl|yh+R(4%5KL_ghh@uZ@cf)0Y;zVJpvnS?+WuX#)?gPiZ$AvihTCCM zR4FDsF(s>*m{I-qhh%@#LC5H|FksIZlJzbY(6tOjrj2AJcYyy6D3a=Be#Cra8l3nz zkgob_j9pw@V&2mxIeSeFHd&2?Gb`6XM~oSyOx8l>Ih$Zz!5dcm&WL*`iMczeBcN<> zjCQ4Z!s>_PXy{H;So<^un+yFwd%HhA-*pV+-u;0N1w{7?0-eLY}OwFYVA7<0&$@X;VuTP-o`W(s!%8GvZ{Y>II0DLAdVdfpv>HBQa6E`%Y zCimh)HqygLWNl=EI8S3I?RKNrbWOgbd>9W^SBFq{HTpWMFCQ1;$dvwVrV`(r+ZuDW=SImMR^zUgQv{>9T>pU8(Q4{gTgK$6@!mUqU(P($t-DxbBGu zu4Ou0RXdx-#l)f4R)!yTDex}=ax}1Si(q!<1}v@~Pre=eMT6q@fs2XqA|LXcT`bDv-NSuvJcPAN9*CK_(@g&8FgjCb1#`asl#U5G0B5i8 z71U>?o6wy%2>Xvd#!OATaOf6K$)B6UL3^qbE2vc^UrhHnUiCT%f#rQ!Q7E->9|0<3UX1ljyJ(lI3oABgNY9}##^Id&8eX(pgPxEjry z-QbT!g5#QNr@`oo4SV~L$gcKsmGZX`Hung&lE^@+)?R^|^g z4#2{jhamH|9H|P3#C@td^yG(FcD{BmbPwx-xWYkr?^ZYD-fZLUmnZXzH|KH3$X@W8 zu$=^c(gK5>dpMcfh8oNEa@%q<)Cm~IH3x?AG3l{<(47#2 zHZ%9SR(PPOKp(!C1=UZQ@XnS7F+a3gxcqu6-q3lA(o;op;GLVeQ!AN(nhnHN4`-`b zG*x`&M^-(Pf>Sk~g2t*&(7d;c4*%-lIBS=oq+I_MB(2ED`?@J2e|IwM+$#D5pAB-f z2-kqx_Y>Kf)GhRailWeR-~iEzeo2PiOTzfHJ#=aVzzZl9E;|oGL#bpkP~;T6EU=Rl z8^u7xUNMjFAVbDu8oQ=Bni?uJp;r1%T-a$1DLe+ReESC7NeA(t(RXGVe2kf>o05^G zigcQ#SORQ}!zZhslVRIT$qmES8tsV3(Eq=sc~k#sns*BiNyegxzr;U^ zyTC>4(=6Dv1QcI)Rja1N0^#!nw>Qy5d7Ts_57)*Idxo=9=O}KR)kIz|xyv@@U%35oC9+UIHisO{I3^6U^}~Y2OCfCY zNW8Q35*jMhIL_z{Cnt~FLvMQr@vaDFZF7&Y%ciC*SSTV{i3TK~O^T*k6-(;cw?nO% zvv^tN%vJj?GJ4cb^_|NX)_N_ep{6d(zP=F%ws<6*+lpY#{r{03LLACbm_% z!#|9J%B>H`hr^XDKzIfj1uuo`!dBwocY-)t%mc6D8T7TVn+(WMBi?6JVR*4b@S3fO zjx%zIQc5{Q(eLES@kHi5KUz5LYDS6WEs5K@FG5QBMv~RBAGtydZ6BvC^wk|sUb+{f zzEqK;o1Qs!Rl8Z0lWXqraZ274Zq|GmfgapgteGbg8YnFH&+)Di7bRcW=cj4nxMvBj!W?jke zgu}tX*p|`5CW>`<_*rA3pfR5*>`M^*ZagFN4~C-8*An(QAg#vvU=eZbTOfSie4Ob! z41t7bL;TvE#mq7z@P3m#{E_<1Y@6mu22PrT%h>B0nE^7e<$XL1PPP`L^P=%YV*xR5 zDq+d)V^~W2d-7=85!~_N1Q|Zx5I=?#ve*cDvZQ3D$YPw%dY{Y{l9zp&=A7EBY*P7#%t?7v#pO)K>N>2lFqLa4u>BTyk%P|31|6sN#*VJ3ocE zbrkSX$|9Ta-v{(QAfZLuPJ%|)8@!sh7RI#tw!v6c3_^>k=HcfsEo2tk0E&5_2 z%18<0?N-C5%4jn6tPuH6v$!+Ct=aZ0$>rBS>^9$iFsfnQEzf05i?v^QkXm4 zy?h!d4Q{N-ZLUFLBj=n{nG+s~7&_g0|Q#+{`3#8~hzABL0rI}*KPZRF_pN$kp&(}KiU z+)?=2M!Ijw!P&(5Q1z=`GJgC^;xPRXn-ioA)q%@U?Q}J<^c@MujKfHteJvRnnnJFa zCOJC#^$4AA4UXO4JDE_~$*v`Bh8Hy{?ABWkq2-4XygzONxf?3LcE2(9?lVK#mKZQS zbYG(VO%~=E>qwqU-(p1{7U0956R_sw;>pNA;I(-*_CKl2Ozu1r zc8!R|rIV%k(bQ@5_v0Q6eS3wxkg}jN#XDQOayM&yk%Nxnvn?_|0w))U{*`z=80YyH z14hS_t2Hkfk&47G`IR6~JJxrEfq}dZx6afRB3Fj9 zI|*J8u+ori-5iDT!58t7Mi_Hoy>RI39)4_{EdM=j8@ZL7D1LioVS>K~#{O3b%i9M_ z-rSxBQzwhegnruadZV~^HeU~Z*Dc3chX>&99ibrea0jnj+l@?F9MHWV%C)x@VsP(Y zG*{3DwS-d0qb7!KJN_XHdaYsA*)$}zXW-|x^Dr{}qA+evnq=fPO&GWNJ}TH7fweFn zKO}|{**@lCZt#I{c%&?jIiiQ!Yd({&v$Np=FL3lvEQXtInjAJx!0|QrB{QDN!<#*0 zXzAr#@N<;q5|0F|UY3i#A0Fdhm7!QA_9Dl=%m%+*ws?B{Ay78epif>N1do}sc!_=? znsnS^et#vz=D!!>PWo6Hd2s_Bc}|Bff&uh-juE;CRKkU(D{yvOBhHsMptlx@OrxGx z5?ibN7+qM3*Eb~LV(Sc0?b-mxtLD)hYYi%I;>`PYYqHnM+3bbhc{VS&c`*2!tve-ZLsDiAYrULA7@mG z6&EJa;;uU^>Dp2#(u^191qy(DrFooX1h%(ZVqES$LB_Hk>{9=rTwNk61`Q@LPd;JM z-Lu$H{0_HBG9y$lHxUtzO_mSM5XTpl1@> zXE}JhqYql2mBsJvI{cARDQuOs5#C;^BGxxlh}R=!rnh4pG0c{O%4%8kJQEEC+BxXi zcm%aCitp0&YRGII%WT8Q8>p1RaK?`m_UZ0iE_t2~S9XRHznufYzqAvRPxiyVLv}&dU`xKPQIp#~ z{t4T(Tj8~@9(8lS1s>08aQ~FqFgAWZggpv|7Kbe~PCDM zt6B@mVm78bk|xzF^E#!$aMbrOzLhzL+PsD7LI*L^>t#BA4luC8iVOReiL;g})~Rd_ zZ{|p0g54j{J(Edz`y{$!uQ7hh4u-1M&3HV)3@t{lB%WWUVVH*$&KUoUwX0a;w0bRg zp$VeaiZ;=a6}LFxre;M5e_b!GgV0FxTWeJEpFUCT3^hd+~Ej zKOTx{|AkA`;vWf7YAwQIcP)IrKptW@{w1<;(p<{)urrTi6e-XHRnD|UrQsCf#SmqFv&Mql!U?0_`aNxVm z62;q5I4^EBRs}t+85}x`?|wcXzaBqpN{3^1$y3l>JdT!c6dh?ACe&rZ8CZKV1Iw~EKu3Nj$zM}W$LJg&`jHyE zqqz>>Zd<_@`{;As7kNz2{TDRODZuVW)A;c@hP<}r2N@xHWhL{1VPuduT^2b4G#_n* zwDku3?q3&j%k>yb-Fg)p6a{E@nM(62YgwVv6xdk43mZ_#nf52E1k+_i`n^FS?oU>k4t6A?`f4C}PRuTr&ECI+prV zjPaR5j-JeC-fPa1)+wntuc3!^eZEOx>PMX8C5=-gf&4V-Bp2@Yp@Xpx%(6HwG2V4f zcrR(iOOvC~>yIM$y?qXt=y_D;##k7TA_-c(2VTjU0z-4=@;ZrYbzFsTjec}(qZtl6 z`Iv>g%?ATzJ$zmsg=? zE}}|vI7EFrAn}geTVr#h6pJ^?k?q@4P{lA8hTPplO>$CbxyUki9_HBTpuus;H51DAOXk+JVeXd6yx8|6j*xkP+Wy1n^Poz6+wfV~i zqAS++#d+^Yz8LiiieT&OE7;Y?f=~J{g^snGi2;X3 z^0Yrgu(JL(I?^_bAFo4$vnnukeg$M~D{xG#lIAX7C*zvYp>);R5`HFe3%7GIr>Vm_ z!S3}zVr6kw+}W0bFv(k%oHiY7;#}b4ohnf7=*w%Gs&G@*4K&+13s1fN3e&a&AF{pH zA)`(a!o$;GzFZu9F&zp05*vivz(AoQ%1M&zKOPe0x52HMB@7B{nD5K+mDiW3F_&v9 zY{#it?1=ArsFr?8GIP`=UH_s$r75OHw!xo8IyIA)kV}&3I#c0ib{Ls8Mp6^?;Q>ou z98J>ZE+&(b?a?ySj~U$hL6n}ICJ~Zz?A?nRaJ7)bKl7GJz6AAw^xs}^eoQ$0GZ}&Z zmYa|v`32;X`e4Z4W(Qpw+c5BG5EDg#nDI-~v452;_Ajm${#A0vijWJEl$Z$NRqGsP zEBXgVl^S7;S}*yy;4C~6?vbBY`asOlFqE}f1Fk{#cRrdg(P3U-Ch#|KHXVZHGj z{^R^MVbz^cFp~|%u$DDETx3AL|D=JJo%i6!Q%d+_wlniwS&4dkMi9^JJy6uY4wc`m zaCDe#Lx0qK#h-seLB94p7;cf`ZKJAr=;bSzJVNx)%2i`SA)s`xF@9X_!=IjVV?p1C z(pZ08{@5xM_y)1+m*_d=xM{$oCK1z>|(>(=WfuFsMichgST;_@O`G#-C9j+cJh6F3`pBX}j2QX(~LM66kpC zrL*|VitsM}qsTEnAQ}Ex223~2cBt+5iga$EpyE&=<_*;yt;JsZqBHLV|I7r*p+&FB zzmd|gx*&p_d3XlCrY>ae7P9QrmuJN7sF;zgGH{gF;$*g1i#wFvWr6y=Ok?>M$P#;) zUq|mF&*jT&9xuEAR-c}eoIPzsTen@9TYFLXxzhu7`agt_X$zS2jTVx2?0&FfJeDNkZvTKu=1q>O1JJUv^$?X{E4%+}a zgGFE9^{p(XpN_~8=yWh#KNKeXGsmm{W9U5mss6$^Zi`SPvqCAmq$uurjwY3clp?7# zC`!AOmQk{0lq3lig~$l^JV%q%uOdaHJyfDWqNv~ZKk&Nl{eI7Rp3mp~Hq5Rlm?cen zYX-nv&HLQHo1n+Ve39M1ddzZIhj&uqphLL}7Bm9cbbC4tdzi~Lr)+1(9T^<-iiBmE z<6!0$SvpZl$eO0r@Kb|Eh$cOKK)%cE;LAttK=%cbbYt%wvhzS330-eX+stqC{l&XP zN5=F(*qRw!B_@P!IByS4b*K5Isp@?8?jNwgrH~&VJqI4?MbhN!@A1=XLn@~i3aWPm zhV7*D!r%T6@<+}Bortac)yFQ-zE?}OtSZIYb%s1@nGaoB<;;mND~x{;2-*X)xP!PJ z`~4K*vCy?qOS;7FZ5CsD?Q~k}yRxGD*hn-aWn|v+FD$4+gI#((g=u_?K*ic{2(HkA zpv+OTHN&fsg;4Bl)TZ@G)*4TcR`s{*@#$o!E^` zb*=;*_-YQ=wMaw!_;gU6t%G0AWbB3b_&LYCXihXX(FeO3~tNkv+=_F#MKf&JZ1}vpZA6(j<^dm0xaRZuL2q8 z(1`c%-z3@bDzN4CeLJ%rQy5+#1Mjq?`1RyWIQAqD>sP0<=xYuT`*$2HsGkHba~4Bm zPbqA>G6rUka;6JvxLgOyp6s~eCYau<)SfypVMsDS2F2%GF3Qn znQgz{M)LGdQFBdszMkahH{hk3vh4R zI4C$R!_N-#AzqS4Xl=4LfB#GeV?IvAds>Fj7_7y|7bNfl9wt1z*t)Vx;2OBwyvFLW zj_lKfIR5L)=t|W~Be?Ux0)f-<7i>xvR~}W&XN&5k_^GmU7`AQ;O$>~Oj-y@d*@jML zsjr1YzZAhSu>=qPy$VM|F)PfU%xA4rNvR}P zZH(#h_bzbS=mbjaPeki+&v9+nWbutI2fNOThe%(HFLm2E2rh>{6A!nYiN7F#&hZOD znXbodXns5^Z!3aTCiiHp)=PHww<4=f8NrJd+fsXrTvnyCk8ITMAxiC9M6UW6vozZQ zn$zT<=(085`6Wpss)7hHIuCn}X+gk<#n3MiMcgyOP%lZ7PCwEL+e{vkxCUSG%(~wd z)hCC*>1Zc1Q*I8g@*af&ou?sj)H9LqFGunSUXmKYnNVanj9nc$7oGoUQwQHEva~9cQ-Du&j)u4e6}if=TSJ36uc+jhucBU!IjWHTC1%5ge13<`S1X$H=@LDL6&bm4z&j z<znVXXhL%j89;m_3 zE=%FXEmoC-d~PzI1H-87ZVN7f3;2DTaK7%D5(b_U@txZi!?*RHaO+lO{rR7Qk)&{bg!$zXsf-VTXS|myq1(R_H^sr&2 z0o}L9kDPfDMXnE*7JA@gAYfA-yt$?e2TS@;s?r!1C|^VUO)pv0jy^WB>|5nIYd9OiN+&E5h34k{?uMp)qEIUpBQL2EWsAn z+~T0m^U(i7D1JWhk}U~y!@&ZtfR|pvbq<-uWzH0A&Sk$^jI0LGHd*U_x-S`Rj zn7?AjCMu$~A-|OvOU;xNT^P#~HFWsmQJ29nl92=db#hhL;gx2ugg)-NB>w8#Jyd%Z204ROdHtwR zv{06$4Y|dzPfmvS&mGQhgfnU;xY&ArsKTRuO23}dgTJp=v1%Gj3`2gg-|7Fzt5@&P zp+}QD?#sgSmP!~prWtE4FJteEHiESYC8;)baN)2VJL&Tn+6Dx}0p&)PcG(OE4qiu3 zYNiw4fg>QlzM9a@Gw5{n`OInJ4OmtCfobe=1Euksk;E;;p;-@EfMFUuTF0QLWsBB(q6RotPo13i_V!^F%NVyiAa@bCUk zrmr$5-#3{+NSzuv`SUFVueplzr0kgSdL>NRwh6tSTCqVdIVijC!>r!vq@ynwR2|e)(PL7Zja8(>WYzj}gHVt&Fe~V{XCgNr76*#M8D*jZ_Wi!)8@PrZX ziKnSHEe(`q7seMu_MNkARry$yfA@yGnk>dFsbIEzb}q2HZul{)jSPy?XF)ba%=x(? z+J~Hgzx!md@1%5`R;nUb*Y16PvyvXd5hY|YDQeC_lsPL;~QO|FeZ+zUp-9Y;`eKq-8P>}TZ< z4PbD?2CyhvgGVYosPU+O(Bw9VF5ika%D3os8Xrtfw1JTllXk&C}v!I0y@isaeHVrQ%r~x9|#yk{L@XC zr~5e=HDx?{MQY>VGS2=c9)%$(tC+>g2XH4>9iCmT5ZSHTY^#>x$D^YMv7aZ6aIf2X zyNs(HVD>_f{I<)-uDt(H^QR)4L>w{TQa5>j#!;L&y@>@aGh@dh?uv|+m0Kay`e8U#ryu)c_VO7%baL7_fEL+M3+ScF$ z(N8rDCgSqh%W(XLU1G8AGknIx;&Jl{y2Y8I>zz`#sTuFg}k=o5f1rj!B<4uFug}p#hcH`@}67s1gAtRKKhj;xZzEOXU;zs6rus| z;p>1tPn8 ztoX{G9Ef-=@S5J-63f)a;JqE1@Nv&5SeUn&to$R1vu8WAs&Z8p@}p zG|oA^SmjtD5BO&)j7;ThXwXqEs}RC^{iDJ0 zj6aN}Us?K>#e9Q-H8wWJ!-U4KF{2hsej#C;=N@ph{=x6~K|JLf6mCy5fg{bndcIXoZ_ zRnk~&@MDq5@W-OPTgMC8$s3~Su^UO)QbU-3MwS&+akk5PAlfH}p?UHj($f&l{LT%+ zr_PqdQShAZkZ%`N56)w$in%PH`H(1OMihDKZ3F|0oXMOcx~S8Bydu)$kVrB76LbES zgF_DHu>mfzgH^8|V#NGDZ z6{1a)74`1N+QOSxcc%(7)uV^-?CjZm z&^R3?<+YJX=Qx4nq5>A4D$6}zG~tsIsc^wMhgd3|#?N*eaQe=9=p~f{K9-(v@ZVn0 z?5tysWh40D9Cvm+X(&_M_mGyB-K_f5hyEn=4564?`yjN#3@647saiMZ%-xA+^s79ywU@j9Up{xmF&P zrs_f6O;sR6Z;?Sd!$q?u{1vHuza+TcM?vz*2Q$DT+%zanHU!dSxnePHjp zm=y}Fp%A+tINZhsYeYt9Ic&ZiU!E@R)e+|F;|GELqFXSaPq>2!y_Ew&!%#l!9X7@0 zkiBiX;4n{c0t6jl*M@H38C7fekazKThrecy(F?@$rTbX({WEZRoh4m+bvMrQ%O%st z#&bUT6yMOUKzA93&pDmmN^OxX8)uQGx z`(WF!nQ%8&peg0Gi>H3rfuor~!x?*==s0Ae`hxxZ*`q6PZImZA^U+-O`#hXBB?S{q zw$L|Tm9TN+cVgcmCTWZFczE4>+;?DDh4GMOxa0a$A!D)~F5QpdIhz;RWvdN<23LwV z1=mCOk{t2EDGt=mCk}+C0r-tCCbQDFaj|$fx=Fn!ZJ+M2DR0kJD76oQ|MH?ZI;q-y z30Y4HQa6wjNl{oAX@%WqRzczOf23(;4%4rUfR2k#F!1IE!C?_eRz4q$8>QVKR3#sr z#%FSwOj8(ehmd{8Kihuk4L}2z?-13ikIzYncsxzSzn9A)blVWVexxLhRQW(c-=89W zK2l6qYA5NtSAyze|09WV$C&4Ty5gtP!Z2*YaGIeehs$Q$v)RRiF|_wF6do%;ZK*3{ zUUd-3+4+>*aDF28-uGEF$|s&pYBPcfst%y@Sc73SmD19LHD)iU;RcLni2EQRA5BL&vd z9$0qpIK1~uWnv$Jv3@QZclKn#ounvmnQh92^|5G{??RkaJeBJVi4ePrqHz10Js3YJ z5l78e1k2eAQ1-b9EvbQ9Y9EW{THj&*Lq906Q^B7BYP?dY@7|nmiA8m-wgJu2`~P7Jb$)1WQ3kNpip8e9=ZUYxae02eeqm zmrWQqd@Cqd#4>Mv2PUIF5IbRS)=lA_Rd`w@l!ThR>g?cZir^@8*TBX)j0mQ zG!+KbdWr+QC{N4jAO~&BSp88`W-#D9d|%aW7hUs7T)cic?35l!Unf2yv0`P|)Vc|0 z$WBAg0mT?|bTSMdw--vJ=JM|=UVaTN8xTO3(+1YoP7<_ibg>u!{HhdLZ z;s2I+5lybX*o8|wS;K)l7inAGOH6ki%Ui5J)2@6WTU1>~e1EJ)!-c2WrUV&Gsfi&{ zgXMV~3+DYc%W0(53bA66Vr5yP3RMs~4{oA7rc7ufXYT02trg0u8 zB^wC+hj4gv>jYbDlMMyyD{=XLAoluAjeSr#-l%3;K#0qhBlAenP7f#K&M9IKJe&NL{C;J?#k^qc}n_`Cr3 zY6zZ3{)Y9xb%74-X6MyEvz+2I_+wngruhay)z3?0PE;PWv`30JNAE{>CWBSc&N#C_ z4)W?&ph3Y(mhaw+70IJWVP-5@TQA826}MvFJ85EbSPnGK#>4MJr=e%}A!wC3g39&X z;?H75o(xIQ_US##`f3iFUkcCVU+y@j`xhBItP^YJ{K3^{s@RL)JK@{*ItZ+;gqP#r zkdnyP;^Je@0*7lZ*B81n^4CS;%LTr8FxQ1^$5qV6G|(OwOkB;@9cm@5yEwc2Vihr~EyY`2AHjKi6%;SJ&%A0n z@Q1K}`P226ncl30RmHVX#82a}ixPOsHHM2d2XN;Uc`j)*k19+&O5Ggl*~!lP;NQ0v za%W8z*znWv{jsBT{Ul>F&)5apuQTbl&bM}|h84JYJy5NJa&F>rp4yf7!MF+UamC$i~RUxu;t^1Hgo5S!Su!9NAOpo6p~b8>9`mt z@YttGj`|y5ZL@#kDEZRw@rqi<6~&~0~fw}_FQP&HwC`x_+#C`9JX%O9++{y zhiD2tH5bV+vhdASa{b{ranfXOe(`TEk=6MHquT4lzDE=A(acPAPEY`kt^@dV`e!m@ zjv9V4Q-l5y6JgW0aM1dFial$k?7-0n;saY``1$qLsGOJzrt%}j_fB=Pl)FttZ>}u7 zy!ISd7{6fU>nXM!Jcskmk3z;Ctk4MRMEScj@Tz95&T9e3qeki~W4VYCew zS&7gq?v3bZMmFlPhj`EWr}#W6N6QWCVerA97|}9_>GTU+G5?ROOXmo@zLtfdmk7>X zDT1g;FDjVmF)P0(u-IH?ljWK!0+*^uR4?-yWqE^mxPl7*>-H5hF%UHat+05;L>P2# z6&8=?cy8fs{2N=sEb~n8Yq2Nw9&QCmbAOU$MH%d1U=4omzlcUM138Izzi8seAa?Xc(VTs!Uh-*Tb@qbL^(u3zlA0L!O58;*-HzTyL2n zk6i5zABNt=3mYuiwXiCZbzBX1X|535UvJU$L@7@GQw-9*$ElKA5{B(S@%Mp2)b?@& zm$jTgUEe5B#RccYo85(X?{Wzqt2CQxHNV8bh5BrW_aXY^o(+HFdz5!gn299~%G69? z$X>V>M=fgg`0Lhzw9dE`Hg@_!Q7)j?#T{^KqXFz3k^<3K2O_IdaFuIC(_9If-qKA} z4F=I$!JPgbQcqj5w zNt&zo59;rRfR*F`uC?|XM6~PUjDi-?*&p#ZV%=$6aHE7Qa(;kMZYSfjwM}fyB2PAB z@B*GZAO@Fgw}+Y9J*26wjC}vl!!E}6!7KYAWYCZ6M02zPFR~cN-EzFZ)FTqh-4Re$pJ0H?F&Nc54_{?g;`sTIwr|5_Y2b-u@!A7tNKegNY!%#^_L+A{ zAJ1pgmbgN`gNL1oy`8xGMKGT7euNd3OQ3sR4eoOCMxP66?7oZ~eJQd68}$j8`s@i> z4VU4U?X5vyUmbk=o!M5C+bnbVT5M^(i^{Lg;iUI!wCiP?5?;}8O z?z4(Fu+=uI^mzqJS54$aexdAl zZWGKJIGZ|b_Qjx0_wn$J-z@5OIhbu70?*1u^KV0sFl$due&*gb{BQd^e4G0nex#U! zHOb&yawDt-JF0gvj_*7A8X9^>@r<^q@UQz7`20PBt4)fzT2L?@kUfKkEdNX_N2s%I zg>wGlj|X|Fvk!Kz=%9nI?4Z@cJ~OA^lxCG(fA)SAgdZ)?TzQP zY8&ahdcZvop5ldk`w9(Ae> z!kwaL6DrVo^y}z&@$#@}D4k)Ab!Mip^5hXnOSp?`MM>DQH38j@rZX$GUu474`#ABa z4gBbgfY^hQ;@QpCtbb=E4Et|Aq`e7+q|sy9-m|fI_h&wP_H7G3&<@5q{>q|-U6(43 z{(FilYxMBTxg+GYyeoO<9tM4ni$u4rwxZ$6M38;M;l8IEOs|#aIbR~n)gxQc<4-B- zE}T#1Y1WX#tGBW>Tl&Qwk!vw9;}i~@zZ_%lePKVmcH!$isv^tk!F2D%382|Mn$PuD zhWeA4BH#WVwtlZO#=ZE+biX|U--q>N$sm37kv%JFe0GB|fqV5z*roTjg>4P%noyg7IApK%l0Y*-F`U&_e?RX5x)dv^tF+yfX2S;5!KVD@&FrPp7KW3;5VyF5=|J+llqb4)*rpGO)OE7mV^u z__rYkdA8shXbK9W)diuTB;CM&*zd%2&m3Mf{4?FZb0oDL-@yyh`r+N-LD=-AmKdq` zA&6sOUdKS{=3-j;ZqGD+RU85{b#t)KKAy)ub;4(#w$t%56lm1MCvbJQ5^tZoMcm_L z$3kMt$V=}GHtBB^IlylaiJ_}7@@Wq{;XI9fxGzSb*#S^62PzGLi&wv|0|B>5A zKC-oS@4+t1jrd=@XSZtYQ26UUOe8*DK#r(AVfEQBv20x#JEc)Vy8V+#?l46%#3YWb z-)V#U8d^|AO$wv@Tt#lt%VERY0`%@003&w{CbwREB~#a#@Go7lIAE0p4Yd&Zwu|0%Qi1@z$iP6or2=5%K3u$&luU5y%2`S@fxrI3A` z#~bxykxm_cjSit{Rc0u6M|fAg4Ww5e=<*QtHe7UL1x}g2gV)!dY58{K5Zuu5D8&sZ9+`0u0mU6v$2b!G*&7v!?SxRofk{2iq38HTqfB6&XZ57TvN z6c3Lq#LG>IqI{1hFzZ4yyXAR_=(rT2#*jZ^sl|2J+hjFt4?H{ypArDSLQtBR`v zTjTGO=VDu(WINBR!Q!mc&*XQ%H2svY4YyviBMoH|7&gL{ROQFvpH4=TE(|3{NhWSXe>Q~`ubPJpe4&2m)gMN4`t-MaL%I2 z-Xv{jwB7Ox9{hBTAqlElz?SFOlJOTdr9(-y097x{(gpm>4z ze`@F3Gc5T;iE+Hr?kmX7FJ#M}ZlR|37Ia@jF?&p|C>qX)NFv@rE_48+92re>SMzPp2L#3VZ3(6IhZ^4G3)Bw z36Yah;E?DqHQpePLE0S{v|pd8MW&J>>y?62-jY6BdjiWv7eFS=7$jD$Ca;v&u#y#r zVa1zncIs~oo1`8~ibDh*^|T;y_oyuVJkJ>S9vXmt;Z5wb`B3Vdr^pL4EU1)eJh>pR zhG{j%xNGq{Q9|S?cB0x5O-lVmQqyjbJ4>aozDN#_|4qUKBWd{HKakiQ*TDJf)A48f zQtH<0$dvY+1;3Mn$)N+&P=9YRnJ`p~eie`6502S!=BLi3w(5h#!%|F-e@Egjz5~nF zd-(2qHhLHzMt2)Ix;n%U%FYv}^!p54dnwKT_Gi#*0nxMo+fZxmc=qJhCU9|mz=Fmo z@aBzH^gr(qdZ%~>H_*$(nqW8j%xNi29wA57s+D+$MkD-b4TQ>zL9jUVJj*ja1-3_o zob!!oaQ}lH+?G8I(kh=xequF#nSX+@7G2TpX+Q8_k{rF1?~F&){)j_A2NAc(cI;~W zjuvavamTXj=>Ex@NDLHMZJ`6OP`1c!-?D4W;L0CxNUUWZJ-}U-j-XdH-U+#it!zq+ z0?PKd30#!9+69aexBzNy(A%6|(Zf9rb z1$9%eF`rl7Bx#oxSO&&X+m>@+;ZjBtE~wCs5@eQ-CHTf&(Kt)UDV%(G3Y_e>tv zp(d&xwZC71j|#)#!`LST6BEP(D`MD;Q#VQC&TQN9zrrx*_e+dh8w|SR-->)J$I<&Uu5IG8>OH+w;orQc~k%4bwF!g(PdtN zf*=?GXRxJ9i!(9s=JQ1Sx3`SFsaS*NwjJVR+b!%$>p79(U3dD~a4UWuIvgg63PEUZ zu*v>oAZ6%xe7wPe-TwZBEo=HGp1MN;rE^2r$H)p6y5%y9$(3VqdMPZ&;1YZ`Z^m)a z=Y>p9v)z<=>7;7DI$HO)v$5KeSnGKNTAL=2oklw<-nCw(C)A&UZKwjQ%zMHblMg_({b=4& z*NH)H8D!}4i(oWI6%-9WLW{_o$efHqovv)SIop9{`m8AHTOCH-jyTZvK?Zn##$jkb zfUw1Ay;#Mr7Skhp?RMLH!S?C~lF4eoVT&2I>|cs0#RrIvD3D#$F~yoTpz2EpQM+bo z$m0*eZ{!?ef2NqMs)!-M8>Yf9nGW1>!33*>ajj%z0hZY*z)^7m4sTJwX&-Om?JVJY z=?nCLsV1FPqe*#gK4g1lk(Jw9#9O~OP_?`A*wQ_f-qz8;95R54)bh!_Z8zc2qA-5M z&K0#>_k+aVr!0B?S~UG?#FQ85v;HAc5EL4N(FI6+c+K)WcKwD2jv4yauEPmMVJkA&w>#6>Ta_GP_V!knRXpj1Z`Mz6 zS@<%D((fc+U*2H(dz3(HMhrMb-o@(sJ~(fLJS1)sasSr&WccHA=v<*G-eVvEJ)@O) zMZhDtb=DKV?wpAVMtjL;fs=V$H57h7I6yYZMWRuwIuzGGhof84Brdcq}bG_)SlonaNR)!g?tQP$|lPwy4|1!vB)DpRouV7=m2CoVd za`p`&EKS=Q%i}42%h2b+8;?Pa&SA)^4r2bLr*MeO0NA$lCG-4Z2McQMK=8Pa6~}+v zffm|ncm{z^zL$J(S&4m>R0g(?)2Hf;IJ&7{WTVgi~q91y@7m_pBdWOTl2via>R{! zVVJo03-dLJBH>dE@kxUzeO?nolcuKe)}p1P+WRCQ%o>?oS}jh^4C1*PlA+4UhCdrO zgKjb2%ZGPc@qS+>dgzkL9V=sij<)2}e(2)NwiqHXt4L~nFjhK@fwe{H5OHcJ`95_7 zd6zkYI!*Z_`Z{X^%C#-z;THr~kz)nve4!6VN=|_2&UKdjCls>}pCtD?myj**w=unr zndC}*pt#i13;9pSIcAGTZ34Q@&@sZ$-y}5>u5ars+lyL zdkcnUX~@oBCa#W|;5p+hKG_)wUM921x=mMz_33!{HByphC_1A*8^EJofc4*WMD6qa zINB|UeD8IpHjOE4^|&D1SEfpDOGL71Hp2ub{YgM-xPej;{)W(Z6`k~iQR(C zkzhNh2fdeUfR~fBG5e7Xix>K3%NG`l4^N0DdsrdbDKvq-Ry_>%G{xzqH!-7lbNWF-nSc88kE?Y5rq0VIQD4~!@Y|@G z-%T##zZRdQb<6$uG((TdO&7=5kH}E9Z+ttv^61S3t`}_2m*@@P)Av+UzB~)AOHZM) z+igYaYXmmQH8Ip4FQtNtf=Ady@;^1YJR+-!FB;S*wtrN}Z@GMe$LVU7sr~mwGlw_e z;6+1t*6vp<>Bnupq)uR51&pGD4t!+ygpAs78n zBR0;`-1oqK=xX9{K1^_xCiJnQx3}Ta(yesLyBzkjTAzQPDeU8#gJHzq_hK9OEugNb zOz~VL6iUUyTKkm5$<#iuJE6fjmbTM zbnV;I;3Ukee;p5o_|N0X#PlB|cycQ<(&;467GD>BhU4JVlz#Z~xmNVLGm2{)`M`Mj z05UnhmdRcFLn2$f@vL4iY57nNb4(-fZmt@6v!n?FS9S@kB5k_q&vG=|6AZ`92at48=m(b057_r)Cpx#c2USeQW37Y?Zx$FBSwj}$;rCN%$`((7Ep-g^lr};}xCzO9 z6-19H2jYtI4^Xi!oHy)ujR$J-tj&6ZjXh_*B3w|j4IvW-pK>dCP(~JM55xw@2)HV34XlJ^Z*9eT_ z`Q;kiDN&co_1ANSE@|4gwy0ur`DLNEV!)RxUE#7X7IMew!tbE0Okgu!!(oNt+`r=l z@0I~>=zEqwJ|54DWlX_$+a_+ay^+4u`5>B65l7PJC6h@*lp(Z59}f$?-{_TdGb|0AB zY{JVfv8K@@o&Q^%+ApH}x~AH^QDlVE6nAQv$C5 zX}BxnD&DoRm*qE?Vo#z11|+Yde{L@m%by*|Q=+Bl*#2^I_TMe|_3xwjjJ!II|Kvjt zev$?-kby({B?X4&9v)aEOJfC3w3T}mBR1#R$?#AS5q9fuhrNe0a@WY06#*clbBv9& zp3Rf4s!-Lo2xd94g5>R&LmL-a+OoSG!i-;w{d^YS&PxjXyxK^tNYUla+dXmcP96BS zNFG)Q;kWpXseH)W7UrAr6kUdzvEipx!DnFzqle_+5zRMPntQ<+S4h#aD1}h;C z8wgp>l z`z=G@qV&MakwfXtW8-=JzgRwdWIg6-_|b(XC;6x9Y51lqhBwJcaBYbt0{5#KmR%K# zJL@N5v0p2F7Ew<|J~rcqt2;sROFdBKbb9+m1K0E#4|{8t0tAhP>J=%(!ap31`!Dl- zf}2x0Ob2^xk3zWHO#a;@jx)Q|iW#Gu(J<;De{{MU^6nnOx4+ZqzIBqcp!fn?T>k<> zMIMl+8X_kCy-dzmnBfnf0Y%mW@WaS*k#^2hh zmBGue9ztzE19MwB9ZH>rJ=CFOjM}{$_f&YHMENgq=lgZS{Gkx#t9AL?YhLtovoekz zqeBOtyaplZ75Jgz4~%+yg}gr&!yNQPY^-}4cT3TuC;B#t92>Ow?XoW@JN%?5d9oh& zR=)_-e>=17ZROBuxffRWYw_QpMDJa`4*p&O({}eok(7ru{AZ<4Ypxc7;_4*6(SxI1 zT{C6|UB^?o)x<{lZa$hm5{DG|I0@!e3B=qe<4|kLrC*;!L?VK%_j{T zkMSjT_*&%>tgcGJMvYCC(Ngcg{O3KoyWs@)lg{C9kB5>=drRrAgQvOECUyG(>CyP{ zqTt``mSGE9%xTk{t9ZPj2&*R_rjDsveCU=Pf>-<&%oeg&?t>4bsX@+Rjv8QzT@U40O$5r}K4 z4!viuM8VeuG|Hl($@3><9ez$O##&+(4563Y!z+$Uj^y{n0wXm-i|U6DrBYi9F?+@# zc2GSLCXG6PA4Q$m*q=sEh1)~keg}HK_7Jp`PR7q~nwT1k#&p5oovfAz{;~2@Wyxs} z{NdACXj@S;@UQN}f)B#wqtRqvR~hiGx- zNPFCGE6ZOe#|Y2&C8Bhy%(v)1gloJ)+$4A_O(yq<-*jXU-BHExYO5Nrc%cniuhU8I zM?>+tF^%|1-~?pdlfZ(Ti|B)!ad0{R2&h&pW86v)w#7YR4H12?v5AqMbQRW1mvGm> z2k@lW9CKzileRN+sL%9oAUpI0Kfd)W)%_&H2OSdQo?v5gw(l@XHhv)u@jLkG-}!uF ze2GYP`v(48|1}ynUgkzk^ZBO&VIt&{%Z(?-;RvUTxaLzd4Ntqkdz)mr5Jo0Jo4Z99 zQX}CplY&9QXKH_G5APgxQs8zTMWr7{z-+QCe>iXi7w#qSY{fgS=yez${!*%ZwX_L! z&$kgXGg&^_N|^s0dj#U!;XGqYF#AzA3=5akL(%(TFem0ADs>Ozs-25LY35FD9W{Z) zx~B322SPxZwhJ?j*W#KNPEfM{8YEsC&xa03ff4>GB3I4FaPoX3IW_wwyS}jw9Ye0c z%YmJkW+BIWy*;_lpfE^tRTf{HyNwMgw_rJqXW-ZrbN(odHvgcBpt{tv=p0{6MlU`eUxo zb2e&12BhAYMUPE4g;;xmGjbvl=h|h#lyOH<-P@fV^Y!O%<$}nYATzvQ@D3|}D3Eur zocRiKS-R6U0xg^#f~v4LvNnHD{?lDemApf6O51Xnb+e1SDEx)@OJ#ZgKSwhEN1v@FmDX; z7z%?$DWq@z17;sC&F2U=WUt94?B0hN{93LLpW|^3Xp9EWH+xQeKfYy+#k=@P)s3*R zeIotm6oA*|zcYo@5Kd!yp+iGU*zH~6<{D~t-jf0YxHh|LgoJPKrY=qYlrI*BBl zufshzCAq#t2NT^rAlxZGK&;@K%MNs*iqAV?drU0(xxT1d0I4US|yth zlMH@NN>rk7AlB+-dfv?)T0J8}9BR&yJoY3+p0zoO~r~ z=riMug^PLc%OZh`RE2-od4ipp=(j5!eXdjz_5G({`m8Qy>LYlR8jeE8z)(0LrAb@% zIr2HHzKiAi{^DG9As@T-4+(mD5jT}&<6b_HKTF$;PaMM7O9unEsOgTs>t4h71TOB| z_XmzFT|{a1AzZY&f_d(7$5*XFk4f?X%=8kYKYkGR{5%$^7YE_f zx6#FW9y8r+GukaZtvt^Kdqq#0c}r){8k@U?$<-1|B> zj*Mo9kISG|?OOUzGzhDOJFBb2Z)kCR2%QtZVu&zfd$e*LuODlR$EGd7Li!DDclNV2 zSEae@=>gPoS}XIGyN;W6hEnb@1-E`$NFNv;go~X|p)^64FY($##~xY0wcr25zUu^k zJv872PeXBiwF}~v35>Wk7V_mPiR!D#boRaj^y~XMbV|Vp4j;p)v*a_)A>Almz91Fwm=g0ZKi zd6?i_IqzGGAsgNKgsE>K9?l>)i{a(V%&Dj3Njzh20At!lirO~ma91mB_Ri%CT6{gr zXB)ghdyQO_*xd@Zb|m8$Zxfy}+K3iZ8e?pL6JMvMPpwV9;j?*K(DdRzeE-sh?`Y9N zrCt+$FEWGAw$$Zj-SRkH;yS$hwg*ZT{-S)DAKf`w1qXyAqE-K3$}U^*ht|`CEb(#X zS<-;YS1Q1xmGWy_r}5DTvQfJKHnUtNP181LQu)FCq7|iH^xyLiwx;%rc%@$uoh%OH z>#jr-jl@y3G{6({W?zCfk9j=*^+o)4E{5ptRlsqJX3?O5!L+vY8I%cU>Y1PPurDHv zSW!WTq+l~gSG{O&lJAr}SYOVMje&kr|OtS!G0$jOW}(6e(@msidMsLnuI zAD`f4MH{%U@53ocQ)rX%G}hiW1z z$yjj8nMlsET0Ave1CJUxkc&27adl=RdDAll4)1BiYgZF-LY55o{Qgap_q>6nhWR+` z-L1+C%YAT?FlV+oVM?Y^Q*^k_aKYputna@)7!$3+YtGDuHSzX5qpKPfjvmLyf_v3s znF~wNJ|$u%O8BhX1)sDZC#Mw>iQMeLn0UAshuptPR;N)`sbR;*l~#)#Cg!5j^8tL$ z*k>rAQvjdV2+XKcMFc{mSpCo>R*__glGi^HZJ&d}_e=(AURQ>$)i2qnyp!nJtb@;s zw)3j~;e4Oe1U^;hGiP;Zv;KAUEPP*M<+afoaMCaeo>~{N@;r4Op0%1E>K67U+MjUQ zoWcD26jd~O+QQXVX7S2^#k{m|KC~R)1YJjFK=1I2;_Oks;grBTh#r5Hq+N|9%zZyl z9TmRsaxOh*unp052ds^LN<4qILR!yg+~gpz&a-1dbUq$Siw_d}UE$E_9K~cmS;N+` z`b^Fvn;1!7MzhIxh!!u0cOMKuCO}{cZ!rT0@g6jAw1w5#`QYdF3GV9*7Uj+`g#BCO z@cx-6cu(LMY%6LcUf=Za>4IAPb1WD}IhB!ZR!IGCR@zqPg8+v}bz{}Q!Og&frHR1~sU#cb5&&qJqCQaV4;wU$fb%KkJ zqu`W$5jzkt7bpMQDxPl1*xB;kIIjONe0*>R+zj)`4yg!UQ=Y;)1n#3$>I1B9o4}0% z_VP~O1pr;XIM?hHn@IyO`QcqKPiYp7H`t6SF=OG7!C~>;rG{jCayWMzoR5AlFE9k~TFoe{-t+z;C$e6juK4dyH4YL|}P0;vka;ajvYzY@oy(jslJfA$I*1;6l> z0v)up&LsFR7k>;`gkMyQMLC-eR|a&Xk+;2zA;w*}j`(7CrT{y{Prf=c1envpl z4+|Q0rF;wE>q+J#!ABmEWAUt5U&ePZO4=m(t#NG*CPPe7KJ+&vQ($Q38(ij3c$Z<(N}lNNyiC1;;F5 zhg#yocRZiNL&v^`^yNy__evLewEQlUO`nTjZ3oe}nW3Wg>Hlz?$0AJDvS6KWzF_F= zD(FcJL0r;`UIIsQxX7NzdA%h@HlfUC!2-}$x57wcZ<2N<8g^^W!9R;{B;& zHt1ULu${R$O>pz%%@y&mF;Q&L3?2S;xZshHJcgAyFUiIiSJ|a|I`HYuC$eSz0<`=! zmmJwFM)yayFrh}D|5veu1rJWd^!Wum&qMI4byUBpjyWh*t$^_j z_HbgzIxN{`LBkWgSzPi7DC{-llWzY^B%Bkpz@G!HFW69&6NOlpW&v}8mbT)ftMRRaZP{(w5qP8p_?Yt*}879 z_x4I!nI1vM%b3Bp-?JQ|N)qwHkNsdex)H?^1Hk*V5+qF7ENYgMA^PP8Oub8jAGlir z|1BK^r>y^gaqLoX>R%;r&$mP0+(+<4{~hFOtrEId+I&}B94Zyq!`737VaEd>EHE0u z-Guuo$@moXCe{$S&ap5=;GX=Nc^3Zq$;0Y|@!b8Q7DoQOjLt$1TTH2UE(t_9&av+K*g*;7Sel=Xe~Dc z$-osbsxX)A99dqGacB?imc*%E5YN)ngM=gMFf%V5bfpDuf5^KEtp!EIa!V>sx5;F)1aFn1*JiwxA%|t3 zeZ`|k%J7e>j!@Vz0&JpfQ9pY$`|{Zv!ls@EvA!9Z>G6!*brCjAZ&`yHf`4I-Lpwnw~?kMHt%`^g#5v{s{1~T9l+~fJve-hixi_!R4djY~F2_ z*H=TTPF#iAjZ?8h`3CVGGzjdwXTjX33t_BFy?EZ6o1!Kf3B7SawC7S7gp*HV?Jq{4 zvtSjp_NgPzvLpUMOT+`uZWHIsG=RvB=O9^21l39k;PHDT#Ls+%=WhR!x`z##8cQ2cs5)IrFePnxm<=F zv}z+yt7hWlaoTkBrdkN-EJOFTCFJwYKJY1tg5>NX&}%pb)$UIC{Pc8yfeP66^Exb^ z8N)U|Z6=47yCOd=@Ye5dw{OpBfuc>FV&|p3M7?JREIRWMf}>_a)yPhCE?>hw{_G^4 z`(Cp36V%|L#w6S`Vu(n({~A73df{M^2qf~?E)ws4jSRF8B~NBtW!rwgg9ObW#{>8ddMGyjNh=EINkcJ0y8-Tr?Xtz>4|*myClhKPPoFqaEsBTA`2k zaj>5!#hQ!`p~2i8cvSNwNf;6b>mHSfeW%Ea7Hph{*H)TCPP+;SrAu5=_Yl`PDPd8? zP)wZm0&P@BFwI}#Y-*rA{&qI!TC(d!qVw{YcW{TW^O{Y`bsD%@I15`(%4OCw2jcLJu!xw=jbmp7@(5ZMM{2__0DgrCPPX<~B zYI3tN#q`dbeV8KW3&D5$Aycs#UKrbgxO*5Im=w?Y--JNXQW1pJ3eUdESLE+$Lt0a{ z84mAlg#9zZ$%-sp+A~edVJ&9CL9@d`2j!^P@%2ygy5lr^ZL0|D45t&5q!f`yxDDG7 zJ&mLeIu0+>22+{SmT=H_2Hv{lNROC~6w{Xh^v$*#LZ9jtGe7l(ea^XxGq10P7mG%* z@zdhb>gynE&}|g$v^)S>m9jMPVhNeLTAyS1K$_&;OgcQaP;Gx>l9k}f+}!HWJbVIg zRkfok0uyfC;eFglZ6#lMdK4?rJBUH!4icY1xtJF`f}ihu&Nl4Z3M1^t!|+dM$)_MG z2(AAq{@2w@=FCu|G&=^AKOaWtRkL~f<6g0n-C}%f6pB-YY{vc$Wq#|vE1&m6R>&a= zTnz(nva)eMNN0w#lRG#B#<#MTYa&>ZYLZ+aEH8>u!8|sGX(ec9dhRGMtaoi2bnRef`qPm zE}m8)XtV5nw1Y$5k(@ed-BZPM~R2@Cg9oxd0I8z zgb(z>1Dp)HGX}TBG8FQ><3!uD@@To`K6tGB9bq@nN&d=|#_a&U_8S|! zaXM{k352J8K78!rQ<%DLEyORi0_`d0ygzO}x3&|w&{iMmYdamn_T9x-p)+8|TsLra zo(0oZEJm6Y1sWs2g8A=gocdn@_`kbF9^1wMStvZ`e9JJ;Y6Kr^f1K|2=)fhL;b5pRSjL>P3LsS^1Rb!pctXZ zZ|w|6qdY?}F&s)uw1S~wVk|%Nb{tqdoWPokUey@_gR z?)t5eI^Jwx0|W+jnbkD@(0l+7OL~IFO$zkG+Fi^<>@IXA;YI==#!-cuAkyt09p&Q65~ixx8lwKQ($-b`=*z z<&wF#{$cxdO@7DgJ1TC|M{uzuYdnYY?iW3HO>YCesGR{%`4HMZ;=J(Ot>oN(DlDJ2 ziErBUimz+>2ji`u3hZNP-n;V`lfC5KeLFSk-c;vb^m(;07?^hQfKy5ayYI}%3ox(Bs)+svS-B(cU z8O66th-oJO24jSruI`b$yuDnxD%tHgz2ET>-k(Ii%4ahyR1%zTi+9oPzrsw^Zx6kf zuSy@M>Qt#aB|^YeBVG_-P$gy7%da^vt8yK;3CC5%@Y&nf(vj=;Rps6n(-WI6^W^PS z)M2=~WBj2IJ}>hjUiVJq3oK7ixsgY4`B%an((mK&zax1^RxR93Qs-}0Wk7R%CvOWa zCeZOF<02_@W-7p<#i7eAPB9m}hDWVICUdo~*~Qe*@#>q8+b7T2cqVyV{`k(%Y5%29p7dvx3YQBvSK_NIC(J~6w`5~U*X&WYP- zx-F9zq>P0}dnSs)ug7qw#~$QcpB&$`M25%xQo!KIw@=&I40&zEokw5iH&?5HpZhzk6nM&wTW*lsnDZFN6FSL$fMTFaY6_RnT22VJkqW0=EYihQI z`tfU+d}&^U{3r zNp`kqS*O4cEIL4L%N}64e-!xSRf8dEj2b?0Du8W=(uH>k;7W~2v^sAD|8CfY;dWo} z`Kc6=>RSxirHdhb{BE)r7Kj!U+F_1ax8V9Hgh5wA(fUm;9vnNG-K;A{2(u+uBnII3 z>c6N{{E9jGxj}HGFFWO51Fr@?VUul!LbXdHdYSg(gh(||%dKSHH)eABHG`Qnc4C)R z9>B>%SPNRY9bh(E@4;fb1NZ!p2Cqjb@--hKVEztc`lW)v&Skc2(d|?|=CPwt z?i+|6Ekj7ytw{W3F_FKpMw}$`o9!OzLd`Z!<6753;Ol5hUIX)KzOuICIXe_M6Dw$1 z(lVYheH(2{A4x5~M$&IVNBFr`3GS$uNqmMJCrh@K(&VBWH1vKqz1=B6dzA-QmG^9` zigRwVqC_de}*^+k8Ql+A^V!U1dXk z#e?Z@e-A!#U=*KPo=)Env81+(R-u_R(34%e;Y!3`vCGT*;HB!1!>4@U!JBgEgaJ&?;W<8q6Gai`@ldU*Crh9+y#bjoGX zc$;zP5}%3OU+AsBPv^+wV1d6hoD!DGqn$qBg`z!}6PyAHSH|-0Z3mfzXRSzHE)*N%^y}XV4|=xb6wdru~P^`z77gJ{}UQ zC8{Ko=F(N=A>5~~jLu#6n@<EO9p_L$VRBjGuzF zF2BLx2xt2SYVeasDiObh!@I3nP@MT1mwpR^8^6AgBG(A6K2jCCCg+0LIiX*1FBFum zbQyYCV~bw`)v1cc2qO4|@Fj^_zY~rQT}=N?DaI8MDxkXEfuwHrhNTVvNNfFW%#vS; zfqp4i?;k?rRmX8@6Isx(Gr`1|Y_!vRO#W>?Kz-{4wv*;>hqFBeu>OsLsKH8LbH_XL z^rkzQt!vK%OV;x_@mFBazLng(Al;#U%5M7W+dOcYe3~qhT20dqRgut5y`Xxu6n;l8 z!qjJx)a|suGip48fot@+rbP@K?CL>{VHUjeLR$RmJsXb;xr<=FX3<=l@ZWTL!nuKF?7YUD)*a)+cd7GhEzyn# zjy_<^mdoN#Z)r!@ki8i4XcXUSmk0V^M^PpH8IG&B^ze(Vsod$Wr{ldQUApp254&No zgd37|RYQ{u=*LZN^cO$R6E@7F<#`EIdevgKXO}76@0W%*X(=g~SP$zIABeiOn`y13 zgySLEllW%0GmkUrrM5}i=)EXgKIm*9H*!A5PwqVz2j1E(9@Y}YZhOSz-!U)6=M0u3 z8+is=JG8l!nikxCDhbuDvTWh^MSNfU5V$g#vP17R_;h8VKk+aT_PT5Hp2Rl1R;Q0D z(S^!0IC;S!f%sj;!#qcvF5lM^LRKBEuXsZz@YCib=m;BeZ&FG zIoOCiZ3dptGUcbojNnC^eb_no;XLBY8&Equlb+eHiqZ?zX#cQ#FlOUjT(vlq{LHF> zKZ~1STj~LUla+_EN1{-{OdeXgJ^9>wFIlu^C0}GB$JLMBpenzI@sGzH!28usDjIT^ zY`Hdw@Y+=RE?tcj>^maz8uF3-QHWqt({F)8{33qQbRV{Cdxh5~CE}gEa`YO_=QkfL zC;BGw^r4m$m}%^0zCs`8V-3PXBPS}lB?05kPv%xq-LM2LNTYuo`7zj&pT1#BJsL4$Ybah=4DgE1{nsbi?U6i)f|M392OF zPx+6(Ol!hT`iHyWi-Vu&*4B}ZGxF-#mYzr+G%cJ;or)6pb_aOb1Ldl(CbjIzu1r`I z@KL|`euaw2z z4CFrq7V{eUe*(vL60FfrVO|eRpjdoC;DwB1`nyKJu5<-<>)8a{{;L9aXTKHicl|E@ zx#u-r`tpmlm3=~$%qh(ErXSYMO=bTcUBj_@5dtsZ0e*dQg6YpRfhVrh*vjiqSnRml zIO*#`oL;a&d?#w7;Qx*z26A&zZ`)OSbHVK_$IW^9_84XtC`;QyD)4q#CbTS^P2~g^ z@sqi~h)qBP?u&VY3%9K${_%+rcQOtdyHkYOdI4MD-63wRIxlb#(jfk-B3=K?ou`#g zpw&y$sefoMQyTl);oprF&^T6$@6hzYL2(RJw>Gktx5-dfY=ebSM?lVbCks}Y$i~{< z!b+_*JRv3S>x{V{J$JNIOpiRnBQ(h=$gj`G{hF=ME; zCY`5j<~jbt&bmrwfClPaP^OdK^uk)95B#V7I9wFY4S&xMbNo-^2yw2Ipe{YGbj-Y) z)X*&j`cJ3O%0K66pQYe1%Lx!VHZ$=$ggDd~jK?P9NGMq84N)6KkTGTv92hKvm#53n z!t55N@_rIr-qH(47nkE!4+pB!UWc+{WVpk_Z>;zAP}HqfgmK14U{c~YX6(Kmb{GX= z#EYZk&ng{y0<@XDL=ms-8;A!ylEkw9FNvh=Xh^^G17*VxFf#uTKdt&%eEst_PIgq` z;tPX7d%QQ(@KvJ6wtRzT+fU-IC-eBJB5jCu>R<{7AA*%*G8ua13JYB)CR3&iplcj= z;SQ?|%=)8-D8XLo)U?F&+z4+B-9bk4hyFQvM$Fi(ae31q26>d8((}3^)16_-D+>_IKLG` z?{~tiFv0UvJ(Bv^Ux&*#!UTTYdPrQ@&cAqVq-A#!$tE*N*cDw(zxkYGd6VCfOBZFR zOkX0m-5JHD64%huymZRofTM|04t+cNJDpK_gF0Tk$;XB)r-Ap6Yn!Sh`%L@T#Jt?6uR-&n~SRZc=##e7zyD2Z9)9uR|D8Q`0(&j+Fy!vCBVIZv$v z-*2Iy_j4&Z_a==!efkwr{i4|SVFnK0W<^4!#{@cfxp2+Calu7uQOxP=Ihe{@v3l4! zrn{F2j+e2b5p^M={*n@AVH}RfhintsAG%DIRa}NV7kAMrKW!Kyk<4#yN{4BZ5`0{| zEd*x-V8+r|5_EJWJUDiaG>&M%upuAV${J6`Um3BF8&`m;f(u)1=|W1%vxwtXU0&$B zfnB%N<~gk( zChE<%!u5+!k>ULsbWL*)`+VL4|K=ZtrABJRYt1my_xU>h^47#%!@5}5-%@;Drv$2J zf8#Kf!%(8t1d-FCEBl)Yh>H9{`lC0W{P}>)T$tb6xy7=8+rNqG&_~43w^Mxf><1Q6 zGl1?tA|`pNPgr~9JdjtYf!LHiBH@T)O~dR1H}7TpuEVPzOxsuj)@o=4zC{v~Kv z_(K9l{=^k)wCI)fF0dkE3mdvVjYzr;rX7{7NT&6{{`r;k%;R@V`q)XLdFe8KZf-y_ z^C)P#5J=t}3F|C;V2Zpo#M_pkYw8^mkST`6-EnApYBE@y9Z&V*Y{2?!IW`(2j1Jx= z^83`pFk=-_S~nk-s61qFt{VC!bLiBiG3lE&6y6WUmf!87s&SzLH%^Tt zZk|mWuO*Vcervc_x`X`61bi0~%v=Tb#nX}(WV@>)DV$x;6jZ#~khg~*;O;pzZ;K{{ z@2}$9v|}WA-Dav^smE~a1;~*~2cxVwv1i~>@s6fZRQ|Uv;CUPPA)xy|Iv&QP%a38m z^$QrC+d_r@ks4Mf~Dl749`#f?>;}Wh`i^4*280o(-1FD{z!j`Ev*!DFHo31$0Nk+l2 z>F6lfFwh#CzugzFF*^o38>}inU+o}9H|=0u5n!A2H0ZeVm-V{|4j(^f*nLu-9@i{F zhri}DETSE9|9!!`2SAw-nq}n8F`*TVP(lFX_*1V*T55q0|)M;`fJS`g}`b zwmSq3zV`?_;cLw9ei^ZB&Ld%l!tB}e09z)h%H0+y^JAOFil6(=X6`p+@%Ys&aJ==4 z$vu9--di1lr8@c8L6D`82b0J&1|^J6PeKdOUu^jrBDAV6*Bb;gikn ztUpv5Y99{9A0@eB<@8qA5@y43Kn+Cr^utZf64+Tgi%1&G#s2Nb$s+R;n7L#i9s1q~ zFC^_}MvVtp@=wkTK2O3^4;Fz*y+17e>%#9p`b;k0seqa{)8SY0Jk~y96;5rDg55t2 zSkjjSc)BKztr#4|MwiFK)j44py*q=Qj~EVYd@TM=p1?D^2SM4^SAr8$MCVGH!NK0& zWOMzla$Kw| zJfpYQ!LwaiSbS_flm`XV)C+ge;%6v{?~bg@6t5=De-d$jVyl=z1EGNU#yfF6KBZ+why0Y01uCV0RPH2-I z#Ipq9`>ix>FgK&n8gU5XPEXWC{sS4JUiG76Yg9jb&JDArZcQ?hr2PTZ0?5C_BO2dI7TKvIR@*)Y}l6)%C{<; ziO_%>5h;0Eo(q!Z&HZ-*MxB)5qLUl>ZY%mU}|aN5-)!CQr0cgFr*f_r5f zx=qu?yk>he*=Yc2pEEIKe=j@NbQKr%3v-WXA2OkQC64lrC1vNO;lRUFboAMkxb8v^ z7S(%!%``C~qw=R6#dm8`DX=e(_wU{>W9QibCCn2J8Y_ih9-jget(2S*( z4WIFExHQQ$UBbdH8L(>?ltu4rZ-{~~>r>T=2Ot>%t?vI=Y{btQr*DJ$UZ}=uE-F^?Yex1dC&2#0Eb0a|cayx{dHse8) zuJa9F7%JB?dU1L-Xfz#y=!#|ZuKNyp>{$w4p0Simn%6-1ZUd6C>^Cm2RpXZDNAXMZ z!?@~B?-fc z8y@p>LFv7gc-6v=yt+`V&&BxZ^^HM zB`BBpgdMgB!;9I2=#gWEq)+x7{F~VdjSDQqdlJ)$>eF=gtUw7=zQ-}45I{mrx`o|F zCR}U~To*cptX1$}>g7jaL0JHOKXteLDv#F?nb^d>+gIb7WL0`(fWUm75{6C>&Wqwt zcR<{)cX+BIoXpfB;yq6G?2OfatX>?-C%pXu{g>S#HDeB4+$MN%@7v>_8hp7*;{KN>u}m&c`KKl5@v#{W$$!B?`_HlBret38c_9wT8N{no zZ{p<}ze2^^6gQ!)(A_$y zuZVTG)X`la;Y&Og_C|{jiFLEXfL@IdO}?#yK5C)3O;(<$4;z8`yFS3}yRVsQ#TJl% ze4Fi(tRt7|>@cJ(i~N@?M~P{d_@8?jQ!}~1RKIT**q6`ADrU+*ZfzuvM}ko8=|{#F zSg`*#q{3{Ui)@Uvzzo*wCbN|a@w};+cu1w&B{rU`C^0I5woM8oaAz6ZTdas|;tAX; zaMCS0_A_(A3AMB2J^8io5;^MqPPo=|*>00QvU_j@R7cFg{n?I{dM`ccxM+J(ae^G2 zko1R-zDH5r;{{wO7zU4~>R{=u5LkY39W06Y%@&6&z%35SkTF;ms&cQgp*=T={oX8k zyGc`U{!NC=4eik2{F7|6?Gm~>i$FEdQ@lF+5y&hHg_Mn(X{xLYng4M+uJV=u=la=@ zn;wES+j42oZW~MuGvgOKT&VvnJxYeeaG!gcG~ekW6l}iF#HwMK-c(GDpX9+Fp+}uL zAb~!td?0FAKAGS1-^OQk$Wi*ki*~#zfhWxuSjUJre9k>Xq1yn|b*dMv7-C8#oFk~A zVK0plW}-h0*6<~+Su}FsN9bLk&-bKEC;fV9B6sCVw8*c*XJZv;=LErX{(cZ~YAuHa zzN(^QyNs|Yc@LZ)WW?vjmQ#n)2#h&Ppieu8_yi}gZPJ5y*l20;-<$*%G$ah}t`Pbp zDXkc;mV;+J1z+q=X&yhTUVNwDTx>C87Ii%of*o@_G4PZTzU&W%UEODK`>I^xHe??= zF+B($y@-X`0~aDtYe?xyWj9vdgaZdl$<9l4MF071cxB^;8x~)~nd&pRshdAk3kQVI z=t)?v?+0Eh8}M?!ocQm@5KvGL#rN%3*?_1R^50y64b=UM-Ps++R4z($sRwB|O6dM9 zNsyvls!_xubVdVd}UR9GXO z`U^j1OT&&64E%diuVkMsg$0f^==e#OlWHZhW&2gI57S~MBM-BWT^B(8_aYeEQ-%gv z!DRBn3~0%Y!>&KMtnX$ls9RXWIia_8LmY&9CI`7(=D7+F2@zfVwNTX4XTz_iT!DMq zLonp~U5u--!DH)2(B(s)SGEie$4Dtl@RM5(?I|nZZPGS3M2IkBgA?#!w>6$Y`v9}u7J*ft?Tbhljqt22OaiuV&p^CY* z)5oD1J!<>sMiGde)L=m3F#1GYfa<_c))y@;8< zBQdM3kG!9f3uk5+AgIK%0aB?j{j(kJ(HHzSmp{P+O+nBU(904IWH66=$Jh*!Kg@bG zl2&*}a2_%kMMO9(NKB@*shHJo{Xz$c*I|Z9BHEO?kvlP&)aGC|xOW10HV@_jo4yer z^);Y+cPPD(?9MNJ$Yehg&0({16i8^MR~EGIr&0rDut!@LzYFu!s0Y#1-PMfEEvA+4 z>yM-1>k#;Gc_=pVonqV2MR@qwQIh|tnhiHR0Wv3Jz{Gq6&CgnZ=jYp2R#k`L^+lh+ zsdqnWWT>)*f3>)zkWZXMj_{ECkr?pyBxs$C0dA|9)-5t>&?R{e>xM1>?B+7P%8<_3lH^KV}932W@rLRGFDluITEXARrBlgw(+6qcj9hPO2~v*>?0q6f8`ab?qH(MfqfSi5rp z-PrdHhZ<#KL2)r!?pJ|U83RmOR*a`EUBg+9Le|Pw2h8#=lVQ^5Vdm)74lcE$P_a9V zrByAYijF0$n0bl2+_s^$=}O!?>JiD9b&j^NAErXE`k|h-+f z!zL}FiT|F!hz29R>)Sdw_%M|nQg?@}rc=<-fY|Zm3iBvYh0&$*?DNoYSkZQZ>}?rN zmaKKbHC3Njqsv>d=*<)&6IqJ$JI;{k@Ni74k%X^#$;4*F9AfR33E?%~%(PmTw{MSy z--WNp_bI)^u}vRttd$ZazFW`sZK)QATOWoUnY*#;sUrGaNoQBjPQ{R;XUKQCb~1W; z1exg*i4X1HqDkK`mJ>FdF8TC{#Ew6~oL!=@Sz;(2^xgyW&*zboLT_@+vtp*Pqm8}z zR|=B%4`5Jw4O2gAjkb-GxbZS+x*^q>SPT2v19J>$K&K&ANT}l|t+(WqRtY=Qq(Wbw zw&A}%2Vz2w7>qHLDh<^pKVCGGC7V3xdXF?}XmAE9E_w>t{bGJ-*HP5-t)jD!x^Sa0 z#iE;N&r@_W#h(`>;s*vF@x&NkJv8Z* zCS$_?8fQg;=p$0qS1QBS!xW`KgdLqTgRY8oa0|J-r1CjyaGGHOgdd+efnE z-algPeTli>{w_XwJ`Dfq>O*LlE1`#ek@=379Q-Q(!)cCjpz!^Rc%Hv5Y?2qa5FVYZ zwZggbiQmr3+c~kKk6pjPLHG`gt6mBBdd}hU@eAn7kpuVwX9YU*Jg0Le9L2~sclexM z1)W=Gz@g3Uctg^PI-N8J2j>iSwDPfC_4;YRQ={noALDuOgC1^u_#fuXlBzP=KNBXV z1%r$93EUI08ldkWeYLpN;ns6|K3(yU;2u8@EoahTtConGHy?+OJ+ooJ(WUsx>L2kL zwh3?A6_JOrt8j*m9M3SH%rt$+^0HSau>V;sqy)M{%(-Myhhi3cckw-$le-h92c4_b z?+2`EJ%`l|PLS=tM;zw)94@Lhkln5ZbbgIHw^eKvdF-o#qw5c_@`Sz2ph*WOsP15& zCmF+>W7eRp`Gb_N6MR(9NAe4=bzp2z3?z)4F3K7^8ZC5P@yP`R;#{6=;YuTWM0T!k)xN;le;1Z{u5@vv7&Hv zRfxsyFTarLfbnd}xkb$Tb_*M~d5+jBXecTVxk_}sjxr@7Be>7Yh9tyAk@jLw%vRIJ zUi)IQ+tZu8Q!m0BRxUWJO&-d|AiMHVT5w$sfairpm}ON)s(w1*_P1)>E?WjFp0?u6 zmst*@B$pA>wXSH`Y>YNHN=5h27-G^CMYcz{AALp`L(JDhL`^FgmuuZ6SNe>Ws!%q zN=qE>Jf25mo^e!tt;1Wa?vs#Ab1JeOOP1H$fw#OXRh(jszkUmBzN+y^2KVB<;0j!0 zHn=K4%9i>LO6J?gM#0|QQS_|iW-d2w4V|H*O9u(L0{61__$LH;et`*{=pIDx1>NO} z=UYfcL?uW@CfWBn{~+TXGT`U2H4vo`#+NN@6dONrNZTL<7&l_A=w1O~YVs5dWXe!? zL@DdF%)|*+d$BULlD(EwA_sTr<6_-UqUXDV*uchoHh8o?95uK`-YY8z-Y8_Z9Z!>L z8qX%r6q7-dy4a9*J-G8t6EBU}h!3SdqBEM{!i=Hfb87kQ$JEnIW9nMU#h(;(qm5=lO$PD{LBVMHE7-BQG7SI6VVef8qE`x&`*+g|*<>nUE_ zxdANmlX3q^;Y_wF8Uv<&60hv45KrD2O3o`vvz;e3c$s%NRg+jx$4a`A9mgW!&nr2M zly}C>ACZ6e=;SNBL&feUDSY@uT`nV@hSMvZc>m*J{6FEF`>vxtHIBMKYi?Rr-T0P5 zyrphHs(vYENtxmeI--wD&5HEZ;5$Y(|$f{1l8*tFLl3q!{7F}I$e*v10J1uf(7b$wxVDt-3uH9EiR*k%br}b=LSa&I!u2!R_dfxnBK`yps zOaW_~7}ipGk9etn#CUVL7R~Gp3&_WTn$k?*1g+JbE9Rr^wO@na|8(ks@yyGnH>`ts(XKqrl31A31(u3j4?` zsHbusSXim!h;?IdXQ2hZcH}u)iiG?1(L^>d*pyn?4c_g5TW* zm`oyQ*x<{s|K?37dP?!4raLcm4CNNth5VtAmoTX+M$za+{GrVeln9XLbG{A3dzGtk z!rvGwvDmWe{s}4GUihAU^tgi#Po?<<;w=kX8qqsVZWON&i&$o1wJP^uco zr#~uV1s0P0`3+_Mqg0JYeez+$8g=Dl_RU1WAQoI8Rm=1?_1#5bW`#Aff^tcbdIeL=wzyf05>k4U{j{OC8%** z-0f!pPX`SXZ_g9Hxv%vxKMx-k)!~63#+IR>F#q>aPXk>;BXB*SiJ$L2hAP2vw?^_H z8poI5mH#O^?|3Y~H;$JXB`YN(t0+W-aG&c)q)p#6RaT;*p}j-PC}cDgQc@We5_!&b zlu)6eP@z4fB$d%n{qEntUY-{(p6A@>T<7z7zqf6IoGq^;oBF(ms(l0C*2YOVe8y)< ze8FZ+_qE66HKVXE#<BsAi)-l|$gc%WP2PN@%Ke1J9~JbX2NgiMt3Z%}Zb-#yX<@ zI2XRLIF8MXD2DMvWoX6c9Qd&LB0A`+z<-NMpeH+;nVy;l@=lrX_R6Y~j#YsWSK$Dc zL&ErozXTp65UyFUoTdEDl4y@DAou+`AX|oEe)dtku4#yE-=rn_*RyHD!#{A)Wg`8) z=?(0(i^Cv&fxff9$Yp-ya7DMWww3D+*>A_7d&50eKqCT{OiYN=R5OrmmJ|u zRW7dIeGwkNJ^{)XkAQ+h0e+g1)))gR6menZXYoBZqs1c6AO-}so z8wVI=8Gs#U7GiPxb?`|34O?E7LgkeXwsu<{J{I!=pM7kxbFvAhZs;K8y8l?6ZyY(O zX2jm>jYZAVx%kg?8z}fk;pzzmkm|lte3xs%M&mRx`s^20H-9p*8UI(}DZhse?{L$D#c9kt2nu;FLU&zmGd$6$M9*oeAA!C-$g_3@k*`K!^?9IWM?303< zs#6r0Uv6LQDn{CG;6H4`zwb_UkhCPJ0UDHyT67Yh8%kX$&=#yqpD`~XsmM%&cPs8&uz+c!a3I@N%Qrj2-KK#+ePWd+M zQIQi}H}i%5!3VfW)n9o3zK~bQJ)x`C6k<&JP82mHb{VS2K`GmMWLt+$Zw6-TZjf%cu0z6>GY;>=;=wP>;pDOeUsUvqUP36%l z6;OO%ip!rg#agw0IHfg`Z(MShw7+x0yqrzgwkec-ci0bM4L86mObVpazOkLXN_6|) zMR2ER9zU+M2jq;V;cN4FJXLfW!^)b_aos>x-S8BT2MyvI8-aW`cZJ9^)7X!gWetjzhlm=}&waV6&5j{{&|W?n$ShOZ@@q6TnD`KWt8Sq`)o1Ywons*Q;biVP!IGbSdJ4bY zb6^F}pMz80LU`)oN)^2Jq5h^C$@pMPS|`1Y_M5$(=KaU%^(z_lOkxWcCU1jDr{qe^ z#$DmHKZ{`htsA_tNQb`fK^U>N2)`8WDQQ{Oj7^Vqomh25iPFW-nB=(qi`lkZ z^Tl@5_IBh=F}B=ZqX55__bb&&lcq_j3DiJ4ng8kD%MzmNNywEkG`nymrsRy~nJ?Q| z#gcqpVb`B1muwWm8i2?j^W+^%6Zvk1J>2%Q5nVh%n}!EAaQks>aM&#cm)#vn`<2OX z*=dSgrRV|M9`=YEN6nNJ%{Tz((oMLAMK50We#mRP9Ql+_{b_)X_LuC9>c4t75HuyQvaVQ_#9Sndf^TSoFpBW|PCOU}2=x8^Q64lHVWGHeJC zxN5#Q_8fl%r$z1J?O`p#-u$85aYz6zIr)VA{C1L*P3lLL3@vzP({;3ZB)aFW?Ah{rw0rzJJhV=oCqW zoGm^Q?+4BplrULgEzk>gxPG6JQ$Yt#0K^1v!)wdXDjiq*qW zaX$QReK@sIJ5ERXH-c4L010)927lIdl6P0G5@z*l;{CVOlc0LHlG5)sTq{rmWfK-s6&#O$jyJFu zy?x2UkGtvc*HiG9dJa zAEOw!Aw&3jqm-R&ETUhy1kbvq;ow58PwRW!HA0cUrb;qoA7R!~tv9l|%D)Xo@qy4ecyzpjTLHluL1PG7iM zWrK|(KS$nwI6T#f!O|huU}E!edgbU;NmXP7BS)^0kGmqM-rI@zc3LorOB;bBE+|r^ zH5MqlIlEY~e}^D{Y66>{>jP_I-k`AlF)T?qM>`DKN#!;LW_;`%k!mgmBkyf!WOBS@ z=8x5UsntJtK9Ax1S{s&<(N-mz5aeku3j={jikk;clmli3cjZ++O-ogTj0 zO9~42fzE+sC_7wEQXFGQit8L4tZzyie1_wtZ~vjINhF`Nel~bCjo^JcZjtkDry*eZ zaWrd)hOe3Wcz)$ET(Bk@n`Gs=UgIjT(`#kn#rAanqP@&wf1YqVypAWv=R!bP8U9L1iL^AE@(&Z5 zFh^aN^q6|UN%M8^u>V=$B`-+EQBUj*!;*wM^LUoXY&m*q0mwE_NBwDsNwz{di|S)Q zmdy?1vA07}v+rn;g~N#P@?k>V?|tz1#Q`$rm@AB!VMBW4Ci3@3Hp0tu`=KW2F7rAS z4%?gB1UvOAc04|m+j~p1Pf_8Jt@4jGg>Ve}Cf>n}{KasMCk*Q1OflSu57)_XY^i+) zm;DCdbn&cfrZgHy{AVt-zq!b3KT1KzwKQ1&TaE7$&wSZ$%b<2}5gy;$pBFszV6JL` z+_rixn9m5IMOM4;Y0_-yC|JTLl9MoMO+G&_OapcAZ*U|=i5{Ne$f`HKbyS<0LC~xU z4?Q16w*76yn~q7)8BEv;DNTryRtGQrMi@3}AwQ6x$o{6qu?bh=(5+z)yq3*nYR_z- zW>^?Rk5Lsuo=(EX-Y}Ribp`b1oW#*R5n!58%!V!OfjvQKsN=3k&GrqU#p$Qeu5mpq z^teVA-99O#?$dy}{k{^pf;KiNBOHS41*p)wL$tn}B-d`el(;^q1eH}IurUDWt2_PR zVfPX2Y1M~|^+VurNIH4_ZZnBK?@lJ{%3~(o;qan*HjLYO7rx5{lEB@wk-fhPPg?6) z#A6+r9I_2pxtZdu`x7N9-?zXd!I>QCafi~YGSHTyEqNd~LG;OIB;cx5_qMPp5A)bY%?El2rXVnSh&+TYo`4KU* zr#VlsdNrL}WKR(9Np<0nwi4AV&SAGk{9zjg8wgQm7ibDzm9z{xj?2>($=(eGY|73_ zLh6WzBthw@{gdEKs8n6e3(oCGd1K% z?QbS;w2c;}l!D^t>2z>VI=mY^4b<8c;7i~c;4eSJb3;2;)I&gYiHPuyJNiI}I!MffN^jYZ`*tXjS)?CnV%>3^poc*c}kJnjqd#Ty{ z@vuB-7e=(b=d=tg zar=P77MSy;BR4=#P6~z{jKZs%b-3)Y@t|9+>9o$d7^XIc;MAGhU~q{s80s1U_Zp5# zPtwVwH;>4tOS@2Yk~Hs~G=)fY{$M`2-&yeRSkVFcn7r}m<8(RT4P5-H%p=u3!B+Jp zIq=~$5i}(@c-axwePt>+w0I+?9aQAkQ=~=ij6kNx)=4J3I><@_hTz(7HB{;MFnaVw zr}!-2%FI>0h?nAA5@D~#CyKd)g-67>jE)iSZ6CsqwpyX}7e7*FzlT}<5OZ)J!!jfez$wb61h=0{zbNU4}6Ubv6=ufl%z+skF$j`3A< zCi1!YW8uk%gQ)VlhV%*ZaXfE3mhLe&;kM&6X~RW7sO&xtYeMB<>LouYD(@B^Wr%*# zf63r5hq3Cs7W6exT_g2eFSFfv{B60>l(#hS+HxI&zLn>yIC{6CklPbG*RfT3vl;5=;JIv6vh*os#vuAZ4TF^KZxM}DPUc5 z9(3#t;ZKbr3$tkfrv*kN&c9qp3EM}km%8K2m9;GKO&HGd6Y5UVK!(0`eYy zCi>r}lBkvQ=zn!LV3g<^yL@9aOg6KJx2H}DV{i15q2u=9rXM?)?e)`ao?klcEO$o( zz4chVt^h*)rjoK^RY`~21gbyh3BKjWnf-@BKdpbPvO{W$@4>HM(wRzGKzV@s7&xqQPmLJCEf3@nOLcSmfRgLmb`k@Y-~^n8V1! zL5486LJ@y!%hU4(QryEp39BCsqxWr0VBLz5Xy8>RoLt+FPxcIEHtZFv_psuQvis3=i3a^O z&YBKBcol06ze4WJ6v6)d4$1tJ--KAnRk$}`B+qo)MFt#Gp~pRBxaHn#oHv`Z{S_9l zmwbj`S7Rt_{lb*z)Z?1HE1<Cx$2MSdzWuw4^0<>Uxgw4?oKhJ-wpKdbCS(^ zA)ak!7XUS`!ve);kfb%0gbnqQ*t?h#H!(cY`1Tv~=w8Q<%xRLu-kk_ul1})R8H{D0 zYq5I_+y_$N<&`@q`H~>$ef8s3e5Pzcmv5f2R(^G zcQ&-VF2Jr5W&U1t@%eQ6N%GX6V#}rFn0xeyc;{?F&(+-|@=CLzs#gKD6e82h9m*mlI@Ub;P#8Xge?-Y`7L~pGmz2l%r8jp^hWx#X zJkvW7%W5aUI{CAbZ)a*@p~70WFn$F(=KqCg7m466&dFz}7vRpCE38gtEWnDx+kcpS{dX2Deu#HceWsD``_F?%f)4R55?P=|B1`0eF2A52 zN9UNXq(@cvQA{zUm&eNSQ0M~>M~ZGwMP=L&$%*w_Iog?U37$_l4~50sp)L10*Emr} zm-da|3-;=ib}J%I|7J)RyIkPD^Nu@KU9qA4Bc^g)@vN(CG@NG5bP>wq=JHi$3*mQH zUnir)HolSXB5b@m>J*M?@s5D9vX-Lxh7%Cqv<@cWGSt+PDO*}qdYvm7=JD`E&UWygcn_ZkeP>l`1+?g zbmN4t@FC z{O%-3o}Yrb9d?kVH3~NPRltGVm8|vmMVuEk7RDvLV}V_F$jXu&Jhk)>TjsS5V=_XS zc6K;sZW#|!C}yt5{=qL+17O!pTjKUO89cX!Vujs)^t0GXc(Exq)yUIHvFVb!)XNNw z(on8(4HyoOBV`ku!KkK@^m#dfKUuetOqcqBl^xH>WyfJ0H1^<-h10QkHSP%o>8{r&R>&rg_) z$`da@FUi8`qmp37kL$3kE(89E8tfM3D=@8-(DXHOe3^~N&hah)Rp+66W92RKFQJx2 z#>7I2S+Qi-pd*kWGLh~qE0|$?6m-`Zw_g-BNy#FMFMa%exMOx%C@K zwnZl?`B#I_Ll2^l`&J^XFK04?>-qFm4UnCkL3rz9Sb9i;4ew5aywD7a8`|-kRv&t# zRD8|gOZa=m2^hKZ4j%dJEp~bS;|qUgW7CB@5Oisrpk6G_By2vxvn+R%JEVv5H+4~M z*9Kf5=7Pre4HJ&r4~Lc3ieP2w3|0r`L3*bj-$Y+to{C1G*woj z0acl7#!-us;U6Z^MJ>MY^2uXmJ)x7No-8`&&w6lQVJktbJ%^ascgSUt|&s zbGGBZJ$TO86289E<%UU@N&NNCFu6Vu4&N?fWjAj~n$7$0y6R`pTxg6PL*`;%x%2Sp zlnWkgEr6zLnI+Ck1<+Ht!Ibn?;UzE>3SP9pmoeEey|9;ftWn0`$!Qq8ww$;IxQm^E z6Ow9ITe#49hxE)6=)DQnSoJ_2){UHwhgM{=-3z36{Yhg!uUngn;=zf8im?~X>9mKofrt`^#7U*Oi7A@t#L zId;HW^tpWd10(D{vDvq~;A2=Dx{jBJfw#X4!HMa7@PXC5rhhyV7A8=dK4UJ0<=@ z?0y`Xry}lE?nsP&w}bqsV8^UWkBQBn56tlB8kCI9X3OW^#V+oIj>DBv>SZ$VeXU6= zWJI=q=|(aAz+up=W~S5ji|qc@B&;=yWfi0TVx?y&_6(DPqxo&Zr?6n=fA%Qqbk_)- zrJ?Ng#q;1bIsrD^6+10eGW5dLdycHE6ns4x@Xwz*)(H2_x^| z>xw@hJ3|KFKiev7akRksZaVz)-~?FvpbeK0Q?YZG#s*w}0=b4cus)-s}e_ly#vbvO0aroJtz$~CI*!+Bq3U#!OlYo zE=LXkdDRQ7|L!P0aP~ViJ=_naBknN|t$~z(TMD(Fsj#U&g)dO)gr6bP*qqYMaOrLs zcMA^%f8npLhdAzDFIk%2jwjg#uvw{VAMa`p?E`;;PT?0OGeZ`tOP(UT--Jb1 zbI?idE=JC+X2nCpNYOt5%cc$!q@7%OeV`O9w|@ec`)K3!f0oo}fCDT_Zy>vFj+NZo zeUW*M(&1531JLM*I`6VdCB4svK!jZ~+dkJ5HVz-n6Xbdz=dv@I>Eub?UU$YKi~Y>3 z`6L`Z5DL5ZDGFbb{rR@k9wBJPJv=pR7UXv*!k-&`u-~Ku;F&arFSQ&=tJnG??97$C zy6=UBrdfD(+I~pO70*gK`yeK!8t?tsj%WWi0edfSlV6E&BH9F(ZexO)YbD3!m4Mkh zS;qMvc(+dr=tqmpfa|-#E&nnK<98c7-WlbMZ-g z8u2zM6Bpdfuvco81T79a=2H61m#R&og&*Htm`$JY#7ELdpg43j6QUU&I#N)kitQC zkx6SQb|)|VBsPzvh+NGuygAtehb})$y5Dz_lq+heZ7>PP-O$2+Ybp`Xwotle5Iy2D1Xepb!rdp`W z{vwQhdxyxTn24;yucWThhI*F#b&M`dAY#D8QQK=M9W%uUN}v3Ksm^u~u&9Sw&RvA> zyrK!8(M<9V{vsn@s=%(>Yb6=F_c5>0jArhwlk_}0Cp=bI%(kEDM?0?Di;O~3s_{G# zyu|fkiifqZS!obFR^BTN4p>9_zUhR?{Wdb~cG21VA&5@NxCTvIHbeiD_HciUi`cW% zXD{{4Y3x#O&_1pScL(&v`mnuB);gJdYF3Aq#aEaTRmPJtd(geV4Xsa#fmWMl7;ZU- zxOmq?;(&cO{bZO}4nHc9+?6m!NL5qA=Epj>q- zsJ9;?&PF4!Nlz1Yy)EG9hF>9J>W9ePiH}LgxzD)pSTU+(7ogoncWSlF6ZH=a#7{My z;MkTe{MJwsiJ0}mzgb>ra5)u};*anJE2Sm#ipH=2?FPs6Hy5y>cMgxX8HjrM6Y0iD zqj>8mN3`q6hnHRl*vjNFG(0*C!yoNnv)da3BI+cg9^)Us5 zz$ZJ>d0!5lx9`WWHu1?>FGXWKQFyaZlZ4CK;3*$9zSn&wYaA9ScHqT%RO?9+Za!A@ zY%1c5Q(v)Rc9CQQ{$Y!fzTnFNvV8pDW=VomfuwZTI0xq|8rYU=$MyGD33t*pm`qJ9 z+7~L~$!R0W=-5YOnA}IK)!jn`?Qnelq8pE9Xz{l1s}V*|LZ{D0C`7~wEB;L3!2^rM zJf#yHW@^Z#WAM9IC24c{#2jZBa-GgTw7y=3@6Z~+o7|CqxHpDXj=hNHH3P{ru~Y4@ zFcbo|KLE?etuR(xyUVmTL2Z9GEU|nDI&aHJ=GIRzbm=Hz;pGfsY?%O77NzX;oQsl& zw-z#$DF>kC{I`<(2m3*c!$%=$u{xQ5Q(VvIT0&34S;%^N1pWpLXK%dvfqHHxvpDn! zZTh;S)lCHHa0gsJ=NGFoj3tp>J{Yk67|~1#B~PwegS^34(iD13{GLTnT{V`USzlE$ zt6WCpt2}4FSNlMwqBMQY@8h|VHH2+dgHYcg_;Jxy7(8hkj>&Q%4_A7TNjWXdSH+wB zzS|{s77NMllq6b-7;-$ReEKT4Ju6GBi7;l<2Lm7@Abq{Dgh6@NP>`O6_~qqJAbjb1^z`{mptD+gL_)2k!g~w!MPZj6iban?%Q88#wx^&{jPkG;cRP&Z?)<$nYWV% zK{djwF*$sNVKNCWmEkR^)2YR&eK==j8BTfChnD9Ja!Oc!4xY_WhncJP5kpo1XY4}p zuXZYo9iUI7$^_VbN0XXOXU(?d_OtuqJS**Fs0wlH{ET!kJ#2VrI6VY1<&6kl=20&>PE zVX#grnjFo;kAWmdDv3kw`G1#gE}9c$Q`{*O^>kZy^A zs~NbKHKMtO19Mxs9V1rFVt@3`v*@09OqinwH=O^YOyqMY9Qoil=btx@_~ee2+WjSm zqqTTY{uyDw`Tt;^R9_x#A`xP2!v$~g@6lzS3g$ltl24=GZy-84r!(Afj4!o0hXpYL P4#t+S zZ>|Hmb4m;Lv^~N6`62LSWqsUajH~?9(RhWS#6EihZM--O zXI7~4lFx_8G&4>78uAI~#ArUHO<(e_G!11&i?a*u1GwDn0sppe1K%ta%qFk6D$&SZ z%H=-Ug0!*<%a`5EdKSEd?%XISlQ$cSi96k*8ruK{yTR7y#zK_Cb+$BU`q658Lzoi{S5N zjO9VO&?<7LGqx;%%NNqvr7fwbTYC_vKGK4ywGo_c)uOjFCV;`YW6a$)lss}w8Q+UbEf3M#Cad}82Wwc`?o%Q|)dW6W--@hnf7&nG7!!VYa@j;* zBHvRe*_oxlKO80eW3mHo|7p*id{&d<(#veiIWunc_GpQl*ul~hd20t#ZMpf`xmda9 z2Yyf-%(JW~^YH%r>FNWcx$jIp{(JF!E<55D%6nFkwJQuzQ_KMw7R|%wcegW(_YYB_ zBoGIE%Om@m-6ZEHCecsBuAe#RH^0v`T%SQwn6$h}k#lWMuaLfsE-y5x5dtyA4gy!x!=J%009 z=mIgjzWUJxBss=T|ko)oo*NlYR{z8!>8UqvHo zcHk@a>9~g#Z{o?d-Zrv+V5=}9qkuMAx0lqS2^9WKf|g7E5dJwHZG1m4CtDXNbJz}MRvl!b{Bdv`zYZ*R%|w-z*{~up15@<*L)>j*tmIV1(+)W-3;RySUeev$7otEY?e4)D*_<51y1I8F8& zhfVp-a3;K-Ony3y4ev2Rm(&qFe_kWxY_j5+*4J?8!zi4!Y!DXI5xz}BmnyH?g=L4& zpw+eGZ1kejxb6HE^k1UHGrugtpP%lF&Q2db@gMv2rM*Jm z0Bt_v_$5Bz+Ch@Ii*gHmPW~E1;jN!8+{H7D$rz@Sk_V2EJT=_$%!LY6U-e0ly4e>D zynMLz-Ac)B%LC%9RFfBv-U^G=MscfG@-XRb0p`84<|C$L^|Hp z+3Y4EU-Mk4i+UEuD0{JHi(K;VaVB}>dx?yS`5+1KTt+~SGbNz~-@S6h^o>rW$L=Mr z>h}=Vy+{$P);|ZG@A05M-5%lMdvxzIz;KUWWZY6u$>!1hgh1u~NDn8l+e^ma({cXL z`fUSQwJj7!6#76#X^XBYZea0`hh#`m_9o#$oX@d^uO zc`go@{5GY%h9hB?{X8rhsR${hTF~d>db&V3io3-gXs28vuA4rXZU~&ptH)~L-dhTE z^Ara-9A|@lZ3k0bi*nG7C=eRfU1W)76QShxP=26xI#sreLdR7PaGmRXc67`}E}v;u zn)%hpY50;;+%8Rv&U`EF6j)@#mpO|3nRtL&%|?Nfu!J1 z1K;s5k7j8;BOgWY2J?BsUO2^z+#*?S&^!)`BA3yUe-D_cUITf5LLI%MLa{pg6cdy@ zu;gSGIemNv8bA64W@nbs?MtX&{NDpU^;RP7FxBQ|-nvv}<|dF=)Zop63H`f%I6vri zU2x5c!#ba8y!O73*tL(MzjvweoH=pyfln0dX4CoS%3R1CcMqei%E8%X0Zy5w%*Qy{ zQtg_7e8>z>UY4W;W_sJvd%#5ex#$8dI69V}8=^-iynG7l_BrEv_wOwJ>Tx!?bt5d9 zehr(M0bdcl1lp86aZ>plUU)Ww>1Juc=~PEJ7P5p!>TkqnY7#J9nu>ZGhO$3%#>2N` zVG{LO3e;SS@z_`>Pqz+0n8zcJ^3&;OWfE_HQXM*;q@h zm)h}3bB@E$s-e7M!E(s|uLk^0w$i~5UBpbHKTi(oPfvJQLeZvB`oZ>+gO$!kem{RE z-yQW#?6+9*Pi(<%|*l1YUC1!UAdGYQ@E#kBxpCx@; zAz5-GmfCbF;99Lk#p+cjaQ%=-x?92SN=#YDV!t!y-UIW z%KN}3`+mHi{|SsP72kh#v6z){0Aa~{#}Tv2B{$MrNJgkTY|XO9jr+9duBBIefXD>gkw6cv1+R@);BDK)QNtA0a@Yfu!Fe1B-WBw4{k!k z<~Zh}SqE~lp$TX49RjxW;o5_bCzSr(Ja;%zkO`kz_!{d6T#VS5g@_Y)kiJ|E8CeiHX= z^EE-ym81PxXL4oSN|-uXi`*{Ghk^l-G-}69bQvJdllG;;&P(&@S?vIMM> zoQC~Fi&_2qFznqR#kN=H@zjMuG}PRO|C*~nz2bM`FtY`4X7zC)TumBeE@~5-(+Qv_ zmqJ8vDlV8JJ{N4Bu?dA=ancHV#9}Ev;if5lw5O2WtyAHD*C5s{T!5-JeZ+iR8*x~( zPk5(iB3#T+gOh4gao)&iRP$&1~F+|?UMQS(A#O{DPVq8qr(t3vWr*NEIZc@jd`&V(_g&E!i(8gxlt za1_q;hmX~-@#V=N{17HXZ|!@6k+q3fZYpM&8pXSG-zV5_<6y|zDvy3w22(Ka6|9|2 zL19fVY$=|Oh2`%Av)<+4WR_Oq`t}#d*gj_cKe+Ifw;B3(9mn=iIc}+*he=-#vA!{b z=sEiaERL8Bu0>zLdXFa3RfR0KaVvX%aVYI-97t={C$WYF&g}VbWl&h?fT7t6JYz!y zrpzxw>G%dnZkOf4iMvq$y@@Q|f0n&z_ClL+%dzOYJ?)4KgN*6n%ro$XFfME~WUI=- z^0rMF|8fAI-SrV)*W|(Ps1|fBeMlNj-->IU4A~_28jna0p_IY^>LGoCz5nctmyCSi zCA>tbZ+2W`Q6k9d&%tTEv-rn)57?pP23zy`3K5H5D`PpHifohRe%@`U3UMh@sLf8w-#-F=eaK0c8|=r!`uKtO2YpsL ze=Iqc6$We0jwT-Vdr@=CO{_J$j*oAgXRk*6llU*Yg^mA8K`Z|nv`kQg!AV7E9xuza z`&yA(vr<^b^<<&NjZ5nOEg(McjB%-FBw0KCDa(mBN5@AO$c^V)NadCwcIKKZ{k7~d z*^(ZOky0`E;Fl|WPP4<#wwJ=6t8dA-F};}N8^MH>)8M~M85LVZH&5X~ve}`ML@djK zLmP*KrhkLv^FL**v9DlOqbEYz09kYn8^QWcG^ z6MI&ZUX?k5fl(Z;Yiwd#cGjrzAf0q~oD$})9nFkuZP43!IOJ6~vdaoR=)G|%j-K!m z3$`a>?{7ue96txVFF28bT&YkBoD_9P=YIq)6sqA$&#S%JTMq`gs9A9Y{(K_ zGIwAMX&3wABmKje?4~64xMLVAn6Ma@ru@alt%sp$Y!GVnxWYzNbAIW@7Z`qPKgi@( z;lO8`@bc9nSULJUF!mTq;_UI`d1&oZPwDX=-*0*-kMC}VQvkd*XKe}=ONs4yIXSiU?0+F?J;u6yNaY% z74lCq=KQsa9)Ea6hg%xSIc=CXo^SE62G9L-M9;|=UV6QN#f-Bkwfp8pC$FfWw<1sS z`9Bxjz`bMpLpC=8sMDO~HD%8N$5L;2|sFl)z0{OJ&d z`%j#}zX3xy5Kq{#PK%$a&V#X5(rnLjcP2ex4Xl=#!VJc&B9HuT;`7C$d4{bj`Yx8h z`eZ}AHEce~(o^NqhQG)&wu_w0>J%apPO)i648Ts-8y^LPW7q)!S`FfH>yKmxK?eM= z;vU?6?I>Anvy#23-baSyFM)Rp0wohxXApJK|3tlWg(Z?6iL`V(MjFWQR(UJ%^w=v{ z4n9lfp0U9Ew9z~=H3^0qDdB3D3#8ITo}Lzchiyv1tnpp~n@y9MeQ`ItHFi8opFcxF z-3a)27BhEOZ65Ji2j1l_;PXd&LV@a0X8yXJ96m9gDrHzQJLBmv|L82T_tz4HHRmk@v$^g+rWn9mD>#3X)9^z-*gh z%v_!%%o6ZtsVOh#XCOE=2mjLw#9BLTE>-gk&0jUKol! zC9<(r%(K8(J;A8vZw{5Q`)NW<8|d6@B;^f_7%ws{gB`}>I?=Z~P=7DeO=@NqUsd3> z{T1f7A&=#rYlYdLr{b`48Tfg`O)~M&QSf_eMXzXjv-12?js}+Lf^Jy4;8vC=-f3%M zteBT+4NjFD%%6v==wNugXeC5%6P@GeAo0F>0tekHhgW$D^e6jByeEc0UfdqCY2A6p zDIXPCK%5D{ZMZnfaX7fC5F{|F=xg>*!?$= z5pb)3c>?WIfXNY_6WH_g3 z0p^pV1k2I7aCOan7&<=~x?Dc9vwwPF%HI}|N8t~vbIPdxUVrNQXdt3@E|knV0-0u! z&~2Rnc@YJO(o?a=H*tAZW5{;KQ z-Z&OiOVXiyo)4_s(SQ$5oyI?32Q!E4QJA;#D%53(_sv;9N!N~WN&Ndej`g!w;kLlD z=qUcYDQU-X%<{?DLf;8CaOcREhrz%Wc!fA zD_ezKC$170bsNU7+fV8>YSCqo8}6x1fV=V+AZS(s23~Z6DeX2`-((91hX#_}v-e;} zNGFL~c?^0wFTgbqMZ9MuLti+q!o0Mv%xd)j7BTxD8T{*w;4#(|)tgqp?NVoa+Ik%} zJeS2&m;G?il&z2|x;Yc4J|PbJ$H-^9?Qr3BBxa7vhI=Y1aPvnMY3`hcC;HsR<0}&+ zbZrmLC`< z)FXwLe_6ruK_cg{^tMFHe-VtY`F?G>?iUiAWC=C=9Wxv22TS}upv=>wr2EiG_%u5Q z-t6i{`+ZliI#-HrI%Ew$6lHL}Zy~hbc_N&fUm@vhvJ}7PJRo|fgWz5N7TC4o72cnr zgRzOVpda54?8Uz76RlL?!@&};ZLTN!Kl0eV{}>p%FQeb9UcxtG#-$Eq;;Pp>#FJbB zlsMN3ZDyZgYKJ==8oL}GH+BiaUu)czP=?p;yVKyloy_y4BOQ>v2ZMKX;MiN~oVGrI zw%?av=X8C(L`}d=vzS`oW35JMhq%UF7hkMDpM-C4r}2f!db= zg8ZOwY|`oB+`ix@nNnfL25r*@pYqL+I$#^vL`$=cN%`pEZjA503W%krVbe=_eq-oR zY|--dM2ly9B3Az zj!MEkO?$}p3=?=bz6iRu=z#v9GdN@DK}hh-kZ?z7l(bJInq?yIdq@bL(cA#}Yr06n zy*`-!ek;sWUWMKl_rh)69F%o)g{v#Z!m-ZF%y6A8xz)57<)pueeuZ@~`SfVA^~Pn= zdL|O?r}+wBQy$@r&?Z*6ER}p8+)a*%Zj?LM$BCLrC{LCnOmq5{b%8MZ<_l@%#P<_jO>eeFNnuYQ#h)%9M{%Y;Gg!l%)W6azx7I$PuRN*jI$kh=kU$&xi^mx-3JgU zIAA9_+X`$QTWB*c#p?1`WLo7>y1CwyQOXe?p!~6w? za6tM&l6~|Cne(QS$=3a0quzI+mBcBmv7Uw|e^s$Z|2lS#O2omAelYmpWnk}DpkGTG zgm1JIm${li(7ilJ?4QA+I>S+UZKp_S@ErWI^e>xQ9>jm8y@1D8{jjB@8mCNEp{_xv zVeGXyQrH&8+<&-}X7hDy@!ln*q^66^GI&S^dM$;MDdRD8V+;fa4(HE3Z^636I@gd>q2m&&>idKo#C=SaNux zNaJ$P!*naL`1P4j81>1R->`I|^9L6}_mU0h8(4~|OLxM9>k9l^yc#ww3xo*cN96I| z2W-ad&Fsa>9HKf)f;zoQ=I13AF^zrap!$L-9RBYhseI5xIu29fb@-?4{nwj#R!<=Y z*Cvr@?Y)Ghwy+BGaAAKc$@l5!@;f_H=#3~%Y#4iuMlI~F)R8)-j6N+x&T*3>y@saague0o`e1awPb3U z9q+&74Zpxj7^20~@<&Ip_UtCOpJ;=#4~4^?stQ)o_6YKi+v2z+e>TKDng44{ATx6X zC)Of0xSAu69RrVxCI=qI0O!^8y7XyQulrw#M5ZEh{Td2Qwr8Mg$96c;e~k=_TW)*mq)y`k^pGU<}VRUdNu=I}xYH`Z&HLjj8_Ggei8L1Wrr_yK$kt_qF?$v)WK8Pf@LOE~ zY5abjxVBT+e(e-1n0kS%h(5vYpal^iJ>>M2fuL7DkI3~)kn2A$h>F{sv3ct~(b8rM z9NN1X-fYs~>zE%~spbm`B?NCC@q)zayVy1P3#v_WrGMw&A!GjyM;DKCr16F?+2D2_ zbryxd9e-W$GkS~Xmu&;duU#lpsE3uGrois2(!9B4B3HQAOU8#h zo-6n&tCvn+cug!WEC(B*quzX#6oe)reN{*Z67fAnV@1=FPfoc#xhKJ zvXK=22SNDuN_Hs5%XZ%C7SUjb8Ek#W1@Q8==0k<&+L$CwQVGk5-#$C^ z9Jv544j;nh+Q*5<4vNIdl|na5eK3IkdvbreJWky;71I62LHd_CG9;iLnkO%12ix)? z(6&lsa`*^r4p!nW4hxhUiMezgdcv!D6+im$xtn3r1NaqvK@ngt^ zJTKT7GKNL$?It$Tvh0hC91N}8i5fAL+|fghDHiEN(IsZLJ=K(Nx%v>NCfdNsE$!6w zivbKj@LLo|L$Fh38XG!K5@H_Oz<#e8#8hfAstirwx}QgY*DntYJw6(L#s3ifl6{6n zo<+|&@2aBzhhYJ70Kca`9%yC|(DqkNTOgf&+f!xmn z;@5OAXl~ts&HW;F{!cZmJ#ZWr-oGN2@x2dKH?(-!U=iDPSW{qf9j1IDm0pjVV9DbREsKICd^e`XBU8RQ7zm4&|ADQ zuo5&Rma^961nu>1uur24n5Kq0=2>+x*Yb9z;jV$#Q^Q2sdw;U!YL)Q$oF3jYj3tdG zk|giFJ$CM_1j&Ldwoz#~X{mG|n{R9+vt=dN+oN;Qvf()?cX7iL%RAVPci9*-r5bi_ zFK1^q^pWO-sYGAZl35uCpv@{jfqSmciVuxN5<385-%TWvH}2s0761t;4Ls;SkM_+> zhi8YD(G3d~Xxn;AEW5agDz6(0XHQE&q%gPjA9EU}*DKKq3*a-)*7ED61F6c`S@_?O zIn=Yi9Tb`t@t5|!(0jxQKc|eremG7VXK>;3w1W1mM|fp<3(=1nPf13sc;0Fq{&%|_ zekr<6+F=V_w|y#II$e)jubK`u3o2N3OuNv%pO4hNfvlgakDn*Jw3~A(gU!4-3NAG1 zf#oR+E~8ISA>t>Qsg^<~E18Iv?mB~IKYelSWNCPB^&hMnca&-F0XyZteRz1Eh-q}H zg1wjEA1+w}cYiMyAC*XBX9Ab961Q#ijg2+#D4oe{N7b|CmOF5#u2`JWWlT27B#;RY z&!aMV#A2_T3(mi*EcVPncxNgJ|DJ|mq~<2l8X`%Z&TVFB5bmx}bx!>6`+O+rr)PwIqhD z8G|bCg;`(h}~|j7ynD^BBlx+_);yA&9X^hYU`(B!m$w2JHC~8zy1Px z1Eev9`(ncfZ#2I8nRvDl8 znOM`sm@KDxj0#F;wnYyw1Lt?y-GQYTGkEwaX$i846WyA7;!q7|h+;5B@YTijlyJZ49+b3Fh&wc{(J=@URURz+YZU=+&!k+Q# za~!kPU##3^MDuEdGw-1}v@9LKU!3;ldb3{Q5?w96@$GT69FzwapRGhk^G=2`@gU}x zSWP1bPenIOi}WX_H^$Ll6;mG zemZq<>*NS-fTm#kU54vu%R+eEM7*SX045h+q6!APQES`|;u#VPbyAnf&Zxos%$)I{ zc)7J=i)?$0oVNlZE@ud{sS|>0){xYU z3}H9-Y4btbLfN(nDG>71621#N4U^I`v8Q1+&WsAh!B@*!gQ+UsI(`jyR&%lam{U+R ze-Un8b{OUbOOP?TW;|KQDyObF1~XO_K)$2EfLJe&$Go)op3$3efyG7=`@EG+lx+gN zvT>MRZVnd9O4*{6lQ3bo0r_-En#&g+!S8Q0=zhhcaN+hV5LJE@7^^D$zXMY-IB+nm z8lcGC3SL2RcQd+cSde|X0s%m%^;`TG(ly&TKAM5nm@lPkLuyhv_8V`B#$evsp<8rV;S_rbGsg zI0EX~L(suQitDaAPc|t2fnV!aLTIg^>M;9;g;}29KKBZo2z}4;pKQ{Lk|u7+x8QvlrKv==v4I zF4_ggu^y zPY)g(!zRpaBOxp5$XDB`a8cnRh%<-dBn=ysTDBGLe2#<{X2IZ67KTp$5>QoMi3FWA z<6ZL0@%W|J@Nd;XxM3?RN~lT`y|0@Gzq7pHee`Q_tC9p{z26JNPmhD@ib!~Qc?9-H zjpQxYm2kynTkfSVVgj=L| zdoasY!}ac#e4WR9TqA15&r8;@eKR&PN}GZ*a~_34`f$Jmn-gWw6>3QN^?@FU&R zse!h&;0&!2Sz6A;-GwTmjqiSg(Wc=v$!b10?m9r9MAj0EoXIFTQ;{w|Gnj1J;stH5 zb6B9?Gu(x$G~Lt%MuvT=Z6XX7VQPLF)A@^n93(ObV&oQztX4g&R!!Q z1h<$&+GX4;SI)n_&LofAqaa*hdX!%rh0`++ad8FE;lpC_TIwO9Jy_^FPp%QXLdHCy zZm7^9Qp21%S4o!Go28LDeEt3z$PP$=Cc))(b&58xq#iu@RW<~TmKJxGEo6&S)8M_a zIrCBWf=l)qy7(=-0eX9*qeCK{R{ZqHerEU z>hSDR39OqSg_obku#NYQ25FPh%?QJh_)2Bt!$qyB^7X?E7<&7&@n_ht{+gsy{d^!hYt^Lj!>;(SwV7i2r3hs@t%Gd*66PKRbOEhb8&*mTSXV=iVr^-Wtm!8*4>!Cz1)fqQVQTG-%3$ z%b+2=L#Q`PQsr@-*pXNUFgk)i`t*`kN1bIO7ew>EUm0R335D!63Fw;c%x($y5w*B! z+yT6;0=DH^hUpBY4D|Zx|-@tC_u!LrZYw z&Z~Pt%WphCTwf(#=5I%P_zu3%Zxl7GvFBE^mc!wUD|oqX3a|Ha<;LsVApY(al=0X_ z>~eK%7nvOZ{nR9IP`b>O{(Qo+(wSKD-hhu-sX_M*H_>E)4Hs>)97oBei<{+w zAmU7wxJhdiM5zqm0h)cxQY7%6bPw?nn-fH{28EN-x=swR{RB!U9GISZB+;*3iVtpA zvDV+x{QP7ixa~LqZ>UTKvxMKG3k4f6cK=j}SI)tp1+U@f{-ZeHK?U}oY$gG#4dJqo z8@9Y4c%+WcBO=#koZh4iCMKCT9M*>t3;7flSCE0}Ds^OB@hEKgGzs=N4&?Rev+?*l z3y4YhNA&*6Q}>d~I67lCwEXc!j2w$Cr3$2CV3zoS^E3AI#~F5Fa;bR21vwOsXV!LR z1POR%NoDmK$e9URkiYIM8S#1+%Edn-(>ELP@gM#1zZnOiF76e{jhzK6h0NlLnj&U3 z(;UytQwEfDqD(e~DhGsP@cAN8-g|@X-d9kv=-nmuJn}D}u{ue(pS-3P-qYyXuTij1 zYj#eqRq2iBQU{e%<66%WF^4I{h*aW4?o6T@u_BQ)5 zrG>CiVGdNc4`IWsWXXlc1945;8hS(LDMa@Tw0FL`91o5<4I35*5pUxK{9bplIP;-V zY2)Ja?C8Y5^mR}dX-^lP@PU%^cT}MjU_oc zXITGb1K!&r%&y#nNfqCR-mAuukE5CxZ+eVv`jI%Pdllp-9z~bMC-JQDPJFv!F?8tX z;srMoFm5==Tr52C;>J3dy4VO``ac(cQZ6G8Lk++>Cm8MQp0hQZXWy`0Sk6Wm<**Y` z5;#QdCDh+e$N#pB1kbU;ob6`_S{fb!kD6Fk-#>_K>YXK8*qI2U+DEf3DbvLFXPhSA zYd6BgB|dC~zYdSRuTHza2BDqk2vih>z_8E;hMUU8o_g-$PnjMN`J_gC;`4kMt9}eW zjT$GKGU^SKTZWVOYZKUSJzeg!VGIqQeGr%Yh=J7&B06VSo%n{>8M6;~LDuc#;N~KU z>aDlgyrz@5%X};0Prt#>Oa0>2jZ?|(TtNBFderdNaXdbyfwf90QM*U2WQ2wSi!SYf zi!Hk#Xyz9?lTV@e=6fBUFE3}qqvh%BkfZQ9cMs?c6?XZ;jC!3?1lDeTg3I;I*o$L( ziF}Qm*l5)Ry55jM{DeZNWdx@^$Uqy}B=QeEsn=Qt1I`}?t5Ll`9L|yVoZ*`H0PPHu<)B1Ay{RiHw8ELrP$ z07PA~d|!tuf4?vnhikk<*V*RuS;A9drcGhQU3C~}7mCI6ez9)pBpP{h0`1xM5At;u z!PRYxd4Go@HJ`o->UJfQAK9+FyFHD35aw?BSM~T-o8!=%I1$o{&XJAp*5dMikHI0m z3TS`|kNG%V#6Pd%qp}K#%;R`6Xz*zAR(>Q-s*r}*6)|i{Ngl4+@r5Wgcfg>qMYv!w zV2Yp6pOx*y@!!nx_wr=2U4H?$4e}+klKhC*2MKX`i!#c8z6%2*W{Q{P9~3yCD@3Cz z1Xk;}`9!>B0z3WKMHFTA41FItv!0s~sJz9Ho9{V^YCiem$$OU(E347yX1W#@{W;49 zWekFfHZd8z_LksQ^nus;XGC8OAA%gM!nU~WZ1gZUd}C6Hr**XOB0bD{oiapUyF*cb zMgr0MGZ^%HCA5qJ$45R$bO7dwO)Z- zmy+mP<{dn9pq-q#sEV?Adi2Bc#UydmBj$NGoUFd+!F_G zMNJ7=F;tSWJu|Ibouih%pvqIy^i%e<_>`_pB#nfZG^Wu}w8Vb(oIY@Pl90*PT} zvbHTU(FJf?bp%>lYw_%*is8wSrra+&J8vZueZMR&QhH9B{&>QEiNX>GQ4Tp~RYh71PqC_Tfhfa- zyM_KeQNyCy^ltkc^voDYV;&pOQ`V#DNyi8bd%lkSj*x+nr6ZyKpgUf=k^}OK9bl>I zWwg(F!T0YtfZ6X>!PA#}h|#@`ByCO+sViMfr^ZCmq-TN`J4TnsFL+EW$G(H^!_P&{ zAqu>C?n`<^V5MxFTttqAJ!4mo{l$-`-RYc{V@oet+`tEt6Y2HV7@}xkR@%0G0KNKr zGrf6U4TnAahX?ps)Jd&`Ig+bT!mN{(u9Ku+KilxWsdpf6{969I9r&MCfeR5lhx!@K zhKr`5%&JJdp|y*wf4_h|d-)ND zO5H?{pzruT#uHq+r0~-233SHVJ!JF!kD|xXLMF3qoajP{GEPYSA!B;TRf&Z8UFoz#j>{lM>KXP!{iPv zR;AF4I)`gXT<;q6@wrV7q{@KQQ9Udj#K`!UZ=wBr1o>Mrm|6@L&hWSxxOsUGd0M?6 z?Djk+4Syz!LgWteHyI-ck1NIa(gmVMfdP;>=?b}Z`~&=I5R1;16BsV{8a7`wrRI}^ z>7_}sw5riwTyiEJzARn@eew5U`S{~t_~#(K*>{Lsj$6l*zkh@0AAR{km(j3#FGV<+ z2(ESs*qM0_lCEvy3YwXCQdwT;+#GBr=n}w6Jg`g6*$jOmzfJQ zF8e2e_&g$&?~cfTEwU#>9=n}58EnPtRtA=A%g%%kpBe9z?G&wZI*P7xhgklD5|Z`h zJ{A_slj42f#TO52kf1JA-Wbsj7IP8ZZ(0-o{)=e%#nvuo_*6P#p)S`gOJkDm0`H*U zI}5N0g^u_qBI7Trcz(`kQSUH4?Aufh{o4-Ho%agxinI*Mf6ox*sf5`^soD}6+(6|VXP2xxF$HszAr{=_s`^5w*mMG zb8b_CpV=_&yf|ygSU_PvvBEQD`x>lHZB}8nV2KoziiFs{P}{1|3s)vQi3_KBdXWj+BLTqdKI%FHp%m9=x}viX(F|*jt=L<95h|sMMX%-d3bong_uHpY!$Gyl9y}3AquC@FJ zJ_3JeNbn)>xI7%f7Q3-vy^{#ixg}G`c!6cQg8ht`C-PzAsHwFz(YRB>9`6yz4#`cV z%t`RpC%4en0fYHerM;jL?hOBpappUsC*rGrIb_!2barrkKKAdk#1r!zMO90t!-OT; znByi-_85*M_j--V(X~F*dHWsgwALjX1aIu#VbgHLmxq}6YMou?K558tsmI5@r8s}e zHQY0QDaflV=R2SEf@Nq-J9<;_}lB}*ySmS`1ETiFPA$i`jm4J z_w=2_lT~y1*#o&)tYF7`bkng$b0|IJCo28+^9Sj?7z{GyCH$UQG)5^(mOgq|#y<>s zhVi$L!RsqlrR9PvId)Y7D!Cf)D>@F;P30sc&)28CR}!`DLZI0DEZN^uM1r>KgKlyf zYI+^vDj9uf;Acg?ojZm@-8hM?7>a#coM~v*0NQc12;_5)K-WP+D>F~9+ohXOy;FiO z?HE8CE_{W}pAO>dZ?W{&!d#+iuLG{9CHV6A0Qy3|8P+Zi1+F|3IyVZe5f3fFl_h)+ zpAC57^Go>6!i<_sj-&Ud4}~gnLi%Ek>98Ai>wCo zHB2U}=apjdi<_u=wx2onCt}j8?_{CB3Z31ggS`AX?0IWW92R-ud8c*Q;P(Ke9qY;F zT32w^Uxxp!jb`t?7VvLpwE6F2gJ5`tI+Lv4DXNPc!rk|)l94Zu!p)$kZ0o6s=;J<= zkKQ#N4z~zyfMWlz_%d_4zKWawOXhbP=kUYD&h-5qW3IoFvCT)) zptUX41Byz}PFBTs|>O$ep%A)a5qvtZFoV-aUn~{rkaXmEc|oD8Z=WHW+~$h;LLJ z{Mi%(hG*W1!j*jJo`i1kNWpzD=-zsg{d7B(gkv!Fp0I}ym<)6OXwkLD9)W(R3A|LZ zrV~ut+4^ng!GdKAj!t`MGF!>Y63Xz|bw!@H+_L1D(CLl5TPWU{?vMWl9%sj=nA1g{ z8*$Ib-A13)Bh6K_Ya>j;2w~-xQJM|y@N%9olTVmnHzA2>TKsGj3&f-e1 zzmqbHwUEnPFk+vGaXXRQ%${+~!5T~=*`9lu&&T4gn#@b%l$}Dw zVGJ_O#W)vPqH;HejFQ?yQlk`@ddm}bye=Cv!lF^+C*%qDAv%571uONaAXt1U=Hf;QQXs#7+IK;OdEjvbwk66RpMqU)f=x^#@3g%7pIw zC3Z2P3^Q9D=??WE2wu}nE*WdXk&8>wENMPH>#j!cKit5#saKETSDcoiSiE zele5|d=7JpUqV^K5wJgRLH~WaO*V(`!+0-8Sm)g%?i(*pZ)Ai)U5Bt!p1zLId1Fyt zw-D>z_OV=rCGd7x1N>*uj2klw!ACiSrO&Aq`}##=j@2PJ7yX;GUjHf@IL&~j-=E68 zg}mLnL1I+4&c{>Uw=v+!Jece&II^5)q2v8p=9Fs5D>Y>BZb=u4H7=8a!msRO$S(Gi z$ia+m8F*^99(LXyO8qt8i6@?7?Dzf#(jgfu3SgS}W>%iy9Qj9H3t5Rq`v~5rzl7Vg zgp&~Gb^L1cd!Bd4mHt*4$*%-Xgo=j)uu%6j|F$@Up5LcTtN;1pq3u6`Ow{6MTRbSe z*U4uoYuG2ve1Ml4Qu)knMci{I&<$^Oaa3YBta>nmu4_@_?g#B*@9m#3EyNPu%03ap zRa3rg-D0{mJC^@?>OxJcKZ5V}&s@}ESE_xsg|-R($Y{D6CQp73OV)Ps-fmZV(G>Xf zSIv-`x{9xRyN(~P`3U7SFEP?cTe+(<{myX z>NzTXyM;HCe)0g33b$HzUv$?n3#|S=fd>U=#aWxfVD>#Da{7Zk=uVviZ)4uG6-n+? zD|jiUO>e`yqa2~RN((H1U&rVgV}4J$9}eFY-aA$g#9p5SP<&b>vI)(B$FtVZ;M%iT z?!EoSq}pZZ>9~X#!zku9QbZlo&Vk{RqwvDx4gOrOMq3}Wg2RcG7`aY|4qIVKLXRw^ z(>+~5@$FsK<^FL$m*x#6H{Y|Gx^l5YtCM-&T ztBQNEOEwk~ElxqR&K=Y_aSaA&MDXD?BiXQIW!{=@jHyZm^w{dRup`w{@T~s9#5dFN z$;VKB`rTV*v?K=0c5KF7xe_$<`FdVwK8_A?*QE4&FlIX5!K<+wvCBUb<_@W|+wjnZ z&fb59jdCl)`1a$_H7lIXVqH*_L19$$Kg_PUi#;D-^A~AqbZzTixc4s!vHdrHY7xld zE;eDL(A(}^yOB=Pis7O@5jsth;IC&d!S1M$pmj7H?g^cAjlg(na^cv=Atmb!Wd};^T_Xt=XRU>QZT4%Dpz|)#cx{W?Zdtr@X{R*u=%wtkmjMH;fndtWu*we z3~E7h*+jZTbV2OCVmRMfdq!kczd_{FeUL{APAQ9D=GbvRiOTKi!B4Zaxxy6%sx46s zHKxKoBHn_mc9}q*=9|;r0q;bmo;xvC?(U6S-4k(Zz#@M4<3$|#0Pt9mCiSUUP0G?T zcv9&FkSb856@FQ)&_bK6i%W&})I*@Bxd3J-_@mWR&Oz;IhnUWab65lpXEoho$|5u)l?|0_ya2xqj0<9EIQiA*ABP6 zXW_l;MC-OKBX{N`v{Pa%LeeH`9kWO?8;?DhAFvMZ)oCg0I^` zl}>gXiLrZy&rod6AK$73=iSYyHRU4D_BaFyZJo62ozgdHQInb&O15?^|y;~6e;os5HiJ%K~TzVP7hJ{~S#fKiVxu(AElJf!C`zMp$Wl=fI~ zt&A-~kL-Ln?e>S5&X6QaUKrA=Iwt(#$}RZqi6xb6izMIMt$1h0dVWyc$Gm)1u{UTV zgPUUU?c^*rXLqW=CJcmA*}ut+v1M3!8ECxVG3#qgM8n8|RQf@Z`03d^ZqZkaisq+; z9?4gbdE)@ynK4Y~MJD;;d!I>6&pYD5vun5NZOQYAWt6*`fT~s6dCy(zw z2sUx6VT4`@=HI;lrw8qVB{spZ%xM|x8nIUtJE4I6$T*HM8z{!!--2&4V$o3EfDRC6 z;KSz+aAMg*=x>Q2gRURJr_ItdWT7M5T$|6Pq*P;}!hPsIP>Iqc4;Rcehg7wA`tnu+ zTXB64w-+1nA48JyT)h-G9~K4=s|Ql~I|3gl`3X+kd6ZU~^Z}XChUI&Q<4eUg?!Rv zl#X8m-p8W2X@{=ZMNg4#X;Pt6JJopZh6FU6x`6Ms83{-KGv+^%PqDj)tso#ZiR7uA zuzT_+LA=~$6;{kUMgy57mnn|Nwbw0ZL6)~N^ zfR0cQCAvxQ0YblGOr|cs+SLc~w%%Ab?lv=+rcT=%vTzqY&qh4gQ@om)Y_wYSV1n{Nn|tPd|KhwSk`x)8TP$FnzgFntzuJ!3yQAm>^Q* zuPY8S(xk*w9m2uqv^-rOF7PvaH84V$L&-H8!QPNNWPD^e$S0fxOSdvm@x6pD7u;FL z(6eNc;?0sx|1}WzuRZutdN`OU$%9=~EGysm8G1+j!{-GQUTpXz%25o(Z@3ORt~t`v zp3|92`CqbjU_BfQ9E;O;?Ll?vIvjI7k%VQY$MCYUdmRd-@mQxY!IPeyzwi zkxLM}@QK*Zs8rM)w~B?iofj>2O2^}(BOM%1CL1s1 zvu}s+Cs}WK(yD&wCmt{_;3$U1*<;aabH3)`9)72L6n7eP77LtZcuVe9PWqmRS`(dd zq5lzxTb>2|Lq_ls^)lFa&x}S|9t2(IV(e_*h2QpE$MyQDeAVzP)Od#hRG9?uUrL^3{Du#Y4#9<@Yxw5wO$@aQ=Q*UvY5KqnH(~{7l-ec(bjEHy|VCIAm2!=XnWx>1}Z16|Rze zp^-lB`Y?;HKd=wdYDVC;t52!rRtNg{Fk)ZgXO^I>P4cWe#Lj&|U^X_NT>Nv98;#bY z-oHlE&4F6n(jx+Ic*yXorITT}V-Q?haL&eZkvz2yy^J@{$N#P!<9`piCUB-y*8PEy8Sxv-4+D1B7;CuB8tCHodosT zL-9xOG-i2Ei*{|2<_1j;5UTT$)ZVUSCQ)JVa^nD8<+la@vvi@mU%G;f$5fzdx5%%o zbgo+Qhg9!3!qDsrw%$pOp8L0fPi>QiZ&PYXvFSRd_@D$19TuDqF;3_zv6#M5NQC1q zt;}s)3=5pFNtlBOd5F*m{I_rgBTHsNvfK<__NP*Ge&7Ijc#N}k4pyQ-laYMpfIL*kYXqt3IB1v)4mGlB)y7K5*)7WU3dLXp8t zZdZ7kjr=`Oa9y4k9}fSAQss(xyC|2KE{GH5bSu%LC$EbAK9;eU=jXwcSrkvC9iR=* zq}ZM*r*LdjBvxMdz;wgq*_36A;r%Z|jM=D!ala$%a@sD6qaCDR((mEe_vk$98Sonx zE=VI0O+%>SDQ`GYeu!K@eT`T|_pogs@DMj0CHHkciVMQ_qNeU`NFKf(19t?nZ<6Ua zAkY$K^y<-xcRzq(pB~-eS^)bxT06>-)7EYmFaPD1Xz$MeCzwY+@pFaZhO8Kx`WywWo)ykK+c6c<=??$eF)s1 zqsjYv0-)V|6I0k*Ml`|{!IFN&ls7X-;Fk}Z^3*ICuLK;}`&oQfrv2huzuL~5PnAiwfdxCk5?i=F0K^qKfCxG&pM}Px; zx!jsM9POSDuU2d&1BT6lb|(Ya_jL){Y2;&GjldIHXI`>vaSIU*B|OdE4_=-RhOQA! z5OU}lsT1}xDmVh&JC&${jt0n@tij z!iT>Pp}FQC&ni?5%XRx7&X&^Pq$b~#x;ybC(U9O z(R70~?mtXssE>tO)dg@Xd5HMKl&hp@#8>D!m;qmt*1*~rX$b%JkR5t##`G5{@?Oio zCDltO;l87ZAhW|3r+zQR{}f-qt8`MZzo2J}ND?*q_4dUaPbcOR$ zik{1F!#%TB;RyGuP^DEZWJ|TU++|AcEgT7(PCBDf)kLzyc`*4hU^^7FnoIn6nwataIC0IpZg^nu2pE!L2Rp*0V7t#<64rB%ou73B7kzyt z-l{zsW)Ew$TYBRon$#OYOTRTl3w#+wwqLyufMK6rvEKN32(e ziefbtQOQjXypOm;@nUs+-B^T*QL3P6?+W<=8t^jLlyt&*685x(IY=ABNpZSJ{+1ZW zEX-k7eCM*k3N^)#1W!OrqqWF2>NkF=jik7il1cniUgccwg>m?`-AP~VG#Q_Omr@{8+(K` z-kFahsH$EBDECZ+VY1!Cz$O}xe3s*9dmqw=(@kjK(@dyeWXp#&eTTD;KB1xg4|2FS zi57kw%{`*Gf_%f@64N)$-`PJ`dGyT{+cmWe(1e3l(NGw}q|Q~;6RQCvj{ zrhc#{-M5{l_q zJy-yNn7iX0Q!lDPw^`HSX}}lJq>DjF#rCB7uME#Id4m~eC&GC9fn?GOD_q+WM~W+r z$X|Y$yl}A~Iu|stOumhI)Rmy6YYPm0*F^qY&%*~6mzdm_TD0lZ<7$TciL2Tj_&P`) zw<=~8FN>3dYmZ-|k7+a0P)K8bDeh!qZa8K=KLOPxMPNGqHvZn<%Pc;0lS_-mIP{Mh znA>C!jhKt9=s_kM6I)LXge!9A#vG#5pUUoe#E>JQg8=HnXg>@v#V5j(|tqW*Q3dYTP)~MU!%~-_^TqP2E%o*Rv(7T7>-iRZ( zc2*-(l%CBtY}$i6{XXIR_nr`}Ge@ke6=B;_@rHQ(K8wluQP?Z6T3!kMjc4~S(MjFX z{O*w;8gjddHtg!hlqX@-@&0W4(M7?0M%sDEUZQNjN2i2#-__^ymj6%Dd53fPy>Z-@ z$`(SD*^p9Xe9nE0l%zpvkR~E+k^o_0cuY<*>9qHM=0W^HWJMdUg zNivPCf&9A%8R4>MdUPM#7;&Ds-#Llr{(QqIvK61ZmxAY^WYnC|z(1`v<~BF#$+DSW zpg<-L^po}B`I=oM!#|GQk?O|d9jjoRaDMbR9E77C1aFw(PoY!36^u_fkivy^OhbJE zN;}A5RBAbFyHG<6?jPe_{pGlKrURB|SaSKX7ez;w>WjBojDhF`OWy4!u#d(cBnh?; zpiwcGRqvFgfz$}n=ZS&1`{34sBwoJqG>tW^=~9P|6cSlrLqqo7ulH}WhW*p!X?|}JGMfc-d5s3dnag19EhlpEeiG)5(PTEA zmaM%cQcP#=;6vTt;BZG3nwt|vO)NsG*X2aC5RHe<@-C67^Z;9jy{CNY^HQ2+`Wh5ZIpYp_R~pwMoD~Ll(A;N6H1ByNj$VHmHtBoQ){O&rL#i0e z;x!#yHqHV!)d4(h<{@hM_8;teFo}hjUdJ%)k)YWvNv&d5(D(b2;ON!mk%oNHxI{p zCeRrIBXh05WLfw&g}DrPN1ECt;X*Fm}3GRFR#$6WQNK}&p_nG4WGLyPl|H)>N z)U#tK-6O$%I`1dGZ+Bx_=NFOJQC*Z=e^hKZ(|fH!K{s9_Ni6 z52qFi{+=Ih_}4cFw;v6KYxE6l`j*PpG*`o+U;Ej=AVb(B%!mW=3~O>efZlPFv3`>W z1niMRC3`LYW^xIOvRQ&jtL4!;h(gQbeK0yfm$0p{)&+fUXliMaq)Vy;%3l53F&3E3zy6=-f z_O2IgDm)9tv;Sf5_TyM{Hwsi-?&Hhr<*?N%pT?J|(TMO ze2oQ<;B?yVIfZmQdx&c~&cTS1quk)aMLH)Ui`xvI3Hno-;e_u^ns>ewM#hby#?MDm zqfbRFYuX4pf1Wjez3UeBx~1eWw7yonaLaKRqZvV5*Cq)}0#j}=Bp+}3&R|v!!F0ch z4@r$20HraR;Nrd#65sy-Rqr@_qMi(Ya^cx&Pit$p?Ei}u11^Ro8s8E+6Rp|=k zaf;yl+0ce1KZO0rqYM;1drV_WjZk)O1q;e96~)gnh0%`E9NH?_liRiU!~P0Aq_hNE z6_PN-$P{#4!*S^H!?3a2nKz8M$BFVldU#)*D0eqwv4d6U#4!fMbi5YLZp>hr-hW8; zvuSv#g~D9PXT+9O!m*!DLRL;-94{Tg9cKCPgsK$#)qOJfrtcu=TYZOHWwD|ueG^18 z+V11Myj&<+)QxRRbK!bU2W*v{0M<*F;AT591SdC$$4(5!I{gPQJ^mv5d4`Fkx)iZm z_XsJA8;*512l3SJckRxZ`!ZGP+kyKJKUi+zv zVUGw_POZWp0=H9#=z!wqiFDP}Flya>9goQA5Xspe*ty-WvG?H!I%W87*e$?**Ij8w zL+@VptLG~Eug_*a%`Z?iyI*u{SQVuAse@kM9h~}U8eiV0Pqv?Nq7N(m=%mG+g4@27 z%jk5`KaY}Fp}mMp{8vRs$vE;s1Eb+tRTQ-_i{SHDxzLASb9v>gVw(AQxsXMPpjvly z=<}s!AfL*)W%+-s&GD38&B^B z?!$@|&tbu1D_Xt!KAY>m72c{>W5j}2Xg6vscw3tD3wCel`lg|HuKGQjQsmvBpXnpg zk9f`(rVgMhR=q=;jHPtg#PN_nN|7HKX+Z1uFCj^~PUMQ$Ce%NAh)TJPZoDY^WnKq@Qzdh zaeN(x=>iXBu8KC*ESQIKmirop$#yU|!9{lM?PxxA#T&M2&M#(RF%^8X-SCXMvuK;g zC+4zD4n+&y;7RaV1T|S0SX?OnnE4m~oX8SwaFgWwTuxzp`wsgwxQTAMmCU^;$9{9) zMbg(jn{My&W8b`bNwU%>A{Ez#UoKyRyQV6TajOFl9ge20Pxpa|>wG#ow3PT4J+mLE zH4YVx7J!RcF9be_r}?V0scN?`cRcJ%7uL?@Hl0)XrLLv$bLwiY{@@sGY3>n;uP)~D z7Q6U4g=pCOa}8Y-Vdn67?P5CSzzO_aH`F0$io9@FtwpE(O~6RA7rbr4MLJ9BE*?la zOU&Fx(U&7%^Z$M;(#O+UP%TQ)L7XZB@qyEX`&fy_&ng=9U$q%tdVGq?$X`N};hlWm z1)!PFdtk@IE!?<7tKrM3A=EJ74&`rdL)UDfFKToc@2N}D5j#@2@9Q3N>#rwn-l$5i z&7aFxjCp~Vie{1Y>B%he!8KeEZpi1YY7%$2%Fxn52Vh)$9lA&DvGR}|O>17k6{2>- zi9gA>IZJ5G+wKQh=?wc$=2n?a z9lh)EaM(7m6!@SEJMEZ|DkJxwEFgcEKZE!s3N+yJEtI#hBAYgzgjAJuG;g|wi#D&J z*8BIeVQ-yj;a6XXI6VaC%?^OI;i)jBuoKQ{CoyNYKJs&CCroU7jhU=X__iBR?b78i zjocNS&U5Ie&RJM;HWvoQ-hfXtXYjWfL*YwqGxQ#rOdq>%V%^)9lllQvcqUJLs*T$7&>nOy{@amH$S)F)AhaxqfhHWo| z{aEQRSnlVKXY0SyzdtItQS@5sYb`;;b&B}unWyOyvnuWs`ya~HO{Hgy_E2jn8Tw!L zCvk75GHOjWq&r<#Pn05WAjfY{0Zsg;*0?d4wMQ_OHL9O0k zI_AS|c6a4+F!F4LHW@RzZlwXcuA|5;m&b|t`=2DIW+o?P_pyF=9!`3851LIyN1INHvX>0QfnU1uoa{bO72aRF5$f1=vKloLq*!f-8xGu{%vTIn(ZY-90@ zvkItn*_9Z& z{hR%kWPzpU|D2Sjn?iK_2eQB30mJJNN8CCEwVsLeOxRCUigJP@f$l@CwDA1aLvQzG=~%vuE)le`m+$*gYERRRM0v?o^wmEPG86K|VU6M91M`;BBf{T5>_3dskyW^J9a0IsoA|HRgFCGjde44V zG;E6qf{TiAhLH-M*rHR<2Iun?)Rk_#CkJn z(){_fNVub}5ptl5PYmbjUk>A&s%Y4LK}ocyr4{$>XaV`qx`yM0hIHmeF8+7in&&F+ zgkYTwqLTwnslhD)PoFn~?-)7*TN@1cmQ==-*2&Y%MuM8tt@z7ZK6Ll)EB4u%qF`Hk*8A2$qd( zME>zOX>^@KYQ&#J8zS=X%Y+w1O5-UD>lC_i_tSVrOfi|FE(ZzS%GBti8sGjW5*9Bl z5eVUT_96}={c-~tVe(HBT=^M~Uly)ZY>pnRcZT1xEuC3vlbCL!3iWHCbsUz}R zhtZbJo5_j`6}(v|jBXCzAe_6`a?SW|G&nX24jpX3YCO*S0(yw(&{6WcemifS@`wBl zm*I_hX)q%%m3AtW^Ai(iVY+`ZpDH(kyPV9U`Tnx}ZQx1pj>zZjajKLKO9qXjoGl3S z<{t`|K;;QHx?fq|!N6r796P?Aw{6tqi}t4Qbt48hZs@I`J5#r#*}S=@sJ5Rub(tE=o8Ddrzp(MV-0=WkoU)v%O&K9%YunE7F~-a;d*>IgP6M z19{%E^wsVpjCy8)0q+udSmFRUoIC*D7wVy=kPi;IbQG88{YIxB8C=5TCQEJ`N25s+ z9npQ3#=SJ6DrFfo{I|e`uk{9>6+?N&ie?nbt2A*T#TO&C(Ctr;Fl}|s##aMQ;WUBI zd#s4kM;j>JJI;@W|7e1Zr=zJ;;W>1X-T=?O__0^9oA{w0&eVEn4p;l_L9+#x?xc}j zTz6A7JK}Nyny;Bs6O9n+QeH+Kzn!G=?bqnI$HvfDw;9ACdzjCJVSK__E4qAc5x14y| z5cqQpdI}d>_gA~Z#A-SCC6UKdJ`yoqp-MGPVyUj0G!I{+z}3|P(9to)@Zy!{^OG7sj>G@qO<>7wxHc2E> zF?qP&G95dI><8z*i=x5no#5p@OX&0l!7XitH|@qFRr1DPlVl)VUzPq2e8jB&REuOK zPhsc`A={Iv3lIKTW4fU`HLy})W*-KVRbvl<`0px`y*p8CX`#-mF5BalGDV0=Ooo;+ zhMmpR&|k=&o<1c>mnwfHaV?|k%vx_r{(?~RWz#pE(NXnO=Y)yDJ8(cRQQBZ)34TTNHq zEa5i|j4&a}f}Y*yMoVA(!z+JRlL@W6__PXbheDU>u+XcDuYH@wEM^K0lS@x%(}M*t z(=n2J=E*gt+l}F2&Vw9U&k5YQPu1X8s^$=RM?@V@DAL)-;&}dFO^0O3={)z|70~~Z z4BzdJQd1vkaJ+YyO*dQw7Dw0OmXEVQy1S4}d0`DFP6=6jrOoi;r7oQ>0ep$fU-Xn% zhHsV&>uHiMn0U8C{E@{dVR4#S-|S)1R=&Ke>#VrFWE|f95{tuc7{a#t3Gi|9GkAJS ziHs~M#vijfSz^o}{<#szLsu(^vPwl+xpo}jx01X~6lOEh+C06_ikn<>;v3(I@VATv zc4TId0;gWll~`Z?&211-YY#-~p@G5EXMm~Daj!`%W?QxD$>ppm;&-XGe4_GC(UX`% z+%ipr4EnJa=WnjVaW%TI!XpE-6(rcOa2(8uG7uXu$<%XS)kCu6C0h$uF?D%Ma|HZ^CZ>KkWJU1Zrc#@aw|^_AP~ni09B_ z(74Q;_mr)&x2y1>rn36np?ex0UveGBB#Cfg>>={t2hbIVW`f+^I4nKO=%UY`*+>JS z8#;M5wwYVOeAfwd^;m7%Q7QPI@APwe`!?*FZ|KnNF^I^EMD*iv1&7nMPockCm-@VX z#|N&tMEmwF5O4XU(Xi>qQIfSd5JvBmA_wd?!R}oq(52&uHG((za-15-FLHtLA0t7$ z@CMl)d*`y}K7z78t37X>P!ri2b#*F6ai_#I=q z6M9+Bs~S+$xGfqG(F^iiBya)b`QvR8q;Y;ZZu86#FAb(p_o5Y}pQvENmZ`uJ1=qVn zGyA?!gUc;<;Y%Lokb~{&xNBbr>u??g3%dK!V3HJ3vJhsS+KE`D9t@{@2jj1eiE#gK z5lD*1f`q~-F4Go3Ob2H2`A0XR?2}eZ$dcw7bEWZd(_CEJHL}6<=Po$8R`{RFcz|D1 zS3_ok4V2nGhsdTzVlUbOUv3qGR&W7p@i~lh94F$Bskboowxuwqkg*>v-!5KcvJ~VU zDEeIA#M+Z;NdQqs^(%*9`L_U^{P-HHznBcse3B?u>K|rPE(&PcidFAYSi#MEVC<*> zZ)Uzs zpxry#Ip-RE=~oG_J>x(v%E;kS;%nTlH<^zfXo`Q={J~WL6XARhffsk&;X%R?m{r$A zLoTY(3B@(!k$*fn<35X?^R=Rnw~V0PSCo0x*M|-Lj*dJB{9&VOEuM3nD>iwwt|3!c z8+P4sgKD}F9`+BTcO`UDYhF5;t~HUY3!O(ZhD@a4yM1uLT^Y=KJ{QHMn=r^Mh&89Z zLyMgQFjo2kGkE-g4AN8J@3W3KC|FMCZ>+@lAy(9oi7_BGeh#RYCn9G2#3u*mpzmlk ze&~5E8M!}^4;d{7Lu&xd!o?sxtN?WrIey<8$u}o9p;Vt31N=Sr?+X=z9 z`_leIm?4^bnZn*oJ6PkMg)?uP!ox?~*~WicA#UF&QCM*`cpZ;qE)nC%nd?z_ei33x zvyfl(-wo!qr-;Xac3TUtFlzp_7QWvzfpcnKA*5P?kLub&i!FRGqD* zN7KkhVZR_VB$IdA)M5LatL&>{I1RT#D4*y|U&#g1nGreky4gy!yAUt1N}b?W#7e&G zdmfbBEaG1_GrBQNiY6U7#{IJsh_}IR?l>ue_C9jrTPn`rYYoat9s`(3t^lu8B zq{Fy%XAJ6p_$zR<#3Z+`SJQRkv*b>Q^bPNb-`FbhR3icX94N2=B`3h1 z-x=hfaw~bIGL06yYyx+WE#j<~8dUy-DRZ4PhWjL?ajnS{_~Y~sWX`37tkZWqUwBWr z?|LS<%ld6-dO!==vN#D9rnSK2-z@?!)r1YXe2Em# ztp0Q4E5m*0wK;A$+3P!8zPlR+zIcRr3$MbYx0Udjn?lpm5FtyU%=b$B!I@P8!*uZo z)?oe)cjd;@eh*82&hG_i^mf8U>tQ_jbPr@F?M97VjrjAwFlu_rjC>U(iq$3z;BKRY zd2Q`S7Q6EU{1_|CoBv*<-a1))wSOjkJ7GM%F>NN#SnNq<&acP5x9J?KlIY_(3~i5Z z#X~X{{BDm3R|#2(v&VyB`z|vgt#X5Ex6LPO%s z+)N;ym3+(N_k54@ayHrF3Y<&!<)DI-Eq`Di_Dr7NTK~0{1qx=N7hu z;P8t{@02)lDsv274G&}Fc^ewIbt)#qb4*j%5V9-l+)?yrRK06Y5kU^xW*CiL>z z(R@{ZIoNqtK;6y3yzE^ppEZ0BxF7YQuDC?>_)}qxFW|J% zc$(JL5BKEc_;Do}>YM)_RF$9OyemOGIR7>T4BJW@hs)4eGQ}v?y9~?L$-%vMS3zmZ zV0Jb86t)E?QqSLMSaeL6-<~*vtdusxfHx1&y)~3u-%+KPR*a*T`p(oQVj6E9ID*;- zt6_IrA^qO{3M+%|WAOV9?EH6;FFja7{I520-*2^CVgFxHufKv0k=Ahfz)QwvOLD76 zQFPl)f4E?i0@r80go`Q>Tzl9BZ2k-6)sx-)u8o&q8au<^55I|dH+w*?*qT4I?joKu z^@!wTYkoMk6IAv8YjE??!d>$#@Nr8QxO5iM^d#g)J(KvmBy0LoHJ0~WwZ&B@s^E6m zJv{F@9NMntkZ3&+-s;)RJa7{D7q#Ng(T&*oRhVN;`ONYZCvv$tMtsJpE_k+FpDUX= z^DTR-iH4&xZ?x_ut944T(*75={u{tM`*x8$hiOd1%mep*YepvpE5330T5vukI9J=^ z;Le66Oh02I_p5luuD$+@y7z2hPeTtX3VThxHe>F5eTu-y9f;2|AA_XIes(%u0!Qnc z!0f;aSoO@DiqC7(pO*`{c-${`Lb!KydT@vUzlm!%BYrE-z?rV*wBK?N?AYQ0T+AyfN2*+K1g$D#yWr}AGU2^U< zS*oiboQL~hwo^RZDE|a$!d>ptzK5t|cY>Pj^hYIO?mf0;etpMFU0kPEgEiUHc;7g6 zvMFFAJrLywor^y}|G*aJa9o-sB+R34c6}sT67%?;fHGQZ`3!Y_j^HaYPeJI5(|D@3 z7^aOd=2`kf=y!=IdM`qYr*$o(Va@|MU_XQeTk~g$akQz<9W{P7aZT^hjgfE4>AJvL zo_jHsesn#BJsvICzeI!firPUwUV$!5kfYUmkC5~$?bzYt$bYIC(ve$2V5?gvSCt&t zxS?_!?Y|m@3%|rcm*51j^pI-2Q11o1KQAJZ?*EZJ1uF&j@+IuG_hp@<^SR12SxO_% z5i`Y9zGt>SO5MFFPF`OHE~Qe``Mo|>d7r?098bfRmnqnG&ll~dYw&01ZTZihcc}g| zj!)D`r{2lOQQ6jw%SYMq2~&IE%#5fJw&lHT8;!fJmzaLJD^QDsF-!_Z6SAXFHr)cZ_O%6r1zN|sQQ0}iz3K@PYT zQ9fpZz?D%7p(Eq%`I0_$`u+22I2&xkb)qlgZ-?Xc>H`LY0)Il+-b|pjV@<`YT`y7x z!H*PjJ)2w&4Z)d5*YcZ3tLT)Bv5k|)y@#D}j^4H1!>2D8MJ#M>==Q&(Dc>@HuROO2 z+x|##rGQ}QTXBFF9rUEyt-9Pty_Ccs{|jHPt)sUuOyuWObchOFEH+P_z_x`Jlj#oj zG_xZU6N4f_^uZ5&=1GHP@n!rs|6iS!yAo$dON2exWpe)AYFKmRfjHuuGS=KV4ap0i z;+Ogj_`&@m?5&BxNc9e~GHEe;^B~%OXqLag>{8=ZYl<=A#3OqZ1z*5=%_)GxWlxMeQ_Cwr7p^J#E2Mb zc2rqpd8PuE?!GFrN^@dQzSz;LN=0m9e>QqGA()jvV7~LeqP^g%Nm9GU?ndR3l(HeH z;`9uZW)G*KhK7P?G=)5O*29v=RZwPs1#zPT|Ty8EKU^UZSc?8W~;T0S1j z?hK(hcD;Caf*N&>-wHd)Di|V;5tFs&&{r}+^n135?|s@uWpC29FuYc#H^XG$YuSz6~oJYqbb?r=>PZ_F)* z1K*|i=7Pg8y4;v_AODYBnmq)*PFIBI)3=g)-9is+Wj)At)e*Y004B~R+}dRzjWgN8 zDzGGmEiRDOfW)W)v@v88OEuwa z$-wJGDZzqx*jDp~Voz53LKmM76EZc5LiTO4z+6>Qgo33CJSHbq@W{yWqFr-geyI_d zU5Z4F_3mVx*BkbH+g?zZs>n6}E5o`$+Vt_%+pPBeHPOMl@9^IbYq7$-OdR^(Z2mEz z9YtFf!n2u6aqw0@)|Y;n?NN`y69HH%VY^A~Dl?xCpXt6)7s2@V5Lk@6i9}?4gYTR7_EA@LY5ZR;oanzE3(n4=5&RJ8JCF$qBc8CRc0c}g zbQW%`+D7i|ZDqFvGX0J>p`i6c2{wdIBJ10lL<0@y(W@^vrteM-GyVk_%w?%Z=BZ+((oJR*KHRZ>+sJlxiF}Nfv*NqpwWEpl+BBoisg? zMy)#u6CCc4r55@q%gqFS@CnS0eT!e8C-So=N75`4(f|Y3=9yC_OHFI_du67aEQ)FzFy)9T)KVvr{46xWd2`l&9MCULyNc)t4!;PoY zk>&xSu}jOuGE&FLYA+8ay|V%plJoH0+R&xdc%F_CqH>QuVx%PFBm3j+S@Pkdys^ZiNEl0|5^MyYZQ8T$G}4Mv*4ssE&6@! zG~O%GK&ibCVY%RS9MmwGdKXF2yg3G7XI6nzWxc^RZY)YjO7Xw$^?1!mjYL2A4S&}u z68W@y0-vs$_=*6nWV6UU-Du|8TnYbzI-%vs1UMX_%KeW5NV%QH>@}*q{pS<#UmOQf zou6S2D6_)ukh-mGJ(qS~wkl zd@iI;3Q17fAVt5PSj7sL#bIGY8J(Rn2fZBs68*+@EYj8!9Hv@)#@NO9>;a=U6`ZK& z;y;jDZ3k9k5blw+b`z&#-R!%KC7tg-39Myz;h4FSTyCyCES&7l735s$81LyQer?Q8 zv^K(+zFO!}s3*1~dg1PBg0YXH(0dW#37NVy>H8%-f4dFEUh;Tvq91DPGvg);_kyd= zRvy%{PGED4qshDvQavicp;r&ArhJ0#ZP6@Bc)q6#`@~B!?JPg~JU-CrVbdoh;5;}F zrT1@(uC#6E3AdJWy5=67b1ASNed{)vn>~m{Odd_^N`Ju+m2WsC)QavMv|3!e=OTM$ zwF9af=Hs!w?P7IX7x3-P<=;B;cs#oyQZPPF5+p8@pHD_{ovW9@zRZNaE8K#j?4h)~ zWHPDmd<9=TtBIcfbC%X|8J1k**gL)mb8_?9{juHPw#ALv^wpE_)2p#^pCa7de4M(k z%)njwy7cqOp^!UiI><|1VN0|l?6)cHrLM6S{6|v)em~<5g@X&B$-)ad>h^(d(IS+( z@e90~)v0upa2NVng}&P6B6b@T$~P}D#_h-YF?L7;eOft_y*Rvsuh_H(!%Ow>@`VZX zlh!w|7`O$*Gf$G8G6|$zVF|UFA+Y^|I_&44Sp?%gOYqbWr}#DdmGn-?H9S4`Bc=}O zgza+wnv73%hBYdaS&3r| z4R)Ev_o{nP>ii#56xKHL`_D+8oWQl|EG3#I$~0($BF`;PAfJ}5;L38|^sQ|?ri_y0 z^RLT-c5y0{EUhK0ieJKx?OLEBu!TBZOnJecOCS}b3`yCqiTyn*sGFnARImbNcrKcE z^oo8oD#6ZSqabyv5;;C;8T`}^#JL57A#7kg{&zeRKD^Y20;0!0%vg-xa%w0Y)XJ{= zO0wmygUI)-H^gU;?qGr1mx=3=`>a+*ozc0ML3(urI{rR|9gE}z&)^5*K_l$f=j}u9 zENe6sEy8@KMAk55FszY?h3BuLF}a7a50bh#qf6)=9+kqe@$Go6dkWmYr-%!*UXxoF z{9xZKd5olINx!il-f4J&6D&)i??VvGv9QE?D+8X(%k^Dmdq6V;#3 znWRUqz2VY(q{VQI*lK7r=@QA{_VAl*@6mKf&Adx?uUCP*j7rp4+<@UJdXxs=BRgk) z!;vNa;$*9C=CFu@T&ofG{WnZBA@DKN>77AL{-tC7IuVSYVn;gsPJ+dUc+yysis`~` zd-mnm_i6=FA?*A|g1>7GQuCs**f9%?qyxDKsbB?%xuBzU&3snQve_ErBCfcEftrF|aIQ z7yDwE$Y!oE6xa(fXgFs)x#Kxq+!Z>UZb+Af3Y}*1!_EZ!UdF+<&najax(3#FH)BP_ zX;6M8B85YzvMp%^*b#v+b*Lp<7o;kFwD+`Vu)a1O|6(sb-(SMne9e1jEij~UkpaW@PG`|($Yfnl8bf&nUURFHOqR^oJJKSoO%@s|eec)ra9HeFMq1=iC1X4($)6rEW<>Vtp#{; z^eVnV`~YL5cR=9m!>m4~gG{M9M;=8UBN8F?Y-;Br$m~lY*Zl9|!c8gcnB`0M z^I<$be=a-=66!qFGZC(a#KHWEP2_8Q5ql-Mhuu5W3G>&j0@al!u&SYfys6A%|C;5% z$-)-RHa@U_p*S6@ANk?tjtr)?pqIEFNG7BAE+s*$_4)Ml`{D^b4DR%NfgRVaG2HK~ z{luxw_OHeOK+O*WC1h>E_8%=n5wnId&d9m}RYTUJQImS5J!IQbUYi()H=jAKc+E{pSK|E z^=Gnn(?qy^C6Lw#`H3&>Pho=X7%0wL&EJ{7#O%BWaAJM|lt_Bx0>KGz*ryvtsvXAt zrD^arER3d&PUF^tvhbmlz<(a{mqq*bpo{BJnzQmC{wzH_S&ae)Z~S5b$Bu^>zD*x z`|RQHMH}qx-a|^(#Gv;I7kn`21?gL#V1HQZ278nwxXwHZ$x@*Q(J`(auRoL`6Ls~; zR3Z1LpzKc4GY^x5#vr`=!;Qr58A@8eC7{@PD-PDS1<5A^@WL&D1Ctg2X=#(NV8d@5 z={N(_-@1yG>V!F~PXzgvzYNot@4_n;Da5vHmRP;a3_pLJ%A$_81Bu&j0mlXm!56o$VN_=&xpB}9 zE=k0|ndXIf=))i8ywemlN2Z7$g)U)TlALnOmHX5d6k%?8i&HN^CgC%-YQAHG+wz6mplNXR)D23=4gq@`t|? zsB%IFUJlYm*%$R#Yi`V+tm%T7{$#vxOp{-1sihy5nBWOjC-h#gN}ujD!{%~|ky2%# zR^CMBOf90iDYfwKQX@~7R^fTckz}X*Ilyo&uKMmfcevm{+mh$-yc1UR_-rRW*m^Hk z{eBNe))a8_nUZ|?%W!HilZ!+*TKIXR|1kYF0W~!p^n3mXn!i27_-W<%^&Y|N&1>s5 zPpeTkf&Z-bEd<>%a@c&`x9r4!S82=k3Kw zv&ztl9K$G&HDub88NB{ai)hRKyQsX?1-2bK1j6`?H!VAFpHm~kNMYUfYKvh(2XrvH zROr%P6GLZ$93EL$0hdP&Xh^Nwg_Cbg5Pd6Ercq;c8m3L%1;5-T<9CfA^|ykCL*?oa z4Dfl6_e}%1{4W_;l->lfAIsR0F^Q<{G!_?*QE7O*_XZxj-@D0ntx zfY{homrm&|gYCNy(MYn5bolG@me3GTRr*CzNGoX?c?HIQuYsK}3q&M)E2v)2B64aY zx%o|9I$>kI*eK)(SzG3UcU~vKce#<&^Wq(J|J{u>ubc_GT5!dqcC=x~TRuImoc|}2 zf=fL<;TXf;xM1Z^%#(VEBP8sgCgPnq|JEX`8F2+>oe|v5Q)Rg2k>@z$*=m-rzLvU7 zmZ5bTPtoMkT4oecOtx>!#-jzt1+L387W3nQC`qE4GzzZHwx~OJ)?<~xI}-Y(Eo!uA zod)kLi3bTG^L6lFoT&P>;C=1PWp6ZOA-JR#r=E!c&O)ZED5Eh|Kx z&rbrESVg9k=V3##5gvEf#hFffNXEG~{7)?rV~bi~)2dYVCv!Wi`>4RLjq7E3q^q%?guIG`zE$6l-#Nyj%MxI8PMqj<{~~D7vcm31 zQp9DmKW2Y_$ac*zfgd|+0dn`!d>bFwU_|LnGclx`7{C{9F%diN8YQf?{^X+B9PzMRa9uV%b9`T!-Ca{(hX56aQ5WNNu23+AjMGM!h6^aO>kUlwGNzgiTgj(0Cm>5NiKM??iz|K$jKDTM3`q6@0rrPqlNVr1 z^G!6N+qmb(XsCSq1-|~#!JdFDJ-xi>Juc#d_H2 zrNJa;3S6q-6VMtx36A<6fh)`QqMNoYMzwmd2SL|S^;;`ZHu;9y|243v8(9$Qahw%e z8Sxhs%15!sqLHkoUDSeg#y+nye1aH8$q;e=Ou!Ki? z?QF(iEg0Um6mALUv$&1PXmQ>H&MMksotYlJDHl&l&fkL(H(X$fmEbtFWjH3Zj%CRT z9MAki>|fbJ?xadYpJf~%Hcf(7*{y{$X^1oQpTeI;F>JQ|if$#vaD0#i-s0V4%IxRCWk%A4(4uU1}IF@5d?y@0YpW8!VlbNDfyP z(2bVQNZ(~w;+>fSrh4i$@XC5ny0yxFRN)(#7Mx7|dLLkPM=>nE@(>IvT$sgiX}a%v zGS+(rlYj&5tm)Jl@s;>I-27)WzulS%Irnwx8Tl?O+u|i~xZh&kEJJ$G-A63*Wg`1H zql!rKYlt8GHDOg5ty;JUYCFym~rT zoZ~kP);;?I56$#hi0%NMwEQZ&X>yDls+mPLwQEC^do7eb{e^XVl5p_KUCjFTe`MOa zlbA9#6=vo#7P{LK8$MRyg$8^3pdvT2x4TC)x9c`JRzDQhE!rV4#XMpDSy{Y(Dp=$_ zGm=GiPlk-Yd$B?2I&W2IW0PM~e)7Z{@$?C@qNO@6up572x5GA2s8lB7mpekUFdvy& zkx9A?&H2I7pJZ+4VRCl-X>wR_iJtzv63h~F*z1*Ju);{}PY&TZYrtJmt&%;|ajr;wpY&6-Z- zo*v-4_x&f{HL0Ls+=d%$Twqge{Q|Y)N<*o1o;&Vm^R9+-7Q6@15P z!rA|pq5FG**XF53f6qPxQ;fvWn|xjLJWLXdGS{<-{}$lX`Lg_G!W%O4%msnP+6Lnf zyvKPl)=Y8CaT3@YFS`EuBFS;IhpBx*(3yHv=m96QGun?yZ0rRS!1h}2X&h$31%>#J?d%^zt>B{m22L?VxMVPtlJIS zj`YJ0zb_&sKSO#WI*X9V(uVABOE7$jxkLJ8V|L!!gkId~1)Ar@uu14<{4kQ{S6w~u zLWnvqC{&`iMh~N5?dh!4@;YeFQNu$^0$|#t2o}G}%VETzxzKdh474`^+{~4AP>INa ziV=C-(Y1mX9(LisHPh(Kd=GdTH;v~?9uo&X3*;id43Xw3U6jb{prr=0i1oc>mUvJWK-~cJ`2!vzB_rONwBLtSGipCUu!`l{5#W5ZQIB``i1V1uB z-_lA9k6*!$s;^*oM2_&UW)H6!QcRpZ)nR4rL0EeJ4|6>uLw{A=63OeeusZ^(+H}cc zVUv3j4lC~wRZ7-DiGHO>-34%yeza)ucrh>d7)ahpSfQS-@NN|~R>I>$NB^W4|<`Mlp9?~K9stOn83h{A|jw^;8SOSG~qX7l!sg3Wn_ z@MBIAn|gJs$jha;a@uG|UhPq7Yq6va_dnYXTkihGzOHr9cV>O%Lb%709*-7&p9^~Z z+DF!UGf|B4Ht;DJi6Is?P}F%H!FWD@v{wq{P8>$|U=4Wt>hNuIB0-r)5gAP>@KQA4 z^NdGgUEUfv+wy?jxMEGon?c|+;yGz61~_ue>VSP31yXdv|-b%0&{8N+7}f5Zar*=GuI*kxT3EY~6q{j4NbeJ_QD14D53D&ae&um#tJje(7mDp}GS z2|g>XNt9oD8h&?Hz}n+seB?4K+%xzQ?!2==JnES$SoQ)Id7MC>7zy4}{)x4>>0->y zfjFVmhFs3eLAB7wtf9RT><1W7w^ft4*m$<^Ofef-=Xdg7w<>EEU&4FSe_@|R7QS(w zgqjNVczlK;HdqFLhjlC(rjLam!*a;vFlTD9V*6SgRwAgM4nH zgibfA1kAy)`l&ony@?nqzb0RrnlVL~N50%U3UyW;0*zG;T<4n$_eczdk@p2ZSKUm0 zVdiUc%v>a@8~GSx8g;3o_zO3gn+o@n{8@&E46b`5JX62bK%*6p1a77Wzpq)(cb>Wr zvO$tm+_HtItdXJa681pZPwdVZL!V_1uZsC#K*wzn7?E-Np}JBQyzP&pUsfSMc>EL} z>n>eo@k7iSu05ghma}+^z;x9R$3bP4A%A0Yns&G8RLM4+0);RQRL&VsO>z@pK;138 z;wSj>Tz&$iS<`>op?rO`MAe}R-XG#>S1H!|ZTVchh+0o_qG7$<73;%B@1@#lf_aHdw9|4y!AU#`hg{mw4F zM5C7l&J9Mxm7g&r&xCI_5W$(U9Pl|V!`oIK1w-i%whm{b_-2j2__R@mijS=qx&*lC4d-X5B4bFe z$LR1M`%HPfz&hXRGl^%n9mc*EKeWDc0WFLM^276Qpqyn6+hS};*UvWKBj07fnTOXf zNZ=xTnlJPsZPTz$VGWN{TS`-cWw_Lw`Is&dA$aY-V(>zO{#CzG;LKD`99l!^#D&7{ zRR$gkOwM!HBUtO?_b{}t1`EwHnAWXe`pDv&xVX+q=rU@ft1sZ9o%T5XwK|`=<+=Dj z8!tP%xEvgzdH`R4T>#Bz{Gsyn4Uq7*)YZ}-OwBY&<`^4KnXj03c!mhpTDf#46 zN}uEj?~kYrHmpM4ZT1q~hyI4C^bg4u{0;!=0G>`hBSNR-VQRd#0L%ZgAak8l#&RvyP30qVu;?arjhS zDwk3SH*Tks+b;*O@n`0t<*Jh~=f)**v*1!0S$cx3Gm0YbAJ&0S+6(q7r3_P6y=I!H zjX-;<9lHB8!qP40;KQ{O@T9kcTvxY3y>dOeR{1p!d?&CiBCfM#gHfbDGzb1Osl)ie zN6~ThPOK4js?XdF;a8X^bOe@@g{jBDdT}I-Ec}A2;vC_^#|r%YJ`2-Zl(2N)649;v zRgj`V*qh^#*slKsQ?BNcZ-N_a!;*s{*m-$qDS!P1v!$mIY?o z;<|)J5lP- z3fwY%A!GSR@%Fh8gu+L;5+W97 zi2a97WvM3~kzre!#7Cz};hn#O$fYHH5IIGcU%d5&Na#HwFKfj3EYXH9`!$u!&=vY; z#unhFx&;DEABvY(ZNU6u1^UnEESdcIBorC$29HB`;Y;iy>g{?3zdx8kg_;L>89D~? zQk!we!ba$JG3IewKahiC9^ij(?^3TGExbCe8l0>?K=nLlYB1~pJ2x^Jmlthd9jk-! z&sryD@K7Coe_8^|^hJ=68HLsvYTWT)AIq=TLW`}&WZeB}I8E;Xwm!@NrS)pSJ#XFMLWXLg9GV8$v3tx7K1@gdpv&dc*I7um7?1fY5oOo;q(DI(Dvq( zkcA2nX`9Wl-BnnOU$sJ<}yomx@v#a51A@|6vLHwFHky&%qB zPjH3lOH8Z&BwF6#0KW{2g-lxwvRS z^lZXy{JKJt<}A91v^R)I{CQDXyIb%k)a}M?E>iTkSsq0FaN@shl0^rM{i#m9GJTl& zAFOV!1?WU?OxBjE3`Lii*ajG3-+IE){H|9;wn--ItP;fowD=@8h%1KwUPNp;5K(Y4s) zw+Jm01Xs-hJ1VhTiccE(lBLrVFhEu4k1n2!**zN}Wb#flsZRp$j%0jV=8WDZ%OPro z7H%9Jj^l4GVN*<#*to#=%>Q^An)_FgQK!_|*1B~fcEFfiT(pnGsT&G8u_Cy?RLEGL zO2jd_VW4_^KTaLpP-$>7fryt*fcv%4*nUSJ=M$l0a{Ml|&AG+CPBJ2o7B>;o**~#P z<0rJI_p*`zD||@$p_mWn30+0ZLGCvfi{d17)p z3l6N5gUb_|q5j8BHoWt%=(Lwa(Ddf@Ar$=PtN3<}fUsEXiY1 zFN%L?<}=ygOxV{MNRMpa#z#vAz>hV+Z*CH}rpq#TjB!3{J^w*gWms{?WxMGr&1F2* z?hSt0C0w^OhKPp?xrZBDa(VS`Pues256b5shR*gMV0!H&*wyRfMTx<5@>amkFZaRz z?-ppC)emE*`S2f4{UNGc4SH0KnRd;3yn635Yz++NYh3R_xQx){)%rj@hb)A|rZkwK z9g4rC+VJh*c%rjN6>Yama;e=N%-QcJOgi&}J+PAFO;?M==3()ebA%G9NwyR}nxp*2 z>EQOn3y%MH9B&WJLi?xZiRz8RklB{ZoGrhxGuuwWnEAC8lhclpIYOSVYhH~wsPh;p z$&Env<~sUpiUeuvVm$WlI!h{lERu`Zj}ON-h<~qKgkS3h!IUR$;=AId`0}a-+#c}} zEw5*Q&)}Ufbc77d6x=HPi@u4&g5=Q6vxtoKzr%{1bh*A(IOd!VMTLJEBy4>iNDg?7 zan>pL?_4P^Z9PX!gUg8d7YP{Db&NJ<>@+*YVVNtem?H6$`>J zu6rOoZr_2jjhX2A=L*~G{+``sD~NSkHaT)9lgPUbV^&Yp(6VO|ED?=E)5`<+Uf&UD zu}?+djm7eN{l8$Up8>90dKyiPx59~DZ5m8ppqXj`b{<@h))N=O#?{x@=cV!B@-$oU zrLE=r3>>jdb~w!%zmgBRX9Vn`GqKgXf;XmqV4kLxkf+ngB!&p=60!-eW&5*wV-@b| zIFTCbbl}XY?V#{?FFoxVE;^Jm8b9F|u>E*|=KU$djtdI3dS?tXdne5=Ke`ASLkIC& z`xY?C?K^qjhe*u*m`?_-o(C?E;z`HMBpmg=m;_4-IkpoPe2qQL;8_4>%A26pymWLP{;iLPhWL&V2qsr_QANj3I zAIZEWnl2L99;^xH-5l7l0kKToWio$P6b4ruddc2PPsPrQ6H)J0A?|-NOFaMnLbQ0$ zC0ch^iHa2p;NHiNBzEC@jNH8oWADn+iB%7o*Z5w%+C7a7sWbw`=vr1d^Cl`>C}7SH zi*ZMl3vQc!3yuu2qW``0gucu#VjYcF%;9M@+gnh=ZeKNr-vJhAUaiKb5746ev43n0 zYvb{cz-_m%&cyZBBJ9MzqXDMS5x zoiOrsF#9udGP2AN=F(sWUEQH*dp-u$C*H*%U|G!Wy#EMtuZ#s zim~~T4X!xjN$n-$=+Wz|>5K;e#YeNDKFbL&d<>xLE+^t>UpZP75kqq?yTh9NHo})J zCB45xK=)cGpROn=z7iY^llLXTwB=hM&+rr8@IEhkw7Hq3Jjud1yK-{sMHDV}m7t!@ zwRn#Rv-alYG%(9uoH6AUd8DvY)TZ}{*_Dq5zCjhAA6?7(&P{{!CNs$Xnre1>qCJ<) znTr#JbK$=o>ioZd``P8O%jwwG3X<>XjE$GCi;DgQkxOky$*Vz{IDBp>sqh%YY$Yt& zkLI^RPfU*c)s&sS{&4&4rv3|ld9bNtifz2j%kTt z6W2e&rOs`vFNEWV_os1{k1;>5)XMI<4dtI#e21gIQ$eyy3Zbl+>ESpywCff*B)f+= zuQkAbwhL@^E?0?P&sAj;k9%XnJ6qhHw~GHAWsj#fK0^jKwy4puPm<7R%u808s?O)- z6wuOT3vlm3Gr?~#A0o>{;PUGQF*u%rCf8-jEr;E(SR}`F6h6b30rjk5p%QHwc!DeK zmgY*XS@dSmdho58L6`s1;&JIm1eVNXzDec=J2&}&z@MxjX_Z>=_?I-SH_OJzxFn+U zFP^y-A4Z3}SHSG6BW|Di5}5J`ShW2!JKFIdZM4flVKhjKDv^Bg{A&BStep+)JtwZ0 z^ur=^d$esgI$t6Rk1AAA5h7SCWu zV-b-l{m494o&#^=3O2v_By9Ct3~rxJV5G_#luGzSrtdX{!he>mF}N4Wu5h@Mbpf%z z6K<}#2u|B#$zP$jKkDl|n5n0Yg%UOJS8#kexE!jO2?r& z*U7^#?c&~Zo8h7VBbMS5X-+RU;Fc2SA|S@@-wh{zmiOwQ;Tu| zlHeFUkbC;S6Sww+V6Ja4RM}^Vi-w!hmQ@dMyuKEIdMpV@5Z+@F1BYiuVBpL%wB-7G zjIY%YoqtW?&b6al=Y()i%JZkA8mg&uX(f71n@A@+8VmcxH$pdH7M(sP7bP!eVxF=y zG=v!O;%~yZK!t)eO3mofiNx4;K%0oMypiHh$W`uJT4 z2??+y1+vQc?29Ch*u~kUr#k#Yoh{S9+zbxGhU2`GktAV=B@EGEDA#d`3=LJJNA#uX zahe5&<`d!WcXt?^9FO|IJY{xq|8K+{Xs>KY@R<Q*rHMTc*Ih%fjfwlfbydCUC zraDNW)F3Ka(t2C$^ivYT|CKVY`&GoT$jv^gQn{ROq`1T% zBz*Ua?fWHYNrnQSyHtdC$a(RDz2C_uA-A>oXEf~aRHj8$70e>gi*Elhf+{p}zT(#b z+BQ_^Q5n2L+004e-v#nCX+gJGr1KA7j*jIsmT%<8-kOnTX|rf}PYNl>9ZKfQh^U5b zH*>;lC>(GRc=>ad$))&)f^k^kI*U7RQAEFr5Pl|Cy(;OWDIdPsmHM>$q4uUrsH?e~ z-wcwcbNt`pa)bS77HGjyU6Ge9isL)mC@)u|{N{fT;AdA5dH0&~ni-~WCQhD~if2L0 zK2==ObO0xBGo{yiB)Mpj5%(;cLt~FC^Lpw;8lv>DXOa_(wCrLR&Bu}DPV#(|Rth~} zHiH`sJA)<{okpCeeq9$EUaW_n^BTn} z?OWM`Q3zdBlQhk|j)!JXpqFHnxUG*G)t0<2wi*~oZ?4$EGGY5iZehF^~iw0i{jar{b*-aA=V1M zp-Zx6T$N~{^24V@(ob;3Ecr;TymI64@T}mbP6x?MLQh@r0uz;8@ci%!oUvpi8}+Z0 z@*%OX9;I>Ho6pXl6W;@Ez5_ zgR%nY@Z-)PmftJvvA(m(Z6C?aVi#VtXe1li$n3n9p<{_3i=Iyiuxui zX`plkbDx%mZcC$Z!V4X0*HMi3HI_5ozkYby=nR@IGUS?80n}iy3P1YQ7LKebWuc!W zFgM$rPZ(lI7qrT0CcZy0vT z39dHkL&maFwsF`P@KPUulfFlg>0jOHf<8U4Xm$~`KRPJ7>KV!;;va$B@Eqp8_9blI z8IGHRgx;LTHu&XMg&KWrl)d<_+pC25n-h2c{97aK8QTFTns+V zUqo_u-@{%-eIbu60||D7uB$78F5lras>_(_e0#vsAH~xCv?^l1VKvTew!x{6F2wGj z1pO)+L~aY7iXrI<>}E zxj&e3&Sltkrv=*Ly;;{~3s@qK!m*Wo%y`I3+;&Bu8|RLJxUy^<96gQ>J~IuLEZs@x zswU$p2@Wo2PvXI>x!hB%#)o)W(aN#U;FVDv{lA~H{rP{;^hB1L{x*cv5<{3I?EcrD ze}T(V2UE37Z6QlH0bkb-E| zmFB?nh%4}*c@4fPQG!y)fi0JkpwXZhA57BXhqGj8({fFS^PYh9`FkOK)CRWfNg~F& z5qfv`EPSSDh=(*jVvEBhToGpp+B;@&xi}3xwdF0bRx05N?bVfz&f776#|-F{-jAjq zirJfb3u4q&F3hO&*o;%Akm5ESC!T)J)QbkQm9~n!a$FCLUFwVfMsy7Jq=3OrQ%bZOkmleT@G@+oRIS&B*Byg+e%)I1`DqE}Q}2U8=Vo}>rBAKeLm_Y7 z1=!^_o+eBCqw(hR@GTqR&D|zQ%=`d0Wy9dh%s9AczMCr@OJn*UY_RL!5Lo^u19nA7 zvCXw_py|B?4QGk8VcbKkG3_BWo(bemsWks~!WDgQH-L@wRh#y^()82zG$Gga7#1lV zqjmQh@WtJm!p=wy{#p(NE3F|k{r*7QvT!NS5C4Lm0uy2Ix<+^*GYcwvA0uAa&Zpj~ zgkhnQ-0*YNI#CIL6Rpxr0DsPb%&m83OG& z5?t0wj9-s?QI#eY-h6Br1RsvU2*tZ1=Spk7>ZTsC`z$&4|nNBxU zi+jl{_3l-`tj@ z;jMG|i0#H=r?dgo#rGMJEu9a>{o82KPkUJ4Jqe%W3a)R4HjMMIPPIJTzjGn@|)!@agHwpTWRTbneo zEO#v;A%6!PerwU`b|q+i;s{9GyGdHh(`na{SPbtyFM5z9hvSv)`LZL@yucucI2;i6 z&@bxn>G24D$i5kp1U6^=MqM0cZoy5l`2$5RhzYC9EJM`0o*&YSS3ds+FjkUlS`l_x#8lxNVnkHq|d@zwQ+?-Y$k=DZWSIAz(^@yuOkKurg&Gf8>HUAW`i9Yg5#LnSb^f7x! zBVPsZ@yQc-lErBHFD(-72d$)=*>(PK?q;lbt7exy+<-Tw+(B0%Yyb4bRUW%5h=y2E z-Vtd*ZHwmefC>7vY*4ORE$l9j)Kv0$+r#M5`Q0FA*vI1CFA@W#aB8;x zCh!rjFlMw3PgY5#&R=)%2PJa+*UHD}l(vSCnRA0LTx5z{pL3A=XU|g}ZUl4H2ke-3 z7x}%;ju-pKLG0s`{M(pzKFQ<&ExldH6<_Ex52rtPx2F_WBX?qgJ;}rOjO@c%rfgDZRWDC%b+JiH1oKGpk#c{z<*p+_GW z4W*0fHR&pw*P`7Adf7dfJRT|$Otot(+2yAbXy}v4xL>aq9p9Y*k2VCQmWTLWaTUK| zX-W6bs}+B{G?ZG+a;2fRMp!cbG&cFX!aMFGVf6~eXAL>dhpu*@y5Fo|$s&7hEyST0 zh7I7GvL0g9_odjl_B_7y3E(HY)*^Slz<*EOg~K|oq1N5)wEjv2O<%6fn}>(~OoO-e*=Ts~IpmJphtDn@;wu`5QFGZe{NZU!FYE_aU3(CP z3nCinc|wFyB?fJ>gUP$U!!mnmJZSX{9Q`Huk+rTkNK$v3)oc}IG8>1Rva-9-9R6UJr*9MYmA7R&#dI*&@n=mpz4dcY& ze6^V@-+E|B#kf63;k0QPY+R^>fzJklwylA z1U++#@5%)KcJDVe@4<|9pTSRmD?MU12{OuBz$|wOROlw6nF-Jb z2GL;aE%b>bw3)_EJz6hq4mBGU_z%-B_%W9JpBco2)eZd<;zR>i9>KR(_bUx@?O?R) z0G#DgM9i}-$)?etSi=W17+DoT+3_*(@lY1t+p~!)j~q@r2QeZNGRIQe-a?7jP=57` zHm=r@rQ=;P*{;y3FuL<4?7KG?CuiG(?OtDcO?exe{IpRtefwNKcH~X?KJp1HnB7Tg z4L0GT7-w#9x>4*rDFKYL127_>n-l~~&~0+s;O#t4e7Z#7l8%oX5v>fmQs?b;6W z>~F#Q9c`GD@R_9^6SysZE3svMIUFoZXL~X8jUxkO*UpQ_Rjp=TxSGYPsY%hAM5aO}38fn%TI$rSnB*nU9Zfp`PKF7;i=CI-ZmohL(a(_4!?^NJ3-midN4ReSr4`rFRqd{kE-Un(k z2f@9982Zesk=$4G6QA^Tp;AlR$iHdPcs)LZ^EK^kkbe|4Sdopv&IBGNoMSd7+t};) z-E?M`BfXm&jCL1GsI}uZcq*&TqdkpjyK*l3cTEHJXR7i)G6S(apq3g(Pvc(6xAB+2 zmiH3=2R|*}(nFD!Fxgw0t90noV6U5C(RGkFH{3?|taD(t;3DbVxR{MD`3m9s&#^zm ziiLW9!_-NqV2+_aYPAn1P17rRSHf0$bjuJLmo=77$G51kMT@6?PQ#p2ThMi$9t+qm zxRt)teD-ldOW#)4OMJ@gRLD7v}pW9_`2mS z4kpRG=z|L@>l?{^^;;|TfUWvWr@{xpf2vV3g`K}35%&jpx};wpuiHlPs4|#yO^AF68=Rev7n^Itx?5N2xmQPRD*FcD?TX2ijqAYRu3}oU^1kq_yBqrQRmtTo!kJC77Bjxy zMtiG8e3|(o{=)wxT8*2^4Y%wk-eEr|M@Kt3~k6@MMLhpk|7`0{Tp4xc8EGXvE5iIog(!lmf9nHDr5Mv8B4&u)57m4?6YXQ@f)5%!X z7`Q$64tx9CKFhoKH-~jx9AD{h%CU_Ug@NJ=Oifd zIf0Ls?MI)%C-LvdJaPK&JffO;o6VV}i?QvMV)f}#(CfAkJAZnD;*u(yqA(SHDt$zA z^?leE?F%2m0-%16AHGrT7Y|st9wS~TK+b+^aF@ztwo59>Y5U#qwy0gyw(>hJP!uB$ zzJMXku}Z;vxX|;z3z^vhS4ib0 zOqVXjxGW<&Q|KH-^xP$*y#QLmvbpCuP2Sd2NHQZ%}Cm= zapWl6Rx#o&-##<%&)0|m5@Oryz0fHko9v0K=9Ym$Tz-KPEeUkzlfrj1wa1CL#m$qy z{7;{o)`j62r`7Co$v(a%M-`1DBcLKWhV1OC5oLXrgq)l)Jp6kPK0n_Gc|8p{QegVJ zFIL0;>sH*vPa9i)A<-7`9O7ZC#HIvX152kQ(GtliV!4!j_UODajCvA?qcg!JSJpWF- zM%tGu*l5G~b8cW(a}<6Ud=h-&1+b!45!J$a@MPpu_%qp*e_k}3c7Dx-54#K5?7S&x zID0x5bD$ov7kG|QGB+DAkZYWq!dFgMW^+tioA#bMOB)Ag;k=w1cu}~X$p0*-Yn{*1 zhnqh0{FSmqT5=ZkQyWFuU1y$I?aR;GCiD1d_E0m+4yTXPgZJ;dM78_Y@RVt1*tg(% z?A1vJ(wt|TGX5-jJyhlw-!0iAcv8{cQvzUBV4(=fVF)&Dw0>v zLr0j$y{nKVBWCtpw~53EJw5@K(_tIe zW2A32G!0w87q`vjJ2o5fqc2}!=Dl?CeMAml8K6c>_-M3Sn}cotsnS%ZJHX>iVelQn zC)9l#tcfj-zx@|;cHR>Y=^4kxy5~^s@JL=AX^Q2ZZI~taSw`HximDys`00jy5a}EV zMfa7_U8yLWHAr%e+7Q=5;*yHI~vO!5W2!mVu|7l*pndzGrK3+4jT0U zwdQYy+?$=~J4luE^o)l!)3|N-RzT zl4JS}thpuuo?6Z0J(E@Vy8LYX&n^JtGz!UMJ#UoRF^d0E^TtP$&8b+w4Sc@l!?=TM zS=F;BXk8XWc3l|A->d4-j^;cb@#Q6~;{qFL$_>noR7Lw(3EVE9k74dHoan8kUcq|uqVIJ%L9Y`X>hA*Cqw_5z6u9tk$P*5Hw#07&_IN?@JHRoSa#@g3vS;X`@~zqalg z*lNt9Uax%c=oWJx+3Z0#YV=X(=Erh=Ysmg+ED>4{7D_2Gf74@nOE2n@)|8&<8fr84BRuB!qHBS_9hwdh0-|? zbJdt0sMDv%X7oe!k{iN3{0!T;W(jkfmybufm0(L+J@a?ok6w;~(>b$%E!}(shfY_3 zD~qG>smCT*Zdw5C;wj{l(_(0II7l}*s*CTts$g-QI=&4_gf}Bw$x^59_~XGbC^=AF zX;hwuiNbYrkZ1@Rcw~de{0qcA{sSu9Ol7a76zQptb75m(JF*ZNt|xSbW{+rvpcU5W zBy#}T5|6;H;c`@^+e(~2J6?Pt&J8|E7V@W;P05%A=g{w;EDX<`1NQ}vA9hJ_nW!Jk zt?Vqc%+%mMxB8)xi~^_N?NqickMY@$QEy-k1O{+^%_EBXtRKPOEKDKCmh14uKN^sc zJ)Ao>4B-`~jx^Kg5K;aqhQ9^ASa)VFo&EGMmWN!fu(-4pP3=bU2)QSCcit)f)8PnT ze_p;SW7;t4zoMH@G+mIo-%YgzFxat+^|*; zqIK1IZr=p1pqj?dZ`R^pQhM1wM=N~o`~)qNB>19+o9w`E!C5>YRou}_(9U@(hCKD4 z@hT4dx{J^iwyGg9qQkuFR16QSkfsmx63{9-0X=)9`QBGUd6K0m=4-^zGRa2#js&g< z@7ZPRebg>WmnjSV|KE5XcFsJ4mVO>wV_h2b6v^_G3Hvc4Vk-VQIErhgc%fUqKX|Ft zV&?@#RH>bf0ee5dss#b`$BsixUg$AByFUi}`)8qp!aMP}MHS2;SBZ@f3Eaf!YAic* z2wz`m$H8lUVfK@~L}jB0U&l#f`>4ru^ubwd;GQTrZ6-^9pSgkSlLzDH%_VG<{%Ck} z)sK~)Hs^kK<^y#VyuaTD@~`P4_-?Gshw+(Y(6C4NAZ81;?r0$OUsAKc28A99^XY~oE}%%GKM zcR7~ENPokrLF;kHCw2HQ_=d>%p$h&hzY5bYZiQp3Q|K>4!PEAk5|bay6Min^FYjs5 zQnMK5_4O8;Bj16!^>M68&jFvwG(leCT2T8KLrY4fAy?@;w*OvDy@saX2N!iPIvfxC zZ2kG8+K*Ij`UOn0AH*xRcvEv2mF%(SQO3_jiM!6AU)gH@ zR&d&6xCm#kofCLgzZ8!jY>n~_>QwB!i^)b=!Cjjp^sT}l=y?5MI&g~@oA)I(|%kLI~m@m|H9TqgZNnN7tgq8PUqcv zh6U^%T8v$Rrjt~-+d4;hpVNxVQ(8p_zv}Wo=3{A_XAb;X*@HK-k_c1Cqu*L$_(>t# zw>`^~E*KTgWI77q{hnZ6eYY4#M<+40&>u`SF`3=?8w2CI^5CI-1+3P+hcdEJ@IC%K z{c`y&uF}$_?<=ZdQ*H|y$Uf%VGEB&B<4}I%NHBeB-~#z48lY0xc=;ieFAM}~@N^fF z!g)MR?I<4_k$`)iEC*Rn3;x(AMc_2L;cumx80PkX6lm+xrZJj$`LYK|6#9pML;QKa zjU@aUM9^G!C=C5Ifg7o12%blMaQLZ9c^YlwMQ?Aaghn{vl6mJAErXCbPS!ZeE{``R^qcc-4HJuh6iLfz=Fa1 zVc5ktBKyj0y4igqU-=-5-OzHw$SH#$KlBE^H&4YeX<@b_cF!h?{4j2NoCgB-B^Lb z^Go}6xP?-@pdgeyNl|8dU+sWPeYZsa+;h?8nIaD@8xQ2l|DEj5aqBwa8hr5uIk8g7cmb?j*n({ecf=Bdn6XE9nY6f{K6mU+VP9KC8}P&OW>Q7oSDArDXtLj zg1Ns^pryfvA71yJ+8-!|D>5mRn;!;c{XjaU_&c38Z;*Jc;3+$|c@f_S4tOT!H7@v} zM+26hz`VF5{FZkGue{LX;XAHi`i!R-d|pZT4E5vstcl#%{}S;zcM4+Os+B^y86zW;O^wWF1|OV$)}|7-*so%$c&+T2IpU0aCH z)RiImRw1;FIc(EZ6b}wh4^`^_a3YJwjKJQ8)i`H~vCXR17;#U=apECaOH{&EQ2k%G zvE^|R%NTM9-2aS)vk}TLPcd9FbvXvedcn&~G0|y`A;X3;v`w!Oy{|JR zfBo#JapNswb4m#{2R4KIL>bmq6-|=uw7^g4A}X$Y3^nWWM501#_WMqsD6q*$Y`Qf9 zgC&;}cgOXjzWasX{Wl$Zua%K)S+j&*;|?-w`*gCQ={1>~UWi5WAF{ot#zSsjBzr1+ zU-oGI5I+irvjx|ug_D+?K)evu zNYWFcA+~oo+(?;4R0YpM}y$=w;?n_DjXNPhhp5yAXpt4 z4*U8y@Jaf}`)_?g(c@Opj<>Sn??nQ$=~OcAb-qCBkG!*yFVdpZ+JvsjID5LKh z{==R2MX>SXM1D5(CVRJS7Vb^#|v8FlzSMT&^?y5B~K9j zxUP#Ut##<06N5lT${8bszTw9=ouVjRNn-h|8b+>L3@cT4k;$wHWkn_=jsdn=P2lOH z!q|uw8JLhG$-CEnCqFz4QBkd$P5;Ll0puh@I)tRH}chO zI!{;CCNCaVvefEZX#Ddn8I(ByRvoH^kw3R#sbdIfPfUSo=_In>`y#w5KZWL^8^o$3 z3B!Hb$UFA~e68gsA=iEzziCVbSO2SUE>n_`dB*Vjg_!B-7qRL473tjFdfY!yky=?- ziof4mN=}Cwfs^ZC=#EXt?vgZt$@dS3*T%yeV@XsV!PwYrThjmHF_HXon0%Xk9L7gE z@xmr`n5=h?tWA0jn~xWYPh|aN2QQgn%#$xLOimi@+NY6=7gJCzsFcuY3Cz&y4~hHg z3VWW)0l9P^ONt%Y3Afu|>sJWi=`Awx4#HR0<@#=I%X_ zm(O^?H0)a0458EEq?(N*F17!Usq+rU@{Rw#O-3P9C>aexNF~?#Iki!=XwZ;oOS^AF z5h8npthA8KqQ!N7&YPq((Wa%n_tK!}`aRF_JjdgY`>*@BIBuNRd410J`}M-*OYVd2 ziXME3YJaldzzcgH9LQ5X_J@fv!8HG{Eto|9cHY;$4sTdTQY+IrTw$lVl{6lgv z<_zeCJ;$l?OJ!NqV7dxFUMz7k-Ug7EhelklO7h5+rtybG%5-PZJ{r}zo}9ZZaglo5 zW{WCT(`Op#EaS}ua?i|^%}9_sG(M*>p=TlMjG@eDk~&#GP>$P;cR?%p3V5;pD-La{ z6>o>EAuqP|WS5W0)2k<(#K$oPF#N#;9Q5oTuzw41mVpKg|9Mdekn0ef@=S4)ngUq+ z4aFJr^DtsvE|D+`;4|wu6e_g{n}_{kj}o`A&wKiF|2~EE>iBXjwI4%@r>8N%65_C13fbCZX@uqKoaf^->(Kk#K-uG#OK5P6?xL;+<<;{+C){OWqaJe)zniiSlTJK)dIB$xZO7-nWbdyQE17QDIZVbCGEMgsB;%&cDg@hYjculTInp=QdK4T8XoX%m)m94 zO&@7TNt`TjtaKnXeuRvNeB>+d_mHv4du0nc$H@M?EZ~Qt+wn-zFxj*3lAb6gSthC3 zc!=ImYFX|lnZnBFm6(!|T&q;aF6TEO+L2nUjVn)2Yvqb@MtQ`}{&pHf~;TS$g{s+0mkvGM$f+ zvh28DvMU|2vNM7PpVIpdT@ZMPkMOgU*+|}iYxB?Zwl(>9>UwMpY?>Wo1e>n^@Ewp5cdn;un?@rL; z)py~?((`=o{hzG-hmkC?`39$jlVmqyon%RBy<{H0PRNeyX3MH`Cv%Us3$m)ik4ft( zMVE9vNd|gjkIZ~TC}_zu`kC1Z~vL zknb(uJ51ir(78w8;^6g*hmKwDzkW<$ptIdrjsN#9XS+!XYH};&t}7d;sp!keg}L;V zlfDN0&x_6fyja~0S5WW%zc1itKh)EIgXhK|?Lg_uqwS2G|NrZZ)%m|~`hVZ&|6ICK zDP6imOqhb&=>Pp^8m6#T{<-L3dW#fJFM|24>v5%8Uwn6Oo>ac_0EGeJV9E`scl~fY zIARur82X_9ltP$T9>?al9{}GGG7LOdDjMltW3$E=2}Ab>&@ic7HK8Q|Y_CQ^Zh;}H zHD95p{XE&jH5{KO_b0vk=!l7hEo?+b2XimDO!U?c#}xH3=yBsQ9@r0+vth z$zPA(NABMJAd32%&?e;q2){M>wl)hkwK$#^^|FQ)Pjy-Tl=bL=ZKzuzuu0#f@T6;q z6ePU>>wUZ9-EC*tc+=frEB(AN8o$wTes`X6<|uSG+5o1%kMV5NE26lF>^Ze{?rOT46S*+ z>2a|n$_YZHVYy;2QyQBd!$NksJNs_ehc3e^Xr5L`}M+oha&N- zd=A+-rxrA7hw_yTl(pEs#{BKC(dS@4RE>^f-ec#pxdARPd9ge0oSsbX$gP0>bTLaF zc#;j1hW+*fKA`;R!)$L(A$#Oyj}b+-V&2h(^q#|CjMkdT6vhOxqS#6@rR^5$J1d`+ z1(lQ1)i<2CpPvR=3(E0oax9TLX1H19v#@*b3;geavACcz5#83b3t@hjgj#xzSesoX zoo@bEtm%czwhmxguR7TRrz9}Fe~9gy8%Ni#y(xUL$>KlgPhuCH%Wn8hBKo-&EVCk? z#03Q5jdzah2b06}NhTQPU(3{w$-%|W{VcxxAS>^F8Hwjr_Lz4H&a#PMH+`<)px{Y{ z6jvdk{czIAaCULPE-F6U$G%)rtQlxx4hB}Of|ge_n9WQgm46O{ z#$Z<-l+Z!s`_gd!j>PrQkAuGj`M#itl@Bv)sFiYoxgkV64tw)!4v&6Y00pg;)txDYbngcF#Tu&8~XBtX6`XdVs0p&NU1zgZRdRr?Fe_&y$+kKc!kKpV93n=8y* z_!lN*wF`PWj{LvvTH*skGcha{lZi^kIS5`HgGQFue$rei}oF0V!N4**p&{wXBuGWuQe>#v=}d|OcvX{ z)Ol{`HN=~xkeHlCEDq14^TWLGkDfP%N+H~XJse>1*-Ff9GJ_S{vT?^35eLsY&!+X! zz>{@R63{|b0*xxbvP=tHPd~9yJ+heI2pzsjeX;}zRiZcQ#>4vYqeiVuQgL2t9na=u zSi;5W5#qhnETMznCLkK zY{rf!Ck9)PUE$l9SEQvlB*|1XU+K&uCn-STh=tHr4h3h7csZsl5^gLaMnlb4Eg=JP%zpVhx4`1)GYP#sp;AJN1VLX zq{f^)#lqlz#2#X5tS65Xn$rG`YTUaXJhd{#13R6Gd0?hcHPn&ijt?G{x@;`b)^H)D zT%WCS*u<`d+t*w?U0dCGBbeQttwirMsECU)<=DGFp*7)UCgQGTJ!>o))`?C{0c63l z2n@?xf|rkvK)J2!*@lp8oW8aLU3mj4<~vZo)yZg_x*cv0JAxgZT2Qgq9@6T56PTyW z3no5eJ(mB(f1xgXj^-&WouE&3?w`V;YbRl4Z7G(_DnUh+5NJ~KMqx`McCItTPAQzx zC-x`y8dZ)V&3Sk`%?S%>7wPrK1cnQ`d|#GS{54J?ui6dKT45R4d0>n9^<||bHory= z7j=UPE?olOB8O%1jBW~V!!^YXY~FMi+%|qCS>snj-kC^;3H`00YQ--J{JuhzO?5== z4Rd+Mniyy~TZ66X(m0F>WZJrW49IwGNwvQ+iV6i%(mc} zvKP32{$Dh+5W)L%JM|jL;CIe?E_h_)$ji&wW(^ZM@2vt%6C8v#X+oYNCly=c&hyYG ziDK&~2|8yy3U}71vzfJtA1P>;507>SIo*vDP3P`A~NcUN!3 z+BcO%cll)Soh-pUR5GA%rYFC@p`Loyg!2Q@?z}m$9JS?-!e-+xaJcBpFFfvoiK7$9 zgT_~^)zKWzjdT$6ETZV(gK@xYl5qUh7|>EGCl79Q$0endI|waM=ldKN7rBDk!~k0F zeG8^cOQylylVDiQXr5j>h3jgMpz1{h=+ZwN%O%*)=|FjIQHsUE=Vn z8E#Z2@QrOpa7F7b7=*j%I0^9JG(Lw1ecB7>J$sVwg~4FEs*HL`(&P0hW8ihnaa6K4 z;p+_>#lCH`u~dRV9xuy*nAAS#u)tK3)(oca)vaLPrz-09xBy^nCsQCjsaALcG`=yX zYKzC<7?0)fLOY12v=-6h^D^nmv-4q@*4I(GFJH4BHNn^v=|qE{SO`OQ6bpgxUNHry z8D#Jc0&iWjgcje!qWR_)wtCDyru6j~4lZDjvBwpb_0eG^DZ|-qI)xN}E5hIYhslVo zububQjU!5XCXl7ex{a8>Y=K>bs6QJ1Gw9H~t__w?~lbxT{1(%aa8hSHnC9YcjfN42x)MU~RW@ z*_)$gEcbUmvD>NntmiKi;naX7sCz_{g*)kxMDts_^Z(ym@%I-as!P3BJNj&3#0>|~1;`#5+Pn^!jzei!RNK+qxb-qexA z7FXg~&B{@y_9|na0>_#I!xGrj*c$TrYCMdd+n1UD+YBFfL~!jKdEC829`_j@MYWZy zk)1s+l-2JdP0_(*!9oWd+C7?Wo1V<><(R>Z;w090bUtxOuVCieX97O`Ayxz|g(0T( zto7$5@=9@t1ir|T-~)Cz_yuLHMx{dN%**71B;u+JjsnL?2S({$c!95EN92#Co=FGkVo9DI?atCpmoFm=8pc?Om#z6k7kr;7#7Q1}86c@>2*|7d$ zXc%A*_U_L}ahhcJB#7WL>;Co-XWeXL%^&nAM1C1XTx#S62ax-qB9BDqTSH`7Jog z!?(SUvH)9EQ1_iG$)vbYG@?VyGhPobgj}ra)qrQ;8ws5Y)S*l}9)n)o#RTU*5cPDX z(B{32hAC^K-J*x69%2LU?kn-|N&2i}+aByYjWUg8gGkM?<@9UdX&7>H9yx5)hn<%W z#LBviF;=S#6ZD6{6IW+6FH9pX$!*M_umrc}Nd0@P6>VG(lDP+y$&DpC5Z$f;qZ|g4 zKcXiI@^!#fhdPoJK>%^xSGntAbg3zJZDp%y&qv4fGhYlvH~zBurv1If6xo4OhA z6dTRPlR+2M`HJpAZ10FJRyFQs&9^^F^muv*KG4{WBWhFOuoPf^Z>`FviXTbNhH&y= zsvACt_+7JlnhK1Kaf1PWQ}IMMeJCI4iJgjG)P1WwpZd3m%C|b=TaD2yA$|+q*HQue zsK%S7&0z`ut)d-aS4q+1%{a2?Fj;+DPJ$^J!^Or+(sR^uXn5PeoSw$Qt%NkT+37w$ z-FcB1*_xqS_mf0}&cK_6JK)NH-_Wz8fMwzy^2D_RulZZS%v~~~F=aovHg6J#G_He% zHun72;I(A;t6`*a-5Lm0JcOgaTHyW|2eGX&5U;UpJfj^&zRo3L;D*ZtCPfM(DwNRf zlLqWr?oH$Vo5s$LRHDbW>VnKY4oc@F5~VL6nQY8vp=fG6zNx#+hG^cwu7~N+mCzTx zx{gZsw|X3IABR1!-bc&FYw=llC|;@20DtvW7@%v#Z}?BaP4}Y->yjW`fBW;fd0O~y zY%0-^Bzu|@N7Jo;>v_eSg_yrcDr9GMAgN_7J=&`iJRU3)J0_XK z^q9Rkf73?#pXwuceb|79or}Vl4I%8XTpn2d(?_S`F}%cVCM16hL(HE{mSm~(x*zx9 zk`*HrkqzRQHWP7yl@U5Oc;JIx45LCGk~#BM@E(!!I3~l8&bg)q-`NJb_+1WKM*{CX zy@V+z7So+SoXO328~jmu2lh_i$Z8tBps9Hz{P_74j?qx^WI{}{^h(O0) z6Is75IbI(o6}6pAxqoySM17aXgSS55*WeJ?-}n%0w}qjv`3BmnOip%mdn%92NW+e5 zGy1)`m{z(J!>p8SylhyF>t~(EHC|nysa3;zNdkcLHG|-J;wAPLO!2+;lbQ{W#zTNz zE3{m2!YyMed2-WG7JDy_vG*GE@1CXTf5@CGKa0Z~ZvVkr4^?ijnL|v?!!i4jFHIgj zg_eK*CcL`08q1TlIsco0kKXMfW`E@AqTB{tZv6oZib92?4MEK3;4l^_?Sph%^|+g_ zkpy-e%Kx)|gDVQ>^3ZrWnmT(r|5Yr{tB;+6g0h`>JHLtD*2?hj6|^x~wH}@|#j;W19_V%BA~W`%1C!=nM#Y1laLq{xFtyQ}I7Sa(d#37R z$3l4?yd@fTuDKx10dHgS^aWy${~g@4;RX8^>&o))ND{rr+Wehz1RfmILlPG0V7%dW zIA?Q)c>Oiy$?5&jXTmOeYN(O(z7>1$z;=MKY)1q-2`VCan0+9%Z9Jyy+MVhSySAz_(^q5i8R_OrA9~8S9m_tjrc)jOn_$!Im9LEoXwXdIn z;fPTft~d`p*14dp)t4o2ip5)x29bCD=ToL<#lrM!#k2b+Ud|pvNjHH7^ z^98ZExc_lxeEdIDI{c1^)dkossVB+Z6%A^V_-lMqZ^38W0is$ZNp1VQf%@n=tY4TQ zzL_!;=UCh0*1(-&e#&d|sp$#%x9uUDz74^t%A5u{sX^qLPPdr3V!{01-qzu*fFJa@{sU1>ezIl(~Y;GRajaER@ z{!4KC)#s$EL)z;)b^~YQY`pmE5Lo-$gY}Lw_@r?KJ)*}_vkB@hN>0gW(l&vADb=T3 zxCX~|81iNNAHv)PwInrmIg~!Or5b*_xLv<$niE`w879*~f~^P{dOAp*U$I?2ui(%$ zTdH{fIQo6}qMgOZ#Ov{{bX(_O4B)46B42^iX79sa%7JvqiR(D8+dimYx0uTsouK4r z4ERW&SBFXyXm(#j`%W#9B#eFd!+#a<^uT>MV;T-uB5sK@LRAEJn=PV&sV44Ex5OQt z_n5MZ73!^c$47igq`P;Qi&@Dx=-@^RFkjy+n7u3!kG;4?O_!!iMU*}?dQURFW<8hf zNIA~ty)S_wa!2T@Tm2{`Sd(jVx%6=J6GnZa5XU8uBSnT-ds2f}1a(&XA6zY!)HESI zdlwz%GlwZaHZ1?B!zVeeg8vF zl5xDd9(=YM2uCU}fL|X4x>)xro_w1N`%iwO6d%$Zi7~WryF6ci*#hj!lBF42jkw$K z5qom5i;(7Q!74Tu?Do#Wg_g(JjqiFj%67}h(TTm;#8bNP%P(B)-Pen)nBE9K4Nb{c z<0=@s!b7@8R>O$gT{zt70@Yr4hNSe`Ox{WB*<;OkR{DI8`1pDrPWz;StuC+FqLfE? z)A$(J?;HlN3KAev)t0ztW}vOZ2KL`WbL`gWOM;Tz#mpn4;91l}c(>#joZovN)B8MT zrW>8`i)kVL7p)5>4<54Lj=f-qu_}xE){Iy09V1qfToj6`prq>~*0^`FDbs_=>iU0z z_a-GaeL*tbGFKqKbH5NU)8msi&cG`Hvr+G-2A`T;$-K005~p}88gty5OOQsW=-30x zK049CZ@1w=YjY}0*Fw$vl33vUAmTVT5u3G7vftB}3Jo=SsM&uf%$!#xjJ$5doqi4_ zZdRq(HYSfG>vw~yCjq$Q`BS3uc#>FpFcGHzUI95uPQ+kn58_pvM-pD`Cu(9cxWo$h zcKB@c^nc@=n7xM%Ab})Lg6}N!+k`p?4norS-oSE)i7LK5Mc1zeWP!mT(2XAHyk?CJ zx4k`>yM8g@7hSHiq$_c-zv=SnrIw>HKQfgB_Dv(}m$$Pw#dEm9=^{MibeyjFV}(tF z6-c*n1L4t81^9GsH9p>DLfXxavdD}q_I6ky>UG-#0lG6_LUb_utb$}usU(OtK1r@y zB|3+jmXYjv1w@cbCEcSB2}=}B$%S$2S@Y+ie2DD;sJ}HzOqce>dzBZ9CEg=pp@k%m z5BNY7?_XdoAMOk8DeYu_-#oHv_C~U12@1PizQJ836?UbqAGsYjP5cIZ#e-{35$9!x zNx+ZO&MIG1*m+mR+Ra1I#;}N}#wL@)7tWBQ1ASS;40ocNN6=es3sxG;6zt<>kmQAF z&OT-5NcEK;%y`6ER%TwsO2W+WrN5T5OJhIKw0lgtUFb#?4^@yCS^9jNs0Ztu7Yhc# zZ5;z=pUPNrGnM`$`aFpCbMG>wKZo~cEhmuNrJLvKd!i~fnB#YW(v_Z zQ2Z;6on5|yj@^5JtT;GU+~yVPoVVS&dby$&*E4d*KYvTvw>cpz{Zt9HjyGwnf92#foP_ z`&9!iNM#3fe~Tq$1B8Eud34LaNb=EiK0iJ$3zhrn;33Z?VCy^p$v#gU7<^JtX-_B0 z1Mq5yu>niVGf3#8G*-XvK#fJn8KG&fC$5_ePo}pchaE1>COwZ9L)X1K_%u+0o5?LE!$_id!tB2zbG__ZQ!Gm z2B4Z)K<3qLgI=8{=}SrKu_48eE*n0+dN;a2kNgN{Ew^)E_^<&c`S%5tfXS>a`aZmT z;{@X+$=il`Ms%oCHWp+7_g)f2r?6fi>=tRXxjMv_^}*}MZ$j90B|cWk7vA@3!T5}m zw8GFBra9|D;I*^(-@*0VJk|^59PK1?} z$Z{;Ik9>?}VN}(5Tw62VE~!H(u%f#^oRkEbi}6YCcC6^G%I2rOXR1H$!bQu+82wZm zXDYuWtE+C+RxxXRyvP#3#ak=d-&e&DQF$Dk7n17 zXJ$o7*zI&7Ety}B9~%yn33sp1JI4p`ZYQ#6n0-&^`C=HxwKu@1b16dT2NnMPiv<}! z(Foe6W=kcm`;grD9zIPvNl)|`5JJcJ@%_{_mPGuA3q%>5CLetRN%4+l34pi z7d#u$g0BXc!kLj%XvJXYYmKFHtjBJu+BXjN6&}K`BcH?i`Utpn zND$d1AZ)y}Ur+9~5%Qm;``~GS2K1yWq9%dumXf3_ndr@V6TIaPjR(e7e>e z&b9;ndMOhMbLv#-{ARfj)z9%H@8xbR{xY4t z3krwu=3ew`(@wU3RvqlSw28Y9-iO)h!vKTgc>iNYFxtS499sQ7@EPt_q6N;VlIwtT3c3u#BemL3w;2TSi*b8K!JyI$Oep5gyp%+)6?A z%?b8yK1CwJw~)`W{rvr=M$})U!Ltgh@xL>AFnFmN)EVxD7fwplW`!mGX_?H1PFe|t z$tAQke`m>1QbmU~a*6|FYhc%>~bwrm8W z^mc5Fv!Lz04)b$v$N0}7-jJTDCfmm6Lr36ed^_tSo;6S9YhPWW*}u_L>TsbG+n;ZNJCoz+MDO8(_>2c<-vnFZ*5*j$F;eQ3nlh&$=^MdHfCUGWdYg_Rq(0 zLJz)jX$$Q!<{ystiH9&7OY;2I6|5+m$-kf3$+MM%z)If{2Q3{({k0cz_dOP}(n(RE zo7juipDe-gA7|6wu8w%@b`x%`Mw&bG7M6asC)ejrq(MdbxUO42ddKIt6mC`JZd3EH zuyQ2VT|NO0x*O7f{~YO@yN|i7IS9fe0G81+53E-X<6b*6vE-NoC*k*b)@~!LuC${Y zRrkc#rdf9LZREj{_=tR`}=Mg?AI<=}k(Fz!$#iNJPlB^&x{@tA;NyymegS8kL? zF?|}BT{?|blUCDAhsChkN6saF;1v?JC5)G+sq?}l4gS77U5K1-=5*V)JIA-%s6x+R z`Y}O|9{ZgGN;`duSEy5d;4 zY}~Ri`jU=;-ruI_1Nj>gryQgP(enh!=hN+ZCz!w}BI{Z0UKWWeli= z^p=SV!$^x;SZz#&~L(IHp=QXp4hF9c0CH9^ioguW%fCE zNB@bgzsqsjO9`Gi=n(avI|QEHwPMdMhf3nU-{e%$Dw0d*h))73S+~;{m0jb}^?o7E z*O`d%A(`mfR~Jo`4Y)~+2^cT*Arah zUGEMyTrU!phfb%f=7rNW(S50j{z87hdM3X$v!W%D*vRJ_4ia{{RdmZydzG})n-mBNli=`5(Alx$NI z*`qdRcG^Qlbo_5R`RQtf{ zQO&#_D3V&cHu5yo8Cx~)2m_zL5hB}*#j@9_ zie65_lUs)q@>+rjoQot?N>yZTu{ZHDdJR8b)kA5b9}C+4AGF3qBkhA=Z&CQAYYAPpIQN}EEkrUC0RicNoMpCbaG_lWYiaHOx!N;%}h6H55?>W8c(v@+r z#QGO2)jv*zU&nFW8yz0kJq^z|e}KHK6IjDY0>>|RV5<~2rQ zP)aGBnQTF1rHwfAj1trt>(e)T*5QZ1Q?TyVUa3$SMcCdIG)#iX7b{5dM8hZS=4NI3 zC1em3n>WD6VPDZZ$CGqOYxJtY&A4Z^3gpIi2hx57L(})~1Uc0P$o9U-{&~%&Cmw3?Icw@!?bAfOF}4a1 zJV|B2uUav;#2Ul?ZUb$XBOuc{ApFo+2Q&##)mM@-eb0v!yRkTAUl9(z5|7vW2MBYY z_M@s=18HB2UFg*u$kv=eytC{a8(>gN(%b$AS{efCYwkkHRYh*RF%N#N35SU*!lA(; z0@dxRP{+Lt?T`LMaqvjKb&$2QrP~E4-x7^-XQXGC+vAzhyKr)9#3q=P)rPw(H$chQ z;ZgxM91V0@iQr{NWb-cIg1aYq%DmoiUCA1&lWS?@j0Gh6uq5tUrGYB{KA}d-61-wC zgI>+D;UiY=WxWTduzg1QT=o1Y%pW+A-;wsXD$B<4d0D-=Qt2_=_9I?c`BjaY@7Lp# z8_Ur1r3bB8ZNh6~ui(vv(e%;Y(R^^EJcOSvuHsd<+?%%?c zXD7jnOVwmX-wYUWuK+fTP@~s|QkrKu1}0dK5~CFN;Fev%Om(IQj1z{@Pg(m3i%j4> z3igwd=gs8Pmc`Ql(8|mfO>}k5lQT$B7V9?aB8| z{fGl*E@V0nlt`b;3AjqPp2=^qg{$vglk7*G#7Q#^w!7u?hmQx4zCC3aIW7a0|CLKH zfEL)0`Vx0~DBr8Ao`PlQhf=U6~{Hhv771E)`O{QUhQh8RVV@LP6xtp2jJX8*;*i49cF z(h_8e`h4i7K~N*NhkgCM4y%6FqHpeBA^+SHah^{MTGeNf*6c%QxL<=m^{sN=)iaFs zNt0tQKMh6W)@WRoSqn=G=c3iJ^Aga-38BIlic?fcg5EgTzA21N?k~@$yq$_$8=uiT zAFm5{J_hl!uqE(vtXj>4A{+2~HxdtzEhg(9~rYAW3JVu~J%FYkqLt^8Pd{dmBLK zmD=N_4JGK*eZRQ%#Wgl9Bph$7ONB#y&$ERYJ+WtD9-MiZhRYKJaD>hho>$QaDxXzh z#d#z*yWbo!R)dZLHaUEt-_4sG{-D2zYz#FI?)Id%Zc!G=7GHfu)&I1EZ2NS`vr=UAqaj~pC}lg$viQp5Hay{*5B>CD88->X0*1f5?ARJCgzaxzZM}GI>Se|m=F=TF@g6?LxGWq-oESh~ zn8aes!W1&KdnuKQX|TAU7cKQ$0jVd=>E|ixeE$s3bC3f) z7*B9YV-mBS9nDq{Wxi=+J;M#V(ailL3`$GopCq~8(P|s6`0_2}g&m~xY+B*Bl{&fp z^ED>MM&j=x7x=Y#7}SzdSX5m_Xt+N$AHEyocWdV`td}(08 zB1%3F#C1L7FmsU#uezN^%PZx0@)H$4O|B0e7`hwvyZwXhws-O4h{>=ft_);{`cbnX z=fu=9Q-1z{FLVY5l6T)y!M{G1s$GuduOCR~M~a_e-`+7abkac-LJX*mc>-RnyiP79 zhL8_ebf9I#PEb6RP1U#Lvi(oKgXxtd^z{wIo;Q0k+ayUGrSKPCJexsllh5PWPyw3W zX``$l2NHvN($MH0bZbgqdMHI2HfbLWBYsPKcL7%P}$p;7d!`#$zxN&1IhPL+RKMD@8 zOtU?B)5Jpv8&E{$6esW;jqTLxoGSbZ@#DMB>)@A_o;2~-F9?)ChQWS;&^9p{wc~Q> zrlj5Mz^&EvRH-_ys?WgoVm10{&^@@cY60Dyu)IbsC<4uFn}IHK=7j^@YO>R8xOLQU znjr0o`nOhKpm`5mb87?_`~zr3tQ@LTt>Iy6dDuAqC;Mrf&SRHsA=Av?R1e>1$Nzb{ z@y)IWs7l2@=N%>4Os8-QS2mJP8nQ{sUb%=J3EzgQ5C>Can(pOn$HI&fflZqZ1`?ernfl z5c0h7+{M$pu5mI%^zLDZ{&a{H>D1wS@{zR_7$CRIhVci(arN#T z@*z%S>C@YY`}}k)xTXobJRXlYjKJR3FImzfO{~08ag(Z7kt zT1BjCVL#eu)dIZaa73JYwHqB@q$?W;6#7 ztz1H?$mSVBJ54rxO7lp%-u(WCxnkQ5c_rFuc{avY~ z*tRGBc>at`eVzxEsr_M$?mJR6s~(*`Z^eW42gRJWqY}hqIC*D34Sfb*WLrNzBO5l& zzzW>}yn0}^v*F0ckaFG>TEFGM*BQIn!tg)1B3zSLyJiY)VUHp4Y7Hv5+rs%*T72fq zYBuezB#fS6NQ^6_?$x_k?095=EulGl{^$a>MVet8{$O3_TEBET_^G7fc=;1-{-%9+ z-CvFF%$H^?o8J`J&mZE8K9PWZ~Ssc#8m&gq~mgb@rUvp7W88pxgX)djmE3d z+TmwN(HR>ow)^S)G0h6zO4;jo?z_ZOZjW)jlrQ+Y%7qg7KV*QXJ{&I_$iM3C!mT|7 zlwVi|LvClXLZ8KC!Xhtn>sl6bUl@cpo%+D)FOQMTrlN7TIk;d|FWlI)7^eoM!!hZ+ zfSb+_Im70+LddeT<`RoiYt7R=IIhV5_FrKEefJ0x8)$y zT!K1x#KF7SNrZV95qpmTIPj|pKd^g0+4w$)^_<<8$a-bqpdWK3AW#&MXwGcVg9ftv zSq^R)6@-6w+CtnO1*UK}6pJ7Cf(dr5L{wJ8ow-M#xalC<>sKk|AQy-#{@!%+&j>cQ zDV>EYA1BSDq)y${!%X>K3~8RiNJ#Wr?56ku%OweCOH2Z?2N^6%|Ftl@%L8xf7{ZtD zTCA#HhS=}Uc(nPf#??*cL#uUnSi7`Mv~6~WYorT@MauK;*X8-D3J`Xg7~7FBT>4UiVOTd6S;9psH3b;PsCT#K*z`Ala%+` zQ*jJq23zv>okLLX`a(3W>yIxxE|YC}55=$JehB(cRGobrLrB8sM;P~-vbd+0xca)e z-0yw>-!wM}?)wduX4IPe_5nrevG@`G`!Px=vl~h^&ExUcp*6Vpk|RAorxbtwosT;e zuAqwj3L&ziPW0ZDj2A}rLDQ^4jPFbYr-L0VF5#n8Ov!{P(ckcBgC09{{s$>jGlv@` zt!&%k^>pc-Y$&_sj7h6@IB!?mrEn{*Ua0rz@^}>Wm5lzSrDY+>Ye|53puN#{XjIJp8eG!!SeJ?2M&Le?iWmv)fPiH>b$gdj_fcJ;rVXsWjBse+}rmQFjW1R@{eD*n-;C7JN zJ4cvN{sz;^%BlE!%_0aGaSH-bp%1AwBuuuRBnp~$BUgZ<* zp_iap$CO^r{YZQxR|$Da4gRJ2DC&ImFGq}9A#G+U@oxlPQR^@55H#R5XKQKcp7o@k zJwm6u{2<=Vf;MgwfDfXN&`{IoXt6Dr?oMBUyK9@#-L@PaIvyv(T0>cpIdGG*>~Ptz zbt3Im_Bbh68Th!-;>Ihd@y?GReAvH)^~VTM>>D8Vxjj_!W;PD9m;ydA>Z}vy(+A51 z&uV=+PMNU}hY^e|^cpBB{&7 zw_d$EmzD?u)kqQSEG+ zgOBlIi6uFI(h4TLOu>`=r=Vczm4 zan_D_Hac)LRTJ_LnFiC~$RaIn(nT$PhtYAg=@v78^Jd_W*L9rPP)_i9FT+#iLPmJL z4eOtMm~IR_Mfat4ifYX(xW-6({C8OrPW@JgRoTCw>+MPQ-S-Lf^8}uTXIw%?Dh{6r zzSMz7+wro3aE|;Xlz;!Y29Z8WLXK!0_$A$-b@P|gQE-@{VN25c*L@i|qJ8g#re(nlFDWUAgZF)9Vc^#)Im)bF*tdA!8CNmN@ zcyW{EWZdolnMT-mlOeu4X?oi?Xi*O*b1%*0ZM~M!B5!wS9^L_IZ9W)d7|-sS(Z(Ep zw~@)c5s%ZnW5q{`r_h6wGqJJ!In{f)8cil2pqJmDAjMH*%H3j|@b+U1IyK)`Y*Z=~ zV5aIL<1r4+^-FPkYzoqKhmcv@ip+m)&^})pBc{bti@|+3RWpP))F?t_=lQJTTw%7? zI)g)3iec{VA!JUZ25!DvOG;N=g082k?DJT8oPWTUNe_^t%PwB0Qvb%Hi^^sC-hKqF z7~LkCgG(Vj*Qtd4{8?FhIYG7YPyU8P>I2Yo}VA!Vi&wz;-& zE^@$*xj74d7F=YjEUozBUw1_JmA!x;Uyosa({UTsAeR(e@qS7SF7?^ZO6c4qyJ`@q z|1N&mM{9m<%}W&LyR$=orsH%0*6wv^J!H=PP8Mp#(v1!i1t?T9-|*}hzSem|*A+dc zSvrdR6_+};KSP3#$k&JXok#Jt;UL&Vv|!C?W7_HTir!Gv<2yvLtm>&8Uepu`YrdO- zRZa|@e7~Js7-#`wHy*>2gJAfXY|^+{hYO8H;x1K)YnCixBlbV1TW9L<3ni^-d4UBV zb*zR>FE*l^b1QLjWeMCfdJM(dKdFBG3w*h;8M-dU!KNoX&eWbxwEtP~%Vx5?gJb}g zG^x6*bo(=riT*QccuJAycO3(hj}%pBH&Lw$7iR3YC-CrCA=NV~2Knj2K3Z3f*A+ja zU59ko`F+xCzmTC<(a45Ye`jo8XT{zc^^!_1l)#+jr%ErY1*1=lF{G!d@vr>rG5ez& zjWFH9OWzL$|BMF=cT*PizXV~Eeku9)`aJCN$R|6}M)6mJibU~y+HvLbHT;V)w=f}Y z0ZovJXS)Io;C@~#wngOAo==AK_ACjQwxx=!I@ClS=N-qRM%%&k7o~e2&&P37H24D@ zmf*Yo46!(D0h#BgF^;{@@cy3^s`YOusQj%!&mHeUty>F1%XIiInUhG5za*X`Ea8^n z5mvRVk;Dbhf+Jkxz>C@VW! zn}5E09jTsw1lQJ%RQ!|1a-rbci*FkG4Z~F=NnBDKQgaQI zeB6S&N6w>pN8`lvTq-c~`~=Kz`GMZEN;wxheL=UpB@T;)X z*0vjv3x7886RKVD$EM@#SgFy-#N5F53mWlEjz4gt&I+$XE6f>E3mu_X@zULJ{84AZ zn!c>U)OHg@=_U#qv3&Z61h7bOqaHi{60i23*pN^`C!398ot~({#)jwOqZ`k`<7u+I zYRqyz=7tVw_e;YC4^!B~DduSFuE&o*UQc`{D3aY<&DdcsHn8CLIS2`ECl;P3peZ98 zS6WV?k-I*l{>yLlY^ehpy6N(&rIm1{%#3J!OJ`RJWfk*uyf7g&pE7ohxG<}ObKf3- zN`EKtT|aNKQ}6h*Mr-mgY3>6u`NCf@HISx@-ft(T_lJ=?i_FB|WOj%?hx;>187JsD z(|mNk|&SRnGP&ZxW?= zx#4RCohy|deJRg!zumb9{nKpUy?G^`drU-Ddu(BL_-EAh;k*RBB)cSOoz}hEgt2`}QVm_U*aI_-3XC~3wUTtb|Fp@g8?<3;lKgb0MOD5vs zXxeo@i$3pJfG1i;kiEVG_^ZH#nputK^i-bFXSXbPH8-nZ^af`CNd}D%l3F{y$ti0USy8TdNOAR8bvKXi@?VJmPm3}r+C^t85%saLiAT& zjIxT~xZ!hy=vt*Cv@UdjF&>B&?^~28%tjowJnBn4E?wu|h)!~5?p>s#VgYyK!Ah7g zXErI=Jjlo#=SaEgRpz7GZn~*#8X5V1Elqa(OFRTf=N}>4Kz%L|lgdVJQR6wfUPFU+ zgmwyL6Pe7cwIrA(r-zV zsE_Rsy30cWuW0Wld#J!&$U4m*Q>~{bE!S|{B0k}1#f_X{VF<-7&2+NKQ^x8=Hkn-! zM9CUtnI9Sbq((;w8 zOw(TKE38j#RSjro-ba#KI}*2-E5HUbMUhj&UJQv+VO+dV(9J$J;tO7?5Z9tZJ4#Bp z#=Y^Rwu5ILy|JR@A+ijbG-0B|LtA!eJ?HgkJ^k}#1g-lum0rGZm}-W^i402R*tI8{ zIFBQpoMD?ez4ypbwDxcmOt`5}6ddmmn}ZkV$REgZvrlH&&X+&fP(Vs2(GO zN-Ff6!f;Z5Ew^N5_gQ+|@e^a?VaS*?U12iKLO7o~D{4lMQz_q2Mx{#7cy*It-cK98 z>hosu_O}N5Y%j+^eNDU=zJ^umbH;PxPi2SBZlWgZcR)~@k>Inc2BA&`f8@y_?-+m~ z(+JM^*GSdAHDOx+ZMsW*j{o#^59@a`h^ARlFta!3n>P&Mg)yJYvD1!S^~{O=8BcBX2A_tMif%Vk;l8Q(tr)lsJLE% zPIC!`vEz@D?C--^)$dJo^>V_G9PiA;?p?+G7xIj@W+W26J(TS3W0?IPe^I4JYOJ-% zCf2X&H`(Upi;mw7cY0AddZp1duh zXFZnipT5uF_pkkgSM5fygJ{JEm0ZOS?eA%&0I_ruJkDq1rees>aE!Ms$4*vels^o9Ud1opw;k`s&Sm3#i{U|06SLCwH*@YVj|ul& z_#(qEXf=5h8}McoYd?G#-*Ei||HM>G*B@So28T|v#=jP-Ir z$lWLvXb}E}d9`lb`;>Q(h7D=-30S!MAC+`b9t0YQ0AvX&*tKf1M)i zb3z+G!PmBSGaAS2#t=7cex8pq8kbZ-#2l9M{S=8+WBVaEIu3SQU*<;3egWTM#~G(} zfPE9P*yh)T7!c=~FL|Tbr?e6b_#(jx(edtE!{)j<`wVBi;s-LDw6p|e-Tgdu*&wy2_!&x&X zakd&c5bjWqE3HpLlyHCfO_nXc`r)%kO(B=wck+WD*My>{Rf+WC4M!ZIBj$9+b)ajk z59DO6!7@2n`cP9DGeQeU#%%>V?^jRArHH)<36H7Q=Ed}sV+h+Lj)L1S?}6F2LB{vi zWmGhJN8{eqU~E(-zc-_tHmux2@6Po?z9WXb&Hf<1{B0GRk&;Zm`CdTgtN|Y3=3r{u zYP5NLMkwPO0ZKVZthu)vt73Z)=6auG_WX&5E^iOPJK{;d4BRB9bJOvZ$^r~nJ)C^M zJpdgSa;R!`DL#^#OzTf~Q#~IkbY6a(=o!zoIhEUlQa{t-m3JPb9=nOIqB6k6DwzD+ z2}ZPqVwn0c_KOQ^W-I+6cBEi%|8B`a& zf_W>o;pvoeG#u1shfY{PzD(JUKYtR@g`jRYtuz6Y@@~<^PM0`we6gzKLAu<+bbD!yGuwWn#~&G$p;%qR!groR#NY*rhs|;6p>Baeq8zPV!dWbqm``pK%Q9NXcTN>sRe7QGb_w3Wd;&^L zx5trlrXj7W$C3jjn0av=J#JV^T#81c?aaN<8W2jGZ!LtSUw6^l>d&c3Ng`NZQGxVR z0XXi&Q^xYC9y)x#&+RlHP3-^nQOjx_yf}V29w>H&-Itz`xHxTSF|olL;xCZ8VhTLo zwTHY1d3-fk0iWHanU8h*$OtBoxsdY2NFzy$*Js2f_Q$6>?DR z2NQQboMuW%llLDDG5l&S@sn4Ce^cf81qAv{{2{LrXiFW+$DBg9*(_s9NW-|?QYGZGcNG3NTkdj5ekIQ zML#4n1hp*Nv>1ts6i-7WkiW`V}Miz?5)! zd*UBS8q08PPYmcVe@VFD?hN{VaVVh>M6xai;*+aqxYbQoXtF?-=5D==B_)QO$+&v< zex?%ewI=+QO+w~ANrSjQY(?4EF3`I)0Ou9lXP3L0u`iAsgM=NUQDTTCiT;{}_bwfw zH(c-Gh`3X@!v8F!H=X9PyaLcB_-9%2nNi|NU-QU4yO{!jxVfxHdNlnao6cvDYIw4& zk5u~F;gr)WpjgfZ7GIdi-Q3_VNBM%%dp3EBRa@z<$49y%`2f?_FkqYeAjXi8LaD}M@HOazH}K8tJ?*fUxNf4 zo_7{Q4@p8wU=}w0QpL8KSdtVZl$DxJWD8+9zRDPjXCgG|my!3Z?V+V8<~{WD3qxr9KlF>e>Z?s_Iyodm6ul zt;B0qx54y)zzSM+k7WJs=b9A@=9Ik z#C|hkC(JlXFW+l}k(xcC#=y0rPPhiYBxGSymM$1viiN=6?qsB+JU`&s2yZtn5q1DC z=o%rrI3m{u?2rDy3{IQB-+7IX_&Oh*&qVS!2Bxvc--qL~p*gHOtA;J76+!X#dgK+B zLh6IF=zg~kq&}Y$%a#)Sd3q(^udmG)Prk@UsLJx}-vi{m_IfBI3;DNa&p@-mP4rrD z9b``5B}47v$n=q?K{oU$b(P?u-R%+_o$`pv6t3eYzaE3TpX5`$VH>eRJ{MBHyWkLk z?-=m1M0B-wE{;z7$0)jK@SW!anNNDXR@=(YWYD05gH*Nb$~^hv15@*YbY_O1rI7jL<1 z%gornBd7DrXV2n4ZCKA=TB-_t>Ls`^dK$ZTO>^1So@;cS{&)8DJ{_E?G!9D{AKJNl zD9l?Z+}HVH^t%y?vU&ILLDdU-A;6JM+GxW6nv{W2y0LgZ=n@P`T!i2z?CQ;~6Tf#i zsK>h|Oj)5#MS00^v1b$(yliH-3Vyb&3rE6rlW?qwcZKHX2f*mm3!1pmiRZ7K!}>dW zS&xS$*cvll(AQI->&{M+aV8il=U-$mzMO~h)1smHSU#4dlnLJ7XY_~MJ=!@^62AJx z;>z+b5W82Of0Cxeev2xGe)rAru>UG7G`|mLY=`ojod)?4NjmJ~H~HMOzUS0uZ4bNd zN;KlpFxIv>D>lsTXK+g{5yx<`Oomq=Rcq;pUNr^Kf@;L zrm*`D8S;vfrhHfLQcy6F$1hit1a{acXc@5p;&q?Hp1cjvFl{Z{>hS|otu@&NE0@B) z1=mT?z&7fk+sgEwpU+;{Ji%^Eo-}Q{*(`R_5zcDS>zQp^b6Cy$+fXBWC;UFCMMFN6 zV3p=ia5z5zvMu)5zHtmKrN(s9RZUPcOkh8^tKp#O5q9vP0B3((&fi&jpKddK4z9L) zN#hDNs9DHxYYu6!w*PWikC;SO=I=S$yKx*(JLO^4(Nf$gp~Av6Gk$DSC#v)+(U-G^ z(t(ABd}>TOxGjE&tCe4KhUmnv?s-bJ>uva%ed=uIBoF=ydl^?PF=O99Uxh!W1!35W z8SGsc&L2%L$EO#svzPzr^TYUjBIkY$rwLl{tMRj#T_LBy+xsoP`TG{-&7Hy1tOj1z z-38~$qhMci9(+Hv zgeA`oW7Nd(sy_we#@b;d1tQcNbiikuFbjD#zFoJ)TntWM38A zf%a4@kXb>%%62tWc&YKrDy(?Bf4g{>>?jgBhcdYmJbk4$ot1qs6m>G@u^q`8{FL4Y z=waJJp4^b;e`UxCGoAuG{d^Sv)`ziQX11`&mV_F8go|0tYx5_nP9!bqWc0vVK^f~O~q|u(52nYq#^JL zjZZ3qiRY%0KJ^=@u{fNlR^FmD54HF&UB0yE#w?;9wgSDEMML1UCuIG=S~^|(CU|RJ zq*2#B(B#Z?y1b+SiOF^5Rrn+9+f{&;q1N>J$O@`vZ7#4;cj92(Gg39Sjb6A?N8Wb6 zB)pO`-L>*O_()xa9)X1{A$6b2yZ?b~D$JyIaFdQKc0sjA)##A4nc693i|_ckLI0x3 zpdl^*i9!Xo-OCJhKj+XPrD-t9Fp0)(yGS1Xa)qZtNy5JU64=KF!NtB7=Gp5RRCnGk zVLx>jC5OoJBlk$d=1gfkwCx|A@If8ilLMJk{vu}6cos{tg30rp4bXWY5MQxwTee&0sFJ<6stu7)x{W5@7`k8g91Ry~lPSB@${bu^vW@XC9#;lD3C zsnModamQI$`I+llKY|;LuRQS$B!3X$;T&;K<)W{ z^&37k64lvxiaOXl`~?NMi7@A6DIGNJW4cWM<7*7iZAUfc`Xtiy zq!VcK`2>~qDo53)Q}96Gcj_}&nw?Q9gW!=y4hGtgI(-Ai(kT?ReI#&_+tjk?RR`&; zgKNpS*PtKvri7m9JcQ`eQZf2bS8dKe(4^U{?0m9dX zOTRW93^G*cca0|8du=0B&Dt%LF{Y6dPZ&sP{YE`|H{itGk~s2J9o=i-g*65zVZ-zj zpez)IDxFXfI3^$P<%rq%z9h&->eyJUTD*;tt4(x~!EkInXvo_+MPuB~;e52f`yaP6 z6V}Q5g8qrq^y-EY+%9hgFpM4pKFOa*8vhK3rx@e&HAVQWX$xs6Wnr)WQF!Ah_@P}x z;q{DO<~&u0llQ`i%CQgh{d7MzVuT-f)B7lussp1J84;}q+0c$}IGb%<*c}rBk3|(& zGxiXjoj(;^-(_IvtV~9?x%+xIMkJ|rIEJPDBsu0OGoQ1@l<=F17}re;JjLkmuKULy++t|1Zv(`d)}QZDgy z3@NlRz#ZBj$imJC+_ra1NOr3{YRmSJj=@tHH}gNbOi#q;TE)Xvw;n1nXEv_=_6Sb& z#^Kef2}JyC5ylRL!bkO;Wd7PjCaUlnyl_xLgKd>1@iN6l17=i)s$DZ&mHeYwIV-|wPxQl;3l z*XtRJwV#NBFt@GAmlRz%t^udRGRd!HJlFqbEYYtS!ge+U;@;BAgb&Gwt z_-!4xY%l<|>{CVQYGKUhKfZLAIG?;2aKMl%S&TYAlT_x*!nh7Qtg1Q0Jv$*o%r_i{ z?S0FcqVpZdi07eh^Ck@b>J3{=3h^zs4&t}j(iH2xI8s}aHyJ+$mjC*Va!*fD(c;s1 zevvw^{4b6_me>wi9XfoE;~gBZ?T2?iL%8Tfb8LK|0+*c1#Z%Z)I&^A0TQlJWUVGX{ zzR$gn?EA^oh>@b#H=QF=+FLMJMiZq^U8UpReK7wFVj+h)YW!k!inTAX8z0G{sLRvmeak^>oUZ zYXUR5=JI7aYOtrjjH!p$z>%Vu|bm$&bPz7b<6OCK@1mBX9XU)ZA7QPi)6(ph^Ge}#B1}T@Jzn} zUz@i@{Lx|>c_^-+QJHikOU4 z*y)>IMTm83e>_t7% z$-^?N%iV{JL4GZ6aRKJ+r5Y~7C5)`PlEB62RhH-fyOP{2sQk8;FTwIbV z__XSBJ;&vlHGd7ohfbdoA6oK^Y4q7a3uE$`P4zjP^4Hs(_4s!pZ}VTGlVFKKnh_JmVs)pW@GP z?}l@Mt4=V|pPw>sjq;d*up`{2;gs1O<%S9qV=!U20R((dB(@K0sHxx^`x>r?^8;<5 z*XT6aQJhcJ)}1B4Md6s(XN524s)9%5bYk7|0)8%Xf#%f5Ole*geQ#5R1%cd*H zLiayZdkNPUJeFm+BAX$jbaX+!2vz1F{6twsXmzkSI# zmWFdPoSuLIctD-DK34YV;M;3MaBHs_9Mxq9yt{_=1>UgmG!hlQiMs_uVF!L zK5Azu6SZ$q^!+tIa%PA+iI$W_*$xq;qy>>P#0`^=iC}BC29-_jB0Z^zP?ukYmf^Fp zB-Rt>cT)UjF99vXEmn1%|^%9Pw}@YZ0`HTXxBTys!Gl zwN4R=YAscXtb&%Ho$sc(jh6UxNd<^9ONn;dZ|duKkQrl`YJlN}vhT!PzVJ5Y6G^`LJ0bm?$reuJa>kg*IOl!ffO-WXmXDFXqH0b7$4~WT|ma1Z>Bb`<3KAp7@co+ zKtzWuTlnBJeO^D2WT%Sp!(3Bh%^R{Y!+a>$Dvj6c)!7Lpj)yZ$`r!VB*5E551&k2CX}k}6+_cQ28$0N8RvKgK`Orc6mR_whN4fv`jFzHX-<0L_v#_C+5*8Y=#TQ>zC zR8E0M6NGCVIT72H=E3sRP2e6hAC>PLg3~-d2-t5%{O8?-W3o!@ze*3}3v}^Z{ZuO2 z)DD%GwfIE-0CyzyESI)egx#h_$P^pF-EnbXCXM#C`t#_1Jj_?e-@oCQ%8SRe@2-_CYT%al>0g2E*g9WR(-$V zJ#rtzUHozt-#70f&-eF}Uu#@gve$&n8EL>POZc#XvD3?s|MOwTjH%(a>taZhxW$9v17)pMSMM;{ID1bSE~{^+Ps#UWP{Y>g1+1v;-&#vKjZ?vW{g;wmJ1tE~N zyNG^j)M7VhNYajl+sMsl=g92iE0{|6PUwz3f~ptn*uII8+>$w=_rG~&ZSG#UAboLYPuh_#lmBf3hA6iuMw zhm`Qr_P}<%{V?jtQTD?62JE>SB4nVASypEm>bbe|^LSVO%G7z#KI}XnRCY)T6jgh(;^*2CaOav^?fvOq6gMXuC?PeP<;0q>&i;NY+;r-uKrpLV*-yb%|)AwhvCi8QInKKJJ z>Z8fSu2^EAslyijS_`_}33S^}FYdaT0(1J;58*eTWXcVt+37`@bW7MXd@wWu?s_Sq zWVi>vJ&>cW-^Ky+;km%)%M{DXzrv~lGxl!E54xnr9#*fe!~~}nGVJkVJR@Z6YCcWi zC2A&-$98x#V>9Vu%p)$lvYKPB$F608a9qL zF5Ckqmc?WtBMl?}n+gGE(m*Dr5JD!#(lp~sbRYAWk#njf>G=x$$fty@F3culY?S#) z+huUx-2|#KZ=Rsh-XpKZi(y;7HV$pea>X{S~zLjxz2nnFUVia_FIw%NPb$kt6#{$<(D6u};w2Mz`40Gf9FU zXkZi{e~y6!$G_C?@H#SO?g{d>`4hMKs4D4-a%QBqSfIr@6`bLj!98nprKG7{rBFKIFlq@?^i$?ph zQKs7kxHGfygO(|`NX?zLuL&2WH~L}P#%!WxM(|DJRN6B2KB@a!isLUxqUq{%^3rAu zuxex2YeMdD$cCA)@kS!e%nFB;mFBcU;EYAe$Iur2MBL$T1VxN2FaL8KeQwNKaLi){JOvtT`#6j*L9%zoAJ*$q+7$AO{d4;mKkG&r zZVsuS){{5!hXrCCp< zZ}d!56XUNn8vb$s&gRN4?amY;6nhVs(YB6=aH; z=@;OOjskl+RT>n#H=ue=5-2-MmtP28&aeB~06r{X?Gej(_*E zORxGu^&O#GD!fbZPPvfs)v2({=_R(Sr_il`pRm2B$Fq*tVqk;SEy}t4;uK=d@t{W< zeqWHp)^E5=4(>Fj?>BBmGsjkXv3D!cXgz|ft%IrET^-DLQ7S4s?#ib|J7cGtHmjue zj%*P8R-)7}*l<>ztr~3x{|VXsPLIiWC2cHu{OUipLn*d=tZo!bl^(*zoOGsYAb<>J zS(21VKuwa&;Kj~NYAc*g&1wi#tG}h$?l-CRfwT1ZvuBJRNa1XU$@s`y$WM)y;cE@v zljOb5B(B*6)s@cC!Kcyu7@gU$#xaD>@r)w-bhKbibtEs-rvhnHci|STHaglOi@s2f zqKoe;Ly=E6fvj`HW$#ejvH=h>H0n-DoH z7gz#nQ~s0{7)MZ-EDiirF$~t(ucD`VOz5dWYqljJhE^phL)4I+_*8!jQI&+v54a>3bn>Dt7`^fmZ4};hDZ*m15XE__4L^6D} z0&e_m!8|Ny*%D2TS_@2Tv&&kzF>MI0x~)WJmW+Ug&hy+py*#$v_k-a5$|gVUC9%S6 zCIlWB!v-H#Wh;+c@iPxSBqtB9CoRVpGWRxAayz!qLQ^G5;rcwsnBU{3xcYCplpJwK|&R+{vwb?noP5FEO@< zecAJZ`WQt268nauIKts3U9rOw{=`0ES`3z=#@ZNB{i+<2x;me(s&s*L!)-8q%~@Dn zFdj5C>L50}n`B(NN75%fFIyFSizGjGfZC_y@Lxna{INYD_`q95^9qTiQ5APcV9d&%D5*7cB(Zn zN1>6%j*F&Eye3NBJ}nM6>>^u6jj??{Cx)cPW{~Jdqiqi?o{mRHz9vq7S}^tAI(+qE z1FFervOPnG@MX1%tY{N~!1@Ae%EW^0urSQASw~l`D&ousswq2jJB$(h^Si%fQJdSQ zAQ#ld9hsmBQKO_-|NeHSV##CNvT`a8@B2yyQ>Bm|QNw5DqsW*1y3&}1H^{RtO}H~` z9UL}kBB_0&=^o9)D5ZG?8+U5bT>BKb9N9~Wq9r`L^T;;TcMerjJVluSFFbs(8wVW5 zV&j~6j2m5u&zU05!b8wjtXFf#)92Ga+07W`AzYJ9Vr-C%MNKIHt>rST)s=m4yt|PG zW>n!3)S!CRHhkiPD0KR&2<83@=xDvs7!`AkKK-fyy<8tT(EfwDnH+;j8$+1kpK6%% zAAfPb&Ev@Jz6ADo>NOHnITnu={vh*q?qjyL94A-HJE_Er;leYTNx$aap)xN=pqk$R zozj>`Cj@>bF2`f(ibe(%-X){KLSL+Ri)SW|{KR=Y+>9C*UNc*kTd@UeLrHPzRcPz~ zkH%cshkC1y@CLF;#7pFjo{{pnXRi*_n&@N9Ax&8QWvCL%S34RR4kq z+miH{BT37t&bJ0Wv3C+Q&xxQnyCiYV+hoS7rWLJEorZ*wde~mEg7`bTlXLm~^ib3~ z^!qy=rf7KbdrmLr><5Ibn4l;23e)41#iQtB{|#7U=83ar70~;Ym9%|u82cRSM1|lYa3}jd&7#sJdJw(V0VbRh{Lv;B^o-?6 zOrI>re*JNa=9m|j89TbrIRO{pS9Ap1TpEpkMvn#6qs#e}yOwyd(Gz?JrP-R12#a@S zlNsNB;U$3?9UhZK%eOybLO#pDwF!SoTz);CDD^^vC-x}jGRTG=X<+2S$mzoqAw2XG zog%DOdS~CEvIn#UhRatnV(=xIHuo5||MbIwD`&~!2U`5kM;dtjV+d@hIz~_Ks->Sc zDB*#OLHe_MB$1nU1Z=dnbM0y|_emqO~I>vn<2wHdC!+1|SjOyEfmn)Xj;QF^@iWPGR_XD@b+N!r6rHquUQk zg5#kqSh7HZU$Ixhu3NGYt3nOgibuu}zrPKhhlS!k<`%3p{{r^nkGj5TZ z!X8veW8sPuD}G=ImOGF0c27$1@})@Fb7CB%YyBnXyux9L=MU@|D4_Pehj4S#WcYWF z(150!lskHhR^Lb?h3rvqxW&NOTVsjEj7DCpFNFqmp>TcZ0=n|{pzzJrfI}_U@J~Yq zM0R__e=jc6j;eM#U$z{-wuUx*q-$JO-OWtYE>f9Mt_~jJd25S!p~4*R68H zXSw?L&`<}Vt;(d!O$Jjp3}I(FZZB72MzR@e#^Hxud9)_$3?r{I477an zss4)dbm=)C@`YDM?u!~cM{nHwLeRVyjw7YpOri7fNIVV3=yffQ%?Yj`ujj_%|6N^q zI96L1e~G+E=Hlj!l9Z4sbcTII8YxLBjqC_t3`+2R3D5V zxlf1HeU_A^i5zPCcLW>$@&XPdA5$soqS$k8>gc+5E+x}9N^J_gzz%tfp~he_T+}K{ z@6bu5pWGi08a1B5wv(@EjRbyu^zkg*Uh0Efd=fz6Hw8Mz%LTPI#L)qlry@{3lWyCo zPT5y~WnG3!;C-cjq_!lVo?UGSk7h$w+nC>r%@Dz&ED?P~rVKsMnh75fPVnu4DAu?Y z(VucJ5bo9XDE3Pm9 zWIpZIaTpbfC!wuFd|&UNHa=3Z0@f``hG|L~^oimdBz^2y{|&$M8qXQJnW8=e5%>CWA2r#=2rsa$ z#T#R^xPdD|ZnHrsjJe^=Y2iO`=?)UT$vuFFF6H8!sW&j^ZNR-VNJ8I!QsqpZ+`u2! zp2Rut;_<%@ZNg_Jj^MNdX_objEtL z{BtETU#QC|X*S|zJ&}~^nw~^HJ5fG{_BM9>0RcwS_j^(HH*c_p&ue zwp767*co$gb)|4aj}RM*Oz}KxDb%E1f{j)y$b0+m*#^SSmrJcAa9#e|u?;@@tB*)nONz*q24c9L+sra*9z5eaxP7*i%=%IK|%!UVB* zkXO)LXU|~gJ^m_UKCaMAMEo;|z4Bi!e}Ceys3kH*Dhe?wLgCo|Q8AzMe7KDmiz6O@? z{0cjUu9FdIxsvD6y5QR8AWXbTXMJuSVg3J5rMp>0@U(`>_tQjCQ*6WX23Fa9{BY)2Xb{bf{)79 zQo0FEXjWw$nRShz@16Fbig)C*{hFCnh0<)Y<*^0MdvTaLwlSLYdA<{C6fb5C+PvXe zXEUt4Y8LD~IUnisyuFPx4QZE;3>rN%EU~&+M_gXJ7HphoiSOyjV7N<{a2v>nL2pd) zVWBB~&7pyipUwB1I?e!(ognNx)5_j?9!SR7Y7F6$iB}1-8QLbmF>X zywus3iHy)G(%0iq3b*PH8Oy$4Z02=RR@6M2Djj;b067;N;j0a!j<*Q zzbx@9WN_SVR`Sp%kKUj96B;*pArVvGfsAVSKK&OBq{ozPm<$<}WT%O+y3GgrRkSl~ z{~`@9Dkc-Ar7`4P&Ig~butwVkx8qZBRg#L_ZhG*g0xe=h)EmD#DkiZhsp4+WOmhz6nG`o zAJm)=1)e<$WcMbLR>*Y4Wl7oevC%5_=Cd87sxXb*u}47ic;q;l?2z23m&X?it=M}d zhU9Qn1Q0c?1#7K#qf@&k0G-S@a{2*hI#A~U9nx$y-}-T+5VH(@{RGKH@}wj4oS`AMv4VHs^hN+Fv}SC}Q8 zfCTFo6YV@d_`E9 zo_b_`brtq(?3K*S2x05=Y{)sm=3t?C8@Zx#Dm5?Bg^FMQ2%b56j!rmsk^ShEPWroq zfRnYUIO<>nWY2f7{Uwhib)^{RXMSuwnOR$x%Q(Y}si+tLxSl|9(qIjr_wtwdcN?uFhpBux7mvwjGocHn| zzEO%wxio>4tBj}H)0=thhTG72+CFv=WY8H`dnJ11T9jLhGd#h1P_ar$(9O1)c6GDB zEA(s0Jl$AACG0HQ5VMy~5WhtREr4?Rq=*~%1E?$GP$r^`L zlD5_N(QCa%NmuC-*l}$-?AtvaXR4Xtf(N&WEdv7*b;a!%-D#zS&Wqud%vUg?>=GGm z;ZFL0ZG+79T-y&7Qs|lTDfXMhnKZX7rJDkCpx8f4;(zQjtyH;{oK)bAUndtL&4I&Y zR?kWr+v!TWpaQ#QPZ&u0_>FEhP{Q4Mb6C;7Ww=w+K?RFbs2i?M6%kkG1HfZeW)|(n zrjufb1;LeQU(Xfv^TblPVaf8a>Vu!WgQ?-4)j!@ar^#k zpmg;+R&y3JxIRE$=JGh+ zkytKn01!}y4hhy`0#hn*pxHat+Tk$`)<979CIbvu9m7tMQ^DOvMc~uwi^u85a`s^g z;PmfXuzi>V>YEtBcs1&R@&FMRqN)oY%kE_Ep5T~ULl=Ng?__S0VI0$~pURl5D4?DH z+=xfo4l#Zm=kS!)L?-9`G3N0NIj(j$VFzIsH+NhnHxjCZ@8t5ir{ognpuN~macMr+ zOmDR#n%;7I^5VHyzNJiTjnb`y^Dx#qn#36Y>lC-Zp@Z`frE%dK3M!QCRc|fm_rbfn zH*%`KcG`v9_GOgY0w9@P!1=rrFdovaTxj?N#=}pV(>=Em$e88eeY1a5D)lcN^ggxYrcP|7U6X)3_&*r!fGh4ai8CiCoa?@{(WdF&? zcS$j#7xJ9i453g>uQBc!bPQ#nnN243P(PL}9sW#OSNPMfYMR0K3T-==|@^ll>d*KF|9a7K4!dN tY{>pk)FS@1odIHR|FLjm<}vy2eDTMfK;W`m_J=`QAT2o0Kl}8dA@DE$Q+%Gf$ zri~h__`i3>jS)-3LSghsE31)~BdtbTDJ~BS2n@0KpN0UxG1fNzL4kobcGiBj_KPeX z#st{gIoMeS2HIMU_6rKMw)3|Ze^+$>54;A3Wt(La`bhla6yyDe(m#RzdE?LHe?E`? z6YXt9DG6Eecf|pU${~Ks7X|o@3Rt>YV5t@-sUxY=N5@?!UsBOnQFBFL`0`befukbB z{X!#Fghd4YPnSPC==4z>sHpbmud@mmHEyY2#Mpp<|7cfJ)K*jo3|Td5e8{T5H5e&s z{3Yl!`u`(3SW$bq-&&s)VPPRlLl=uJxcRMh7hn93qM%XIu(NXvhboPHY@mGg`qO6m?fG{WA`If&%>_SA_>gjPeMK zSmL+hU*3IAMp0K$H6SoFBJl4jq9hgj{pC`&|881*dw`<)KP3L!qn#AB{t~hKcM&H= zoj+|v_(%NRhMd`?zlA0FS5#U`2>v5t$Nk6E6e)S}pj0a*FE61c4u2yFv)PL3{}se) zIe$j^Um)RI`*4{9j7O z{nt?Om)dU0x32QCYO*?#Mv}v%ET!xvog^nox=YNHJ|KC^RdJiRQT*y7uci^@dc!IU zwm-ELp5K2M+`eqaxt97USa^?=)(iuwi(%+JtpJ`(RRGD|^6W=*5sYZAVN}12e5wk^ zi6<+`2>T9E?4 z<}2KVxkWoz*@zaw++|^)m8_1=9v75CHz>hRI)LdaUE!2Q(sk~BhKDoi~f ztx3f0wim$6xerBoiEfZr7YDoK28r^e)j;Zl1jyZ;&lZ@6K|^0dytg0%{RWoc_3{bW zGCvHTA0udYa1SbjE}DK2k>(U1@bNN-`QHSrbp14u?&nP0^y4NG=*%J|o`r%-Zlht* z`A6(&#v0rjvJ57r$}zutb!55uC9*-{G5YoCL&iiUf@{eiq&;vIgbdt@(@T@lf6G-d z{%F`!e3jVmOhGa%mkpo3LloNb3xo8A(C+Ip@Jorn3%N=*$VP*oN%s-iOz6P){+U?v zyc4I)?vE#)o@0VjFCk*zcpkgniQQPU5KZl6d8G}|ugkAsYp4}oJoOAK(rtLT=?fg1 zYC(O9w?k2k9%R_|rNb-*I67q;JK`7u*P?Zx=1dfRX+j(ragKZ)G#M`*%*B%j=QDGo z7PdfUxbSCfEb(fY1`TU!V8A{XV!mM&1ek6m#v7x-!lMl$Jaka0v>xjGWnu5o3eqyb z8bduMLw^}d>~ctElb7DbxW`ctylg%+*r>y*T4!1{`;yQg=_FeUJc;L_@V*Dv%6`;EAc^54uL|7DV>HA+?_J*tb%aIF#UxD_S5 zJ1It3kWd5H7vvG6h!yPP*E6i2|3IwL&BYb2gGtmdP5w@TLch;Pg#w=)_;Or7m_Ozf zd0|k%+T`=#w|y*2@2Af*W0ydN%yrD3Abx(iT5zL6hWB$wXHh%q$-~Qcgr1*E(IQ01 zZj?;K=R+z5nuD*Awu#RmchOmvnjr+I34P#teF`7pHJ{|+|2(E#^8S>U_*6tR704eG1_etW00 zckhz$+5>&|Df|j~ucHZTauS4+YgEZH%`8xQpo{Y>b`lr=Qe0DUjotUkCl3iFYrjrF zudFQc!NXp-;^G%kQO{6pGQKW&;t-2*{f9wPM!cx!=u_4-R2#-lQ3Tt}P*y$A8FRlL zCj6Wu)@<$%N$Srb$ut1FYjfDEeiG>S>kDb?if4D`&WGTyax~deNS7*4T*fnYX!A?tFq`BR1-D^3y56kC*4KNnq@xFRzm#Do z9pqr~m+kN{W;(b0W@?;j90v!q zd|2OG+sW!JTVYbVEIz53B5ZuPgcOb120b%dMUAT+NlAJ(X5Mrqlfu=}s!xAmd#Vu| z`soM@C|pBoTRYg}I(7WvyaLyYoqBk@1katJK&54>ap*=XyfecLln%bd)ypLyet%zh zR@sQZ26d7j>Dy>inlCtxkLDA2v;Ea-oM0x8{YN$6J z^YZec>CrIE8>|Frf*K%lDG(kv8A?Z$lAJk*U|NqzSQ{3~ULB2q%eif$Jtr=aMJGbA zkNHrh*J z7}m>vuj?X_T?LqWCJm?boq?Z=I~Z4}5_!FL!6@cRN>)45&NKdCoK!_3(syEdqDW|% zbsK*j{6$_$o)yk4t98(^vxT`5BhjXD0NeL58S}L5!RhdH(a61-cv)%)4J&&`gjf7U zQk`{7b!h>-YJUI$LFO=N<30BGZDif6Z{zF6DX>?XGnLkQcs_m|?`!7GWIRS; zdV3D8@^~h?@8w4Z{fcMB!|!3^$YESZ?kpw}MSl8TU!HN%mEJJapdVV4`QgHTBE?6G ziK&e$uMO$Or%{D`h}Ks6aKLposLGA28}EX5uDU#b`5T8H32(6>`Z)R4Ys^m-OVd+2 zEiftIm9W^rl%oA6lsu?OhkOyD?*|F*s6GzIbo=7Ur%wf#@JNkcs7e#g8L$G) zr?}xFm5~C`!>{Bwy@BQZ%wU?;0LZ@w)cQgTUmPig#pj&KF*%q45IaK&cV2e>ReE$2=fkEqHI?I?{9J! znm^dHf|uK2M)O`wnoz-y8Z8Bc8mSCuJHjGuvfx6~w__)&m7AXBf8LMy{ zJ4KBK%sqfz=CZ8HekHZ=djU@+34QRPgFMMNE!f|^leR9M2JV6P;h^&)ysl*f`qNao z>#{^X)};jmwjWt99}H&k=ZLoAX56~N7{;T7@3b?a%k?43&Z`CG_4gsD zX^-Idk0jtW_K>~YMl(o-=(QC`}k8eg;+`9ywseh6;A= zqdPq>VIzFKMNL%ptPCsL?O{%PvM6Bjc<>l?6rUf~rO&UlK!5%XOS4>Yo1q-e>R*Z9 zK7_%dJ*7~(N(zs!+|8z5Hv)q%o0*McfN1@&g|M)TL+qj?NS>1>vP@b70U@WEOI!z= zJbNiQUn);~Jrc<9z&P?P-k3`19zs525Q}J3#*~pS*n<<>L_KqqsDt7c5-`yOjEMn# zAMujyRosdlsuK8Kl!!xL#gHuJ)$nM*G5A@g3Xf)ZU|4_*Y-~FNHLj{8t0kDGKW$+* zlb*q*i?$pSyjXhXrE0T}S~$v13Ns3I`AMH^_{eD>jgTA3Z=)RlYPbgv&ArUpmEOWA zUmtofIs@>J_qb(=Ex7YAn6+Mq$7el+uJTx(cU_mJo=w1?L!Yo~x*H8fAGQeF6oIhtm|%XQjt?f6^r>noD!caP%L zq?@9h{WsvY*RdGCq(t~#F9n0X_(00i%cOYYOY&~MHdejtX5)`PCq+I*`mglGeJBb@qkS!Cb0a-I2bh27oXQ< zg5J7&>}ltFvP)iwomnoTCAkFaRr0F8tL$RWHV(tl;lojLNi?d-ufy}Fv`Ck(GnS9q zhy$()ASt(j+;vEE1x zQyXPybCVEnTg8I&h#uJ1YRgTumNM0xQd-kjlP?ngzg@66EZiHIgVPGGqR$ouZn$+U zK09}WCHL%u-;)xkx#U3-bb3E5Ob@`M9no-p;#jZ}-62cY{bbKa`rwx820W$xjy#nK zg=g*qk*xR#_YMumIkg)_s^xB2Tj<1Mw6CD#lR5bOiwu|gvK3$47(ktEYKidoHXNPb zgcgfCg%YEsA zw~EO2nee$XpCNzIYYad35oKiRVCL$#@P|$j%fHwmI`?!kDbj2tF1uIY^Iij}8!(E$ zSmH(2jM0Q2IFoETSPG|KhtZe^O04n4Z(NY1TvHafot~F(Al%KI@0oTPjOS(YS4s?F z>;il${~g;dn$st%2Y`&lG=BE|06s@b7gJx%;n^+nyltF66y!^B!x`zYOtTzkWsRnx z*?Ig*+G+H>T!vB8o+ED@$c|;nIhuP4v32r(xZ%75$n>>*u+_jCy##aq5~bjx|6Pdt zvJ|^lNN^)6sF~zDkB+CMToiDO8%a3f1|@4p?RkCqfv6ZP2$r2QcZ3~S(aej=TEL81n(SvxL0afwfroWc#PmGOk?Rj#d<%GI`HV8VHI zoO^c^k7cR+<4YuK{?Mk)y)8@+e6iUy8B_FS=st_Zw8Hf_EV^`w1WvN13)gkQ^6PKO zEI~aj>oTEs*Z1&;zK`*%aUGYKn?bYobO?X1sN?th>rjRDN;R@thSbVJkq;jo#jhl2 zQf5#Bt!LGE>HY-%PJc7~SYkj^&duk#V~UBsLj}z@?!byG>#!iYofcOgq+2D*ATfSD zyRdW=9oI7q*8S*P^K`*`EZDJ{cb5#t*N19Zyn1AfneTQkkXgcS^uNI6e74b&tSfY& z^iz7qw-3MY)D{~rM?7UFUcK4N4)Pqi5VxTPLml# zl@yb<7%z}^Z=j~7i}={g$-D(GLqStB#yb>%(2m zVj_eahKBRaPPL-6E~xot^p?2UMDaszL$Ka@xlQJE=s1OlC~1!nnAa$(#JD4=`i41HjXgs#=*z}7)AqAVV>L(w6tyotr$%{GhsJ2%$MB}xjFy!zYx~woA!hioDjdU<* zzRea$N>q{gz8d7`x&iEAhywlj%>>>HSCVz^5?H+6qx$>x=R#bf1`S#BAmm^W1?I~N(L-CAZeAV&&pxfg zrnL-qu{R)4sDxW}XAt$8v2+LJt4xL2WM!_YIL7=5 z`9tFupDx*ts+3C82yCJotWVOm7HP);?-uZ(J_>w5K@IyLu^od4E#~Elb0LzOf}58C z*PgJ1<(!QXrr&TOUv6h%?%I3oP(uPK$=?hzYD+=MK7h2ZNM)Z7Y0;NYX0WB-cL?vY z@hJ5q4*R~|ifz|Q@YP5Oa({IyE}H)ZE}toeRWT;y&AVI(4U>UyuT9}YO@D~acYvua z+SICF2J1MR3ybPTW3P)E9QD^1P3tg*o3Y}xfp-zUBWW1vUeTMJeIEXhQW4P zY)-EZGnxcu*yqj>V(JH3xGKr>euNa9v9-|Ed`# z(r+}w$>uVA%Zhbql6Dxnx>88l(NTEevmHGiwgjP`%x+$Nf)5*~!8ck= zf@aOb&Zk!VqwhB6U{XQ&aanTU-AeHBISLIMuS2x!HCQpw1tq^<$C&3MK~k^6Vg9(G z)W7H^QT#Fj`c6({iu#J8PpO00#>E@Kyk3IlmUn=R#w=hu!{}A7Oi{<~L)aTR3G3Sn zVfKtC%&{pSvc`8~P}3lo;vR>O=54?gOYR7~!kTgOwSl~FyCg5+UXZBaMpa~Iz~X!* zxT_QkQ>JI*UUd(~d=}9y5jxy$Z5FyUhvIkp6<|HM58XBOyKu!vZGPtGIcC^fh{2b4 zQ?2U`eAAo7u-*FpUYj>jiCFdy3)z7#&8w)^Jtj3Ph^>_$}_bnzp?QE zsO+u7x7&|F@P<8j(L}dq=!iKrSd&zX?B0(>CPMF`oOX50AGd!NG57*X$)Q z*tI`KzZ;9wV`kC`Sv}m$W4ADBlrld)U5{()j$i{Eck(#LK{ZCx{T)BwL7uh*tH)hC ziZ9$>p>p6^TKp{s1BdOZHr)|J7q(T?k8}KK$$}5Wk1gd;Z^0wA)oOm*cktb5V;$#w zQKx}(&w|V1>9}@|GoA1MiV5po>8YY@9J{0nZ)`8)GW#4b{^v?)=;sgJ#v*JWs^I2e z$`^Nj1kFtcvFURK9!eQZtM|NuNWXz}dkq}B&C}2)WP)W^G$TP z*;=ly*QcgiR;H$IwUlGQKp|!GO1Z;LT{im6YAT_&g}WpOu*Fb`m9A=oGUXl&&ECo? z#_!(R9zEgToGTw9}KRKS~kB?LpEnOwCC z!p|!WXmC;x2CHnK-f9!M|0C*1Z8A~AM1k5UYjc;_E)u_`n6w{$Lz{w~Yo0Y&@Lg*L zf&8Q4bo*mTI_y*xPs)A<-|OqKUDX`hHf8aKHKp9?4@sfY^_$dMO8{+_C6ti{T5|mu z^A<&5ZSiP+Zb=6ChU8s{pBQG{jrB{8Bv1sedFlCNLAj^SCQtA*XMD)P4MGW5=fAfSZLA<0T&MA z=m8($inb)^4lsbtx@H`nnNrWWCH!324%|0I3&x1Y^p_(HX|Q=EcV7OR^!t*;l-1LO zeO^&!y0K9>-E%tZ(t3b4nm=((RVp_t6+qR(5zK7iMK~6_3l2R#j-!L;k=&26m}lup zzd0$O!6;+VnhD*aiEHfe%=&7PPGLFjjn;(o_g3KJsU?D^KQ^)(nLFXhK#JY(525w7 z9^r|{qq*bJIB4y^6V=~spb4kO@e}R`*^1jyuykT3lxN6+ASwb9GBxos>%zl>-lG2Q zskGWjk*~Ii1H;)Dafjm$*2m)-I%ay~uJs6E<9j%65%9dHYMkm{q~(!vH23sl`eBb| zjZN7?9=gShKS}|r>x}C5xDkHi`I9%fl|vfW;|vQJL#@XKDMXfShpkO z_G1*ttKs;E$?V+y4LEJmB(~3G2D5MX1mD~GX#YAFm3uA`gR|*qa#bDO z9!7}FM*fE7o$hR&+6^3^cL0WK#DL$2xhVVTGpq4kM()=9fyOC}Jc^8h{pNXW;GH;p zQ|199tLAdIadpB2yN&7jDTO%h{YWkuX^%TM|7Jgw$KsIGP#$|)7M^VbJ~%uWE3ag; zTUXDK8TrZNQsiZ-)?Yx?d)#AW#fB15C# z`PEF};f`WrzoCOc>ry19s&VxlSPkaW#K|AAG{wj8H&y+Vf-?4 z^6iHSf*=PzY?9y;gQ7w9StrU!%@*yO@k)ft4})WS08UP(s1TROH1265`e{OqSt}d9 zXE{jR^JZ;#`hjuC8$5krI~14hW+QWyVCLv_Gz(vYA;a7;EG-POZx3Q6;r$V-6w%!A zCJX=NgvEo?;qth9aC)aIc^Cc?oo9RUx3~*72H4@XtA4mCLkf3JmZtInia5aF2#V4g z@yEbqv>rPGwLeJW-aEf>^AxR)QF@X9 zXJsmZKwv}PwbtYE$a)A*Uj?}`oT)W0fIfG194CA9r9PP@C~~Pn|IQ{%AL_?7z24x2 zUO7j;?mS&LeG&Y4eHrhSn$p9Q)A7&`3%WQ`f$!@tPZua2LKF8&csrX=n~Hie?^ZGL z-RY40F&ZY`*#LTX9|4^v&zy+_eQlA4epiOjjc=YI89NZ1e@uY&!<_MJk}^BnWeY|X zj&#nZ_n4HY%JcxSRJajEg)#4Qgdb$kRJ`ZJ|6bsLQAK>f-r;`}^Re&luk3 z(11zfH60IVIYI1b89r0>2-Yv_C7oMj=$S%ky8Qf1IP|%Su4u4;j7`$~O-3>H%IBj+ zzo*cdZN@(z$prODyZO_iX>jA?DOhCi6RJO0z?bd?)XzZ;)*r7!uPeWy>P8ZtKDQNI zb5?@lO?A3;!8qO(>?ca7&B7D43+ZNo0k&9=;CAQZ!EaGKSon^FZiUJ8RpljKZPE#! zMZaLiYE|a#Q;J!KmSNTdapflQ8U}l3kzIT8x#_?wnA#BogC+)o$8<@mdLaQO?3jY} z6UOoPUfrZ}(>Hc?qX-G^6}zr8~*vU8C`k06%*sP&}-s+$;b6;F*sYKIWvfl zk4qPG3`XIERaKy%s7$Wp+Hw2GW^nI#5B`*{VWpS8i&}=40ue0q;) z&k?}S&BOWfZf#z*El^naH4uuV2g6LwuPjL*jRkwl@xI$5(aM|Gg`-BNv4pZ< z?EYbap>!HuUziI&r;OplFRGEBc2Rh+DTYkET`U}A@vQp%tHb!qUIy4g@tWr9D0C|e zVA6}Vv13O%xv2An*j0If{&XwhI4LQVc)WnDYdgk%q%Rg~TL02mb4&O25Hzo7&ZeJ%Jt#3}<&fNo#iJy2toh4Tv_6q{T zPtc~k-zb@~m(KLmuUYVQH@6zvjQ!gOac@02J|V}Fh6G$8hmVV3m1G*zwfZP3Z_@_z z=MV6}J_YPqUVtEV4(>rEW@#rw?_(oY_-s2??pO_HgH=g$q9%B&EC;=LJJ8=D0}W@5 zhOC=cgl8=C*}HyTtTk*abD7^DJT_-0tU7jt8JD|bPkSs|5M{~E8oQC4XmMSwVm;eC zRu?rlbXO%L6p2QjN+utZ1=zG#g2!|hGvkBJ#MRObcQydV$01{;y2^(A<`;vC4$ zx*+Ud~nGRTSig)5ief|7Z4qSUu4I5U4K*KiTju$-1>>X9~Ka`o(WakW=%zS)|0UOPe<|Hz~2J1nTm4% zq=l;O{udQZ%~D$MUlg%%|H~i!i!Ih7+h4vw^qxc`HE`Y$rtBzb8y>3@*XBrPTXgN!ywahteN{8Iaqj5aB|B2 zilU!~fSy_^?lwQj3V&Z?w;n6QrfFm7lkby3^Kmo!j6077$s1tM*I{J;cRBE{egTsU z*ON`N&Eb4+EcCQesvO*p=ZNCP#I6n;zr>&YF<1{TtNM|ZBejGR44*;a2u=RHHI7Y= zOrpX*k02oX2Qv>i4jBRMctOhr4Fx9Pxq`CftL_+nNrrpJw32KoN#5S|gjxG&;2M)L z*nCuzt5`Xa%E78I<@j#lo7FmSW&dxSyzVnb`;-W7&Nt$bY18>SIU_z-&KNbXgz@lm z0n|uaAI#+MgPf-TF1=ceYYwiUXLnEFnn@!`xNRmHDrB-7w-(d#i&D5!SA&Lo)opNPIj1;SUehtT4n#wOUxgS?L= zIUZ((M+Viy+48+$c5yJgY(Y}G`w+YM)&QLL6tIn3PNKo#ASUcFL^r!NsIw_voa!rO zpUiu4>e11ahriB)F-Ed5vq?)>B57N_KTwlNx*f#SdrrKf|C8$8=b6G4EAL`_@@lNl z8!URM?}8_0j1zp^tBNM{T3+Kb&`Dv6GZ+u zR^i$XNwV*YGECZdnA~dIMcR8;g2KUKT+%qZI+DC*`aQFR0aqpY#D;QW7Dl}UZ`NB7gfLn6#**CUMC`1QfGGO**Ty`g(jT}--)ST%17+^4+Se9$9u@k%$0Tpft9 zr}e($iY-s@*_d(YZd-JA+Ez7@hR^`k92KFt^a{onT!n_i&8$ng2>WYg^V)_7Fm;Ln zS8Y7UMx9TCxjk}hPUu)(LFJh9!&qWD69h3Wh9v)(J03ahDHz|~_z7Qc)3MU?nX8{w>kVUQTILLAhT-*3UOu9J$ z*NK~eS)-tT0ba1t!xL1Wf%&uz(& zyL2GGUDgWCWx6!S!hq`b&4q_+SMe!HD~Yfzla8MLM6_t$1}ePq7W7v1=TD~2WA~b3 z*dKN_7-%;eHsz_2E5qkO{Q485MY|X`rlyFJAG~0NHG$ykX-h7esqm7_?QGUnXN(9Q z3{t9YIH7eH9y*`Fk4T+0dp3d;)GUFjj2PbMOf0#hu~ebJ6m`Q?mGeKHD?!sOZMC2_zwEHZFSO zfP1fwYwszTD{zY3HLzd(JLscN+%h z#_YwP&&3Ne(=TkqhG(R{@i6>adIh`#=Ri4#Alp`tuKduK=1qA^mZ-LZ`^-}EHR(9I zM%3UyB|9GR<|G7kNfNv6c+B@11(S>B!uM&p)z%BO;bZz;99iea<4o?Mzl#T?xMWxB zH4lf~CBwO_%uD=rZUS@rRKz6St;8wnb!>ciFqw3$3Jn(;@wuAhW*ZDy;Xps7647oq@$)L|kF{EQs3;>tyr11?%|{ePgQndS z^Yr_o@#b@|bmT6kD!PNUwf$+>Zd-^kJPotOWW$p>CS5fT zm!`llm3PErxhdQY-cfB?cb#lH`HGC2r~qI0KSh&OGQh9eK)C${>|>=yq`Jnia|sF% z8{G)2m)ru?q8QNGJ&)hroWt+8+4H>yXHa&j6J6i`7SoPjNMT(NH843S>O8TA&RCEl z9GhqbSLfbC$CGn;XZ$E|u2rD+>C^F$(k(c*Y%MN2brM(GT|kGyx;(Tk2#(pc!5r5r zP#+S915K)t^xX}!&n@QmlS6>_*wOro>16-$3Q?o~I^2|#!tBG^gsY8earVM}z&A%> zQCJoGGGPup`Z6Dk`^P|5%xTC{34}EVz1fBfBXFe2ZoI{WFu2qmBm0bGqkET<#ShED z=90DO;r#@1=I#yBWFx}kaR&5&VxQ{egSJ4z1$C;rVH-@BzKM^WM#Gc$+gZoyE5vKI z0XED|t1huzDGDq+MV9(`pt3@TsFe6JiN*OSyRegl7@OmSYeu|C%K#M;vtVIX0_Lu7 z;9egkLFxBZQMI51a<5n7LN6&MVOs$UONL@Wqz9IjW`W~r4Opcdj9b)Z;QM_okkQ}- zv#(BqubYmsUrQ39t2&42$c;wXCz@R9^L05Wx~h z-n~KtuYM>2WrtR>NLq{bj0uKX?HZzC_lit(It6bBm|(>`FIaQwJ+ptYQ+RLWNAfk= z19a?}Klc0^Hva2YqwZL1V>4 zCjZ(OYT83Y8%=fjou+0MB^tqOB@UwN$%)vU`&_ttzb@`ecA)viW6^)DBs7WX&AATZ zLRro-Xv^`aKG2{A1K-FK)hTI&961lSCcgvYWkztIa}=6fyvdT}q(OGm0XVo}7{0>o z;JKxg%^tr7QQ|3nu&zO^tV-Oc83!ger}0gS2JRNayA!G*jkR$72K>n<@cwA3`I&U#? zGS;Wtw@QnSjvImH4TH2IB^BS-f!93`pdEh!ebLzkbIhpFU!%cL9~E zsleI465vL|DF~f1j%#jwOo9x(Y5q+gI!P^?e}-7Tzw9UoKHh-3pi&b2Z5EBBFB;R|w9`4r3_ zzOAa(-WArJJ%$HF(d5eR^{5n5%0x};+3{0)EVQALbT10y0Rt)p8x|cU^8Lp`wQV_W z-1!JUTWShxY9{a+{iQ@{pd7oEH5`XImyk~@zq6gQ?eO9ERLqF#g2LC*Way$kw1E61 z$`R3`Tw2Cf@&_WMg{Q4d;A%0n5%G$pj@0HQz3eJcps#_-A>9p_S37C9VjI+mG|fg>HYC_#7swk zC#`g8O!OG4mRLrN%B`r>?RJ(HeF#rX9mSWsixY>*D7}!4 zs6@RG&L|9ke!dKQ&gP($p*H*D_fF`3R)j8MV)JvIXz)FskJ`MPRE6Cof|J+Kpr{sR!5Q5$C9aFy(wHt+XotzPg&gVBSNjEi?Hfy0&DNi zLV^2daF43Ony&)1Yk7~k@`c!ab^y!BHpS^t1L(091=>~8kJhK&W=;){&?I{)+V<%H z-C_A`#r(7Aq0x`e8roL$bvEvtU{gzY|x9iDY=V1npw)fI)`~?GbPG z@$2bOHV;^odTnjtz&A@y8-{Hsgemvc&gw#Hu%zr{+wM|Y8UYgm7 zKTWlXsb?j;E7^hDo~^)&%Ac$!Bp1Jh##avsYQpPpZNSqz4~CAofI)_0zYG>|ZRs6w z=}})Ma){zFi>I@hwM}T=cOoTHrqJ?f6|+1xuF7V%DQN6LGR-)VFE7{x?{78nI>-GG zA}$`Pv<(#bjk}C0%O_#o1Sd2kUl=$$qxz|Z7@OpWp3;hZVSNo`Juk$1brHS}X@(Iq zo%prv2STT3F4Qt63f8>54@2jQFk-v}r&C~n(ms){ zz$7})j>zM+{#>vol zFdkHUt5EyMcD^fQ9Q`su1)gb`(212Z`R`04y2L}Auo_<~Slc%Oezjc_K6Nq!oz?a{ z{A>-BjOk!8r$@6;h{xLQJGjVj5tw|{Fr6Qd3(j61yjBxDOSaFgt2(mufGPy0uqy{}u_J7Oz*% ze%VY54^g(#E(LURhoS;$#jX(XeD~8`nA4SwB*7DC_z?bJ{tVc#!5%JO8qNbOa-n&A zKX@6j0ggI~^cFq+@`sD>wQ zXoxQE34zI-iDGgagOw|{pyuyrqOSjl1kTMPduDt^rJO1B%*@9utxUwi%4_hvn*%o1 zOoO5$qhQ;(M3}H37DxA+CF%;4#>%HHcwhYiE>=6tm-}Bwo!%@+d#_yM+O?PzYfQ(G z+Cb5=?`QPl4YT8ETuX5>1{WfkUQGQ(8s&sqIR}8f_#*)DsL2uwey3J0=dz|*en2aLk z+PD$zu2}Ic(NAz{yc!Kp>m|;4TA+55V!9r%z3a2Fd59C8xst;*%OiAAqbm+X z1#G6jlF3foOTWMSEZnP?fLS#s$P0HV)YyI)PiK{5R7wsOSSDcdl6rup8eHb767=*v z%i^=#@yrb&+&{UB`*l7dbKxrL-mQS(UA}DLo4dGatPAQVhBBWK?c{ZsG_ly!N!YRt zWYXF@aO7!U{$x)zc1spP(K1oHmHpj(lR z3vL#{+or3`TkuL$c2ou)<{ctZzmJp8jlWrUCB-E>CW8NlM)*0*1`M{{z>}X1L4L|1 zm>}cAK+zVO1|{;r(=U;>KAxn?j!@543#pr%9@_cKag#Z3Men1I(rhJjtWX^eMUQjY zu%lz?!Pp$y6D?1bC4S-&iM!xZJRZl*QRIr{o!}pF0wm+_VYr1Jzn#n=NWomV^7a@^ zeA6PlpCu-9rw>Mz?)>VA33B{Pi5&(-zG9-^5~zNCGpx?u%{9GG6Z_7g)VAt7sW-_- z`7{asTgjYJiDaSK_Z)U_;(B=TVFMnhoXl&-%Y)W*iXN#^m}q(h;z+bvzii2mwGM~rmwtmyVK~{nQku2RwSk_^;*E?aNAt`P{jg+60xeoS7T^48 z#Wq(3yb<#ZMVkX~TvD&-QtSxS?~=jjp8i-;WXzhU7cqf-K8{LO!JgAPsIv6~eiCms zs#7;2DX@p_I;X%@noD8k^Aub&{D*MV=Fj*d`>t@}SyePwafOG<$52nTg!u%h({u8D zpx3sInGUtUJE`vEZJQ%c8I;@yXT*r|+9oqhP&bDNP=ZG}#s^UxT1mu)Ck%C zC=0fvla_75j>J)5U2Q;zN4`aqjoU%yh8#1Cn2B!owJae`6Z&lq5H4mPAt=dScb|jeyw7+w zA%zI9r@}_E4aPq;C$sIsl3*ce%5@{3c26eLhTb5@LX63}b>(b_ zc*Ewel|JO^>tVQDKS%gMJ{a9JdjB6~Z~j(e820@(4~iryqEu+2qLf0-c>He3pX)nT0N;{fjx_*AR93J#G+wtcc-wK_)(L4yMtWTdA=_ znqL?xK($}f*!-;~Bv_%*agR$nc*X1` ze6|wL9owNni^?oGlNX`TIb)+BTICg=3nOrOyES|ZcH>&y2UFOJuiU-xYvRz{DWUl= z0q5o6i<6Dz_@aY1II~NxFv_)+3pTCf4f?$C&-MtM5oXITb4|is3lrhQK?3GG1WUUl zuvBv^7XP(_xw{VY%Z}XTZ_V6?cKMTFVznZe-7er<&c|>&&(0LakCdh3qu#(JF$@$i zBUPB*JA$nmaS%>aYN5x@0^!BF9;~~i!)N|Y!~3saa!cy&;;AKBeDjja{JmA>+-lWW z7~|%M%Vi!3B(2oAp*_WL`c4x5b9swP{@&!Z!q&63o#XkO53=;cZ6Lkxx`c*>!=Ssz zl$Gn4v%mJULE^Nh_)Z>GA9OMsVjmCUwdxOZ+l{1Y?}P&AxjF~^4tjB(!WORY;vAvN zhZuM{&a_j4O}=5i$ls-5Cm{*`0Z!u^1vTr>1>Wo%g2R@vw@3|VyC@4cw1YB&x7s?rPAxU`lT7z6X**& zE#~62Qgbfi{V1IH%m=0}JuMDTiy?n*v|-?hVq z^6Q>)cV*9F@OBr#_XQjuWC)JI3n1yn8$MmS3IhZD;j}OEZ#M0M6^WDh>1&m7=*3We zSJ6%W&$-XMwqOnh=xN{t{Rt5NeGRPG;0m8Z#P5f;?Ql{(5~mlr^3#&{aFbHE*0Uc5 z6f|f9mwU1fAm4^{KAsBFnvVP!$Jx|cRSMSM+i+}+1sE>9gd^6Q;zs+G=o>Hq;%#im zZ1Y-dsxQR*yCtE%b{;sCR^y+bb0};x6bzTO=YwPn*`Xn7bbb9|#_t8TJm4ZO?9!!g zgI9t1DOo7EHH_UCUZh7KC79vT6P%HJ8?WfOpDl|W$zBzILDgSothCS@MxPOof3Gh4 zx)*VuvOQnDd^#^-I-Y)v72%(2DrElk6WnSKK?ohpN3XPCal@Y49GcyUEqfwBZtYku zYgj1EYAwcDzBBlHqBIQIe}#+pxQZ(FTQDqR0QEeMgt10rsVD!X&~Z#DG%bzBif&2D z+&P=dvlPH+Umv`Dl}@)-=p6{>ZXLac z4auMIQFs|PT`7g1k)vSDz~kt+&YT^Z^aqosN#e-F8g7_;A}t;%4&lwqL{;&8=1;FY z3{P$onElFyaVImldCrHh>e+BI{Cfj`e#*kc3Bl;IqlFLku7ICElJQxB6|_z-=WmE= z!CfznUlQ2IrQiO`JsA)NZ#PtPwJHzcKG?X>;#lWjhGm0`EK;Z|j z;m4X`pzSh>ExDxzrI);Dm8S;N_t}rvuB%~iof>NlPzQ^^67YAJ4VPjiVZQY$u;|`L zuHGGJ{I7^td{10p+b%RcJ(%5{s7#JK{|ScsZD4T&?_%t{moR#~Cd>=ThTCnsASGZD zWmn!nv+M)H>i9=|pz9pWJll_(n^T0#JKV8r@LT%V;|t4@^uR;79`F8Dr#JjCCV#D_ z-gLu${H$Zi|2vb0)s}hiYg#OS`%NFLpVNr8!DaC6tymAxIs-kX$JCdERRcZFhPffC z)LUkQCZoDw!<|U}<5g4oW*|k9pAeq-UB{gYhv46-9e9OrgPNWf{K%l?T;TknWH84b zPDKwys|UI`ZlxVen_0-uEokKSwj05U!4~{{%a0g)Mw&T)tpxi?hH%lq7%V+(sQvUc zl(ndX2DhOUaxxqL850+|a2CfuvEyE7jRg7d!R*M-R`i{lgzNq~b5lw_3S3L2aee$` z-hTW^KG5q3cSfIJ=AaGW9rhltdu!2j2N742sE%#93UKE`r@*<&858t(gj# zpJvL{FBYP}Lu(^W6!_tzvu05A{3AS=r%Rb%kvlg~pVKnT2E8^VoY!m$?)oMCv7A5* zF~0-edajVXEKE4#%V*v)Ga8JhoW-Z(66od6cCZsI<#wx1p{HlFAZ4NoR_0Wqa<~Qt zivsy?{+-Y-vl9#d+OQ*fnNW07mw7yy1Y?3OayDb?uU-(<@{tAzJCgG3sclfvGId;-)FPETnj5EE~Ii)@$6B_#mVr^0- zJa}XT!>iun@X!o2d*MucDTbHJfz6C$T-~q(q;9m~ zxG%0~AwF9d*j8}QzXx#TmPOd_8IQu^<+!$RHn6>l%wD_`_}V`eyw{J#{r^65FT%?3 zoz-9Hn79uXA1>j3ig!9TFS~KSSP(QSNrtLRvN3CjEX&;-f%2x8xcU-p45@O%N3;J3 z<8>ZE>dVvo7C6DDY5e1qENY=>w+yvO?GV5KZ(QSfkw$eZP=S3F-pUa_XVx~5u3ZoN zztzCmXpZ)}Kft(SLQbbx8Cx%y3)QO4aogoP7}n$s>QB$$&UbOV{>oK+*C=;eg@r54o4KZcWM?!xSEGkN0_FFb$v93*6=a1|$u;r)+B99JVttHiVU zx#89jRPY^Y_RHg-&95*xsTdEsRN1as_8G_fH1Vm1&-tIG+u4`9y+Y#wnp}0waeUvC zz?BuKkhG|Y+i3S5Wsg0A>5q?bm7C@0FMotn>+%;^1RjU~grSaKm&By2GGq|Bm;WHf z`@Wc~QC&eN_kGW3)Km)RR{lF7^oaAve;2NU{)AH8x+(_O=Erf=FH1iUPbT9H1JwT? zI=TN_h&Fid|Aj{VhpWz9*7pB{SaSH^3G)6Y$|N`VKS(C2(NcyI<`PpR?4^t^{x3#q zlG%S_r2g|;I{e_;q`gA*ZI=2uzckh847VD|rqL{6> z>SSLwXK`U7AGkSc9&1=HfWTvV?EJk5IxOtPx`=G5xsyd1-F8fQ<#bfPdjZ>{1(fgl z2ma-`&k)J$Ch8za1#mOwU!Ws94RS2hT zGh%x-4d*`B@3VdMA{*{ao<&2q?WH!4PBE#so{e%*6esOxf}GHsCEBOapc;hl5%v`F zIf9$|K8{@MGwI)(LFi?27dJetKs~vykn_qKE?O8t_ndD0FkPAtooPp#kG8|c@e%Yz zY8O0<^rN??T5ONYA$oI8kJ%rLz^$_nP>}W$*qYl45$EdBv1SVDHm5?B<5DKNX+dsI zsLj^K-nLos~y zIeNHb8h5$k8TbVp7rrf(<<*Pi*nzy&u;utbI)C#vMa%1v!{VhVGyMQ;@VYGUSo2Q2 z>;vdfl0%RD<&-M_3v}EqMS`&&xZ+9--q!icRenCte~EeqO(D_f{8a)+5B20D8$P2= zTrBso$er?M&!aJgGO#;A5fW$}RhtZ?VLPQ+nE2Vc+Z%&ZSLm~{O$XVRO%C*JPcE)m z)C-#~WU$rCPEpUzZM4c_vN(D5nysj9M(LVlHnd?7Ol^G&T2D3kAwP0x#Sa^Xn-BAy zX@|w>(OGQTZhL(Dz=gIZUSUDQoZ(T64MjW{!7OGDV%rM$(&Z+3`Xu|CAK4m2Fvx%% zuRTE_Qr0kj;5|6w(~iNGMp$DS&gRTrgC$`vu(Fk7io51gdBZyHwX>!u-)k6a7`qRO zm3L#z=Vq#-^R!<~LrvTMkh`lIiwfS{;oOM3?oOIK0-i-)A1{GCGF z7c#kkZ}k3i9>2h+9i$vrviJ)v_~r3kY;;^qQX8yT%Um%Ht8KU)!Fcv}2gYQLVcNRU6y(Bq)p;QtypMn(sSC(8=ouW# zQ-!U|eUZCm%J9o!{!W(`vkumzo%Ry2$JGSPR)o;P(N2(cdjqp4DK_$SoM7cU>H4Yp zuR$UA5}ZEbz?SLEquE=!>06f@WsSW@2UKjxed#+eDEa}@U88B2`e~T-LcoH}Tlhzp zWWmn13h$qq#!0s?6elZp!T3MNu=o6YT3Fyq>&C|k=gC&mm9MA3|G6jqJ6^}POq|81 zmFKYq<7&l2@i>(DHkek7&u7iON%%nM%>34w_NLt4q=6NGJM*+64t8?#?Kyw5Ucr|)4y^C_TGwuEg2oyH>?crFA%WTzxOkZ zEESRnPv+E&^+|1Y0kuT-a*s!C#qR82-g>AU9!TrJ6DQp8iQvP&Eg(u-2#_+{rsZ( zvG8U}Bke1G3Qq@5B){du+4t~9`aV;It3Cb|%6aoC);Kdo zoz7G%!41Q7YF-x(kw3?>&Yz4Qn7u?i1RhDZ4C3JCuQO<5wiZjuXVMi>FeUbT2?q_C zj91Oq(B|TU_@iwl&hXjHdz%}R>X)muVVe~{w&WVk+p(YgHq587<$k!WbT%6rDo?si zdMraB2RW%&*j054gI0~B1~V1bd0J64EXEC0K2C!fp8AmfT|7uDkz@5*TgY7^fUR5S z20u5c&@b=R;M?s7B7rpPe{~OntguUWDQ2Em8DToMK%WL78`pS-PzQ5b|~ATe-~ZeWwO#iS!f*Ag+)4d1e<@{ zL63#QsHS?Tje_ZPYUx@bHdHi#y3__1*53fxb;hJ_nZleaukrecHvukn(AS<8`X2v> zSKBv)|5oyvQyO>?#tzy_TgI+qqt8@f$FeZoER_yLOPA@~bXwdij3)unlF!r=E zpLcUx1)Z}>$mB*n)3dyYU%h8B|6iIYXZK9_+-wFW9!dqLyD4xd(}q6pj9_ubZSdt} zJaZ3gCa>UBwxI7Y%ozESbLafArgthl*mVs})|=yt5<9$6qCq;K%CatB;MRtnN1wL= z{BQ>u9G5o)qXzB)!IpNA_;?8{#Y4*c?x(2iqQxGnKfnRy$ZPMpk53Cm*YEdtV~dY{ z#)oqjk*$3c=a#YzCAWC$-|DXTSLoRUdfO6C2rV^H6+n^bnS7m7F^;?hccx(xTP-M#J(m zE794l9fs!bXI`Sm_^Y9e=H#4a`oZn|Q^5@w`6-|Fmfgh6y?QXiYBXwS+{9tu&#-Y7 zU3~fSqd3+^9}-p?vKjl&!OAz)!raSROvWR=K2#-;4t=Yp-Z4$omz;_3vNfRaa}HKF z^kZ~cG3RZYipo3dATH99vx?VeT640nKW8Z6-Tc+@4@z{j4%@1mM~51}(wi|O;i$~kA>8y~>e+U#H} zI#k&C1M=w0^62v?9ZcSF3vOI+BiHONc%)-4E$*>lhl^Y}1N#p!?RXWGjoi!D2iIcK zg8*h-HG^IHt_H6q%WzNHOFBR04Jg$p;bomD+L@Yz<7Q~Xxz)AcfAJ{PU5^ubj@E)% zeVbWpVlF;wuVw~6CFyv>eE4)Ffwtv#l9PEA*P1wyx-%I%Snq~y9@Z?osR=8UPC(#^ z zNvb#Svip{nfF`21(7)A+lQs>-4ZaeX8spCIQaFg0<3>@i=WA3n#EPwHTY{7#A+{Enn{mw`j=Aih0t7lhXIz;CBj zuzYwW%1#`_Rw)>>j8{&4L;WtCzYYag;+DYJVcq!1X9#tM%aBn_0QHIQN{TYCVA*jg z_CRJT7i-2?#CCU>^G=$zzl_GIr|tnBuwYF`)5+JVh)XuBq?dD7f%V|w>|ALV9rWh8 z@iIgCW$sf@WS_%dne4!Fbgb#b!5a|O9SH@i9JsRlM%vKTMRQMdL6DuIC~x@#(lWMS z%}wJ)aSkImt<7n)-9Uxido&qWh~c$AspHw$1UaVCUCv6**weUy=ScX{fIQy~7u`Oj z4mYQbWnn%sVFdpo-k(-3 zcIKP?4#7LgLy+8&Nw)tI*hGyZ(6Fu$4;nNJrNsA)8+qp;eeG@R;Pc?`>SUbKzJjaN zN(FHQ9BM9=vLe@Ds(h!yiXV%uC3Bjwu04TU**}(Pzv#qUi^}NQn3ba3!a9$ei*>IHpO`C+iijuU|UVhs<~<`F|rC+f+WpnE^MH_Hv7J{ z9y9D+#Y6YU{Nm<3Uc;&n&P|?;pSDS(^{RWIXgr$qcgBlc_vg~F-BPf&suxUcGx=k^ zW%Rjg5F6a>1RIAwM5Z-_B25p{Sn<8HAtez@+hZVfXet-&vzR4Te532Z@q!EoW$e3C zj(+ctg6kn&n($JUa=t#Gb>iIJr}_g zYZ}O9`LWgBH(>MdDEffMX!TSL%D-YFdf2J~`V~V(`ku>J*~24j=D0!Z^RKDwrLie% z*4zi%jNZVi*&W>0Bg!Jd$r4VttOBhYwdvNi2^93)mFbR;MO(LHth>nuON|ofLe^O* z)eOZqQ>4aOgF1bD2jr1>Lkk6c5=+ z31n6&Pp)l4VCg3pl-V>Lo{I;2(Z|wQ(EZPBvS}na@0TU2T>|GKVz86@iyG<8Y*X9X{ycAEu+d&+V*Zq2M;SzJ&TaWV^v`j_MBEwUot zm;KaW)4~1y?n1-u$KZM$NkPq-Eo3BTBGR=XUH6axVVpK&sWGhkrfF?Le;%(UhOKkZ}^9KSo31!$av%=@7@;CVG`aMQyf>)gm@Run`? z<&kB~X}apY0aQ%h;=TGAbnSQpx07o4tr<&TZgv?aUU-W6zm9WvH*cWwI}&*MYbqX` z=m<*;8~HuYyK(8IB@nv$A>MF!3!CMFpxgR7-$lY|dhcTo0&FSXp6K~>K*sV`lD9>&SwuaTL&>xWbpbGeuz9!Jxj z$EKpB34h>1q!^aaS;V$}a-g@Zsr30o7CmT~%vvuQQ){U*^cPC7o6h}^apING)3l5K zy(tsQQyif_wG?wET<3G(2j@CI2lDdu;MUz-O30rmHaq!DDa+0APQ$h6;#JeR&C zrH18{nG_5^9=CEeo8;K5voZ#scY@F1={rNP8^Oo%tPWjV_cCK=8N45#(ntHM40mE3uAAfe)sf62dFp_$2 z?iX8@{=n!qT_${A&W4_oqq^W?dbv84o}UmwmwP@xZ_^o0>(_pkxwK>er=D0&vs!CPHe{?&{HSB}D-q8atG?`?yGy|UD@T$4qVdf{U4Oz@t; z(XRKq=y(4{`f%nC?n$tOFL$1c+Y;Ww1(#If|@ZHGb)JGsz<;(Lp#dpQW4D%w*>TEUQC-6 zD$vMhGBvH%WP)Qkc&qXhoH;rdxI;#q=AP-)D~6bq(nXxXYj-Nwv=*QBJRRv#Be@Jc z=Jk(Y>=E&qId3WF<}O7CA11@aYE!D5F@RgHeh@>(Nivy&1`Le}XIA$un0uKTYrolu zl@(`bxcmw|o$Wt486rDp(1XO2yj6rd z^N`Hs`iy6DI~G^sPfHINeLNbNzXvJ5JOa<1BJe`{ajX)Z;G}<#XBR6Y*n6vZdTx<| z?q|9n;=>X!ei$Xvzb-9$l%T`E-aQ`n_{7rb*Y9E8eQA2HH=C}H_6Cb}6|n2eGwzS_ zDDodam!{v($4i=awC(0JS~mVNeOb7Vjc+JoU&Ze@o>qGNrZEBRS3`j~92$YAUOa`B zm&2HAOLYBBWfjrFq3_VB{S6$@j$+{{I`G`*8!jF73OuEEu-JcJAmnx}Gh}mQ(z_-;#h`%@B+Q&DT)TG_a*Gd65wHY$& zgiBZya+O`t8xDPs2eTgQ-89}Ql+DN=Vb}3O3@~4L4O16AgcVylq1G>f{Nfcw^>5Cx z){}R*Q2&`MrlgJkZmmnZuD9cy`*!Tik$6yweall|GNoN;!0UFI_#TCWr>l{}m(Q@#AQ9e|Zec<122<8dH+EtF4SYRGk<}SJ7YB{R zP{6WTY>U4HD_zbp@7tU34(icAg}qGe{y03=TTj|X{p2xw8#^NF$aEGgVtofK$+j&Q zZ=Scppw<^~BIGkfB)hR~bvNOlsxDrh^N?R0AZxe(odScBEK-@D%FME4SYVVkbAK}$ zhMW{P4K$e0`qL)7c=O3(hA1&vg*Uu{+aJCr-+oXGnrwkj3M|p8Y9^?LouinyY4lOolbLJiuwDaCF!~!s zZyzd%f{m2n;~80USu=`Pm^khA(M_jOle}H z+N7fi^!R|ZX!O`f?CPDwH%;#5s&0ZXlptRvX>x=XUvAP*1oLcpHZp{2k+@<56_%uvT~^*>RN_MA%hJRw-FLoG6c*wR5Ebh|)_ z{ate#hc8ru%STno_(TV{N?D1j(-NybRLy_i`d^qv=HQUzr5I$vl;Mc}WoLyu+ zja7WU&p3#V zy$EcHp=jdTGCCenOzKXa(B~y7aw)BVl$o2cam{S*)kec|f&TW$O6eSY$u{HAD@W%=i5LK(`Dp&@VYj`g^eu!eX45+cAQsusi%$^_@Wd zE$FA$!BsYdP_U=INF}cf^amWK6DK72*3{7g$s?gGs3w~wZ1%;LfEV15fGmWO>sW_d z5I&vz52kwVLGo~C`o6L3ufWyrPrd?+YTv?CG-|DA=r*H?$RjuR~$Hqfw-f0M#N4TeW z5m~MlpWWWxY)51{PQG{+Y8}idMEQ69Cua{>c-)HFr_`hD$xqPqejg>3v_jbVS4?8g zUoLp7GPT?bXZCsdw9USrOD=BZ0;9$D$aq&WyFZqu#@w%~KBy1Z>#F$BEG5jbTS*aV z4@mdvBv!EfIkfIA1@(@@)b=uxMx4Hl8cV#P{?ZqCojn9jzq*bCyDdmoVjsNTn*^~p z?xM7U1zE0&r7y8cBIgNq6k&S=eS0-+?%ar@cR@l(_jG0rb1ZPd$nmhas2D2(hk~!i zUzBaqWhL{PuswB%C`sF#Y+UxRl2~c3=X?{FDvDy07MEbU^jE}jy~48liWs+c7ke>p zKa{wMZN4|k`8q)~j{0~}So8b>tCUb@i|(Y*g=vc^K{1LOd2u*ONbba{*@hUFJV)UD zdI`7g`(0|8yPchOvS62-K8TwVBH1v5+29wf#iZAYLB@%5S-FEVU*BU&YCASyb)1Oq zXJ_L!2Y*)OJdR{%N{H{QA91`mtmiXu7cE&L!^vzLj|(R!(Y5+4`ncGZ>#Sz9b(Rjz zzi^Z)#uv~7;St!jbGJb5tTF}dsm0fCWSG-iBVnucW&En_NH42;sM=mubmsdgx|vwV zqD)(0$wqYsil^aA(QQ&Z*^2)2pK?oc&r^J1A=PXdPN6Rrl2b(-pD!xG2NxAYdHqHd zo2V_i$yYJ+>kDAd4@!LRTR!aq)v>GSjJR8+f`jj=n33N`om2UB7( zJnAH#xRpx>2l!CZhVf$Ss5?7lJdjzA-$2*C{l@-rmnnXF8k(#f%5U*3=Q?!fL#}78 zu=R=;jMrSqLY}?>!*Px*LD89%o_wS?=Gg+z7=1QC7|vQXIJW3TA5|=Lp{&;fX{BNU zrS%U$yX;23XilZ=UM+tXx$igLju`KBr(8=7# zv`5*2^RI=dUVM-RKYt2|hZpnHT#nlA9`{F>^)HlJojJt}Kc=wwtP*DYEKQ*OU>=<> zYDBm7s%-ZMM;1IT9TL|MX66ZV(BkPray??std3qo>yQVyFMT!hf7np}w6lyY_HDzz zMY&9&RQ#LrilN0Do4HiST<$=`R5*EIF_X%)qD88s>BEOR@bt+?G`yruz50>NJyVDl z#YW7s^*o)-GR6_n@A=uAGwD-?5i_3i58JfUSeNoFm~}mcLe{8|^QcO$DE=zmpIZxm z6P!u4`Z5_8Kc%Hf-ME!gwF|%z?AeGyKEPuVyEM{`cFZrwW@`svQ%})w*+l9oS&nW) zvN5J?7&(Zg1Y0UcQNpYf7_{;sSr5r$tLGfSA$gB@naM76@|6U0wu+)J+tkq^CxS`8 zazGjTF)UBD71oMWQKV}L{VuA!Wq=)%TcHiXH+5*+zD>+*TRM)?H=!r4bEv0Tjp*Jg zHoo@-svYzL1ksDR>w|ROonS{!p)3oN_xHYL4 zhQ7b>KY^+Aq7%F>Yva0ay~ABoW}@Vl9(?b29L&ee<(78T!k^q#^hY=c95dvoBSnE$ zIctNTXg_+1-;{>zAArX0|4}OXpOv2f>5uwPd`bSlAgTXGDLMT2`p^GAg;eeT!lNwy z-*}XQ?SKEQ|3aevTYKpLITCg8?gE@Lq?uDx-NJMXCo)y-U=|)Wik)&Cforc47}+gg ztuMVmbLL6d6fp^|?>~bjX0`OtcsLBa-HjK^N||(NGN^r&rYE0QVBR7F7HNGAWPUdB zuoT#*RX?EqPID8aBiQjt zhq1bI4I7sG2=BErI=4tcTpnRh*RAF;+XcPCGe(0zPw@cXA)A4VdIzxV>vF7Uf+Wc; z%i!gW*RjcFmGI+_GIUk#V@*AhXd7WoPmYfU`^jgxulL3H#+?Y*zrc-s4|{|U<-b!; zKon~4x(4zqOxU$`J-AXV*tB)Nj<0rbRQOdq-rsi!{8qLK7B?M)X9w4DQ?%qjTYn*% zoOS^1GehX?iVE1gvmD>arLcl`sub-!5N1Bm<<>eXk%7(={G96xZT-n0(>E3dx7ks> z-6Xv2r9jd>h5YhCHLy_r6j+@(B2aifh()K2V8!x^n0_jNZC)FK-WNs)iw4HB__}!@ zu9<|klp|>AZcYz^hTuNEO8gvr3T{=6gv#~2VEJ`h+RRBq-2?}^Y$(T~&i3HQrZh+$ zBgOLUcCcHv`|+^zUN$3MJQB_5gWECd@#u#UFxo?$VQNp|cgVG&+UM;!R3Z^$|AxXY zPbbb^_!1=>-wGwHra@zd0R&yo!(Z49-xON;gCiyi&rSR&m?>r*HGZB4ox6$kr8U}I z`TDn@J+VrtI_4UTzLf}{i-%KVTLd=lY=(~h-=Nnd4m~bjOg@W(&>%e?2j{u6a)r}) z+GZtXrDkKP+D=GnEaQb$J=oa$2=is7$*w4YKF&TVa5?ILqR2eFvqXjIIlmT^E?CY? zdZX$5rtkdkM}BOqlM4O3Jew``E5Y#hdm;B2@qZrIGS#_WlpUVPa$@t~?Fl88fmvet z+)NfQTA7qye&XBQ3OMV`JhW;&3iDHkLTEKYU{)eU=tYy2Xx>~R~YCu?Gv%Rrj% zaFBl+k;7hf-+&1R=iz_^8&nQ5VRtR$z-xFdIt)6&ms!taxBYzS$L~G-n+|DANjS>R zhQ5Z9Svv3{U!LMh%mm8z`?%E`V>z!aMKEvBTxc#BjLXUwfq`W@F7ZE#FGF|I+c|r= zE?)$--{x$W-%*@o{FTc&7f2Td89?-h44T>!&D@`M!WGZGIJ%nH$>g#K03JgXnGH5wslha8GhtfQ^%k5{tOWKQTPPbx*uRlX_>A~nRqbc%S8Y<^bhFOAC z)O@MHFWL}|M>Z65@6Ztp#V_j%>Msd1BW3B|-(36>Z!Rv^nFWg4!}v!pMEt7_eSB?0 z5yY(70i1aK2aio5bBik+u}cKoA946>-a#mvzaD*u^8Ajq2bpzGD~x>>1Jb^GIZZ`F zQhhX>QE3jo-fYG!hDAbRTMpm6)OZ zuDqXramox%wj4o!w85qW%3u*`#;l4D@>boQe4dLOZcY-fFnZ(ojXilbTfWxY`Y)Ny zHGkCNXa5_``v1-5@AN%}o2gAOxt>w~uYu?wpFvNTM8bq~A26?52byw4{FRfIpnKe2 z>hvtwPz4ZgL-QmvTR+ zuVxyf6mYrjN3O+KlDIY1py8b^{F%5NU(H>{EL;9?mOj(Siu;Z0($4dB?lb7t-#@@Y zir~tuI4;L#4OnE`)27`HB;0fk|J@7VY(`{a%2f%Pc2W^iBYkK2*)|L3^q zj3QcW=a_AhteyKaJ2E!j&&K>z2CFssf)6*vWOVBX;o%<^d~?<~NSvd@4oR25hd&?j zU#dQSpn+ia&>Aw7H`f=w-^a`P7ou*4CTbj3rQgTRas9+yp4A0~>E^a9QCG__om5EY@u-7^v&uweeS>XJ7%! zL}f#8qZ?%$x{AyEKZ4)S2jDb96GEr&<45iH!)Zb_dg1UH4yEP@e!^5zYaWKdQ;n(j z@jS6uHyws9TMSYyJ^YCE3t(uwG{tJkkym0OR$VVZL5wR_KkXCTC|L#;i@aHG{*ZcS z(}xh6|6X7gD9KWnsj;Iy14z)P!3zKM=4ziNk;7~_aLVOu3-#rc*9v+~3YUZ@(_Fv)9*A{fqqzE4@I*lps#icDD;$euz zJ5KeVEiFnHXIgUCb9ow*nc`JBX8CJ9-F&J_-R%vW(YPgSVR{OrFVyGMI=nGZoZ-&e z7tAh;*O0m&XQ9GZDcZlx8SAZIb2nZF2=4|DV3lJO8dCtPt~|{yAny54rWI$*KsDP zmNX=-58v=}sdM84xEwf^G({EQ(LNX6C6#j<fOvNjP4>4Fl zv0aI@UhI`?$>`HL4I4HO}VQn!zF^m*Q$?Nih17g1_dzWY5IqSEg&PVw1iiME9K}uAq+X#Uv88 zCz9N}6-;sXM()XR8+Iklg4%)>fwGH%oyy`^)~AyS>1hI7+?#;9u3?a%VMtO(4cN#m zO{$(c7G9n8V5tQ!@toWQG15|d);vt+m#cGdiHheLc&=|Ftfx}a`GM<8)h zLdQM{u!gO%RvhKKzl$+b_OUDXSrf-BV!HmVzLyDnj)+x#&<<0_meDP^ip2El{Z>Sz{FSu4CCGfverkZVf{2& z@d`vhnnT^WaZ4_-@++MX(w@)Gm#ecGfoqw)%Vyf()CO%w6LDybI*Yv;hcDZoi)&}L zI^=H^p`lYk{)Ft9Fv;Glml-3vuIZ}+Nmop$Katgh;K87;aUxt^hO3-BD zPd-H)D?2g~@^3ugtkloo4&_!zPta$Fd|bihzA2YCLWUKTpN5~8!%6AiIN1MSBx9MU zFt1P=5B3jd?HBB*tZ_dapXE)H21U_1w-C7E(Ew@alS8;nzD1l%wWcYnl3~62PWJC$B`n@A14FhQ zfxi!)@TWcW$$s$)CRHQLtyUUOuS3c(ci3PU8af-hv7RjK=D>NS9Qt{$4SNf|;L`b# zG$!W<-`XMeSjBY-y&7)ux@D$pbg3-4TO^=@82G6jUjf#Jfspt78b-C;q{hJ+T*~wc z+-SN@(Bx6To>%N;cIlPSx_Y=cA`s3D!k1Fb92r)#b%@=R+qZ=td&=?l#1i%*tOKnp zO~5N(o87&<509TswjJO%gIHn$Zn!KB5BGUA?)a$ z9N4x}iu&RsaQ4h4R4#u3#Zyl4QTB=}F;HWp7j5G7Gx)mHC3^v8A>NU7H;yo(~QSu{+&wSH#k zM%tgbg+d36g39Gd;+RP(+jil+puN0LFjJi2wzQXI9p=Zlj#Ebk-^H29sN=fiei@i^ z!7IF(DZv(6`7wVzu@g-883$P!uh5W?T6*D%xHlPYu6FLyq}!{+hO%!w$zxt zzp#Yw7{unq+A&~v224_s)j`BqVD0;XAf5=^yh4B68 zcTY8MJ6e;?3)u|T>2t(QUy5Mndu23J?ZWwWg`hua9QnQqfT!P1p@Oy(mNjR=i4=K? z?i1rc#qs1{DPkeN?%~;()npr)N_In6;FwGm^@AYkVRYbZo|pBHF)c=BCXovh(E0JV7Htu<2&zg#zU%w*oz5!{qPdTRA~z? zIw6we>`AffjhUN-GCl6z!e%>q;?YgoeC6O>%xj%3A2IhSZ+7Dd&JBX|}yznVJx#vO6 zXO6<0b=$ycCE+B`fh^vy1h=V{vT2X+u!Q}Y>|gpE8a?qNT>N>E?f-bWeL>w?rpndWsif~o6xs1H+T>%N{B*2>F3H&+t$qU%^)z-_2onG6#B zb8uJQ28t-rW*^qP;_rV970x%CaG-cSoIcSHR=0nKDYDK~KOr2Re6psCKMJ^L>jCV* z%E$P+a5Ks+&_|z4hAT&Ck!JG z{RMO%ZKSO2VkXnC2+C~du^@q&+P~eC#yZ~v+pHkgt~rD9j3U{nY6sABEZ`JYszSW$ zUM4!G1FJ_AV)O-R_$VC=E`cYwybYf0gO7+s1@&W_I=ykkPD?2J+6reh?qOe!AEy7~ zF}SUxE@QM6#pn3ehR2Fr}4& z%vkPr(pX3x^bVF74rI^jgjGOy65qIK3`iE=g>l*%lxP2h$N3Yg&hD}d8%{BkHgzMZ~$Rqg+oL|!=Dt%YU4R%YS=K6np&5~!h zZpQ+4aFrm7-J6UP6(+OL#eLk^uhP`<@(?XqJ_i`&kp5ByReUOy(2*uZ9#I@HZrjpDr|h>othd4M(F&dCF*6 z!^cUFp_v!_G0p4*=51Bur_3wmlJ#Yo->L!pt3gxo>EnSoFeINeb`=yB{>8}y;FBY)+3xM6d-AJsywzG%9~;ZW z)+Z@&kr_m99>HFVUSr2sL3Ui_g}VK;+0)VgXw8EIe9${13O_K6MyIEJ4@Q1;79sJkmh-(QQ^)PC3S z-9T&hWJ?T;O54jh7{&1W_L;L;#s#cSO_##vY=@0XmbG&Irl4L~8Q*&0D&x-8i{DpH zXIg0;G`XgP-OsZ?xg>46pgg_q=Ab}aapEK{oumcDu^X^dNdvdv3S|kNm+|(w7A|w> z05&Lh79DmqBF#ELJJBBY{`zFL#LAu)aEr)gr5hE0uwmZsZ_)9xaJsV63BJgz=M3BR z`QQvYAy(GJwps6BS_^yx8Fvec4x7^QtkG~O*PN|P3S^EASD0hQcpP%pj%AkFGR@9q zbZVk9-7(+Gnrt+o<;rIKCjFZ$*_keKxT499EgJ)MUe9?b+>KiV@Wh#_er%-bJ<$ra zGUlh`0B5RQXhFA_qJR(vuF^_$`0p0FPlb%^WAXyMimM(8o(kp z=iuc7>Y(!QI$HQ>vAY8excHR<6Zz~8K1FRVN$V}7we98*b8!NOrHFC+=n#_cGGn#{ z(yVyrcZ`$d;E~O*vGd&pKJ;8y8sO&5oFukDPuU{O?Gs^S=n%H^x-m%UkA>{Yv+T(1 z8SL7US5WL(ZkZT|-I+8&|L(OEP#GY>=$e)DNJ zPr@1NB(7`CdAOQ-RLt2QfIWje_!SMwZ15*1c=bmHB|Lth^BN_}ySke@B|ibnPwt?Q zcoQ!1%}egWFin~{FO1U@L}8W=5+rqZ1*h3^1hh4GqxNQV46+Qu-ZMfCdyNiz{zHPw z<{jm8_b$SNe;c{BlE+Xx=?AX5{*aUR)MkyTb#PJdFXWFpi>p!%scBjS^N8Va@!qLy ze$ET0^vm*eym|@j2x$hd`(vrfXB6|b4JDad!}x32T2ytYkz_Xh;J##W6uSC6J{j5u zmugf*KK{zIXT@ROpy(d&{aFfcx|j<0l@sxs<~;#X3_e~ zZfJCOCg#e@lGh)U+BSHzn&DIeDNIR1^&%Vhhf~D zeqPu)c@_H_Y6I(6&w;hev*CP=GlJzJQu%El$o>|9_bme)Q6NX(SQH*~sDam7``IdQ zo_iZPnN5l6!L{4GQP0he?QPzNZDZnalJ05j)EtA?1%}7sjsslZihaCe%Nw+rZO)bY z7O}_s&*OQa8PM^$4ohxi@ZWCkqGuz2Lfo$cbhdH9to}M6zA2*A1IJLSXFKis`~l}) z4ZwvHu0d9ADYQ#5=&amF6>3*Fx2-(1?M#I`;ni$_v=$Q;?tvBi6{umb2idLOP9YDb zvb%!d?a~P7MQ&i#T0+!BciHUWrRBwX6zNuls>^fX-fv}A2nc7(#qd< z`@wf#;4tiS91Y40Wa;}S;uWWH?3|P)^$xcu?TJd@*)W;)4XTCxyJX0}=pVN(ScXnJ z3mm>44fa*igSoqub8>T6V}6epOwr&`T6H_Ud7=y~c{zNQO2Qp!*^nVs1Yg(Y!lcKG zXxfE&WD}U^fjxwDDiRi*;!YSUrV&QG{xdI7`^RKb|E8~oJZ zIzgCOj;rX%CXZCxqj@P+KeqjlE$B@ZVu1}y z@#v63IyWT(Hl5_bZJPx9W|F{a?Z&gv8MWfH#o7G$^#f^DejDi6SdhW{EYPetj543& zscw!ORd1@~*L}9e$b{jTSTD%Po+RMQmphy?i}yjOlrk0tw9umW`*`nOU6{3#v3!F% zL1H?J#cT@2*TR|8bIuy(ps|d6oOiJ9#hy&(%6RsuL4rO;TCy%DfyZe(h9>y$XNz?2 zK%YY;9&2ZKzVic)w3cD7N19^)Kqq$4ya()_bYr_*E1r3pid$~HL#dQ}tX*dV4Q1PK zZtYYE|GHCu;}r36Oqtt&!w!{0 zN6r#5@ZF9k3&+FC9lzn&m>IMoNSXz`sR31wJXkYt8+KKUWBX8x;&Nk&Z+*_#Bwr>m z^&whZ{EWkvWx(Gv7jOehq0jMgxZLobz()Uou}uUT2M4ppLV3FV+MC5FIrIwGB&T9O%kP zJvQ>_YWC{uOE|tF9dm1r;4+0>q;8@O2W?hS`|ugOmB0_`T@*rRha_;bman0{u_Gx! zBA-wGt3?ZSta+oKv3O&48z|foD%LsM;LWN*q;H)8ekm#ZgP>KkWLPj5_Faa;RX_Lx zFOt}rWEXtAY#glSW8v?IgOItk3yen#^QC{$5N^7S3Jf*q?AwXta9SO2=LgZY`zd02 zc1iqAAqlR*iEeAUzuRM|x_2g|_H7649S-cz^JO^sYA^*4&_(kT@#uIvj>U{Q3F)Q& z{Pb}R_)w_KxmSnbj46Bh-t9g(S1AkzP5gz@k&AHF1vwlx(-h~VY{O^mJLvoMUtqDw zh&g>5KsA$A@qs5U;A8J(bT|CO$s|?6+BhRN9qMo|uLF9olgRMvan5k*6k00P0(~Z8 zQdstvH=Z|&>G9_I??KU@7mDO6u>vYXt_r)PXgav9 zh*r)5R(|e_knd=MIBgkLZ?Dd}?-$~$b^X{V!5tv`NQyj#xH}!yW!eSOLfW&2OL(M0 z5sNjMvPKo#9rFM*1FnlVJ$ny^zl0s5?|B^4Uz^_czJc)puf@^F)G242AdWAJriq{C z6_Un=a6cSiyQ&*0H=sx2K!zlKw_M&Q{q#keQ_8f2zwQKWk$o-axRRh#*+ z_}PDO?@G{N+f1fmH5+f1+mhPm67H*|5^Jw-gd5G~qGx-9*dfgk6ysou{p0{9&T(MY z5oH*CH;j&W4P?>HD`}->7Qc5%5CsHIgX^-p>EF{H=(}jb^d_p}NslVAny@z)9cmMo zO%D^>mtSPX?Ls{~M-SEO&B;NgA2{iC!tcX(DKTandF{%B@q?oOhfr_iCB^y~tE}lt z({*xGqK*br~ajw}h(mUh?GJ!8B-*5)!`X~i5}+Vua1Mk)Tk;++0FDD}T(ms}P9#}%AL{a1|XxwMLc)PI`x{`1LVq0;|J zhY|u<6X(VHFJB({U!*Ec9a9~(QA$q#>pHH3{tvL#|N4Rd`4T<<4~VM9|CPZS{l90h z{_FC}PXF)M{O?58XlvKS^PYlxoGpz6it+zsf6O8 zzDx#I=;x!vQUO4Kui;%=ApFS@z!1K_V1$JLAZR+oKahTdhVpUTrIlmpmCijnw)zmv zsj0wMIs2(K`~hCs5kUI62H2DvL?dTO^FK2`Gn<8X;Ea6%tus}D+KVIDogJNHH>g&z z8{*NFRsIxy3smC%NsD03x=}1)TYu(Pb{*~`*(nt9Cd0~R zSTk9jCKd#fsdxcaX+4H_;UX&j*~OWvyR%2V%V9{TSS)d3Ef$Au=L#}pVBy@$aL~9I z2APWC+>v9bs;WS<_Dx_H1SM;9a47RWG!X0^bLrKd4XoMJl$A7%rO1?l)G03FR6d&E zIjys(C``*#CoAKrKcivsiOpGE2EJ?(*QfV~D*PLBHvlA`n8L2}y5*rUdjw1#lR_4W7kD|@`@H4G0MX>_5%i({7Ff<=>`v!ZZ26ExHnF2<+xZDt zeKM6V(A@?dp6T4FM-p6*PC1U8_zV7pt->$W&#-NaEt5I5o(^X@(6f&Z`MWcAumR5V zQTh2TXxG=H$5Xq-oL?Q!Un&B(fCj#y+@5qk`%{C@GBi%EqGOt|(DK)kUifq(Kk_IT zDOj?RYszTo^=^zhk_L?rR7p4f1HXQDA?nEkH<7D8a2O-HZYJZj}*aDEkwKZa&3x*2if_?J1h@&K|2|o#=UN zCL{}Kw)q(zc>QcS$Z$fq)G&<2+M2MT@1{ZYC_6r{>PFqUNg3SEC`FdW1f#(98RXPE zn_N>z!r{7|=zV_$dvH%1caRPY6O1;8WPd@lrxO?IGEy|uWG}oa9Y%xZ5H1n6rdkox z==~ZgXRB@IV7xUIM)$2_(+A3;=0qbLGXD`6_9SpaB)s8UV;GzM>o;ha=CCa#iJW8q zRGitj3u{Yr+0%xPc#qeh^eJ+jMelL+jw#31>%G`xq6h}7E(jBg81gM%NQXaL;^4#T z)BuUBtaKh;?Z1#Eef4H{oW9|{&~`3t(M5L7-h|yzp8)aq-hiImT~0OMhCT+NWbE z){24nwn5o9SXKkV5J4WD5-(t8~ z7Y1%yLddbX5k6H28`Rz{0)f%1F1ztNuD$63+^$^a_gtC+r|g1#V{I|XT}Mc%%FtVt z&7d054X!z!Y~uJfeox9f9Ahzw?Y=kf@Sj^CM+Z;X^bU&yGif zCsxdu&*A<#L~{>@J%gBsootJ32+lq3j*}XDK`-Jgh6S_;SZ6o*Taf^R*-M!09m}}& zBU!bQE_=eC<#aj|Mfx{eIla~v(3tj^E`MskCa0mW{6il)UNL3web&L>JtmZFXUVQq zD6(76GT^;?EBa&&rVD$N*w&0J>|1gd_kFZviyv)cQ~Fs##eO_h4yoGUku3fThcmU`fBrypFWBV8&9S7V%y%E07TkckwKEq%8QQ z@p%1xBo2M>4v#1r)b$%+3s1V$uyXzf@Mw;~cUtMBxAl$qo8 zPOLst4TCaW$>#Y;(kgq+8SI)$hXfnw!$I*dZrGW+adJXgd7Kz!?mXgD7d*soA#V6+ z)h$6~ZAA9BN^!T{Iph;t;ayEUSww#ohrBpe_gGbqW#^B>h*C*5qHhE$m4z^mi$&0A z7(ut5yyVm_SK**hL)e=JWVx9dWOo0)cwI#z>E1a>5w(4==f!H;?XiKXWrR{~vJscy7DNxGeSk$1 z4q)@(zo@2ggU&lBux$@Sd|;3dOA&w?EB|yr;MiJDdj2+eH{dr+J~;#`u8ktQd^wmN z^d9o=RKg9-8eB7^h;Kf1lhaDg#whdO_^iGHzjoh;$XN#{`eGd|zy|*5(L@MN`31H1 zJXaV0hy${Oq9vxZzEzby-<%JLE342qQH_dM7*fOH{qW@F3>Gl*4H*piOlzwZMe%WS zxZ1#e?0B~T!tu~2&NmQWowEn!*?ZaP4c*vUk;AMiqS&9FP)MG=2h@Kv`7|0-kM}~_TgNn{lbEsJ!8X~I6rikOhMP&Vo=i+Q<$y}+AcDq)f~1LMwb;fbr}2+g71I|I4z5)l zST#qNzgC|k4$wbE#;QX4^HmV*U24NR()Iv*775xy(LdBc1G?uPhj71AOc6FVZEGFS zF{2ZHyp+cy>mTy1wnLcqfpj)c*oGeRlB8v^Zv=>A01GtU#jea&z^L5E^yb4?;f*hd zey=?XQvX)4D6SoYy0$ZRjrhFHfv|6{zqs#9rt_*VX?Sd@8N0prB5WD|OnfuK3x7d7 zY&$ee(7cC=cQ(D_w|G5(W3_4m2q_WU+XKb!;eGH`Fb|am*9!&z1a6=6Y_aRMTCU`` zBCVS*m=^;Wzvs>czNr5Y@%_iMNnJ;S)ZdI_vY#iQ>2Y8`lLo=f)#}bVv$EL!W$rL_ zekG`+w(*T)%DDS2x-coY83qmo@JL3uvT;6HhTBob+6;);Q4Z*5gb7!T*$9oRVo~N@ zTov#Wf5;&|^|UANkUISGU7GvkWr)d6v&mmFO*|m_AGCXRp_im2dzEHH!`{TRApLFV zy{d!t|2Lf(Za)L6-@iLN49cZpmD`y?(+j@&Og;l6B8^p(`Hy;1%p*(<`*)#x-7(se_ME>k%8L}DHVeOZ5R>WIdB|LVXoJ4a} zBKQDfbyD4*1aUtiVcO|NNPMfoY;V?rT7ebop1B2rHR5sk!*&{yq(OsztR;Di8vM~A zCv1z=$S!(2-E$=L*9*hC@6o{bE8_SMbz&Q%!^~4^KJW4~pVQc^4IanB=~2=R_!51H zcik=x7UaFmfi^w+f}3e6&0KaD)-TSd<#i=OD@CvRMX5EcX(LDJfZk^GOR+z_9^(7kr!tmMUiEMqXuw@%ELgY6`gE}LF;6t`9J-+sZ`N~$obE^sBFAMj9a!VNM7A6X2 z*cY&ExfEpTb9hhZ5Z=3V9jiwb@xFiiMC}=y(KFSQZTLytFSqWCO`LSTSfu1*9uzZ*fTlBq%V%E)J zeqO?M^Mj61W}HbGf|WbzZ!mMSL~ORd$BnNma&tk>SG^##SFXjdNqSmqmCR?5b@mqFbOF<;_apKrF z!MZrqiT9SHXsv`>3r;k|M4bVqi@iKH8)P8)c`^Wl<7mAhnj}>s`mk2`@#l z;LkR05dMY_mZP7EEn8_Z5~?c(`CQtw(Il*aCWc3+))BZ_+ANrZJi-y8uUR_uPJyvPGaXe z1XDqE0l4}dWOwQXqwj|)%-U!&TkYQs2RWETc%_G3;P2crMQ0xq%PFO)=Vgo~HFaP})- zc$9vRGgi%qX@ULms7(a9s^#LVo2mTrtu4a+Y6(O~#(-JsT{O-R>|EZ7;M1y4&33Jr zKII@ZwdG;K!XOM)v0_P+)>7}5!D4H>Be0?Hl=$oH6bRB=%9Y8VgQGdOVe}ATPNkNO z+G)4&`qJ4MAG*=M|3G|Kc1yH!Koe?g ze-2_7C$`ewpFM4hLdh{Z(dn=~TRC+QtkJrRZ8?t2<%=a#jOpXvIEFrE~g~bFg83G-aop?-`kbU&`6Ce zzdzufyzPO-AFVK^pA~jo-UHj3V<^q;4le(0LI>N7Xm`;fka;|qA}qJVFqJai&vFt= z-x-3bE*w4|UJH(;v*CbC2pBJoVdL-Hupu+oz+oXa>CrKY#UB)`ZBYi~E11<(%#G;a z%4piWHiK6GTFk7_874|q(iL@Q+VIQ=QVJXR_eSxoD*PonFLq#G0_|CClo}1bCrs77 zvPEqhPs3DAGp;LCk<#3rV%B&yk@Ba5+~FIBP||%8jc56yp6gZ$4U(gE!)joT$pz7> zVpCQa--wYhKHQ6VNgDCy3hynn&a$%yunJBNWygKtFMQ9zk!jK_ZSF~a%8+g7(NIi* zGDo?&xfy69_F*m$3+h^qD)ajt4svGhy}ZkYB&K|C8$HaIN3-WY@q++gojmLsTsl3P z>8iivuiBRijmttV_;@nRO3G&HmWGX?c)_{73=EKqraRQWmJucWY25Rn}1IezL zzze{C54qcX<@OiYuFAu#fbnqm?hS|;Dl`(h!@$8Ojoy{?!Re=;xv@WtoI^tHP{(c% znwtfXd)@TPvlPrP2=tz@a3z8hR>hGdte$D#6&@tQGHbr zWbD2QI^TX_Z~Z*hz3+s$(1oK~p^&{SL7K9AedyO28CtFG$**1_fQ7#ruzZd4Ec#t5 zf85TSZFn>Z#}-V67Jn51dgbUWf7gfiKa~dqCLG{r51P*6j1*ZmFTp?c5#vDvNhaYw z0eu};Ly7MQI`!ruOz7N8!|qOIr}r+T>fTxGwCZ|(xzMyJGulN9`elhcqT|tF)p)M= zkpv5gf9v!>eF1Orb|vkau$*nX<$wz(&S!;-?b-XfS~#4&$DAMh zT+Eg=E+UP_DAqjwHJr?H0P*n>JS05{O#bP69(7pQ{y~mxHHAa=1RV&zI@4p~l@(|^ZtY#V?G?}~AAeb4&!@ZxjxO-PV z>X=W*0k?&7!HanQ?}pp3)Yis%^G7i&Pfw+b9?}f^x9}x;DvWIocC!R))f(z>{G z7QJ=~*ZuAZA5;~Eipc~zWuHZNH#fj9i4@98pUehV=+QZ!Zp@pzmaYA+#a(?NoCPnx z{YZzc_LXJ1+G@nofz7IHV;2?oVe8D9R59upIH~^Q zZKv#Ib0ivg*%hN`=ba^x^_8(#7Pn#QlzfaEuE5r?N20w7#A) zOuwX*mi#oJ)yb0uh;cFZ`RQL?MO+9ogfxo1;bD638ODa?>WI3!ip2w@HPLO#5^7!j zkY8RHdPi+l*oE|>T1?ckoqji#PWt}xoY zoGJw4+*{9VHur`q{#Gic#Yg9Z=7v8`2`|IMx%LSp*?A7C90s#Z_gi69)Hzu4d@5M# z@4y+3!zo#;#A$W{6_0v=Gq%m*;sYD7Oil_PRdowz=1chY`dr)}5DxMO?D?!fC;SvU zmRy9CbXLYPX89nUdwY!F#@IZ3AafBl{%KNSfCvA%-WtQry7*dsXXf^5EN^)KFt<>8 zC|x>j{2!ox*6~qVY`4Z1>S9O2v4D1ztBxU)>BnJ=f;T_O@HN_J`m>LTK2C{mWtg(0 z9|lFSaH*>_F;w15*sEA#N_IWQu9Bl`(M51sb|>4?ZA``{JH=~7dN9IAh)K-s z=9Et?04cjsPNQ{$xmID2UsEN?u^T?j0=ANbr94F%>_xqqnb;dMl!B}`;mArZBH$HB_^tCGUIjj$Ai+qOSnU&5}g0Y(WzdZUv6tnK7Z6{-ckW>b~IHm6K`g| zW_cXDRl}4AC_+`YADEmLvo}$HMLPyRKdP4JJIIayo0K+GWQ1o6O<3@P0 zALnPo31ee+e7QYmsFF_welbi#{S!W`3B=zefx`W*1I|8n6MwC}1XlYulef(_^z5t< zHpo77v0UDHQCtBR+w97=S54u=eUt$|8#v#1F_|fJf-uRR~ zH{#d}PHJW|BngCoc*p51>bnWs6Bf@Nv<;vYc@i{S*e}g%HDDTV2g6HGbGrM+5I*Ar zIy|F*bNT{U_U<^w-l+kh`0{ z27SZy)#Yr~Ul-Oe<`?qUi(t;SEqv8P4NC2L0o;swNKOBYTk>?Ud7T5xv8cvptE)x0 z>=~X_)~489-Qp4V&73zB`Eh-1E|ewL0NXRH@#ps0e9M)yI3mJ|sY+}lN4cr|nyoFo zzV04)>uiPJ%*T+ooE9WW#E5RRj;GUqCb01bZ^N`EIo7x&(`o$zIXrIk7NNNtYWE9s zI>SEvko#EdAP5l-UK%R;7JG~=GG?+LEjzI{DG=!OD=wx&pK?~p(JBF$v%2gLEa{TvQFCNWy-WJZ^CxoV($zaqvYCFeg~ff^$Y1RWSpX~o0%-y6XL?E4=qBi^u>U~>hap>4QO?A4oou4L$7(-kot2l zt2YjyU0I$?<+Tzj?q>Ad=QK>(e~B+VQHc{48N-KF3iNG26^X}fq&>6miyo<-L-)GD zRJLLO>8+T-Cw)Swm~t2!?-fAIv2hf6)S9$!qUh@Ic<6cV3&r2{X!-SC&Qxdzs}26m z_rEF2OMR$?`p?I>_!l{_V98ZZ<9I$B74*3-^|w3rIQinCm6NcX3&0`LEwH72Ifb44 zgG;v0!SLW5JdYNyDof9cf8S2cA3|2Z7GJNDI$_re!bY%kE;@J!=rOTi_mh>-rrUS6;rdtOnMLcJ>n)by(rh$U+oZ=HmM5 zJNSwJ#E$pA!VjC&;r@Gqr$t*a#p|ueTR0mEw^g`Lau65f;|8}}ufe#oe(0OI9;$1v z(B^)loQu96!MZo+om8Knqw`~?Q*en5Tpw17N>l5^FM`+6M?-&fyZ;ngMg-Q)sZ^m0 zNl9FDzf0)$WjC8FXTiSw_8~5`f(0`Z=O4~%VNu>$Ruz5xmsr3Xq(U&ULJ{=B|%k!bU~Ou`?m%&`>QwHw{KIGhIm-eJB>&6Kmnf zC@)Uka~8(JKe+xn3!Z&i#ojDQ$I@ZPneN1QSbVPn+=N6V_w6`7ntc{``y(rjaN=x! zN};UYb6{T+;E8=UO%&yD>6wMhr}Y5zc<)B{Lyde`f);gbmq6~A9(`D#OYC-scx6{T zI4mi^ZLI+qJVzN`&qxuE3lW;8^WN|+^A7R4oHXeu_V7Qi*}w{yWL|5eh*a$L>Ea7( z-cv%7JTFb5+>mPV`{*B{75!rQe{NCKe(??6AKlD3Pi}*M+dgrrx@mZP_YR77eFeew z`|<6%95(K42I~#cW}l)ZsaWO=|MYq?I;K0~xpmGgDL@|TS4Y+v={w=|D0#tpx0r7+ z4FkEzboM160^WaTB=T3K+GUsFu;pdg>a+xtCl3M9iJKx9*8o^H<{Nuo?2nH5)+}+0 zJUzVh4oe>mAe-t)IwRj!m$(p6a=R)!`)eil%-;f2l?~yWnlr00^k0{%>G`k*&8!@gx1YqA1@6JMiS0jtk3g{p6_JK4t(UR*2MDVH~vv^ zm=fC)V@o*??t|;h0H~QVgc5K1gY?ud98Eh4Pj_#17f$#L0yuA~1*tZ$ywyENV_sN)b zq6kd(`tjTD%h3OXRM}d4M6UiXNY#G@m{k5dd-cDil>Q4+^`GDSKO;-GWwjLK{xf)` zFClyx|HqTne>_?IZ;&ec|9e2H-+w`>{>QccI}&C8|0fbPxkv>!2!&j$TuTaby2N`+ zj^JK(=kRCp%~*^7ZNP4Sc*e)GWh?q&)r4&Lk!_1N z;1WL~CJ$C`;&4}XA$Eo5@b5fi*yYMSn8OLj)%oG<;*%77e~f<5i+H+_N&MNt=iQ%$a+!X7{tZPo<=Gv?uy&AM>dY)H z4~WPr3%y&FpmUYLJ-k=J)(`tjxvfLVF<}qhOc1dTf+&8@;dCtVkRZMpVW{mu7Gf>U z5<Yim!pP zi!PKgn!&uxLinH(Nb0LcVr;u5ywShFO-vN3|Gs1C#6Vs4xa%@o{EG+wjpf{`5@i-# z{0bF3bI8-zh8avF9Cp70GIDsd+JBhxV+1#jt|r?uVhBG_A_giY<3MRvJPTazNgt=) z=iA25V3)HuF*bKM>^~UJB9tqz)_EvZ09Kh)l6j3R?`>ZNX7seflKlHTVarwEco%A7-PK$1MI^Pc5E0 z`n7s-T7ob(He(wS1GwpfJGjxAR{X&HOKob(9D zD1t>?8qEIe*u||_n+)a?ZJ5iA0etTKA{dN<__IWw2Ab`H`D2yY_^JC~(JRD(I}|DY zZaJ*JeuJ;Nl?zR-)7bTS0sw9CA#m6q2acNUB9($e{0FPm81iuu*Lpq&jc?uKS0@;- zFN2B&Sj{Y!c5WKWO-x6nOHypK-8;NLCl&3^YEYt#2}lgng3FEd=(qymLW(PS?EMJw zxwuyi}p<9j8g}) zjwN~Ue#}nl-!KBsvxm^V~TW(!~p|cEClUIMG{bhHodXW0U69(eeysSi15Q}74;-x*MLPG&@2nPa0jk5P*l`{+4z}Xnw+4gx6D8iU`y9?}wxyR&QP`ier>*3StFlH>$L9;& z6PFMQ&Pf!Y`2Ji!le0L*cLP$$5H_eY9Gidc$HT>ea9gnhY}Njtp4xNBE0VB^LDDi@U&ub6;Zz(DGlmxiR18qq*EWSiVz{CCQux zE6e`umscuE(kdb0@&-Xpj&Y?c>zC12J5GJL}t}hP4%GyoRK<5GOeZ<_^!e&EYq>d7)k+P20iL z7`zaBW>oO&hppg$+0MbKPc&J*p&Cpw?$54GmVvzH@%-@cTpUt*74rUB3cglz)_T7f zg05L&R9_N4HS>U57iuu9T9F*s7LnF|bC8_L^F3plP;>q{k&DVyx;;`Dck3w9NhwK@ zSL#4g+xHMPc1EJ_pznO)?06V>atGSYR-ll}WoXd56Fmg6y5>U(TKB#YnvU;A2=D`4 z&2f}u)iJj*Z}=IAGhaR9hxos1%7aZA6NPe&0SjIl7bTXA6UpTD#BRl&-JYG#6f(Z>BuE@ zeix$BCamG39lW=6#odZi@#ZCKDpNj-r|wqZbFY*9or`t&W^D}f>6rtf&m-B1lKmpR z7aq9m^GbGo;UBD_%SejpT=uBz7&7TRi2e-3J$uTS^iN$Tnjoxt1}tNhN5^CP-raa8 zbRvu$7RZi9EMTg)oajk%9{yRf_qW(5 zF9S2PbcB^v6j>fWL$hVhiFcomq?$rUR#GyJBu&*J-GDe#|zK1_jj-L{=7fA_+5PqPCjshH}bOrwX{Ik zKI8}9SIH7hDbnNiowBF$FAnrlSCe9$YXm9bS}3v&fQK5oOuY;60xxN{=$57o+#! z`ybK#=Oqo7J%7WyL&9K}}5#4{u!;8BG{DV24vHqDoYgzLO%B+;BVaj}7zv2icRJ;?r zOgE)Lxf%F&n*}{Pb`k!Gn(%Ev{>H7YEW}7&ec3$v4@=qHdBfUTm}D zvx2MflfeX_R4)h%`Uaw<29T_zPCYXcF*W%szq=xly$tTevIR1Zp9&76ZFCk}Qy}zO zj-0}|9M9%9_FTeIcW*=f)3fl|a4Q@>u>xj_4|CV+e6VTCaeCD_ne2i!xCNg&VC0xc zHd+{`OzAEr_u&WeyzNAGXLA@8c&Naq&l}!dmyVkc@S@9d7?#4F0|%t<=Q1Y zNYlU^J~%6|(5a?;_S$dUrn-ID&%ZxpLoR*9lB|5N%FnTFs#1>*EuW<|JBDsjJzwY&ke)99~Ibd^$E0Y zmnXMmUoHeHBxB*MdvL387K;|1IbUCC1`Bf)@u1q@xS%)$U2Ys1*BhGwFGblfrS2k* z+}psZ)j#J{b8m~LtiFc!ufHSi{tn9$4&aMcQ*5~%%NArh@*z5ZP*!?89!($4=I;sO z7i!+diqA&O!QLL8PW>ou&Du`BQZ^*vbC4zuKFIBo5xm>WIxt~?0^224pm#y$SbXz3 zJQDh`JoJv#d_6Q1`vsSa_i7Fo@9OhsQjF(VC%n;`Ln4i2nwqGM|31{9g>obu z*gOPXE+$gip>mqm7leX22Lt{Mr`+>H+0sL;So?MuwYKK~Q?WwN>Pc*S*f98W--g}0 zE{$9LRM?sQOZY23mtmQ?6H2A{(SYkYkaO(>N+*uMr6qg0+o5alVZ&c6eYJ@V5yXLZ z;Ze-Ctphv58z3s>APi3Uzy%zTVTH9GG$xE^z4goSg{m~`nBhc=yUY0Pws-N9#xicl zligIKHl5Y)TS`Z=-~s2sT=@Nb zhONNi1}1Fz@H%)|cS-cUZ6vd~EyS2+cvF1IYhLN)X>3h25V{O9Af`u#`99r;3DN6B zy-b%h8Y(#-9|`__vvC#Rt)RdxZPGJ0xF>GehWLmVQ z7l(p2V7p?3m}WDeO}KvGcs4 zAl^8}*S;yk8|SjQ^g18NeBH)}+iH{Ccqw$fY|M`A?!l~?pP|7}me|}3@qoWqaZiLT zJbdYf6MxjMbkw*AvSPwqR`UxgV+pr}~z{lF>;eA_AT)N{MO0nMG&DYK&YB7$F{EW1{7QZR5U?AQTyoKD z#D14q&&!e$HHBDCymsfc?x?qFSCXdJO8oM{k#K_eLCnx%qMQsn(c}ThPEi zYux^ zRD^d+o{AS02wm`|@=SAfEE-+f2<~m}u+=P{+uo#wsk>a!PWKe4xqs$+J7hrNVmu$R zLkdd-q1|E&G0fBG!4amjsAz|nUmjeE+6Q+*$8ULVVNfu=T7DQqtgInqtt{EA_F%88 zG%97y!(}1?6^U96IlDxR`*$AFzs7@QTpI=r?cxnr#L|ULZMZQsS{xKR(P5g07q@zC zA+FQ7%R%*9=wGOX{Z9PA<9051v8NUFK0CAXm)GK@tSHf#_ctMQ?G?yqxrhpbM0C7j z7`y4~gSGRVX?1f3j@EgI50?pR-+}V%q;h}QF!MYP2`gkPCluqa?m~Y1u0=pYM&h%- z{z4D4471&o#zI!w@j=Uc*t0C*c~Mf6Su{w{dLtt~%>2SNl?G2E7{b`EE@3Q|nc@HXeyRDxSqbwW?P96Puw z1+;%&#}PAl7;!reS>fVlPs#%%? zlhXazQ*vRSgYFB+j5G{7I0psTQ-wstke0RVltK{M zC8mPGg>KlVQz@Q@wfwK1%P>NGj3s85K%uA^{-`n7u9Rla{w@Lu1#Mvk62>_!$`VEF_2n!j z3~{}yGjFM^MyWG~v6vlq@#V#_q#*SJ#vM~)$rjeIF>{3QJY@j(FUq+%PaF2?f>3DS zV@87y%Tj`ZH?7+?7x82;&X5=dKf|?I>4{tTd*e**`anUtE1^%WM)PTA(i5B#9LtYR z4CD?+2$QMHAGr2E{l|%Cn=v;5Ob5ET6uE?L?=-EW~39XFzHW{?FNu*Dn~9&Ran1qFZP;rfLc%ke{pIl4eZ{DsgqXH z!G&_9b#xlWU8~2ZS1(iap2^g9?FL+Q97bavb@7QRLhp%dDOTYGN?T$JW|G-#eRC%$ zUtknG>pRc71d+^Nj*d|u)z1rnm7;l|R(%ue4}`F*nuqAwk_qg5tSdLd$DDS35zc*yN)LMECtt)f+J3DGMiu#cMu-GXA1_B2DN{+Mv`>6g2-NX7t{+f%4Zk1aEBr$qwLYg@N9=4N#B}5cuI~0 z&l#7pd>|X369c+#^VpYhsr=vv2I)(kF=~CVLiQ;+s5vcX8 zgv)jJ{&u%<2FtfI2W@xG{)8q@EttuClLs-JT`EXXmQ$$O z2WX$q$h_h^j=M4oCneklldn^G`Afp8cELw{b=#kLL#ukIT_M+ws4$vI^0;7g|2rU z9s2)WiUGUEib9u3k=EsT;>aEE@!sZdkfr=Yte4bZ)akSy#;h7gar0il)VoEvW4$sN z8ouU+%NWp`qr+iK-vHKWIGi^-8v(9k;<2{>R2n>OAdalmr@5DQl2eH@badLo)c4YC z$e-JIS#B_n zE=pm@mxbcz7AeBa^9-)Dvth^bYd8z1?R50E6B%7-6;S*PLA9_77oKgR$`pCf+ab@I zuC=knZ&$(d<6$&9=R15C5>ZLu#-CCcio>S`vPbSSS(r-#oSa!K9$&r)(&s(qBhM;O zyTT{@^R+*7)96q3QhA)x$iuKNTLoG}e{h8>-ob-J#JGun;8@Ih+RaB}TFXn^Xnlwq zH~$KMY*9Fs6;Fn?FPm7s!CP8&bpVA~MPTcGRjz!?0oas7oVxT8`1|(&ymkMFwm!S~ z)t?{YPObr7EY9UpZaTBtS|0lZ$@#rSBVfBEM-FYR+;o=7hQv*$7B@{w{pyJ)f5?#k zP%EaRUB_2#UWADnfv8n2=2G>Kvpd4M&gI${v_Clv2W#Ae;-Fom|Na}a559(V$69cZ z{W6?-CL8=zXJB*5GJ5hy=tqjKc00%m(FQ$P2eC_UpIoI9w=d@8qcV+JL$5*Kym zGer{ruKx%>Bsa0e&0(NkmH;yzIpTk_0bpFYxW5VXVx2p%CZK#=)bcnQuxde*3UZ=Gv+9X^&a<&{@d9eov-e1C}#Ad;hs0>KbmKTrS zB0(|pU2%<9H2UF8@SGAW$#l!hajeEBzVh!j(s=k&q>$RiAKrQ#f6Htk3olUpv-8w2>?O=RV@pYU1nk~kn-zbQV4}ON_@mnwT1mj2m3sJfmgOLo@53sV zn21-8u!3D0xj5m*XnOiymbm%GRQ7}Tola&fZN3tniweM7&+=eX^he%sPa|AXSW43B z@3^j>Qoil$0dAFW4Hz8P1hZbv!TPf!Y5nJ6U_EpM9loND*~y0?%FUFeEH%Y~sawEG zdK=ukoQ9KOD{Xvl4GWDTc%Lt-Yz}>Z;W7mz@hOBaKi0^lo?S(6Z#~4{saH|SU6Nid z>g5#UbD%iij!AwrWHTK$k;Re^c(z>@S8R~Mra?FOjiIODQ`{r){~(Wn7R#Xe&RuSF z=qT~PZ4ILIf0CrA)Q+;#6R_!`HB{eIgGs)(VUO7t@vTvZxr*7^%qDy`y?$1Seo}kL zq$3vdCUxW1$oqIGMFsVq+rmjB8`}9R4kGj(!GfL9Sa8gVGtXPfSFbQ8X8aQ_dB1=w z7t`6zNNX6VGKb&pu0>4}A9<5JJ4}x);s3tLfzNUFbUdvZt~z+$r_*?$?qo@eTUyS^-4*uS50 z>fA{G-~<+TDFZY_d&%NmA>EvjN+)y1lGvb^^AmcV+h6S#zxwP=vhoTP{Uu%K&)x!X zBnxKuSg_4QtKh`YFxZuz$3^73F|Xx$Y~_k0oQv0Rwk!BPp1qU=TP_S`4PSoY5gSkT zhjU!XGkv4T^Vl*`IAC^rTLMN;1V<#nD&dN69**7Nx`;J==mU zPP1U0x)+NRoj~g|$N3w(4&d(D;ao~y4DT5b!4*|nuvt5D>6iCAhrx&U(3}31SUmqI z8Xq>KPw`&d><3>V;G7<<8#Mwt-+#coTSXX>;tx)TchSi+qcDBvJPITshPWh+nKnl_ znB`sK=EmMgSdN=rzH!IoRX*C!s2p@y@&O^PG(Y(+0ktE89LQ~CJJhfhk73TUY{PW885|_pA>kj@)btK!E7$)?*-a*^pF8qHWQN2w{^g3%SDQ9e;tnRNk zAg+WTGW$15oD631^;2s<&$q0NNPLH~b%k_jnkwB3)M49%3Ibi(^E9=4HJSw}{O@Wg z!23__*`XURA;fzy ziws*qFXz6+S;FRLneJz7tqg{Y3R_ZN(~JJ{iR|?L-@Nrg8+5)ioPt%KVc&Us<|n_D z25b%MyL)POCzK8G#) zDfryA-*F!u<(S7%LwYWm$QIS4vOYaS7Gb*+f^T~OR<`m@j~hVufj1hbF<9y`no2*l ziT}h8V2+Na!sD)(W80izvrx&<^3s~FPO^eElQP9xY!vWy&uWfMp35#63fuV`{m4Qb z1P{D?sym!?aoXZq7_ul8cCKp{kB$l_Ydw9uU+n_Y`M0p}Sv*LL$|eu>a^7X~OYyyd za+EDMk%`8~Q{c@dbl8of*v$v2>dBzmZwt#YaNrpJnBKF2uIUz|vspGat=!G!1g{3EbwgNF z&1~8zsNee{HDToNNqlXJGfObnVjG_vL#?k)a8)vl!WYg2Zy_K&`ut(6P+AUS7mcL) zxNumnf1WgjX~r-6WC|@Ah{nM#uvoPb?~gtJ!!!;vr2*Roy=XitlujX0-ge4yodXUB zUh@qLJXpciD_Hncg(j@46T;|A1WmFd+gNf9x}6N+MvD^7n*R^pc1Vy*>BiV z@wjGu7&Z(KrB5QiSxu1L+{%s9GH3gBby?ZBjrcHyyfXKxdP9Un&<7o5i}o^Ck$t~m}4_Yf*v9N9WI6H-~x-(gg* zG@MAc!+m!Xz+p@|?^^93g!+Di!`(90kUI+0ENZyI_SNJW-G!<*LfO*DaB$QXo-#h> zVuhh0yDd@02EY-4_5!HVYUcTHIkvD&@UjS!g|nv)vKQ*TuPw;YCEUnG!BQm1@f=n?Z&=wGjVhEcRoQnncRdx?K_bb8@T%f_*AL0vp$>o zZCnIN56#i)EM61E~Aw0J>?mgZ1WR@UPR0(NFFY9)GzU(;BSd+9+Fk z5vjn=kNyZ|enoIC<{K_A{(|j!<&?L7A)nhV%< zhI6Po%70aFhoUW`aCx*9#Xh--&esRB7~wtaC*_W%r>C=-+-F|5?=ol}k{0=nxh`^( zVuC`Sv0tN;d5z8H^ifZdyQeUMbw!0^(|!>v+t!TE9-2&jbrsq_K7o%HhJoGBJouth zgT1%vFi1WJGsoPAM_*>)!OB~p=W+-(9=^rR`ZW>tT8^M>_8z?PJp{)^7zuKTMM5p> zMo1lVgio;B&cw$)at%kKnZ?WoG@EHeg)h#b@A^8vGk#o6>sN1wTm5TbXx;;^yCZ~7 zs{b0V;Pw`uOU3aSuVit@#nV`1;Le8>siA$fB}^|HiX&I3lVwNpq?-(10IitML)+fQMQ_I0fEdK~Wh#m?&%xe(htAzPoe! zFQwU;PirvN^)RSJ$I<4eCQPRO4hH7*g0@pGy#9Rw+*13%d9fb*{b&U0xC!E)K~~_C zvyrY^&4-=&t&n{n1-CiIL)d&>I%=?m0`9G%*)@6SdvpmkPdrav=f~2Z872JSneOy+ zah^9u9J6jnoCUTBS!z7 zLcs;A$i6ZgZeJDxvwZv;mTPH532pTQJts)e}U7u3ge;}LH! z+VU>~-{el$d2fD`eCZfoj!4it9*0|BPse)#34+o-*Cm zm_l0*YBB8)59+o)2bU*nvIVN~v?To$o;y~}+en*(;x<$2c)c0ICEeM@IY;2wYhKWw3ni~-F%y)cMW61{*3vN)nO_aL!V^*Li#E~cAUmdi)r_{MkB1ATKluZHFXP^C zU*QLs5SH7qw0L2{9)6H!>{uyOupDEf=$>6B)4Sw#N!D}gw zmvzlcD*HtPd31nzEVuE`U%fm;^=7JWr097yYZ7;>;f;8~gwn?P*J{p>(E(;ZV`QWfGiLL9chUCen%z69$NKXImoJH(@BS5yiaRZu>}O6hlB@aDzD)A=T)=`d+VFuH(2xcPLFf8v|i^p%C!uC@gFii+WtH zVzK2^CjTcHjUvXON0lFJie>a?p&_%;y3bqXn9}=TX|UTr5U>7PODpTwqjqtg==*ss z)@kR){>><+)W&$~wN9bNe>~3PMcm`F!J?5WUFS#Ten-o@pQ~>+%aE3$D_+c~pquK| zoVuw46dqEeJEy#080}_MKZ_Ym>%o5Ol<1we3On)E5cGOJW6NV{);?95yRm%{`{bw2 z9ScnZ@c|_+Z|V+EnLZ6_S5)z9-dVAib8BEYFG(chgl9g;QSj!QOvXa^+iyR|9@yxT zU;SQu=e~-I2@ZnFC6Bmws^MIZ(*f>ze6Gl0<7loY9dTz;98C}8xu5+n@$$;Df^@G2 ztqsa4Q)vWV@;iWQr9KN(R0OUXIu0C;52Ha6a#$Ls&Ta+nqDRG}1vz+me%bd}OU3NXV^hYb_ zy}Un*-I@cB)NO&Aehs^PJjhhik%YkdZ?#*ah9)Bj{+ z?v+2-_}mMm9Lw2stx))6X@J27_t@9aw>b3r1L!fi!M>%ALzl2qbn);FP|RA(`psR3 z(-bmc&e|z>&OU_oSItG~&{A?d<3eMNj#Gz%CZ*-i00(U?Mga?`ov(+(_fzR@iWr<1 zS<}GWT8w(MnC_QOW_NzaLiEcp)?VX6Pn*xM*5AX}?e;LXN>!OEYL1e)`U{@Z_|0oX zJ>@1|dLiCj7=cQYN)htL(8%*O(3LcpdOcq8O$Usj+oA)0Tj-J9$W+!bIg9J3@4;5y ze-DYPb>P(oU$zPNvXZGg`2F?ySeZ|t+N(;6UV3ohYZ8;1d5+dE)uF%7!7^<)R99gMHxEzF^E%&}PH>9pFA~8%X_j zPryjoC|b8z1pI?CF102dik9wSWnWj*K8HedcRs^TefWqQb^pNAuGN^6RfBr}q-nj@ z9+q!$0o5jkF#FC#*gSU%*?w_h@&0?c&3R>%ae1Za?hP@l*LhDp5<E*tiZ3O3tOKa|Lj7yCgwzFU*e<0-N<| z;IrZbjA`h>?YckFa`bqtZ`*~xEW9Aw`4<;IWjQk()1TRTI54$IWh^^Dpc-5dHu;PZ zD&z&p;=)Tpcp9;@>@vCJ)Z_Opv)Oc|SboMAFQ#u(xZfw8PR?D85Rga{A4{?c zw2gv_?U4me#0M{$S@EF#bhIszll?8lhQ+5)ZBjHO)n3A*BNm{fqELzZ;V7?C+sanF zsKK8*F2bmmQ^-5W4wOe`Y)}(g&PWCx9>~z@XzGd{PCm8 zpB`YO@&Gzc2kM(%0#0yy?7kClz+lNrn^G(hCV~;hq}AbGebUZAd8> zbH|T;ZFMFo%tpI?LN&*{9lYMk{UrHVhI@Q(IHIqmApcQBT>~4+vl1!`8^+SN$Tr?C z&KgElXi~Rf6*R|KbJv9JmD)}hcD*2&25L2v+l`0(Na+sr2{5K%t2EiiP*1kP$(kv5 z9B1$UUg7Lhw=!G#dCb&iCn)XN$d2R>W}QdMs3b77W=d5XbLc6-v;9n%W~3$fe_c!I znN{@KLY=H6MHCz<(B-;m%KIepdt$-#7dxS) zWH#CLMX(JmEwJpPyyN$SmTXjbGWTh&Hfeh8z&hV;JU&upca92jnd~suZBxakyURNI z<99gsLkgTn39^ykVtAQzf@UknVA_K5bU3Xa)ZTT)j#)=|>9M2v^MyjP$+r$KhXjJD z$^&kdRy=<1e#U1RBtxb^db|qh15Uptm%H?}0NDN^^!Bm`ZSh~m>U#cQOI0My$W(&tTL)<9 z5uqkfS*X*s<|r@Q2oD^QrKa$OXl^`#yY_am$XhcOS%e;TYiN_R@l?tv41>E#U3dWn zG0>|E@MUx&EVt`~^9~izUAvz8H>ZpK>4%}o;YNtL5Qr@W1e{TWNyy7ZOIZ_OO+U2~Un&=t~?TpQbB|}^LqBJ#_hxvRJgr?*uuO+ir4ire2a-5kPja^HJl2T=hX!%@k@bpaPUbM&I!iQ?4B`*QPrWit7 zk38#8N?5YBOJt&J|b~oL*E83>4 zP6f!NbTUr1Da8X^BNJb!7dRQ!@0Y=~+vaqsawh9H>k!jAS`SK+R%H62 z4282GoiF-`77nK{T09yq-A=&Jv(fC|&f{dh?GM_HnZ*{DO-0+r40_Ns&mp<~Ys72T z-{sRA9^i1p9`3Bc4qDnzW5 zfxqoMmyezB2!Ez;>O_QBhm2bV<{qvyoGkoOXT+H!1P*9bQDL>oV5kuB6ryF?nMi)fq4 zTWU!7hk|LJ$+R40NxDt2Z0Q2d!$lfLHjPF3b6@aqaEDk<=03h`+dy(Et~hV&DO#d0 z{0-k70dK=l>YDlyM+u};oABA0n6jHwl^RE~Q*T4xtDk&DX+CG>e;Pa`UyXNh(13~s zXF1!dVQhSOIJH7Kg5p33OYOuuE)EuWI`UcBVYuf)GIN=^jipH}MfV9qSaYp1lQL9? z>*+JexzCoewj{9R^HZ3Nj19yd-h)M#?y+f0UqgLm5VMZn0Jq9?SnbtxxNdx$RapR^ zH|rU896U<{+qxiO>{k{zHi^P8i%r$r$#ly);B?Yvx^<%x3)Ks0-=PTfs#`(5(<6ng zjG|*y;Rsmh#nGR|QuN@QKipJ#!_8dhLto{(xHtXF*|kP*_Sg3!Sgex4gyeM)ni0ur z_D6xjvk1~Jzm8=(m7t(D7xqLNF`MB}@L{toO|06@`xvCt&1-u^lUj|Kns+lF-BpPJ zt8@5)B`Mfpu^7jd@!Vp`bZYU`XD2sb=6;D&=&jX#T+tvFE~6*dh#96-x1$k)GiTA- z741ytjS{uZ-`1!RM@4v9;$DfK~`6fo} z)#yS@k{bY}He=WiNpG(5&OG+VUy&8<@Q3FX*O}+6KnPxLfjZ4QSTnlN@>WfH9iYz5 z`OqK#UJ~fEjvD-OS%sbcQ-w*H`^o2Q1bKg+LEDG=qHX35>Q{UYdQK(@bHpHsaC;7( zKbA88yb8`_k0U!T5GtnUfZ8Rdu)sb^mNVIvD({>_+c$-Lj{Qx3OWGH)&9&dWvbQd) z4t$BK2b5UIve_)WZ#SR(N1L-MU*bP5l0$12g-% zu?JeexHImtu%a`Di`yzglig%kk}&hH8S?^dF16r-7o9M1(LY=!EyZ3GW#hp83iKj= zH)f_iQhhBb*!nkW(h;B zXhM`P9e0=nfjRfMVDWPFpW4JN*jS4Z>)QCj8+{l*{3Zk!+=M~OfjGidL>vF!z&ZSM z+!`@}xty!cP|T>G(1HRxpO`c^rbzrtik*+6B1GAc!qJm4iB8 zG?`@W1pdjlO!OIdn!ETij?&zAv#U><*`}K>Vc`@JY`LMy-Zx+5r;HN>!h2k6mK>T( z=7|&e1OAz8_eVF@Klg*^%)!raM3Bz!&3+GZb*`*?o(U@xk7he!hk##@HTJjDVMYBq zxD#Q*zEz_H5?z(y;pAS>-<;3S*p`R2!(~YS$zO-~Cz;rB@i{llFNq7vPU9Y}zt5{= z2+*HHQ@ou{R1`q%!{5Bp+6O4QBG1e&2hp*5H3|&0$AL#v_~DWFK-=yL zeDqdkH-h5Wy)lbnYl|x0*0E-u7vmwJScz@eA0e7ETp$@g^+S^tl8lu+hEj8X`ZfLs zT%R1ra(7>V#c$TJ?qlY-MfL_>yVD0O<|&*TmW6?qUbJS{NE%-%>1cZTC%n;)gg+jJ zm|(IT?b(DdLDmi8)#Unso`CWJgk&w(x6fI;(Fc!E%s+L}T5bCgKq`9A15JBs~j zm!+kB&qcq2 zd}$octt`fp8;QK<%}G=n`Wiig9$}N35sdRIV4F0IVG9$IVz&;m(Dm9F;IbND#%(8u zY!9Ij;|%v*t_N<+5N1m4dmt)7NSO;?J=lDY$f;uy_;!n+XodpybhLrkXa_5n(t+87 ze)6H;CFtARboRvM7ls=whMlWSDEhc8D|vngAKX%*C0r$3weezkcMLF{XZXQtDmy%T zH#cpP3DpeB#+=+fwAK-GWx}j>tDitzT+w2d6VpX<`m52-)EQ_&9Zv6PK+}LVL`KGR z{A9K`M%^2Ar{;s)*Ic|OT&v`iia|Q~G97hWN!>NY=re2s_c%$0rnf}n%`k0Js>y>y z`A7U5Z*yL<8~9zJI;`!37v64(!AZ*FY41CKlG1Mj%?l$iNl5Gk{`d*66Bn^9r0=g%r*fg@J5?mNDBT@qo85cLbxq8tmS@(cG&C>+t)DEOFETUw&QVF;WZ< zfc!u+nya-HFkOP~$&?V8_QSO`Q<&V^4AF4i^UTY@h*uLxy7`;sV91uKkh8&nSq|r@ z>5))1IkO(CmL&+u4IS3BH-pz~O(l4)14-H0Tt{yV*ROmha~t`Ai_ui1VNMlz&OeDp zZ7Rp7<4kymSvNuTvL89C&!Vg$M{sk-R8|#q26RgplYMEzrl)A2(&bi|YhlF(#nt1T z#8P?cvicfZwm8fQz5C2*)|D}A z$WsNTD(vk;o5yk!*T-<)`9~ngaW>UFli>f^zP%soMcW{tVG)cP5`|k zIro)CAc}g1uP!g(PuYFsg7)>W^{Z9sx3WCD6TASY+nvGta>>jv^ED`KyhwqL3bc2n zI}EJ~q@AC#DXhkqvi79W=IGz>{o7~UJM9R0k1e5#cdD^vq7SfYd~UZQsw zD{$`x-<+dd;?O$KsToB9A+pS4`dl_Q<_v@>^gz@CYdrDcEW_lZxc^Ky|M++{Jl`(C ziqtN`@*feb&cg}M+9{ITCSP#zX@j-XN0a)({WNObW1*CzKxBNmh)(S66ixU$kj+|o zincDDLXOpme7lqwTjE#4cB^)N$=C6y?qtfUeT7ih7Rl{<;z&8UMZJWcM7gmaO}(O5&Vi3d9XM%j%7I{p~rkXuA9@P zyVv_u&Y=!I$Z01Ha8IL;v-ZNh^^zDB`2mh-M6=?XvnfVZfm%k41hXeV&wmZWJ8uec zKT`rv?tIN@?Kw<2Sc5XAzhYnaXTurV460@)apjh4d{cQW-qo4Rs})}rDuOqOCb(_j z72cKN+0ForsQw9Rjf!m5t2FSI%ps?n=FC$sn!IkV6qX#=eXpa) zvHfa)e95QKpoREHDo|YYHvPY3Rkr_^tm;1iCbj?Kul^gQ^dGXS|Kn@_6OH=+C9AUk ze*#hi|3g;wf4Df}v`GDk7vCDS8P96O!l|XN@Sk28 zEIOEnjr#|XRPHoVbRsl}osEn21G!nXIo!^eX1@LUQBE;B61FUz!YXzRVx1GeLdK6C zZfubN=pHd+x{(W!XBHHAHyj(k`LSt}PE&-X8qQLB&*26UL<9_i6qzNMrMDk4C#Hj6 z^ap%WZ_1YUQ=scR)tTH6j)LcS;Cr9<{0y@soL?(+og}V=V|xolcS?VAxz1DA$QA?k z>epB_(ykXj$y0?QgN10St%x&{C$WQ5AF{F;73}xEIvi4Qg;}`DI+iOLvyx$nOk03a zSw#%qGA!Yqd{<_XcP!Ymxyo>*6kvW|Ci5R12a%prVeiap^s>`IS+Ss|?HxsN%jt(pKy#gopxU<1WRoU;trEJ2dDpA(sCwyo74LJLK41lK` zAu|xHZ(zko%t@${=CzqJ?9U>TgPR1e_uZ`9@od0j1a=v=^oT*{RD%fr6J*# zw9uPD_+dPcU!>Al+UtixAT)@ETTkVe+`fbtI#-eQ(;xhUl76guQ8agRMZ5SNdBTmk z{aM9)D^bO3L#ltZ4Rtzw*|`uS3R#y$o8B5x`TH5rzFdwPKCPzOU~LwiahmNd5JVX= z1F5i5jy;_;A5(_!lDT`7$#%eeQE4`#^agS0He^JT2|?y zLVyG7FL8n&FWj1UG={UTZ~K6*$_pUyKTK4J#c`58c>F;KpY6MwS@)fx`-8OD;P!Qx z9B~0Nf5p(?ihttWQ~%+i;ey1h=`>yowxyKve-2Cby0iO&2i2pp6b=mHxsKVHEa9#q ze_uC?<>(ZPJ63jyj^tIrGFeaRc2G{l= z)NpPHRlb}IGmFAeQ$vbk7S%yt{I36vv^W39I(qwdjiC&g%2>!$h6W-&>s+FVLZyjD zB_*0mrOB+w7)7a2k_rhGu5~WbNP`A6sZ^p=nl;z{Jo~%v`*rWQ z`1mD=z9-Q#@8^VbCyizuy4rNiM|C*fW(o@%1ec0i%{0wn8eQADk^Y=|fkb_g#=Qr| zk}p$6kvn78gL;ipd=bI@`pd)Dp1yRjSrl#CuF9nb{uYWZz5uoNu5^AyA=lp{ zIvTq}*{fBR)uAaF^omp&GfRGg$s2#O9H$ntsX(58+o+6BvIBXvw^&LHI}Q3$N%ZD7 z&WC7D;c~y@c$w2~9&A>DU3MAtcUJ_$FQwQ+T()F0WZYoay5igE& z9zop5rNWZ7a^8CLkMr0wYV>3NF8(iL1uB(`WkmCGN&bt~{NlvXQ0bdMl^r}KDaS>x z+gP!9Iq(@UuUnwN1GtsfBz`<+Fn!^y!A;|S36(PYs8j4{uH&~B2SrQ3`%yFdez^x{ zq|~#jM{eTBwiO-U-M$j31azjx5P10iDzv111-#-ru2IXuTy-4VQGonT0x!8uWqP5an_W2 z!5-Gy+lYtBY^JdqsxY}7;nIC$KEC)mOPwiCPqwBp%~%fix)k}OK4tXik`1UOGFQt+ z2H0AvtM(yuK!!;daMO2MkT@? zBWIdv5x`H+)<=8zhV0i=5dbooyS#mh(T)31<>dhWOm7M6jQ8h8oA+T4dquWajmPds z^60beH2f0u==8H*=$v(d$<;(dm$EOce#v~JPz=Kb{=}nv!VnZLIKlm_hOMMIH zl!IxWLm%1|rwRA2kHQmi1|aVe1gFFL(zDYXX-aDfJlZ!H-{(((ca7)i7heTFt#Ba5 z->hYoZ=1-zmsQ{wdy!6%jO7D+l@dXOfR#jeu)=UFoV(*N`*v3xoo?$-ZC~BQ{mFx9 zcE4GC^Z6=#{4Sq8x99{1n`3;nvKJVSJS@mLFC?=(#sb<~Q^}fvP`~b~^W5U)+_1J8 z6HXKhy;%-^9%jrPzUou2tES}m(^QOH+`_jFQR6G&5SCW0hN`8;pndca3d77Ha7PzZ zk4=E|3Tu3GVIp~8^_l$1y9EiWkPGfv3w+Jk+XQy?fhy+OD`3WcI~^ z)nzv^H?71R?H-`MLct{eBGHyfeHUGln^C63foDb)R^J_%M2|0( z=W5z7*d?olbam)3I!`QXZHf2eU*+|9UV|O2-5LxpSS6Gx`e9~;5#G*w3wYd^hd3ug z(Ec2JCOW?2gyqm{`gyX!M2;^xy^`n88cbcz_vLUWn;e{=$Xf%p^V~`4xI?Bt9o*x^ z`p-+|`zpGV}y>(LbAbI*p4@Go^ea9+eiFW_G9w*@hF@l8ORRYy@x+; zWso#e1Nuef7urmG2O$UlfT?yepEYGY?OL7*p6#A|bKP+!?b(B68sBlcw-QZSdIGPW z*o`A3ieM`q@WuFftS{>7~p1C|tE^95zBu@PP06RhmMt_H<>{Em4}=dc)snE2Gx>gTeQUC1qWHe(Nv{`*Mesj` z^v{-eU{b9?jhSl#6jMJ8oW) z3Pkz|Hr}kpv~59XcG8OOoVJ7yz21j!-qZkJhbO|ZP$y8+(#1u8D{%6m9^qf#xv(|b z)p_#kIGkg;6f%11$pT!83cdQU9s0l69#eUI99=_y$3A?FQs696^d_$gT z?Z>#TuQ0HA7gZay8SCRUAUmoRJ}G#!zG9^HU!^sPnx_eaA9RrRwY_QdrVki(X*6jT zoyCsPN1&g=Kv=&Wad}h;2)LFWopI%ELbYL#tj~NHEcL_wMJ)Lg_ zHF`BG4aRBTXV14p(gkgXbU^KCGVbXloHSAzhFd=Z^I5%VwOwyM;`JGm_fHz9#ZD>cv^0 z-PIVb{`e$HJzEOnU(6wKnKwzkb}j#-y_NJieGtnQ%>i|_rLanECeChMipGDW`NF_B zn!Pi`q@R*C3wz7P;V7Sv1$`(&&MTv zlbt{Np!kIKjM+~m2czkJ)v36vb}j$AYB4?Vwh?{=IA6^bWa~FbEKm*raegHxX5-@r4aymP?7d416u8Ea-yA3Ul9trNo*%R6iIidZI!uIQk3Y{JN=dMw zJrkEj)RHqlhVsX0C)n|~n_#ZuTs)AQi-M{FPc|QmljXH>yjX!5;I@mbD$+%5A8BeO z0%~-sq_~3Ia;9>San*4-SSNT=^-nV)sLU6Zs~Dl-mp`~`douO*M7!+XGQ41!Ljs8yCvz-(Sxt1 z{m?o6DBTle0Xw5F@|71h(E*M7=*aK-qL(;@6up<@9xgAd4fO`_uW|qh(Fa{BvXeT4L&V4flHs#Vzr?!+3A_u)Uvl4>@3ir(mR9r&mUvCr06neKCPopk>+rR zdvWuDJNU2aR9d6G95dY((cXuhuwQMLq(CZ^%19hZXNBmPzo_ z`GD}Ucn0+Ia>tBws{H8IefWF#Xu9-f8T(f_hMV4-#9O)r*eqKQn(i?q)iaTcoM%2L zN(+{B%Tpf(4s*M4|;pu7FiPbMfbM z2ocxTffzP;O>zwZv@Y;-cLIB$(U3onpfLB&+1MuY#@=Zw+%li2m}3QW8tL-)yk z!ac6yy6@;Jo;#)jR&8lQ>FwvC-!{VKH;zJI<77Bi-a*EUIWKsN{_u1$@^JstIeucR z13Jd`g(Fj|sdnr|IDGdq-dJPEeO!LS**7=1;9G5lFw&{Q4^e3z;4{>W%Bi?9}hB@!k;eMANHMLnxO%?5_MsOxh+gFX2ZyR{%+0%5c z?jDdzbm6~liGJvhJFr^U2UOF{VZd3HnzU)dVEiNz;`MF>|E1fG*@MOiifZ0GE=pE( z59?#>w!a|AU80Y!HSs_tbIN<<=(T9zSDrRvW7rlNR`pgAWfqAS6z+gUNHLkP!=4^J z^$KR0So1Zn%bAN(6mFB*sqO|TrufBm6C3T z=!|%Dcp=TzC&sb}>zzDyl^A=^QK%Umwv`8cT+X+OYx4IG%xL|%@pS7CZ}R-m4RqdR z1zP(SQr2*dnok>16%**ns-_z9^vWeveflnpwH5f)NAmP-Yai$mAw)jQM?%YfLmK;j z4SOBXshE0fBFBv1ROg(nEk=VgvOlJEq-n7b-7q^9hUUe98k~V^CJu{)UJq7cf zeCfnaMSkqnZ0b;IOdma6MRx?PM48za@x${wRMxdiQnSoPGUA6WzA$&d>N^SW?c_CF z(L4ngdcGk6he~J{ZAJcaGJV)bmXF-pf|`L#;EhZNPK%mBgWXEeIq4dF^qz=&v%_)G zjj=qpVFXcb_T@H(Q|W~sV|-xgOO>5JiE*(EeFx)g>Kc9;qwG+r_gvEAPV8^_EmE&PoVBrAiMi&EgKi9-cIM2yeJM zfy?<`z%N5%iO)t?eq4mc&eHLK^0m()MzI+898hJ_g%zB48DpQg@%-w}dh8yT$X*$l z<4ONI%9OI;pY9lNta89hPSYU8Pm@~rNyY6?L|5U3L%8L>9^ExW$)#b_9(sC%G@q)J zjbrR;;dq}%xM_F}8tPlpPwT4Lr^jPxz-qy^P3K;ENxb`w++7KRdoLc=Bh7d941$9{ zU5L9lZ_PT`LqaPbv2knMq3C!dCR$yB^?`$Uzx&=a-BXMMt;m(gW-5|=6FZt0a1#~8 zTFLs4`H+3{4zoDw!N;sQEXpwMNlGjIAkx`|K0R<1uQ(R+OA&*peR5y=V&Fl#zdjBw zRo;h-1EuI~e;t0`!IWk`j-wtctFU*V2Vd4zNH0Gup?2^Ly+-z>lF3K;S=EOyeU1g+ zp4eVpwQDRf2r$6e%_78X_kB38kcxP!3StHyLl0s=Bdj#Iop6-Th!5bKIY;fAYJA5z zhO+juA~em1rcLA+E=GD?qU8Csg|8rDnhUw{Hi!7NNAS!WUOfJ4IkyTnz`1QAtn|%8 z=Yj{${Iy;z%o(r1dm0~r&3rxj<=9Z_XcCRdVailFu@85Cw}r>`E`|%UPm%R0k#yy@ zuh@0E36D84Ft;nCe-_2#lwSj}WPt^Br9;IU#BWUPdkqU+f@m#7qixwqJmr@oIr!w1 zWa_*SUUGCH-7)SG+RdFz=XP-F{xgV|Z@2}6TpZ}Lum&`;^u_1Wb)ft}oj#5Bqi(ID zfQ5@rGAn61c+)-_qcQ;ARY#L+UP>6yU5t~?U5CnEz38%(@>G2YK zj4G8Q2W{W8(fcmo#)-(=!GzpwS%s;QHC0>e?dd!9Pi%;`3k^t)f%=uEe0uBw!M}1M zwqBXaZ!P>t68uJRxx!TPk|@?>G_}F*%5!{@_!=<2>CRQBYU9x4!|`PX^ z%I32JKU7aKe+r*IM6(%lj&SCq#;!UgVZxb0c(!5)1{TaBV@^K8f}&k`bmTT@iQR*e zz(dUFs{wCJZHKnQS@^_|97m*FP}leM>*Ht1rYm_J>V0>eoiT%v+#re+RmEPk@Bv6EL{36|}b{L7#{U z)c2YV2mIVgRX`i+hlYyhfeG|zoCLRSl7q15L!2?$L(_aWj)yKl%i1(lQg}c@ zeqO~a*LSq=)Hm=_a)H(-w%GMO3%>sz#;<4_(CfR@=!#Qb;8A=9YV3C4tZ7F`kJWbW zwC5uxewa-x0%hQW(g580UIfg?#qntUkE~}%J6eA@3YWUa@e#cuxYe)EVy)1acI*s; z0h5=}f|}{L>#r0oePM+-JP$Jp+|g81ga32b$K9&ssbQ})zO!{MH_cJTsV#MQ{m&Wh z3N295N15N8`<&E^(EPziKH@z2SUTE9pUZ8rrW0M)QKe=S|CdUvT=gSeU$UR-D-9w4 zP7a`jeePkTj+oeeEl*7xHz7Xw$nIY>CWE@fNcAcmnm~?`=j#=5ww)ebRN{@siwn_y z@fuEp<2m~^8~^Qz;WryJ_{1YaVcw__^nJS-@4saPS8z1vi#9B9YE!O;#sL|0z>-qv z8NZzyk1XPfR~32O-at5a72$-eJU<>ANj>Hikn$z{Sw%q^+%Q`}-~Zl=6H;nPQP^~@ zsrHyF7>wh;Uz+f^jwjS#_=1}+p62y2TA=Ck5!d8=W1&Yz(tDmFMBlauvkdKdQlkO4 zEtpNOb=YFSyXW|p3=`u@OK8C4i)gm>3=1#Nq7TEGAe$cmm)U2rE+q;g#5w6CnPqxMpRsg#+IdK?)n$sx9YkfxM#U!EHB9q#-ZLYrD7oH?)K zu^(%2LSPv`_`;eeicZT(#zXkGQx526=E~O=IHIPzc$b}fnJhj7Y+(OwII?auAMtk! zC>IXqkL}d?_B$eA{8AJ$Uy7`l!Yo6R7>H;a*JOUi2DA4HE`6xvO zi*=AxHlkXb4;TM-ZWkkxhg=r3NAK=HXt+F`a?>6&6OHH;w|;z5#U*k6u7IpZbPSt~ z;-ii(0L$&+G-%Ig?*6V74cygXN?GmN`k9s!G5elnBwBP2hrP$Wi4t5Wn>4?C=v~6o|THc{YBeuW5FWE;x?_)0g zbjcXk&WnMc;@(kbdK|>BaRgi0W0G-aSJO2IDSD_)re*R$v`*dwDp&5t1t*hmanlR3 za!WOO*=vZdW*zG5w;A7`p8)ZP%Gk4fF-G=6hadd3jOm^+hGB-SEG1r*>|ZFNWBgb0 z2+@0N(>ROP6(-a1p3=B}bP=SEuYzlX+L&s!Dl>%HwAYLh*uP2xj7;v}60?E4c*cuV6z`23su`3eWCb#|1+qxLrJV%193YQ-ehM zZcqcvU$6_mh|dw@=`*-$q!yjpOOI-euM@sa(WxoXOoeg1^sv!xIjY?H0}3a^Xtw@+ zJYU#{Uz@8#a&AvY2Qy__Yf_IIp7OwDPoh(?EnlTq&n&$a=!U)dJU1+p%@dt|56)R) z+WFmZP0fO@n)a0}|B^~Sb-R=MVTZBuzAg_=bLHV@vgq5r)2PNPHNIlR7cBg1jTWWh zc=xs$U6g!?8taOCmE{I(&ay1t;TjJH+1bqgjTA55bb$^x(uY3BZsV4JQ~4Z&P#o(0 zU9kEwnkv++X2pj?P`~5@be7DZyQ4mVa!(4k6NOnh?INaO$R$bN``IiyEP)D1<7odM z-{IG~JNUw;jBLE00#EbXNx^SUEV`S~*U`P0lRhqe`1}_~_>e#!X#JWagsift2`S%zBeUm&k)Z>gn>>nl z$7S>Xf>n+9Z&=lT5>cA}A4sSF4om%y{L+75RsZ*+{8w1&{|KwH`+vi#*kBNx+I9-JSoh)2$7*8d zvl3(vhLbq@8(!ySZBcs@?(`-a2B`^8)xTosMPe_CfcH%gldN5Rr;siDQiW zvGj9+aCf9Bmnn(Ibt_^aWJonuO`n2WXH}AYp$7&3@?6OU%}8R~-psr|YvZ$qDEvGw z4dnIHCGkcDr04834BTKtN9oPRYoA{esnv&Z&f;_A>V|>zbB-}4`>3-+3rEr?OC4aa zB!Ox5E`%75K9JkbmIbK}W~-hpz>Ir~1fANSU||%A+JDj{+6vFa(`YKHwk*I{=~MVr z>I(BVO2x9H>tOW$xgZzw0Q>d+#zxy5XCu`A!P!qT{IA_D`0inXd1oH6n1SC}Z1o7J zjNU9Mp5VZ?#V;d0Z})@FV;_mlxHppZj?I!iw@wL{i&C)PFjanKy(N4N8;l>{?qlC4 zc!7Io8~!PONu(WyVO+KX%_)@+MDpHl;tSPhNT{BW?fwQa zZB5m*>%C-oy#iAm@sv&cT8f_&&XEbf67h#y3j8fjfbzg5;-6h7IeSqBr?GX;#C9R^ zEd#P>N(!1^I?rYgD8%pI9x4}sIl()_2IE0`)fS3A!ii)kJU+5H8P(Dw2)W|c~a z)A}Oj8k{5++up*@7vdOqjxyCt>kFqA_lC@_A!s@^iApCrJxnh@A1`GX_oF2i|QM!0Iv5`39$1)D$00&l*DW}#gWeIo$YlWt+5l2~Fs zp@b=?VuXyT)3N;2Z=%{w@z1&S5^1gk@KYjaB03YSGX5R&b&GVtxH#tA%!QPDp-><+o8B+(PviIQGjlX)N!)S zVXQg58L|xnFlc--yLDg2+3DU;p?KC677#u$D|wTiI-#xUVql4BN!keFjiW$I%)~TTx%2i}!Q!Mf1&i`73kugh zk&spWVg1S@L`ljO@;?uUPghGx=zu~9)lOj2_qAcg;3gEFJgbUye*}lCoCMiJH`wv% z%UNwijx!(UAgGkdu(n1&R;K)%<&GH#o#H2;a#0a{RrF&+wwZwUB^S7=xD;}GcQQp0 z8Z-RNWA?)lG;WFN!ux}rhZ!Kgq@(i%hN*QNp z_>iCt;%h3>()r=Af6QauD6}4~z~nR?Va(Oz5?8kjcK^CLs5!`Tb@9x*u&x!C?ye?3 z-*yQ~+cZ#OU&>TYrb^z0-x2D2Tf+T=y}@abK%T1(#PHVdlEV6_OlM{^oBaJd>5ly+ zto&dDtB1ZOx!(1{1MSUhUhm21|KT$kE-ecZUpHZLNv9;Rav#oEFamS?takpRoK0rt z8j?Y!s^B5Bl8s)e46;LqVc=fzR{XV<(KVW6VX_HKiSU$k_bp%wG{Jdei3k?ku|T+~ zzl#XVPdg9G_Yn#{CQ81EK&s)>Zb^;=Z-6GVW7YFE45@bZF=MF*4M}jUIc)OM0^76G zg(W?HSP-rYdne76lsV0W_<&4|h#3GL|N3*=W>Yxry%@C&ro)uNi>&b83HUt=LF&>@ zX0u~1Y=f0>-h2o76g>uW*D1lpPYNvdvm$K#bb%VV)okv1qn&HR_N9OA5 z%GW##W%p$?*t3H5WZT#4xX61bt7x>w;Kv^1o@qCGJSz!E zV{KUJxP@iMB#?0pBJO$4Mxu7YlGNwS#37DB%;fP0*7~BAyu7a{S>+%PA-O%I?)Fya zzvAa$U7jWW>}qnh&8kGNra|P&-eeY&F_y@B8bin`8AvIOCB5gUK)$b-&Nz9WJW^E_ z_Wqhl>c&oj`p7}}y!T?b<*fzk&Potx9Z4?Q>VrqiUecPKg{pNi_~Xqcj6C)c-)En} zG{qz6xONt#`=krs3sP9y1AXebbrJ8tQ218(4y7W#O1hL3vDw5FkM&q#fUp&UHf#o~ zo8#CmB`x?~AI1967&!7FS{N+V!PZ$s2t5Iz#Ie>0?{!QiYE+Y`DNi8E25Ib>>OatX zCXM|n(^>!Cb1;0}28_671*gTN@>ne$R5}*{&pJL<2Wm*j;iD&nhvNkFmUe-M?*o|L z+Y`8^xer|&G5{~0S^?XWEU-gV_ne+O77Sz}$$ZT)QdBa7MYcWw{l(Q7743uJL9gNa z&;TqEamxk^-0@u6TNdE_-1)$tY3yQ#7E_UVz)qY`VRL-?fUWyX@G>dGDA@v>d#MvX z%BtWd&?RZ#t)O`C6PQ23m6SNo#ZRgFBnMzDac-% zT0Oh(V@AZ2{ul2vl9lNq8jv zb!Q!V{GI}{&KzM^Wi(m)kl)1k+KM_Fmeg!GklSNl>40>nfniAr6z+|gM&Bo_Yu2m zZ-gqt@$i1iGv*U+gi)V!iHdCzNm<%KE_;Zo?t4S%_>=PZ+jkVVwe^7U|MakO{zg1w z9E;h(*|>6)0VAviht_EF;^)zVrOZ%vqUSkV;CTRvTpTW%WXAJ;MX>1ddSnYN(bjc2 zoISXW4O%@HM|@8Qv*0|OJah>*_FN#ls)ESpwTIZb#CVvycqtr+)P^Uy+tBv*7<_Mj z0LN;cV6)bKa1IJ7VZJg`;b!t@oRU@s8&tNzQneHmmaSvgHtk^v{a!n-6H^mba+6S9 zrXO{F_5sFj?8hn(>Jse*y~HG3I(u8!A7kSeV{NbvdH&6U*L3Fc=R{3 zTVjV_oad1<{nH`!ZXf1$q`&a}#AN4;NO60NboEiQKtlZ}ysl3EIt@@KGKO*qtU}@+`63-#CYT?ZY zF;O?5x%#-fA_>@LBr;KFLi?O7a>HO7CS18ne$Lb8l>tC&_@;x>M-G zk7KfUmeqUqN_eXzgF&U+apGWKCa3tD$u;J}rDOvUh!`nMeY1{y-#-*?J4_b78(HIO z{aP$v+D=T;rE&MYr6lc(3v5qoCW|EMuq4(9;hO^lRVb0=YB^-X^=-`V!e_GMMj<=X zOmNhdRx&lVO6atSV-Kc1#v3i4;KQYK=dekqnO}P}q^PA~<`*rD*{w;+oA*J@)_7s< z(KD<;+6FBD$b)h6T5Rs6#7{XMVhT+XB2`s|YC(Fq?%o)pUv(ACqgIiRRdLX4eik!4 z({Ntji$wWGCNaC*ySmII5YLIW;fJc*aYJe{x$m%FGH35$P}ivxUc@S}1I!K+OVw$_ zZ7F=8b{$q9UrFrD7GcfgozN|9h-*KjlT(|EiFbt!xGlUTl~u_~`zQZ}dwxcExmcCc z&Hai0=u`+AX~-njmN>#q3njimu&z3fsg2ab=;1le{#q*d<}8x$%Tz$fU&_31T4LdB z5lH)C6dW$qBH!KRup!g}?8p4YF=ItI$fv%jGy!jI;_m06J*AXQ8&VBav^EGx~)sTM+SuEN4O&>RvloGra4sHqO z$)%3*?9sHnXnS1)?`$rREc}{74kkVjd`bxn+LsI+qDBYhQyKP8#TIp6Sdp45CY7u) z>+uB0s>~#^a~Bd(v<{UIwV0pI8+1QsPw;Gm^Vkwy$h`B5yz6BJXV)8IolF?%xHONo z)@@>4%hJdk6(;$;E=PFrdNR!Y846cok294e{uno@0`JealH_}4vYvh)S*QF$*1hAN z(3)!@c_){FJ3dvwtb9XUu{lpzq&J6sj7r1-rN*Swa~=D2@T3UZP5?7e*_RySiz;e) z%yRBkHlaR~%nI2HUdw{ni^4{sNqRkoSkEKVa%G|UxGkPsF_&ytP9lDywqZ!H6SR-K zPX0wC;NFn_p!RC1r2V`vd6OA}g-gmM%R?Vv?p9k;RbS0Ymu9iD9rwtcT}NQAM-rbu*%w|FYQk*S z0g!MQnZms!7&9^(w~MbgsqyaEz2Sqyi1xce4u$ z)$s78KYKA^4|y6dgu0Ua^nV zS6m@s!W~vJ+lJk^6$?_;qu?t))0|`gk0!l*`ik)JU9Up9t<6+2rETvEVt=gLHrCU~7l| zV5R-tgg2|^NFKl2jfUQLs(W|7Wd;id^1U@S!q7?`80@nMBoogHwL!0$-g!g(m43Lo z>PR^mRW(cUsxpCPWO=fx!<{HUO4KVaiG+#+>KyeG3F@MZ>!&Z=&ArhMGw~gwtl{SmhyeqP{ijyrX!(wlyIQGA*QGV%ujSzr&LyrWoSD z*v~NN%MMg1PbNWM`eRl5W%5_wS@1gS#k93-;7MRB`{mlr4%W|*EPj*#sxJw=ym_no zmvKCF=1#!4d1kO9$p>$^-zMMs{FJm@cc8=8W|498!tks3TARNA9gce53x}sCV_951 z_|6?Z&=+zq1Yr>&Ee=~aNuPg$CGa|d?Z+=P7_{jd!)Ik4`%sZmu&XE zN4WTW3=Vb0(_3Wl>#%Wf(d!92r?3^QV)C%FE=?GfvlVZUMpCqCIS5g4K>JN2QW3{7 z^Ord(D~@N|+f3P#QRBsPnya(&01<4rb{V-JyaVSrJrq-usS>9VYUD!TaZ>Ot6FzDL zz~;tCHn!;vGuz+_o@Kc#0QL)~BZrWfw?435Ot;7!{RCF&VQl82(`<4>lz4vhf}{^K zDi_GOmYeNy?rskuD|b67oEa!7ST_-)Ya3a5Uq@!KK$_UM|0W}2 zJjn3%m&w-Kx-4kY(y3cwTnFk zwO?VPIgh+eInIQ?yYSN!Pdr!kUE;Acon5GHu3o$Uh@f-!3VAIt6w=S3q+s$%CR-*i z6b*=FzZ(N2%P$nd=~=GqzQahkaCIeE{XGs*xw$}ogb51lAR8H5Nv_Na0CYeP#$U*NlkkOanCU9D{+`3gq$Rb{Mv2K0es-g8bN=jtl#4#rkwn zmM43v`q6YRoKRIH(e+Uz6J2+ZHS!T;|MSII`7(m6eBa4pw5Fr+CLc6TZ~$pH@oxBa z6fZuWNy#ql9R{=iYcJYZaE|(S_@(%8}R(jd3fg4 z58=QqZA@7Mu&ehGzzcRlxK1{RsH7b-Cre}b{){%kimNSYdIgaIpFF)cF_ zLbjM={VRX+@}Rs3wsm9!yUxOz(LdN5FHPoLAK|<<_9;FYHda(vFUFuh@7cL4?r=gY z9K(BSvhAB3u|W1K7`e!iYL6D^->HZ{3df;z{t@&M+Y>pLs&Jy`MRHF%76+_tku2Dd z2E8tn@q^76te^6Ka&&={EMIq)Uz$8>W)ERbPYuC#|1Ff4^1(JS zRo%u;G20uebnP`?7BX!!3*KT$|5gTJexWY*Hc`eGRvQUfZi7bkm)OGRovbftz~VYz zJQqbEe}*>wvg$n^lE-9d9~}B zB+6Y(B?VSN-kLD-cfmd8m=lWGE5cagb4_v9Hkk$LaVQAcfU%`VSiiFxOk2hk^vqoG z?)Qg46Wj!$Dg#rbEU>{M5sE!hps&my=jn$Yvje02u|+zLNzL8OCTcH4*Y%yKO7`IO z;x%|9ej%3madAdyhiiIg;T2IN@biT&Ts81T|F_4T{f3&5tJUpfb$T{C5Saw~_8rFf zymatbrH!GnBhl^haGc!n4x=nAiOoDk81**_zp9ElSwn)|j~z*Y`a`xc?I+9ql7)J< z8Su`;o`|eMGRtB&o20S_D%-jw-Tel_GRIDd>E=>QzwX2g-!67uee$8hNK0%o&V`0XzP*T^=Rj4#Ihodj_nOxcgOxbVf@RJmAagZv5Lyf`!Y+@#cx>1Y$>VD&&Y#>=oQrJY$)+)?INmc0A9h*6 z2ERDs_&owMPNzZn(}D2pm<@ZlB$-KF?`Eq@zk)T>4 ztRJHa<^wme-am>ZL%kE7`Y3-P<||gg-;=SJY`TVh9kqoW{(D0N7EOnA@44VJp%-^f zy#W5%{#Z431pc-DOPcyzXJ=MyB^wSsC(CpqVf=7wSftd2Qq_at&X&pI9V`jb76CLFaN|S_>-rcZdDt}r55G|+&0)TzCH|T) z{KkIrO82Y8L&$U1(?}Cm)cgU*H%b8W1JJKQ3df9bhV|(uB%Zl7Z1njE*cWU;_W%2Y zJvHOt@w`0zb@(m2y>=3wd2GQV4uz0~t7D1R`WdWdhz5yMkcIxnH`t0}1BJrt!(jBe zzQoru38(H2fKzK95{nvX()Y+AGSo$cKN-bgSJQ1W^>YbqyXpiQ%dFsx_hC@}@`puS zwt}A?StL({n|kHyw}R+3Ns^AgBE0L^0H!RaYUVdeWAW2;Nxz@UkZTqI zuH*Vc+ih{iG^T_ETsZ>I`gxPR_istM=AU5kk?U}&r8bO7S%YWh>?HDHI%2~&d$#yq zBs^UCo-GYD!Gyj|ps6();!BQ6)O38<8|CX{eA-?1P4Ot}s0OH?fkb<)@n3Y-1+P?ZW$(5;VQ0N`_f#c!GwGux&|MWq-Y+Q-c9v$hBrqhkh4{8_6 zM#SLM=rB=z=7Utz%_(lga|{&2k_io&>_ZU4mGuSeQdd6qP8C)1BEWO~2uF0Pn+jxT z1)2Ow7L3+*cMz0)0Cv2I zMR@8X0$C$*!}&9~N$DlNBNCXmQ5|yk8sodlWw2n0sI7mcL*53M!8wHoO!wLl_#Ki- zzPYQRWPvodGJ8k1%_%^Q(3j-Ot5HCDJ(nn`O`~lSrwbR)$l%@)Ya!zAK};EajV)PT zOUjPh3W^Uk*tuKpB^%QoFkc;iw&FrJIkGJqLuI}3&;Lc*nMd^$h5cUhprnyzNkt(d z^gGY~C8E(RLK8xnz4#${EZZ-_J=TQ(MGoBV4fhbx@}jGIG;tG8ct4r(jX!G zy+Pr11rFc#7WbNHk*FPJY@_2GHY;~KixR5q4-Ht!#@d*&Hd!4On?9e@(>euTq-JC9 zx;pN#og9~ZOAWe(GfG{d5XNuE3A`o0lC-^_%`QtWlD+qMp;~+><3!1DW6Ukws3sJz z80d?Z%zXmC)oe-fS_7K2a+YLp=OJ?7NE37|&tm0sEZE}OV7M{aUz{;s8g?iIligdz zsBz~$+2~pWi=!8?`ESnWBu}fDndBK&E&Ch_jB&`7Z+AG{0Cu#oE)+X+tq73__JQ_A>ox^Ue z@ocj4ex|l|DyzPvOjHdYbKm0X*jbelk?gw|V&+#3_qhSDr2@uID-mY_=F2mc>tC;9%+#U zIdMaZxyGEp?lcv$rlo<~lT$9qt588h>1Ck6`I41w9wdtU3Gth9i0*fx4tswKPTr|Y zD(>GUT!sw`GU$gPYg(D6|5)}}-IU2Vm9mx{ie#c;9eb>~6b~xDXVnk=NyD>Q_^QE@ zUCyLz>cC!HoWGA%RO|=sk>eQjC`+7)F_T@{PJ*3Q@u_2F{HGeFY4mz zrDjo+TgfPUvIzA@KeQ{-R%elyN5Gex72rCgjc)!hlRFx86IMv~(e(YXFz#&!9h>u1 zbj0}q_oH(ayih8@QH6)mL)H+LQ^RqR^&Cm!Ssm`z@k@|nevkM;Xd<7Sczfrb5S{%kb%i z2U+&R0T0@#F?-cssD1Mnm6Gn`L3agm`>ql-^qhs8?cQ^z2A9#~uQzb#o<%5SsluFY z+=FVPWx#1FuzdR*k$L|q;NaZB{vc_Z#Byg=u`555FsoVPcLH`p9qZIs7XgwoxwEOjqqE+7b9EykyFl_@xcB7 zZsDlO5N7U;r2}5k?K&q!^x8@D!ZqNy%&79y}umN4>ahvK5&%znLUErbq zR75fl;fa5WIJ;jWc4j}cyI5OfcPwrl*I>=DRNJ-iJYoSPc@M*phcZM#@!@cF<|LZk z9>BgRAZE~e+>`7Tm^sY@Dz1HjPg}0wu@Qp>)a?O>k!7&oT?Bc02f*cJ680sXg$fH( z6kkrmoo<8BsZbs}>jyz&b|yWy(}&{*_|U5sMzsG`6}Yx@H{Mx46;3YJndG!14)?Gf z_{t{?GwvONl~&L2qF52Rj_YVCIYU{9J04k=fR)InLB$7UZi(J2Sp94cSt5TKr>Az( z{6}{1%=I{aDR}{Z=iTG3+X6_;TFZZ zLc-c={IISD-yG`U$j3g~r#u$Qcb9Sx&-0)lpl6${!eCKjBpp64)$YPvDG2#E3qQLJ zMlTmfurZTI&w)cOj%v7vJN}9R(<3Bn)}`C|9eP0LBtL>(IdfQ}N+G^JFo2!y*#lC> zI`rc%ZC04Pl&hVyg1$TC3;D(eaK#W$+S|AgU6%~U6xD28xV}F#>y;-5)2@I<{8~`H zbsI#|uejs3f5Fjn6IPAr&qi(Wz%z%#Sqw3e zxmaj-o!b;~k4hih#Sw)-+Pq~B*SYlvcV(|B8=^H6iqFbIYx5Bl(bxZdWXcWf+yaS4 z2jOP05{8HMXP=ugX~XY_D8KR|c<;02ZmrJ7{{4*cq0>N4G3qFMtiPxwyGt9HnLo>HkQ2$?k)bL`Xq^(zzWbcfo@wW#PKS4NAQ}mLX zF29T|FB#1$3~eY2I)!uM^x$i(GMYVd13RtrC^vZ|^nck=rKo+J#x*2^QDq!wua!*e z7uG?wc`XLKR6(LKP9i&U61Qr%2c4p(1mnh^fPa5ZKuG;1$@+fj7n1dL@OfD-hCU6# zrp)1RrSCl#)6U^+&l?cCY(2*hmZI?ue*TQH_g$e$emdd4E%Ec2W7Q^axDKaDNfoSHaOWczc z8nD&kKA7vLLHPX~JTX52-Kv$y{nkD4c%nLZ&@0#33(jF>d~LYRLDMyL*>DIsP7Z+1A5q%4q(U0_>UM38q~qaeuQfJC|I?X(y^MX+wQD)qF;@ zC}RXxsrqB@gCd&hMZwH;G?Z4i;S#G|@QI#*CxsXB$ldQ)DQk`n7H>E?(N`4Z?Gn(c zda}7^fyDoPDY_PS;gh|I7&tE-RVs>L^Ns6h^SKAEpIk3;s%wJ`^#X45!Wfn~p$;{- z2^zqv%iMf*J*s13M3br|sAaz#wCb+npQq&*SGp8@u^dwaR>N-lA&h$3)4;?L=sG!q zJC|pOT2owL{c&>lfQ7D)*k&I}42{YV=l0^c(HM`mwbY6HvMQ$p( zY@fldX~tmM7CF*6-&%C0=LdJ($OaCnRUmu+9F}DH!N~kBk*AvmiRqCNX?}^Krj2eA zzxc^e)z<0d_q3OJ$}D<9Ou}+?K8+c=O&5|ETixWNL~qa@S0{sxcWV2Un5W6(%ULKL-o5Ofkr2J>t7T zIAu>0?caF`LmsB#cb_=8Y3hjMEzWTJy@kNrz-P4g(-Ewx9|*C+adYRwewe)b9<=_> z=F<0W!(l;stj50+t4D3)?gpgMN%s_C+hCq5?Y~dg&SW&&?>L$j4PiU;Wth>)XWV4j z-+&c;+{ThuE_rm1+w&|IuARvR*8|#AVT&SpXmc3ey9`E)L-wpzOkq~&OI&Ow z#-01#aGxa8vHN5+x1e_fX!pN@N~Q;Gq4%1JdeeZ6`FWG z(+6x%-G}F6Bk0Qem1#vgN2!m=mKF}?Z)Af-#eYz+&SA&Xg;Gx!{>8hGCACO zyA-V1Fc+4wsTiSh0L{uZnW(>ns*HaOzoqSQr^+Y5)ypWq;0T?^k7tRwOC|ZoG&nR4 z$MRl13_l8FBFrVl|y~xNjIN*%|=*$2H@ord+r@q85iwFOsBQ5}u#V8JOT? zEh=x&Wct1nP^-98RQ>uRwmGEG-(}t03>hi%VDTQX`O^%0<2K-YuQM?JexGDT%U6kh zZ;Pa5s2tv0R>Rfom1F)-CIRG*Cr7UFxT|wH@CPcP@^(7-URwaq?(Ksiwx%pGMvD|I z@IiTbXWYBH8SG!j(bFx))b=u?e>!F0pTjsTd|f74*%L(Hj~Ilx&epIeutc=X{c2Uk znSEH~G8GNCBtT`VHal^_0DZZYWc>2I0JX2MSHT4}?IWu)Oq_`8;jh$pawwZLb^!Bp zAIKK>f57P!&xIWWhoY*dJM5i0i*B5A2(=A`Be93k^qSo$d173d8J(OnOWF=i^qt*1gNQ>BvF)$h1EGriKX61CO-NB zkBcY3AZ;I%JClrt+bqfUI&+j>$X88NY!;n)KZQ-67y^%c79hMm0+y~LxifAfVMT*1 zOZc*d(6i^%zcPR8hInwi0KbqZq#{0wTV} zbMJ#G^1|4*t=_PGu-vz$aFB}y!NQ9fC9JOxb9pQ|*913d#NbeWTmMX58e?}<4~kD@|A z`7D?6!wkWFyr|54ZMUHJ zlu)`y{|uD(#Yl2fg=hQF_f%`ha!jwjfHy?DIOPCYl%flvXwNzHclQ$Q)B6B=YY)<<{pRnS2t+MM2d{I~@ic? z;i2%SRs{=poP<}$V(F}RgYjLRtz^;D6ufE@&Hap56OPZ`(#!>?xQ2;gV7NmK*3TXR zmn;;a_q7(&RzC*`sVN+pF$z^WXG3=xAiwvuS=S$qj&*2Id&e~1*xJh6b| zx{GK(Z(nA1z6Z2R*z{Pj>a0@my&|jhojJ)29Blih^bM889d3r0{@=XPa zmVioW&1RKhs?0$<0b1IePB&rt)f9w*Hfyj7kWu zzmq1>E})e%`tAJnmQKG3V?~9YQaTrA9JuU#JNtYWXS_Xl4N5V#O3#yn8&cj4py{k+z~>|1Z$-@hC|??8>BuKEqdnbkuB#I;n9hXVQ@;IdktF zWWys%*rt$*=dJhR8J9kIzHvUc>C7s!phtxiuIx`!4XP*U1f4|vvy?`~&O(QG9TGc5 zHKA)<6V3I*xTEriV8;p#mgn!wJ&`ZNoGpLQVwMbkjE%;-nqtwHcM5p&)MvW|CgJqY z#nCW$%r!~3jt!~QQzW+&e~V6R(1x??wQ--zF*HfK46pb~TJ~xj*xo#h#m=^5(K<~s zY+WM$ZnuGTwo#y8T?>4E3gD01m^1wf3!I)0o7}Hp`&LuQFkB7qzmCDMuG#p-M!@yw zIdPT_D{!`xyPajT##H1=+B$L{yohB_i>Bh;F`7E5d(ER9&=o>ZcRK63|xW!B?b_|8{q36 z7d%#Mis>=mxaVDm*oF86kams{gfl6e^_Ib?G3_w4%1_12_yt^ElYmd%aEJ0?525MX z7&1KQEY7T5fm3(6W0H;zm!Id$)_#qL@)TFl)Y8Z8BZbD>vv%y$;t`UA?xj$PqhW9Q ze#y#*8It2ejp6Z<7#UM zV&yiK){oL74;zng%@4EDb+)ii(pt-QH!HE^HV4?EBY|t?b&@-cKR{n!m4r7Cs2@6w zj$amuUk}`Y>l?m+%pPe_4voaF>8YIhdMz-D{4OzEzY(+7$l-(Tn{f5zAnbQE9yqsy zFsCM#JC+~CIpqz2CGP5En5YEzE;)?h)QyC1_CxZ>k}T|yWy(gj+&1rKX#F#W%{O?5 z{A&xe%`fFTEDXuo)g?4izX+`#C*u0kA@sTZ3~c=*2y*0WvG8Sk)t}*`SlYC2lBwcc zs-!Q>QCFXXJ(vL72YX6#;VI6L43eg5xnBky|8xGw;y_LH7 zIakC6*{4EyStZO1Ifx%e{NWZYmu7lZZ@~4#ZAwz|U{~5ttTD)>#Ipkqz4!@JR;5Fc zUMSJL_zOmyb70rUmSDhxads`*&nY)P5Y9~>$IKNPxoexPaGzQR85EyQ54f9v^nyl6 zb(t(Gto4!1+F%K5hUnt^?_S_-yA`?zREs9)N`RS7g* z*Ws(=q3nISz@Z!~bycXEp%c8#Q^n&gXW+`yV9Qxsg(F0{T3RH0`^J zi*F6$%rtFjmfj?cb#8`NPp@)CGUGV?5LJ>9+5!D%RKPod1$Or;z=J(U!29M#ZfRPW zJ^ zSflc;RS=s+aenC$>}R%>EVmp9U7zmI?b;Dk`PUJAYRFd*Ce!^Ss9mn*W#H9jVWKcs7k)oz+W=O|6KLk3J|53dN=0 z?m?fVlUq8eg0|NdkhPzM6HtFSb0 zc^v*_5IetW2WznSVW-|=C0aFn0W8md%)OAhVK?u@6m)iUhjdxXDtAr=rvFVuW0yR5 zF6#+9RnMYZP7SrF=*MDQXArFom9+1|1klu5fjg-mk(k?K^OQhnGaH5m=0o9<)g7++ z+9)(nc?z01Y|`jvb9Qj$H>xX=#XUBY*!K9LG(5)za}Q)-iklAU&CQ0;OlvOZ<#4jj zc_FaTrC`~=6vU0MCH*}Q;p==aa(&2J+B3ZjrU}!Pss(aPdxkdF`AuT+CfcwtS_zKM zIS2cO$8mw1!=ZS}6)-=&81}9!u1cIH!50YxdR|&_>S}{9u4fF+toz879*9NjSV-_b1yG+;Goh-;a#@`0y9jgN>CG1T#luiw8B5>v^do9&Yq2RZ4Ue1G;D@q6?r!01?z6C$y7=cN z)@{AOnXfV88uC(zS5~bkpim8RmlLXas!3$~S_XZC214{Y9~u#HiVpYQO$(2jK#M{N z?C=ys*>iQ^?U^s!mz1q|-l6~_>Mig~NUz9q{#qOsSBleHuiJ&%=YZXhC=AXSK%&OJ z<8B-@p)rGui0DWh?7#Swqd&%z(BQ3f;i;pX``oFRHNuM)$eskYB?O+@)^i7&Lg4#G z2G$2;NZ0WrSlDGLs14MK#oa@6Z15=TzI+(QCs}gzcM~=z48%y=3G_hfS`0p2$_;sK zA;Qujf=v6A=&G;*g4cc5Syyr_@EwCNK>_TRP>hrLyxHc2Rrcp1U< zeUZb?JX3Hqv!U;vTQZN#DZ;%pV76l#j6GNa{ug|)TJtftByJW{j8;LfRWh(UdK$;s z9Y({zCG5oBg`jjX9^xlRgJD=ME?}^*izGn7<+m zy!|f zr!9na6rf|L9D0j%=*7~@P^5K9z^64?;UqQub4is=o!kn{t5xEc`5XobVpX;11w>Kq z3HP#a8cYnjf?cZ5xEJ;|XgA_B8XL=zW%3Ca);OHiyV%2sFNoWYe+9KQ9@tOywZvHA z30i(F!`p`+KwiUX?#z^Y>XCUuB!y+LVon$LXR9*X^ZhYO2PKgAW*4cHTMe!|J)cy~ zNJZzR1F*+Ohjo0ME9{}&AX4@Xd>?)uXRaxS&lh!=^(s4V($XI8bS}rP^p{43srMj! z+ELnnTpU^qGUE1|U98et{++W>RbV&DKUK}8GHgpj1Xdc9P&GV&F{HLvF*2TSQSOk-5a2gz7UJ zV0!;T+z?g|_li?sq>&$quX7M3POJy5@wvjfyOv9N9t2(kbK!`TH}oXUBMnJY==GE69 zOG`;4CvqXXO_#&mNMqQ1w-eg09cFiHMBvnA0^jdOqn@C{Hf_SthEuV4+wpA*ThnAM;B(9wQq$tN5FtK2?$jA1i*G{Ut{WIM#E1Uulp@P^r&G=S>g;8p zD@yz_X!nR6mSjOCeLLbZwC{XXld5x;teA{=R?v>_|N{n z_#h9)6-rULtAF9l^g2u#V!^yTc@|nSiS7TT$_AbkiL>tvW;Z^#06C`0LUb=$cNDY=6d`Wi9;Q!*I z{x@W4%K!aBS82t50sSmrg=#3P`1o$v>MLlew$0eSZlI5FzhJ2`x}yL4wNupoYQw^h9tDO5IStmS_m`^8=f zE4JGY4-$o_BkX;wK7ZN9S3G5B3;$8OhU_u8&uSbESf_UYKc>=+x%WL}?;(KC7lKbx z!#vq|_hZbn^B|sje2FzptR%0VDT*KT*@!QWZebShvY6ZXM0WdUCrj453endFh*f3G zaPSD3>M_ao;)q{pN!qEwpY4Vp^kSB0`x zZGG{afW744^bU~k%HWN+8HoR`)#F>5{K&}L5p2xPp?vH)Gt}#RLmcx=$)a=(V&!QA zHrFl0g3OYHgij}S_S4uNn8^Z;MDSt{19J3AKYnHF4zlmkc9!oEPx{pxvWF%gAcI$A zA-zxFJevVyMO(?*lnioz@IBC5luYEi53nWKS^N@H8ERygD!O~wm#9x1OWH3`B6IOF zZb;SvjU(OM$7kEv10g&!bNWyk*g1-fsj|g&>+@m!@<%Dlf$dV* zD1C=Cf~$DcI929mq6)|C?$9Z5>g<@p8&aeE7BW5U+21uKe0kAB=-lhW3I__i&nw?> zOqM!7>YXNj(?}rom2%?keTk6uFoz}{;bHLGI}oaJmxKNkWBw&R z!`h5487)s5r6NetdPDM|Hl8&P{D9iYIb?9(5_ToH2q!0~G0T+6B)!2K(z-b|$o~@E zP0vF^dm2BsFpg`vIDm9NRw9w#)ySVkHcZyhn1wi1lBtV!vDlA`?KBIr@k(3)=}4N3 z8qz9w*$6Ra@+YD{#fdLCK}e!#4{;R&;)^>XNxXO>t6gfz7u^-ehVwow<EecA)HHB)V_56!;3%p%pE}m(2j^K1Bu^3MZ?a&o`!u)6!9Z=8S zOx57)_czkl`tjnkev8P;YY$|T4-}H2 zixSwcOKEIi-2kQ*Vucg3c7VK~6TKMnhXnivHn;f;_c>e*|NU-bekwqo2_(hfpJu@ zn=G`hJ9jpS{2Z0pSc3|-uWuB+RQ(NgiXwU5{Uw~Pk|EflEsh_q#ufwwva7O6u)=+` zxT5|Xu{RgGq_oa2H=$gVJ{jFixZ|fi&gGS;zLz|fAMNKPk-;_MMclqiP`)36DP{-?&=%C zp*70lQx*p7aG*9B7}7`vdusBsFIThUyVcp<&67ympEq2(-xGTFYdv31%CYNr4osUQ z%kRDHPmIQm%>yO|{>4o(tCskzE>V*jA$3V9;i>nc&g0pwkQ z6dAZXi*V^fLE1?M96W|HN8$a~9XuS&MPymRQCrk%hX4k||F1!fD6_kd|G6wG&%OoxdhYn|znsQ#uvSEt7-2d-YgVXdZEY zyn}7d^kBSR9(B$t6KA{qg423DOnDf~s#U5<{pj7WxedAZ(K6hPsqZA3uEXgDhr7Z` z^dug3=qElf@iERaOksF+3gkMS70=LEPo62YlIz;(xFFw}D2|Ing~Mmr-4kgnW8n$R zw9FOS!1aj6yqiotT9H3pzgVbp+r{MPX@OO|hS=h17QT^A7SE2c2l+>Zq-NC$IQgIp zHtv?;bz(=;sJ|ZkH2FI)ZU0?%d(#U3c9shNEPgtf6MUSEbV& z`jdI>XCc4VL0mdd(>^+Hmc7^5Sia3GqocS2I+vAZne7~-AaY(Ll^|rlWzurcn zdUMA;AoTLUkk&sQ|?#PH@ z^yKk%O$$rns>QPc&$FIOCTyRX87!>d%Ad+{m*T%~-0(rp~zy_uE5Z z;EQ%Hub++BSmQZ2cVZL+jZjvgIzoK8E{L>xse|9_W(s$9fOGdNbjw$QixK&p*P^lP z)EigwY@|0>tB->GsPW8pod-BQ*dxwNJ`Y1~e}|eE&*{3|A@Cx}Ml5~2iMukvTKsK8 zEp9s*E0Ee1l22a)$mZ-E2>6^t)go>ZsYP87?l==Xa{r+H;NvJ7bcL?G-CvMQ-N8{; zEAaJIS8DmmgXBLOjjB53cHKfqNOHOf+WM~}vJ(%p)e3S#?V=7j-PuMjU$rGErFyum z@ec%SG$9M5Cb9gLS7B961YGxbVw?L4xPvKU$vWRk2-kLlgd}Y?A#yZ%nxaSF?#%+} z*c7JJF9!uXKJ1VxmmFO75mRj)G5Y%yGWEAIE?Tt(x6IhV_D7y387)TQ&$l08W#@g) zm>PiA0xya6%8Ts7;h)s{z&P%c{1q-_Upr*xKf^+|K_mx4`O`cH8UeBJVrmxowe%ND zw$x%N(?uY2%b8!V3T(j8t>Pk&IMMzgbS7CQM-`-ZiTKwQ~6eK!Y^A)G> zG2b;;#dBuPVMV>M;`$GVs^@OGDOOjKss2~{R8uImtJvmA;bjW5jq zKy}hDl0!C}@E+Pg!s1`BUH)qP<`H`2(y%7@H`_(rxj_y~E?2Xj#~QrhpMGM!d5L@ZKo{c6zO+e_Nv2`QaKOEunH&<59LG zWXd;)KQsd}xQDc3&1)3F{?3Eeln>}5TtGcywF0RhPM7v z;oN1OLgoowLA>%4&jqSs&$Ul@D$RpLOiyL^R~{sZNyT8kB^U#wPIDdMEs(c!9;96i zA#IPmS&pRZ`3q+k(W+9no^<4JDzB*dkwcLehKuA(B(Z@nMIGKEUwUiQyMyk zJV~m7N|zXNr!Gx2HDv;(p3cBzpFH??JfGcI6T@XFm%*WbhEz^rBa@Wy%uC{ht6p7T z%_3pqWSoVPJ>TKQb8k}QGgCBsvm(n$j${dn$7zDmAr?@rhgP~SB&d5X{x!8F`%XpS z=;c;q1(xy)`)whq-J8f|?=x&gOF7%7F^E;x{Y8WCLs?pQ7<=P2PrU0-D48rhSiF5` zCrpvtV+)JN*)w$qFmlTi53t$AH<&fDs9itAq^VqNZ}UVPwz{}_gjTz_V_GGfzD}F{ zd1_EyOOnKkhP}h=k{WT|lgG57J%zufLinB@Bl{8ei-~>kZ#db$gf)JTaIkd zXpapRmo@LgU#*sWSA`FMLAIAn9WNp~=02nOKZmpHvD)mx31Fu19#;s2tedAir?o(i zoDpP+okx0Lct9pQDXl?oJP#KKNt)^K7cu0`>{ndw%f)DyP)BALPlp51@nU^RJ1h~k zLd<1VVJf~Ap4R%4WZMy>>fuPzyRVd9YPG^1xt;9Q%`(WCHo|ddS}R{T=>jgbhl%TM+@lhfy+r+h7Q?z_%RutvX@MoR7u_h zJ9AS*Ug7=KbI6gVFX&w0j;Y%p(R0e9;N#2paDTfSv9s03b(<+YdZkEmV9qy)Fm}R2 zhwh42*B)jsuL`FQqBpeu05a)+Kd{_l4ZD3=lT80$&5YaH*u6G&<}j!M_s)EZ!TX1@ zm#w+DI;?>`9~gwkO6y6)>hoAswS~kwUL{sz?~+34G=AgnV6fb-Anp|Eo%SpZB5#r= zldxHiENQ(1ylB`<_KV-ZoXE}O<<$@5WX27u6_&!hUG~^JtvtdHFM1;GNa@d}RmfDk zB@MG*b=uB;w|P45Umj9D_qUP#DXA{;v>o1Tv8g`Eo_$9gcrOJL9b3dk4wG2@^#-su z3F1RH+Sy0oXY%!;8jHWpcm>~B{)Uz=S-MBWj;2PlH`Xh}_pgi*kFgrZ(o4P)ugQf> zeP;-H{ZSDbgo@3mDow8wPy~Bu0D7U~O84IOk^Cd_(%rDL7iWW~~$1N|B{r+-no7_Oo^Lsxo&gdG9+tP^|Zi`4> zg&=TQ;)}P6&ybCt?=b5tArDw4d0KpnOwR3sw!R#qZ(Bk1@`p^c4|iZU4?CcAWRu;z z`beT72(Ct(7(+~i0XI6e09Rk`g|gywb|G@MKnh=?TRYXUSE$ksH+sg5^`zL5@w>6? z^IT%k)y`Ur%c#ly6FBao0)IZ*hFg0&0&~_iLfAGV{*<9EmP$#)O{;a7m%axH94{rd zUU5w_r#*u$vbe}1TCzx=<9=3rc_T@*^AcN^6hhO?0;XFPNIE7h5GKS8@&#l*3{>cl_X0RQmt}G{)hb6LhA+&V8K}1frZ6b4)CNfD-tfZj! zGUqzt1^0GS6K8VP0@tWl6MYYgZ}ei>9p6~oEv$7{`gY@0?|kCbRL2faIZC!@N?^zn zfC8&P_9Nmk&Nh@~dOCzyc2sg&tDQ)>*%{Wntb=A87OG5?4l)JTGPWQ)m+-nH_+M+g z$!<9-h&y5mhX-9?Pna~4<=5eDU;4_!#lmc_a(D!@I@>HcyE%_M`jgEiJPT(evJGd_cu=g3;xwMrVA<>lBK2%F zH)_%nCfa|2{yds1+PBM)zF?YguFe^d{SCOV`j&qPoGdLG;A?R)Q%uY1DA8=GoDD4^Ct;) zDuqy|6-eF~v5%hOixNAqa`eQA>t^ByLW;2`$e7K1 zcLCcS<-~uywfUU&QskZJ9kG0JUUX|fH%SpBljC<%W@0DB!`&E+^QaOg>aW;@PA##^ ztPoIibYQh>*D$3$Tf`lYm+^M%!pO>}PU3@?WO49sO=9#(NBqWI5n4*N@sAAi8Fsmm znJfE&<|RRZ<1e+wv*>=gZYi! z`n;y{F>%-hD@?zTKvqd7wYiK25O6K z%AZrO))r#q6vF2Um6yL&1-a!uPv*2ohUhHY$zERafghU<*|3e4Y~~_W^5EM%@lsz8 zk=@w>Zrp4S#+s(_@v{@TJ@ImU(A8q>tNV_>uJxi*-80e9Q>t)n22Wp^UWEaFcp7!ViG1V{*<$eI7=ImF=~xu(#o?$)psago+&MEid!tuD^j>u zps*|UOLJ=v{>0EXFHqC_K720e!E^3ciDJ!DSa;$vsf@6Lqwl8^Q_H#J;YAa^W`7d7 zW|_?17#m6|g4eOa*irCm#X)B3G>(aM`=Mp93~9P}lnvAgyV$B?B|dsK75|u5k_nTZ zkzv;d@cuD##a@g0@wxUPWW@CM;JylBkL@xnojRBpExKNH-9uMAAYcj4TfgKa-`0y? zX1_qO-4T2kGmjYzmuE%vwKzNJ0do^(n86+uiI0KYB2dOtHlC+AD_g-M;~U|4k!NpLd|!9TO5c%vrp;+nCt3Wsy@s&tT1_A>_i=B4QMJfcc!YVO-+| zwq9d|So+m$c6iZg#xJjh)5k`Ojb&_@WospRR-}r57if`T?W^&^u%8$qqbq)vmrvG@ z8_TRzGuboUQevj`l*rx^sJHXByvT^aH5XHHPpNwmRGZo3lNo(haX3gRhI4ljidAM$NGE2 zxRGyBLRQKwDb9%e>lg^bFG?2;m$a~~q5q_k9MsHBv(hKAqg z_4^Mz&+~CU_qng@dS4<*u_bN)u}XYQsS0BcroyN$V{U!(9OLcj)a>$XSUs&qbUoOT!b?Y+*pOBzkZEkeVlN6%7tb(pqqHrxb9~GnmpeJo5Z_`wOg~5Mm^G9VM zsoH!?{4I8Ss;y8jc$_KqzGh2w3NXFD6PS?`=KTz!#yOI_Vg4MHeDVM%*xwzhb= z?P=OLTySo58SyoRCuo0*E#yoc#r?y5ap?tbyfv+p5@l)7)Yjvh-Vd+t@)?SLOCDoh z@L3{xY$cUk6-xW8N6?c`_CR*AiQUYRT6W_zcJnPGPxAD~_BiYFT)T~_Aw2W@Dw6#` zp}J_nbUXE%72JRnqnfoJpZz+AzWShOx2d&>YIus-`{;Nc8|()0~1ZI>dgVg0Ttc}&ARu>;IyHlJzjjNsf+%=dtrM)D#-aZl?SRMjA@1*UGbI$xp z_A-&>fW4&lK?a!TXRvn~TdRDW6!>wk3Sv9Vl5K5@L$SS>>@q@TU8{_2{4j8DZ-lID zBe?%)Ir-?goj9a5Trz&~76#O&;P8i=s?-;(8L5bU>u0Vjzl?jUyfHzs2A6CsDVZp0M_AotTs+!B~$MWNF6^ z;x%UwxQjF}Pi_RNpKWB)FMg9Jbp>QIW$cU)FI(Hb4C=4AvARn^FzkDTc-PAlWa)mC+g!4GqRJQ6pL~KH8LW&F9~eHFu#E0)E{BG3OCVrXEr0p=Jb#{M z2HL>^Tr_AKPE#+AA_&FGwmm6^ZvvKrF?FPHn-x*}*t|abP ztHP~UCi2jdt90_KWInIRo|d;Psg}`Iw2N}t$ooI)ap%={uwPon&h5xYT%-nc(8M4H zWD?IZNFq(+5~$_Z3D9~bjZG`l15sfXTUab4ZN!0?)w~lXr~3-`$!k@$o9kJkP*rFi zXh%}^7_g}4pWun0adxZpVVfpn6^E9#+F*MiM=Q+y&BfV$edL%^0;mdb z(a_gJ__7P9!N4(rj>*_Bva`AhyM~+>l@6Q-4Zpq7WlB5@Gz%q-{Xiu`?t<-!OSU7H zyd`Vr-)A4J+sTFJ*GbCzBwY7%5_57@g8p6;cImYMS6kRdo@Pry;)eBXY3^cn-=GDm zGb&+ZuA=S9cQ*gmf6c2kp?69QX>cz^<45P&_r*?-b}1C!jvi00B(+qTx4OfOl?#~S zDZwQgH3YNUBFWK{mTcriEwC;7MmEHi5P3r>*#3y3V~!p<T|3GaC^ zfi62e#qO(35dUzsn(2-UfrIVgpep=;?N4YC6?Hfmb zJG`VdcLKRpsuk4;sA1%W0#B|O$kLpvX~_aFa8s{f1&4dZEpLvYDCQw~k{!ilyeDGt zn+ou6b)mVBtgz|QFy2*rlwIl?OiI27LszR%gJ|D|H-$MaER&+@uTEGju$rITaumDl zAIb-RCRikU3bh5`RIXAx@ssm}>4O5qpL-*5dW`}kfANMDiBs8q`c1TVj{t7m{|VlH ze!yCy&x$QgWg%?m1jsH8#UL9!9yH=1$cw`1#Ib6uOX(D(ep18E+y$_~OHY6S&4gvw zm%{2&Z(6zfBy6bDBVKFs$)T~!2zlE^9*vd9T@Fi_*)_)G>n_8F!Ag+V(7=2(?1|Uy zVp1Vl!DNPovjN$5P_lV7_%&uSBlA@xUr4~3Z9WF;-+dF^39T1OLXL|+Jn@HLy28$3 zV;>9q`vB&V>9DrznC)Yq8Y1Di124R+WaD#+*?yCiARo0DFFtw=4!?}a<2lc;z2-wz z%9$asJAE$1<{ILwFT0_;?1@$7tX%P%@80}PN-(aGJ3unFjAdg#N8+}sBWUU+!HWj` zVHZZ1K}MJzZaKRhM!4>wUd0obmbWuEO^l}RJpOSX>D9uS-oW=ptmZ9KVya&Zif0-B zso<`E$DwJGs@;u*7OHe3girX-jEZM}rwu!z`KIn8)O<)ao%K|g9!l$>N(UvV_|;jk z*!qV*D|NG5Re#t{%S?$EyR7Hqi@a%drUtKwo<`3;l|YRr_NcO=PUJPBleU|TqdmDH z#MyEpJN!%*CiveckEOdw&J$a-IORouifvI@BOPZcoxm_fBeV-lVv#F1fO6vz5IINT ze0YccDyy0Cs7P>JFBWFj;Y{z-M0B4!n8#*DV&>@_{H>Zz_S;Ltj?>pLvBVX|#XKP$ z%e%;vat+pMAtqNoOcV`FHlmqzV?jMCo!$TLNEU7BfQh~??9LB6?lIp4hF$Zb1CPIF zg;sZnM{y*M4$}mg{ZTAT$rV`MEV!k$lQv}kgA9pTOmF&kQI)0-(cipQ9Jwq3wWe!} zPhO74V3$GE*|~$HD(Ye5#l={$Pb>;v^PE^|*unL#e)8m2HdH#yV4t)fAzWL_R5nJS zdt`|C-hewOce#pbxB0=A3o&GENF|eUpT*Wc97*`p9wJH{P0t=TKt(c+Kls(c(!<9S z*SX2?Cd3&(PkSS_7-ht>!Csv8CJhs693Z1xiS^Y82`96$nEO^ubaO}#wiN}VXu}S0 z)%?gZY>)CcK7(o5pAY=UGH0}UZNsNF7vsPg$MB4{HFXyC(4_hb+oJXB`N*?3(ayru zZlkn5*UmbL|NKjN{KRG4T{4Xu+Ki!@KhoI|2S-ShNdi(IM_Vjs!7!O%YVc+dSJ}Q0 z_{1x8?fxflqjEk!R#b><%ggabxF?G-I?B&IPNh1!kKoOyBM^S@4&AiiGCWFcAgz~j z#0@E)c*pk~Y6{+>DgK>ANlPH5DCi2l=%;MUhj3=7m8W6J85I!A{XR%vzz?Q9r zm0qXGiYIQ<7Q2bbeSjZm~a5DeO;mEw5y<;>{8 zNb+xfHRw63peW0j%`+N}778+O>T@zE7?z5Dxmytlbrn$Uk`o_1G?zLyi@3=`H&h!a z&C}-=gLc3%Y(J4HnkjW2#dhPEK}9PL|MM6!3Vy-dp$|c>tqQG{gn{(F_i({?F>Qap zg;Fmqe!ski{>as&seV)JjyM|gsFwHi=VE*QDO?hUDr93y+YYk3G?D*^olb>(02&GO zmD@tF?(uJP9J-(bXIq9)pX3!V==NWlmVN>K>V*pGhga}&N)7bf+JSR6n6hb+7JT7} z6ZHDGoA~;RD!r#`D(G-Qka77HUi$9?ZgqakEGrT~s!)+#ZYoEzU<#Y_Zy6bH8cJ7a zzYv8ccUR5~dRV0zrOw(VmXq0Bo%xRY3b&%?;*a`e7_L@on{{&)RCy?imf1-VuP@o+ zj+uiXQAL=CBa^WzED(F!@+PArxNx$iDBNf`3v%L{nr937k+R zqnkbu-6S{L`)6EWbh9C3PydZgr=&rp?F}jpjKth^0DgV4By8vhwy0QmuJji{W}p|` zS1UoMi-E9mbR4?ei4*0FXds&!Tm`6o4KcYF2S*mC5veji41Vu{lP@pDYl*Me?d2y> zTE9e8e%}<9MaE$4LMPJZs4Qrf^=x+DN+xgc3XkcZhuFka=G*fEqN3`n9yzbZwDnRL zct`<76TG2!=Rn-^IuHhiF2ft6wm_s#xA^eri7dyy8n+}#@eU(%ad1%+OL#Jmy7_d9 z#%OXOEp!o%U1893`2`xsKgTzXr|8*LQ|XUrZ+>zAM=~$!Ci_0+FOd#b;z_+H;C}rq z81o!yJbO-jD;Ub8Cs8N)8mjbQFy7XDMUPY!fXSy*v?mXE(2#P91LOJUKhgBlyopq6 zw~+WM9z*%dL>jsAD_lH3hP0am(1=ZcxW#i-esyU$Rc#CBU0R2!p-{QJa(e=VieB-V zx1wn1UICb%GM+apAEzHuBI#*tz{k2V;4=9t`PEHnzUy;RmZgR=U)SSWyD&Iw6p!lJ z=kdcW13bFjlSRg~LF(KgaQb&R9#Al26}n5&$i~UG1O3p+>@jFS1d$!ISA1<_CZ4+$ z4X3v$Vd&KoQr`uvY1v7lE_kQhV_)LG?lNp%3`B064A`zx!%0@n5HI+CoRXfCm=XUG zb%zMivjaQhH zbskJ4B?GRoG^-$6pDoIwW9Jfuy@oK~&Tb-2y+5IAq%RB28jSOluj6pn`LNGGT(#}$ zb=d!Gw@~|@jII+$h;Cec#X59K*{!Z`?4-OKR880oE=AeoOa2SUzj{V|-c5whNF5H? zZNzUa9f>i^Hqp=Do-*5%OPC~RB$`tOQ2FcEQEa#fx3r!EezSb%LHWk!cFG5Wk1 zOh3P!DAFF1ju%=3Smm)O`qTdx?k?KIrT2tWJ)ab+kB>y1F%ou8Uar_-p&ZDh^(TH*ipD!I{~j5|L1lj)BSiH-}U zhzEY`Ap7N0A?ffM~sp^OwVKP}P4cU!<#nW^Gaa{3I93Z%@wJiJ5ymKA?965qZ zr2__QM4;P4fuvLLlFpqINAgAv;EDk=*#_g+pub2`R99z+x%vjE=O;%S8zW(EgBf?L z3}Y+bs__}S{22g3YLLuS;r1_+;Es+2IL+R{kA1#IYNF4<&^JAB z$DmjAufcQMzaQ2c3%VUZ`O-UwG@bgc^K<4yvhoe*g~d7_~{ zjm@}(ZpTgFT;XaQ*S8EKVoZ4Ci1}5+o|lrF`%FNgC6Cxho@7lC`$){wWROx*2LI|z zVtCY(m(LgcXD-LZTdzMA^{RhLo!^r)ustJXPpvB_52FxolXv&8!8&VRtj`p zpN5vav#hu}7QW85LAq9#>W{rf{;a-A%!N7D@ku(>Bf!IB&gMCTX^MWL|e{27fI+20gW-wNzI=NEdPWW2i_;{G=_{Z9m(3~=Q> zT0hAw*}>FFeE_Z0)Zo*Xw8CDKSa@w32eQKkK(BigPN|`Mr2ae

k9|tU%eEJAEk~C8%hEXRw*4`79vZ?EZ?3?eUJdTy zIEB7cyMy(ET5!Se9pD#eM-vyG!>1OJ(ELsTtfT_zit&>mVM8G4s=v%n1@+^M-)_9% zz;9MuqQeWk5@_Yimss~skLwRf!jjbvRJZ6OxL(PF%}0L-evHHX(IPR7NH*t@!(4fV z#$*gy?SknJhhVbud-&yXU%dZ$6#RpF?AsS~X;RA+(kwm&;y3l;F|U0wg|EdIdWWG| zvH-1~`*O)KL!pysp+`aqIiO?3WCtF#Z7ttRF3MN1@CaZFF1;ji)6c^94};0yGr^cv zw*cL`+exZg4jZl$%9Bq!!+ocGTs^Cfq~1QyBxTdd;dV!unPVjSdC{2lq`ndjDQ^NF zhcWPbqcl7981SmtjD+bM6WRW7UgjkUM`9MCuAUlP5j65C}l1_$1l&#K?bleNp!c>3xx@`ev(M^^=qC|gZ7CnSlfWw}A< zV^i#Ok7q}R?8m=W`mlT3d~&4QlI4~I+H@C8+jVIA$$y#FVZYPpnkU(6YEF=j@+cA0WCJYQc&m-Qqu;9a{ ze4xy6cKY8GT%WfM4Q=$$zUEEkhs8_8PaA_VOxhU~tMbIfZZpC7Xd0WjZ$Byvdxc9K zH~5>Y$MHJw3O`70#H>+=vG33kw0n53qC|BrI-Z@*q)#98vpmc0Ae^Lm@;WN zJESpyxu+gu_cZe1`_F5TR1qfNE;7jup~OZmyOnKSV$Ec)-e$3uV+Gp5Ym$+?8EgmU z6X(EqaC_p(zFAHb_ZBCLgMA0ljc<2DkgPoZaT`dqRmT&3>09LUWDplL?iX8EDPdvY zedhbS2i8Ock=H|>f}UO<>2yBJer{QY{`&q#ZopBTSv3j21&GW-630|z3N#VMo zLt$Rq5mICu4GQWX$$`@0nHB8 zu&c{USgyh%(f#@;EHi!pANB@SPCg~D>=oz2`-F$kqq%~-sZGc0W?4*br8Av1_9XFh zw!&Jyi{SNg4^bbhMCJcJ#h$6%H1mZNN?jg7H%bqnLF#GrTFg7rY4`?y+fzD!_jx+# z$v4oM-6|AJtI?4cZ0M7u0t_%yrW-Xv=&nYEzb13)lnhDw@9s<_yg-udHY{Re^=6vxM>?^W^k3FqK^TRtL6Epy3_kDsFPc8ZO z|FU3)&NP0QPsfO-Q~39;0BA6q!fag6;9rA*_+`8~TjiX?P7gW&cjBtx+)x)-aXuUd z`v!u}aU-sJsR)`Bg1GLtX(ZwNU3_b?niR`r!1pt)xG?Rokae*UKZXN1v-LIkulx{^ zPg?;lS#P0i{uh$+=PpLHy@En{!0vs8IA@9BJ7wJI zsx3!o$2)C4@A*t_@%T8=sP~`&OC0&)*FuT&!xS9ve*)z_)rIU*Djn5x7}js=gr&MO z(QdU1z4Tp}UE-u^Ugi%l3lHb*c^@i_cjZ&9)=1i)p#UnY^qEAI37@X&jsKmu=J7T& z=nsKX(yJ+nL&kof6(08V!mzJ+l`;C;QH#$Q`33Brn$wGZGIXQzF{qG|5y$;IhSK)= zxbNO!ZhEDqjStU9v>=7mpU?lZOE!ZUq7vuz~k2;bxU6(?cNTR{t(;f`-V zFQx;!I>j>*@37eA3ot{tba%Y(A%P9Xp!YqC{BQ^qON2NC(L#7U z={R}!Eu5v78k41pTOd?6293J{MJbAdP-Q7aLPB z{PNZI)lCzcl9opvwC3U=u_jyf=R1r(n#=9(-h#mqM?op%47>Vj33<`E500IkK{qdI zCndkb`GQl4T%kV>z0YpLzQH-*``4O3Iy;0^1>U9C&(*?$HZ8DETS&j8?q@fSM8U)h z55eM+CvDr;4Wr)|V(G2zZ13(jq<4i-I)az*#T6~CzIq9odA?y~E+0hNR~@K@LJ;~S z%2az64(C&A^2t)!$wJwlFaLL>7vBAqfQyon)idf^p~B%6_)ZpzHvPS+O}iTocFKZx z-HO=Z{gD*N`=Y(uGP)M$?fZ&+ zYTW>_CzsIiZq;muaK{l@>te-Rb%7F_4~f^kNv*{MdU@eRQH*US>{}$ohb~))>tu&; z+m?7D`BjMrtjL1m_%pEXttmL2YlagCj$+r1i=rHd22p@VIKJQW1KvcBvkm*V3yz-F zCfjo70y}MmW5(t|k==4E-jXT)Xy!#_TKYGjJjPSX!;Y;NcJpwxz_rRcs|j4!g)xOD zO2oD+;bC$i$t)aB3xtx1f3`~e&Pxq!9-j+24ky{u5I<-bGl-k_>;(098a%nvn7*+P zk=?TcA<)MhwhmhXrJdQh`NeBUjZJ}_U-!cDidok6yF<(uU^L`BbSoieScFfABE00jK7} zG(=UKj!$?&iUuK?vS_qBGQE49qui-Yuw}a{?R;8J^fH2| zOpF1kT7HiFGa5uMs#x-?iP>0_?9E=Pgz)`meCX=6s?^GCK7IYnRM@F)#27mnxNKJ2BYrV*&`);6Mw7e?2I*RDUxG>p~MsP7VW3 z_N3tJT1}c#-vkcDpF!^aZnCCh zBQ6hdh85A1@uk8U*!SxV7f0(;%sCGRJ)V3|(+2)~#x)wU^uEaaoCKXQtpudrEu!i} zN3mTCGx=lpO3ZO9fy~pH_}aPw_>L1?GO8KUGcuU&L4wNr+%#E!I%D_IQ|OUe;j~|Up6w6cZ%FDcP2PC#^AG zr%Ku?(EeQ@RUSV~jfNgXU-=+@%-(}-{rMQ~Dh}s;6}?35nFQ9eE78-8&h|F?X2%o;# z@B-&*oOu2@`*OCLe1Gal!rT*Zo^1k_pVOon%f(JDz_+^JOloU6C%elLd z|8bJ&_^QEVi*q6*dP`xPsSY1`{05Gny%*xSVBHkX8WE^>uz#p8H( z^Ek58*qi(_t*{+`TbKI9P81#P8cmYj^I6cayExND4yW&xf-}YC%w^RH^!KqMhc@O{ zt=^hN9O9&SY?J~uR9~+9sL6ooY*Y#h>NmQv73@w&gNiSsuwcPbl;0=IaC<#D=E0^x&zf zf3TqDG)gKZ(`AW)r`GsxG1>mNHhYrz*HE|9RmPu^h%j8+Xjc# zl<~h^H>%Q|W;3^cUxfG8ZK8Z#9UjX}p$8fah`!lWaB+_Ys{52Q9dCr+uMPRV556e< zc>%^96LzZW>%~hCJr~G9VQlj}6)rb$JTy1#XZ+eQ>d}%!7S%P1Rs?Os+XY4B#`U-0 zvf&NB9B+bWv6e0TC8D-Qci64Xy=>*EW6XHJ1Xt}?3G!x4ctqe6TESf#!hi|XqC8XlRP)6z6!o`RB(b&x?B@t zj0+l~*{oVq-u<6C$nD%j-tL#co31*j>`_2Q)o-Vv%iS^S%WSNhKSA{U@o&_M5G3-N znW*e?)pnQe1$KD45_DfY!0$En5i&nmJk3*=K4YqQ;c*$8{A(h;CHYkFkN4tVulpqU zi7}sQ=t@%)-owVzHZb~^FMpQr4&jqJG4%Q?@!9^9Tw-e=s@dldOS5qLT+15tS7-A- zdP`t@X*SN-TZXQK#?ftAdw6Se0{3pb3p0O-_?0<}Xy0yq5N`Q!{GByw{I`_a{uj%B zHTc1)icT~o)A*RPj%b=xM84ZhpvN6Iz`e+7LTyLGsxfcL)x`mjX&`C4&teYo4#>k8 z{cG^({bO-JmN&fqa0bU{?Lud#Dz^TO2yf0df}U1aka~Coc7|^iC0vRi;c{Q93a!n^ zD4jCqzGf=_=`{p24b)i_T_O0TrZQQd)8b9r_OMnXf6OF%V5{39=+N8)JL5)@(G`2i zv{SBNv!GAxl(S!KIcOWVOgChu>&j7WBEtC>(l9}sK!#}_V>;VpR)Sh@K4)x`;;v>mdgH$%XaTFiy>Br8C z)Ui%RiC+IKi7Tzl(Q`s78^Q^Il@7g8!(nvLOcH^BLNEJVnv!b2uLx^H?fsn6E79DVM;$D$wKr_mode%{QYx!>JRCaGT2{l#dB|bXEI3>33^syMxHz7L?;qUKMNWZ_YCIypTYX_7;v4N zNgBcpNvW0+Bqlb%>);!Z{7y;;EUqF?WP*g|fS+uejXuVy$-!yEbHrqSF+}VOVGnNg zF@4=m(aqhFxM{X4?*6m1YR{=5@cq;v+LmjLFHh>Sxxwc_MSnet-g_{k&OfZKZiCoQ zxe4sA^kGlPT6onV3Ag6Ci;U-of$4yBq0n+CUb!yAq7_QmujA5eV8%e^Sv3y_i+97{ z_0!?PJ{_{=&;W7&uQx~<*TS~YKVvyYIwnuEna;q<-!?X!l8Empo!|gW`A8 zHvR(7J@mmQQ-^-6J;!Q><^leR;jJ%cz+bb&_;Pj|kQZxEN|>wkmJh}q+k42B46XpRPN!)QfSER`954OeV00FcwSddC6pM?;A18_=lu(P&WTC1P&;EE7kF@u|_z6+W-OvNB?lHmnu?N}Hz93?0 z@J*nf4S;Bce9`Su*IDtwQSd2y8IvokX0cvoWaqbm0w3fi>nLp_^JlL`6yK~ob+VF` z7fhyoCclV9bRi}jc7h4EgW!>OIdj)I3Oa`_!C0LDGIZDr(bE(^{ARTP24@E2nSCqS z_2)-n=H5|6W)Q%;U?0qtu*a%1cC1%%D885R7aAkRk@cyMfp41+76rbDVah00x(T{cVotjG|&0vb4| zum@+CyTIpr3n3*(9-A$c;nQMsa`bZ`EU*4f67wJ8PooAb4z|R)_*mlfTtvh5%2=&e zF4Iw{!lVTO%z1hhD8GLQ>n;W0?sfN|{9!l-J{2hKOM>9_aDP(VXo)T3ZQ+OJb8;nr z4OQ9u)>h_?Bv&qP8pR<>w?ivH1*-R)&GGh`8 z{AkFs7|3kfjOSydp}$OyFMK@$J`Xs88#ZS1X9KP1z@Llh@{Vwr^vMR>tDoWF%0ir^ zzZktHwZdz?Hu6(79U>A&fLd-d@%?=S1H0P@DO}6G_wiI%~M!(s`r8?xFw!3LQZZdA2lfsKZSlHL-o=`=IYl)&o|aU?St)P^4uKu zurptzX`TTq%sX&gkRt=7yWqXOSll6G59+;`*lv`KcpDvxw-XK7UbSC>o}eJ?=vrZ0 zhB`?)Bd{9|j3BZ`2VnJswcLEbLB{l*VRZI%;#sN(qsUNX%`>6h^e)*cw~%>%RfnUh zC)qTgIpo&wtt?^2Hg@uLAt?y@!U~7!^J&k9;jpR2uvu;#WG@ZCp!Nhdx6X#uD+aLh zr{r<`U=5MKULQ&hqu3M~!uB871_pmJ$iS{e7_sIl3x1`9hm(wKedwJ5VnkhvjYZ3M{o z2oTnoVUQs!4{M^wh~Bz?BDJ^QlKES$@Pgqu-g$2xIGpvR+vBw9$les3Y_gE-SKGyG z%$!6!P6+!j%^Y~B(+#Kf>gnL}?GUcLjz5x1gB=dH~+=?Uc@ZAH9-Zq=Q)%K(_ zSB`+WMkn~y))Sz7U@`HC&Becem-0yONa|_%MmR5}z?!}RDeq=>*!DVkmOT%z?%qge zz79o)`m5+T(wyo`j|WqUB=PX|3)vRg0+QvXN@d3V$Bor4VVs`+3-?Bp>-<|%(UhC%y&1~mwHQ(uQ)31xULP7SL;~p&Rb|U z^(s6)5lxO~Yoe=ocGZ%-KnHxdQI)Ylk3X`DWBSHcV19o;x65CIN?SU~?OhI{ovT7& zsODb$a`XmSR}%&fJGI%-H+#uD)tmgOe+ zSAH}QXN6ffT-ZA~=fzoi$CTjV71lKI z$qCUsd!g;<_jVZ7cM(i-(PyY1aIIfd3hDHbXqH4tiyFE*r;BcNcm3QqB_NvR_ z$M&(zFKLg^9+iqkUg`96?r?nfYcbn)axy$$ID?DNY~WqVH`tNsiJ!WuGCI$17MHirWoy&U zfxEINSy61tT4%(7dU+7}=PNY2%%4c=?c138ssG?p*I!7O-A(*F-jd~a{$lmtd+bYO z9g%a{EV7B3h~nrr@uY21WZ&-TsI&Pztld;hQV*!Z{Czd7b%z4Ezv3{+MeBoylR10y zU@z+J5oU)oE+nn+B-TV|i>wSrGmDONnA#VOelGHG!DRUI&YpnHvT}zK({F5to}F;jDJ<)!QG*t=Q$Pko6F)S|8J~1Iu;@~)?#N(K;4{y5)a$YuI+;GeJz6q?Kv z)6jvQ53I*&%jTh<-#B0=W9Y9(DuQk?ke!}X#IoE&X-8fl$ebC1&n~&a_+=(Myn(T` z(=V}n`5>y(uZr8!pTXZby|yRo&*8)?;bh}fn!nN1k6jLG&c1E2gmqOIA< zc*JxolnV3BukFULU_la7aobNuJ&0zvXAgq5qDnU9VK~SwKEV!Vs|bv>GQ4nmC7z>+ zxF`R%c%QW*s`zEY`HV=cGf;=dkCpf}d?f^K%VCPa+K}MKh(-HvSfUz_^MvpH+6+sP z<%0-8r}Y)+<=4Pbf4X>dra9c%K#+vZg+-+TMsMaxuuimNiA6KPXoSGPRF4Op{%G`k zCl8DAr;s_D1=nqa0)HH$NN2Q+hEuX@A^TS~TO^zpADl=sZ-8eJQ*Fx<8;neuKcJP~l+fPjN%U2e6a5;#3>?g4;fzH)+xp3y{rM7(_;m~U zJtmXwR1XK;DJg95h>0wsL`z^6tRYbgb%f6xkK4v3!&Zwwq#<@F^Dj#jCHeF+g+q(T zsVCIn@;Y}oaXwm9s?x}^F3-YO+bV7UY|?@JZ;9;T^kL9<$QAZJ7$@>m zN@DQgi+JQy1K90;oDFwNs2uruK6vYgF{Nvswzfvy%(?I(!C^h(Ws;l7mj#L9p+5`Z zw|tS%cD)=9T^YhpOWWh{1+i?&gj7M z@H0QK_WO;X{yYn7#_7{vx*Le7RUW>@S(9tIBdAIFWU@Wv4}@O4xYy?taRd0*ho734=?g-Q>TnV3cY41Z2Oe@GFXtnMVT zMUu2Ka3DBs&!y%+j-y}aeKxqcgZNEdflrkw*O;He3~p4C0Tlyi>)KSzU3!X+i{A@N zP8Fey$7niijT_GCs%BRfXyft*GaNWY70v3)VQIA*ipCY;y1olwYOhC%cE#h%)t5a^^94rVXE(rE zr`oGbZaXoJ`97kDNuA{4Tc8^~46tm89;hhK<<#E@9~{gZ{ztdE^$JFL-Nyg{MQi z$~+pFSqO>uM)KX$Ka=W1e?Vz2!uQ2$c55%yg6&*0l%7yP=dE~-syg8qbNLaR4LHEJ z8Q(?^^B|V4x)gU`7POxFwe*^w3dUWWj4~UJvs3dF_=x_=aM2(coMN`qVPUZ>R%j=9 zP+-A(oMa$WVC)2}s}-3?6=QF93;bENAG)gkvaa;;wjZh&kcy^$d^Ke=dwqEdvpQ1; z3dN30Yfuzc)ywdOO?!wbIgYc0d*bQ=ZTNek5v(%N1r}<_Xvr~XkIN99bm$dT+)F_p zq1E+wtS$Ka=Mb$5ebi7%#2Wv5qG7$G!KQC6EYN+)(yTS`wzD62`(4KE?^UTr(^clb z1`y3CMkdU}RW(<{Vfr=#uVUChm2 zyn|1>Y;fQq1<^R$P3%SL_bSPjH1O1_C)cBO(Qw-gF#2mLek|XDc@sAi`gby3`4E8G z^aKoPuEK;@@x*!c7Iv!&uyR2m`5SqZg;{-v&OJig{9Xg-TBHq;F&nG8T;=#sV-VeT z$;6$nm$RC#%&M_*T9`4gP#hANLZk`;QNA)1-oKw_>)snf)!LKc(vx^vH$?^RNkX2 zlOGoZy*?K^_Z4yvI#TrNYctTQ6cS~MMC$Cd z8_ZMDfXqV?A+wLD@BDwS_s4s^*ExHy^*s08goXuYX;14kyq+LsBOEoTo=z}-9U09B z-1nu^8dRuU!yoZm9>K;8A9Qn+@I;%3P*;@Ws)k2c%eD&EV_z!1m_L#j)8Ar|_F&3y zUn?KfZzryNt4%b&_67GT*=(H70XA^v8%As_!Ne=Fj&CDUnTt#v4xYWk zQ5yTPnumi~{!&@I`DY-T+3Ly^H<`h?pKf@%w3e+Z4kYS_Gq5|tf$?)Ygtiu6QDMD_ z#0E&hvnn7CimHL~1s#ru{$-JI-~KT}b9GFe*_)JaJs`#pJ3(&ms3Nw{n(&T~M3i`@jiT|7SLBfQPnctnh|?zAV3!oy zNWoQmbo2>j-=j|A)Ltso`1N#@fB%jBnB7Jm=*$rP{O{xarv7Aq{53Kx^O!Z4H(!IyaVT0!iIzuuv$6e``W;2HT@{j>^`GYXbot@3r zXC`1nmM4zfRYz`jDUquMiS+Ntwb~(wQdk zJ~kHnrFRQ?A3Vt~rOEiGF@+4{2ChD!$bw?y37$`ezs*W)OvD@Z%-fHw z60EV8{RDR8MmF)2H(*Kg`%15kC)g`3M|e9ynRIR+2E$E;;1w7vT7NQPg@;Xn4DG>A zg&rYihm0Z%Mug(A9`=~}<`{g{_(!H6T|DNx(kf>da`NO zS8>IT9+07AOou2&kosNTur>DxSv7aNps0Qf*Ra)6msFpw4eBNrFUj%x@qI|=Cc>7@ zb>ow|hJzs7!f!WYAp3+99q{1*nBUHo_)OYFE1`*0XjPJ%P8aawY#rKp<13i?EJoQg z>bRnBBpLG`;fLG%!Td7h^Cp~xu|1M#yTrEg>jwTKqn!Ne3c{zOquJTi3anc&gZ40x zrGGBf!|#5zOktB1&fTHP%}Yj+7w>H<)fZS$Gubv;dR~@(T6~7jts4t|E`6xU)?yy_ zrjOH*B%{jMZ9l+ie<8L{m%3yPr%<<8hi-cHoXQk^9X>JzGQvKQ_Li9y zNe={C@nags)t;gMwK$XSUILz8^+tGqwu_zYp!jBwJTyGA1Fs(!$hGQGbX?J9xYK-= zjU8o4tm}~s-kt`%J(^hixZ$+FY!e$O*}1E=s)*8dZ`eKM3tLz+0eXAnsnkx{qczw8%tiXrJs==2Uihick$+fZfnC|bPc;)3`X3%nn1C^~0 z(CB(Mv6wv?$6GhT`2foG*5nH*KM%mC6)Wk3lnUZ0WaCvosW(!TM=q+Uz%TPhOmk^Z zGX6GYExx^Z)E;Tx7j+z$OGd{{;pV(r_8x8sr~-N?pB|jk1pAbyans-$vZX|hDQkPs z+3xFck={8N;rgdO9j7zQk3ruduGJmG?{ugDb?Eo@{#wPxg%BYxQg4 zkFOo}n|X%LT)z_s7Lms}gV9wUd8xweT-p38;f1>HjVQPKC?>4Vx`cmAX^-_a_j&&&a}^KD+TRwIdA| zGsIN!lz82I04CIrhJgGLkUicHy0aT#j@Ak|6;TL!_lH9JR7Lo2{VaAhM?jx}lLZLR z6t=e{2r(@q#JbApiq^*gxca&&OulRkekR(u*Vi1vI%1$bXDIk6gbSzQ21+|$2Qu>C z5^Q|?o+MjF!WY*u6>ZHgNLQ&lPMsjJLNx|~)_!$}mH4MicCVK1TLQj(Be5uk4Mn># z|AdsQib6p`J*roDlULd+A^-FV!FR+x@^IZeVx`d&muu9*#71fNdQF}89j}TNLFZYi zK4b5vZ$)pT`=YLKWkt&1A2`$OIk_u6cSqazW@}@&KyKv+*cq>ge=hukMREc;qTq_# zO{INes~p37rf45tjR9T3@F46VZVJE2mTZa_BLe#I<@vhsXnikkm6;0(-ulu!@G@+x zEhOi4CR6WxTl#g?CiIvRfF|*d!i%qyKql`tX{#`#qm%vNVW%Um>SfK7$a9t+I{;d) z9mPTqPcrLz5Pr8Uz;Q9^tZ7iCc94^2 zCPU=paWL!LH_L=TN+Bzc`7n$C-4{%O^)v}`HO8K*52 zqY~WM9m|TQH(`034F6l@0%L+&@bZ#t%urzp9Fyl^Ku9A zL+uUrzMHdwDraax4=-G;dy{;8bVIOv{}%F(4#OdzUP#^aH15>68}_8svdeAjS!z== zDyR)1{Tc?+xw-~4MdK+%U);gl6JNp@)i-R_(-2gdxDgJ|k>OLGKV@mNPr}++AyC%n z%i5o;N5{8UB!=MjTvGk?5c?sLoIsXk(pnFMS68YQ;#Ny9Wa(18jsiJ1k0PJHGg3Y8ZE2X^B|e5QbzXjKsE6@HplVknjqXWPM$ohyTLAAvP82Ufx?JI zsbZfe1JJ!?27Ect3SC{gWHw1B>ORAX%5H7Qx9`PlpTtU@fPA4Qbpj^)DoOL_(`>i< z4I$;}GGR~ET5>g=Gn=`e+1ZX#a_wUF`R?lyx1+z<&MvaxWDXTBhsG8~nPM=KyDtoH5Pv^Nac&;9q9b#gZ#mkE#lF> z;pDE(TVdIFXVU85EOz|ffbwpD=Dzz-@%{z6-BU~O?O!Lw<$ehZCPX<5*UI3o0bTG_ z+IPxJ0FiCeHVdn?Qt(qtAn5sNk!ki@@V9X%3Hx^pd)=H)gR*m3zSn8EI%m6d&MPCs zF14V2%W%4G$VR^CmsE8U1iOn(}K=ys79e>Qxh3YuTTt7T&`U^+{;! zw+1I$MKVLnL$rI|Xi_)$BTH+S7tGRE;}wPd*mac@ zHfTcz$)dx=2&oG z8>mfOChF8i!?7Wg@zG&-E_-P>CAlm4gA_Z=@-CtCzNpg%cWW@k0yMFFft#+RkriQ` zY+0QZoO9X4Ez2Ikk76^raP%!WB7CC$?-QuT?Ew(9`~-Y$Z6g{(C&ELIbkcX%X`EEN z4D6K#fKJ9ttjw^3p1zeRr}&xliGD(=s*j=CI2+m^FALB0U0LsCapJPBIN^s^CW#uP z%WRvASxieh95$NFRy@xnN2Zxz=}Z%`Pu*@deupEoQH^Dle-d%*IUgporJRJkGDKnV zLJau#f_=#NDl9V`#*A~jh~FoB)?Zs5*4=c&s@N68=+{bA_|cnO-I&B;B&O%=^xjyI z9YVg}`9OSX-0=Ok% z8uIeW4{rjm9i+e)t?y)=U8NZ;j#wwXvkA{tNRjolh#H?2&9kxbP)j1$PZp zLe=%xh5R0en65`()?!gj8de{`=*_{<#NMLZt{tRDxDzg4e})Z*EOsWnn(VXIVn5oe z%9ZR-lH3nE)b>(hg|(q3PTseW;dNuoDUIb#Q`ds3$67usc{kgveIIS&HBe#9I5ccu z4IvA<;n-JqHu0${J@@hz-KC^}3kENTv&JSk<9?7>)^+j3;!2EIl0=6b zn~isy4f({KTX>Hxs(fzR24UXjO57n!ahA#jH0aX=zF#h&!o(~(b*%zjTA2s$b`?Ov zlkqfX8Y6x>mSCTqjO~ig*fz=T*QekKasDw6XO+Jbm(xeAHE;-MDG$Um6QmvI^TTlT z=}f3B=_{tVWs3hzS0&EwTI9pwP;ux)UC`Lm6RMXL2@`x@38hyiSNu&f6HIDiFU}Da z&~4RZ(*BH~#nRW}`aekoLf^Apzm2f#&^gw;I*7c>QHSdaUBZpdaHjmdxT5}@rkIiv zFO2`DhaV#&Nyfr+Y^-aUxORY)P1>PCqS};j*Q$N!qp+XdrCS_}mW(Ef_E*`0)s`&p z+$B-X=qOoyas;{XGlD4?jTSGR4RPEV@EV?kG_dgB^Uz|&K*xx6_XUSblSuZ)0pxkZ z`-|G4vvD`)0^S{h{$;j!G}&Hi{}MK1tsBc&E!{I^rbEUA57F>UCk~IbfOq?LiN6kw zfm;PHiM--72Osl6XdZ3N)_>5%3%wccUMLEGuSSzYp&Q9tqayg?EV%^&!k}R2MZ6qn zMT}MS*qDLYkl8c~9<8$_8}jXO@H}I5&zy>h6Nb_oM}34FGxw1DtL~Ji<))LPqn7Y~ zF?rz7<;RDcZ$ithKZJG0kHPP43j8*Y+WJ!4+E!-3LXvTBv1>@@hucZ;dXtQaK8m+?FEDRnNJK>zjH|Q{%y; zYt0NuU$&LYUu$C_UF|p`zJsi3%EB{4AH%ZanV`Ea2Of_vt9W&(2UPyKE-bC)@Y=}( zUA1E*R=>!enLU7Czw)u@>ljwGFM>JUiUo%`X84mye9MlRWNC4Kc>H(=Q(SHY!P$XO zlM+MbSLQIcIs2in|8DWt(0NRI_7YsHo)5*_qM(oVxKJ1QZ9&34>NS3&S ziB22+AjD)oY$|aQFUT(xReB3V^G~!;EBl?9ZL^1u{Y@}u-*0w0vqU_Ya+?%inaP|# z3mCELi(_(VEi24@K#Z@-LVDF6rb3nq5#jHIqYjHmPQiW&%6VS;zYb!J?>57`Xd9O9 zU=I8JeVJ8_Hdc9=u-O|HV18GLXmQVi#PpcS<{sA-O74xueMbVwz(ZSDPt+!#4vmHb zQr`4iUt?6$c!mpOBwl^%HBolj7!n-(f<@gbW!L;p6WylWQdcjM?T_op^IR5^FFGz_ zw{tL@dsqQc)`zik4rjhehWy#6Ch5I;Mf|{hsLQ6~q-pIRrW?0H;2&d1bzpCfc78i3!JU^gAy>haP3h?XbKBJ`btLZ9oI|RWuMHodhq48=RVI94@NrmB=IA&+ z>^S!9KS*L%BS|#V;k$`KWw`SoIz=b7T=mc@B5n&OnCV7G^9;?NH!=nlAWp##f#eMV!h7^_R^-7$#3x>=c+6v2ILtbC({|M zr2AU+5f#Do@@h6rSDt(bK29#z=!3nPALs={h*rIFgu1D*Z0PdEV%3s^OwO+-S-JE( zD_&rV**?X@f5|1H_QHs{D$hetR|ocC^j$Qs%^`oi|sP-IQB{#`}CZQpFSj`(N#mD=A2g+ zGw(4uWq-lZ@bldYz4x_Z%8p#7G^L;5GSq}p7cLf#wZd_2cX9EQU1VnNP^rf(aWTg& zLXE_y6)XH|iR+{wnD${7_YU8NW$`|O;n+RozwHL7oa;*GbZ_R*dNqo>+Sc%%k{i-7 z_%YdNd5&i7drz*$J7Q=5-Z05vI;;e%N|j7Y!Dmy8cxcEqw&Bbf^tQN4E`A$T>8d#w zHRl>sI$m2UxL#Fo(&%-QQhTGyyZs0t9!}v!{e7h%~e;v>9Ge@&t1o3Iv3Li zMQga{EnTOmr`0q@*1+k>H!CtQe=}_gl31um)Um@%i{6<$$!X=sDEz6rN6PyAgAY}Q zz#x4)k9Lz`9)F(Tq3ya{wzUVH==DI_2^>W4*apbWRHL)X$MDGAKOpJ+OsXYiV`dl* zN*TYzV{_I;CW1T@x!1)p8;naK+_gAn3cVf zyNxx2u&4QWqEU{2YDmSMs`bK)V;bmNz;KIeJ{L-R@k^wXY`$;9V_&x8ra`u}G9dIX}FO?Xi563O!dmAWA7U{RfQ8+bh7$j}WM&$?1{KosUu=-{a-FhUK9xC$WQL`3;iZ16b&P{_q zNuAKrY)1c^>;gS)x^duw&-fzk748ch$A(Q>h5t=F0s3E@xTU*)<-emAJWDskX@hW) z!{(znNof=qeND%WuG_iWfv5azwI7_)bmGF-7C3*jj^4jCh4Wdr0k$@ycC*wa*)Wv0 zDu~qNg$?cJIEbywmE(F+w%fF58uytrnEx82K&Psf!u=QVMdopTE*dV%$EGAtDERr2 z%=?{2ucpfLZGV>2`mx>Y2tPp!TsPwOPZwFwux0pkksf_HWFKClnQV1Q4mlq#W&2;n zVAPyAG>^z4iEApUZ1)oZCaau5OD>;ah1+dN_POjG&>G2p#IRP;uA^ zuB-onuVq_NCixhq$p-V-csH=uN@QwEB5iEmN1Au8pgTiOqs7@*v?6XlL@Xace$F$* zO)JW9(nu5TVp9Z9&X3`+?jJh*N#Il7_v4TC&H3!DHgvS!YAAW^LyeZ^L$2{z>RZ*o z7f#nid1Ghs)3kfs`|EF5FZD9blj>;F_|bg1Y2V7h>>27`Z{QP7=aBbf^XaGIo%mSZ zMEtyYC9Rnl%|rS)@SSO!xc9CqG<0#m2$>BuYM>@>d*O};gdPxnsu$ePUri^4dV%dH zWB8{&iS#_)8w|`=(~Ek?@taWzHxE0-C$AsN>b2(~Z?V9qn>O*3LrWo|rz51@t4-V^ zeHvH&yA@?ed(plXQQUOD2|b!=4sm`_V&KuYAT$NT@?*}haYHz(-fM>E2J{B27yH0_ z#VFbm6T+vA*~MM^J2N?DUpjEq9PYeLiJnxS0o~4%z`Dmzn2)pIyn!a3Bo}a?^+IOy zCba;N%Q%?G^Ui2u`a)xz*|`Ak-n#-RRg1ai*>+(YKvl-n}R77bGU8 zr3Z=al}nor5cCw zW+ii-toq735t_^&Pg~75nvNhTwSlxDBbS%m?tq^V$o;m+@NQ)*tUrl-<<|YorAdkQ zocE7ivy6lH=}+jeRv$Xn#Z#JNTnCaegj7D=3D@=~@*DZD*tm^Jyx03;`2Ob{J96}58KelO4AmzR~$q`x~rW|$u~IbMUS*`FO_x9uYro^9jjrisF<_W}IR z`6r;RJO*MezT`^+y~x3X@8H;z?bI}+z%k!sAPo$j1WOBDu>ajn^!|n=Jae@ynb7kI z&GkA^9Z}Ge7VhA!-<*yEYfQ$AL zlV{Tv;&Epa{U&pV*sbf$S5BM=GmdwH*Oz~+zTqKZLFXW6(k$w__%Zj4I**Tneu7`y zeQD+yNyRla%pq?CtA6H9BVDFf>^^AAre~z#-Y;xx*AJ->QPYtXC3sj)8jl# z2mMq=OI+QfQ2ir?-cQYeSN-LA;n*cm+%Fn;o|Pk>gX%y^rqR6lQ~9-=MU8E6WNP|b<}mN9={Nm zT~Tnm3-y+s1!qky{#)TKu6Vi+*nvWHIEW$wR&@3Jm{FV&$N@ohW?W8SUk$Xfmii?I?qE3P*ecd2=*E+|-jw5qv zl}!e@zvU3rNF-sLEj@Av)Uy+^@N_x}Z3Gncg3I@>n** zOOxxL?8E*(`-~}9OC=6zAP_A#Vp;YCT~(iv(Ps~n$3BVhXM}yl?KSU2f1S;6x;Y0u zXG!kJv-6=WEe~6JzG5e{LQ%f&5G*{O22=cHv13gWei<@T(0fG#HQy z;xG>3w&kR%$r{JxD|4F=FOs?P3<(=`9=sa`h`;}U{q@m-nTxj4bCrblU)7U`NQ}d5 zy;lzN)K<`4RcAonFAp>q&f!@y{qVIyE9x|s3Yu#lL)78r^xbwp^v-dkjSWkAuuKj; z5Ff)2$U5*{-Q(cO&4v76F{ie%D=Yi`n?Oe$h~!rF_u%~06sm+v`9#Y@ypLWVCxfqj z__~uNK1 zGhNqWh*P@GzGf;wTI6XkTQB)>rfg@o3I%4NB1ff~6IizCli(FftbBGo1o-)qyi-B! zrQb0D%X^AB79-jHUo*w;HRGvW>lW}R8V=7Ry~y{IsnFA{2qwuHL34x=J-a)Vh2H56 z=F<}KkGh1!-~X5-zB<4KEq+%>!q%+ufg`**Ojr zZ>&XC@1J~&wr27Nd+ky}X5 zrrAe7QrqM&e5(8s?jHM@u79J+2d{m=I@@Q_{Y6IT9k&5S=gsCN7AM)7A4+V6O%}KH zI!xY5ygtj1Q|R}Hir~5FBB^^ehwX_z3u@9%WAz**vaQt&mM>7?TcM3iI_ZI)YbVn7 zdpeMAdJ@jaoDj2uE$O_Pa&pI|iA5Njp=nHl$h%Z=kEtayC>}&TQ%?}@LA;C}%t zSfEJ49pLsN1g+& znK+aCJtn9(ekP6Rk;Ine9>Jyl^8EgYL(nL_7e9(Bw635CK0P1E3{_q5#jtJUwcTQ& z_o2<$5r2R!x|s`G)ZEz0x7)BfHI3)>8cYM{9^y96$LPDcTHHCW0p7)g(VVTx?9GQl z4im1xa&;N#|91(d8fHLF0+4yT7K#6v)v%4yIfPi}(NlKg_(jEK{9WiWJeJgh_i-5M zlq+LWnRaXv4NxfLE25^dY+p0_$S{y!j*7$R9&~tqx{p0N#%hB#+gJ~z53iw9n=q3P}SSVVRg^G@1_8|02cUQZJkl%+t& z$n+#{{C~jqCG~7kvE({@q6q#iMtFa{GwXGJ1I*46+52bq*fQ}v?|<(;OZ7OwcO@z~ zxh`tP{!-WfUxyXl=32+&9A5JMd&{Ziq;qJ0dJo;Pax`2ntD=^z!EpENWPbZ(I(+<5 z1+jEBJy(4gl23Z0X1q5ISssnucm1*8&048f7fUAvp2Cvq-7x=Gh~vY8xzy;+57r%& z2h+cKvbn)in7i>%>bl@F`1owbiHmxGNs}DW@~DDM-O;4;?Hky(@D;{>8%0+QSEgoz z*TBK0U9h^q8lsn&5%0Zd~mDVzlT_gJ9bdPO|Ny}15$X%hA- z5|)=-fuZ01p}0|wYJ9#Aixz9rPge$kU-$qP-KGzzMlonQ&<9p|Mv7?afIE*BV~Of1 z%=eM98tHMc{@XFIRsISp<0e3A{~+k2vl4>DVNiIZksNGygV7PGs5JQlyZ>%9n%>W0 zCq55l4d*D?8+8KO8WUhe;3JqbehJ+29Sx1Er(%IP%CTdWC$YJnMx0ki!^c!@EL^o3 zlLtkx(eZMUuW`RL$DKyHmotg&F&Ls`gCO1i5b^71BzLB3U{G%j;vJPv_NqN3pEK`) z;mupO^NLL%|g-N>KAbcFN9g?sl?>{elS|H6*bMK<1cv=UhQLT`;t4i&TFQm?N27H|VheTGb#@yCA;_DsBZHE%}_n`r3;`{4{Q7+M&2Oo{-{nKI!ayg9=}-Xc`2_Y zKNDvp<-yLqWso)FZuzi^(WJ>hk4&z#fP16HVWUnN*rsKHZ}l(Symut_pJ)Uhv(oVG z6orb!jn>RbA&0COGa8n^FM|G>x@5@y5i~c%gUkvcV$g&vV!V2_cq4yiB+BC9&5S6-mJ?No6N6~QJedrvi=T; zx%Ws&`j?M>uSa6}lYVGaG(q^ak;9dKSK$0fZR&e_FGh!jLXFi{2y-sLhn7t+d(KQa z{H~has@G!q)_LUmj=99=!#*-*mm*nalS=g7UWdx7Phs=5NfKLE0gEJFTEELWu=DO` zX~obEX_?ad)9MPV{Gx)XdrrdBE*;P=AHp8onhDd~j<6WZ?a*>rlkPmef~?s$p3M2` z2hWTq6aSA=ceQmF^WOZ4+=3BYHoOi)L!ZK&nek9F<^VG-GjmLS9E{ls(eOE2i3V9I z;p?k^m{LoFIA!iz$931sNXUym-06}&Eu2`+tF@=HaWV zl!%i`WO&W!Go<*L2acavMN8*BWVfmAa7qP#HouPMV0u-xOKo z-l@bfaSnbeyv7DS>rpZNOtSD_z%f#j)|(f%JeLCg#UwW+86TWzh3__R#NGLW$=jnb zwB+tN_JALT%8|QRag{2$^VbBmMoSC@{}bZ9&LL7>uow4|eL{|nkB8E&P2^6D9Q3b~ zc9W0l$j5$tY5I-R_^bE`tT2~_N|gb)?5hT5EO<+*+jfyw9R-Nl>yOrjAIRGsmhft4 z64*=*!Ool#$LDKC(2wr3Aa}wEtZ&c&lsyKMW8GNkYMY86|7>Wg`5^6Mh7o_|QScx< zQCPfbJ>1HC1sgPq*~X_*F6rF@Tx;mdj%}C4ZL5o=-O2;u(2pu?Stw;Vu0}v+xgnEj z_e9rI_sFVg+u73mxlmJc7D`q;Aj+mjs60Cfi&e^*&$C4F#Y0`p^Il7SEndy<#K?n2 zOPXL-^bKDvT8V#k>|y!R9-zN0oYXiP&;dVBz~eJg|47QfY}r>OexLge!tFZ1aIq3^ zJK2|7-M14As@_4TU<8JKk#yo#Ew0@A7QWiHi*L7OC;bdm6$#w=zawm5?uId&1>H4>~#4mSk6dCbkB5@bd5&S~IqcdGtMw z?p|Fm`*are>up7bA4!1zTlb^ss#3@RUkv;?i`5CEv3=1HT9P0KgWPZ6_aDi;dtE$D zd3+L%xQ%13M@Q0mYq#Lkv5Vp6k$o^R`hl>jB>`g}UB+P-P2t$EKz#BdhkP*jCM*eD z2w}k;_{3yBU99jQyxG-3vYT8eSiOWdI+k>V-Buh|Hi}PdIgjCHL2TWB9bheEhJ$*? zvy1zrC9JPL_;UxCsJDh1+y4?1UG_qQ`zU%L-kG(n)}|I&tI4dH*8J1@(sZ1G-mtO6JkGZPs^Q$Z<`=N-RPjtY?kl|qZLqQ-nPQkLwt?(jPj$a?H zjJ6BfNbsr?aNg!7*>zc4l1iRNX~6ROhicP_+~%HqRQ52@vDqJcm~ZA=YM-H<>^iz)hnD2e$s&4}oarw8G{~LWiC(Sm z@WebNzRbM{EG2fdY|U^QVkb|N+%@QTxr4Nz<1eXAlBW%&%b;1!nkwsmz?c#XK6F|T zz51mHmq};(frC}(aub0sI(WyiX6Z5Fp=1WTeaf-fG>drFU1UkoyQCa&04}_u1Rp9E zvF(G+c~FTwJy&ik&0KDfj~lgU&E&0Yla2{wUuh-bLnYsc^P9;J4j|8^+>q;yS9q)JCMjrtj=6bNM6SjTRf^=m?8RzWU#$n=zrUh3 zZwWM;7J~5uRbk=qSx~;c3UmsZ9sjAx@<+?MaQK68@uXoO<~eRBzZ04Sfbf*nK zQ3(v3eugE@vLpN4m7$;H-28mPiX9%20*5}2A~{n!@ce_jxG2gR!zwf|@^1-rK7S+5 zY+Oe}L(AZxn+eRen1w@p8WbICJD&(mA* zyYW5PT!4_*njb0>1QwM`goI2??>B#}Nx$MdfnL-A3mdBt&qNZ$9w zag_PTam48g%-LH6o2_KQ`$Zl#)|7F|jeN=SMoxpb({1>(=U#BN*}A;5WEuA?-iuQ{ z9)&n59}!jIj!swZ;@x$B;EJv@vzcE4uftE#;j0cfuDvr31}NIo-dkSaNY7*Rke3dT zjV*vKpFKG9NQBVYtBYx;9_A;u?uTgsU+_?364OoDLDg=RvjJWuqNCDTvTB2?V7~bS ze!ZH*-uWEF@J%D2ui}5Wrn*_w+Fs0VE^y&FGw#CB>8FKIiA#`Jt3*SVd=vv#Ckpk} z@i67;3!%Bfiw6hpBFX_PU~_+EpkLJZojpf|$HHXPWJggevyGHppG2(IjTZ-C4cM9a z3AWAIpm2I8bO@h?uPYMq>ybRrvq+|Lw?2`(+u!2iUYmtYDTu%H^h1m=^o z5%+i&V`Q-+F0+4zuYQlAo3s6}@M0pJyY3WdTeQPN*%a4`ve!T+jb7L*6@y4my=2Lcb7}=Wa(Mp>;dXU z2T0tF4(4>@94_=NMqZN%V;2h2eJV)IIXM!$3>Ep8`kv5mLWd{QT9SOll^)KQ6{n0d z0rBkyK6k0A*l|Ujx_*xWSJmP4_xUtje7XPdO7?)Z4A@Cj^lMo6L4kmS>Wb!;H|$I6Wd%bUS6Ay`ZuoQ zW$=J!$M)gVe!Rl&`Aj%@BS5^|xg9n^5()k9B9YhZgTZA9(0FY#{SadhqbADo1$8?d zs{;36Ti?ZKoGm#u-bq5JgTIMXf@0*ydMHk^rt6o-ldghO@c5AtXe$0 z>-%1+*!T=@Tr$PG3As|cSx)KvgPqV|5>ZR`q0Ph3QB(%tw=7fA=rvKvLbfOpO zXW2zOQzC_P8%Kk+QX!i->=*f^SRpp>BhroJ3l2H+np`+K7kyNU;BHzt>2cYJ20Tu| zjc2~XomDkh{>BX&idSP;`%!ewP$oey9zgv*RrV`FjVIof<>%vluvtD76+*|cKhIx@ zO;>7RZ=F64EYYCDUzqWz}`kv6RTB#Xb2=JPKmJJ2usH}>t>!Timp@@A*=@N1zi9rkGwWy32WYjz2l z*n28Jd-y+mnEVv|`m|z;(?XnJ;38^`-N^alKx(SJa{cwI{v+zox0Osf(!Y6&zxl&R-9+f)>#+UC^ z$o($E)uT3up*L!<&*6ipvgQZ#2>*p0@&Uwkhz)VS(4XAzQh+wy3YHe!pM1Krk~z-! z$5NX1(t7uFNUO2tMXz+(+!1eu**!Nqm}RcSgX?qfg=Pxr|8@z`%jS@2+K-y-kcD^M zBVlMq58^Um40a4{rUNw!;U=oF(7!vFx5Zy({c$aE7>DDO(oOUJRsp?PQVh|n=5^|feZYDt|8 zdx*1mu;cf}c#@DhnyTG9fvQCp;olGkWFMk{4<5m{d-TT(A0}4VFTV}B2g}%_5q+sc zqzuk>)r3G(M~w8Byj>+SO!G__+i_zhPXD$H$cRboUh^@yeQP~$(Ao*tzq^teOrmo} zC1Y&be7dG>EfjRr;F#_Zyy|$DjZ!Va#|;MDc=C4f$9#Rc=-j%T-U z!|tcp^yNFdd0;O|NO&l&RK39VOv=RWBYWXh`Eax@x<{0LPe)tLHqrjkLe`XXf$cW# zU`tzKKz*bs@0=maCod{vul@V6X&cV7Z&|&>@)!+V`$q>Bo%>$?;!$7Rdpi(&PhLmD z-ydO@c?7z)uf&F5y5QJy2VDja!?*=9(&uNewhn1`Hor@}bF7p7+A)XpB5r&TcEd0!VCxi}|h&3)B z*^&FnY?j+h#-E-<7tb?jJoys&Tx*4ceGW@KHbpVX;V!Y7uY=y5JJHHW0UX;y#BZB* zgu$;TW4W(6TA8n9HjRzUO}-Hg+KRBzZwxt7`A{srtwZIq&6zQChtJC694%!tux+_B zHXgpjPI^}R8lnf_D+-Q()a zz^5A)jqFi*Y2031x*`rtOC|nfL>kiyH(`O++GJU+75j1GFxIM%XS4f`B@Y9u*^X&H zK`Xc~W}irBSKq7$yE@y-rWse6*Emk%yzLxS2P-p|?^a~|aU-HTq6ZGi?t_CK-Xh6q zN@UTsX{^WIWuW%pBD)ct$DY`PpYY!QgQ<#eNc{Z+N3Ni1x%ynwANm2S668Nk}yf*iKg+ss^ zs6V)rtXDh9hIk$%85ceZ+F67Is)RB7Fh61xBK=2HzY)CjL#X8b{NjxwX~$IOxMSUs ziqbGeGUqCSK}f2UUoCV{o_7>_$W=Sa`SoBmX_r{&u^ziW;?rNpoG0?EI#lkWZTLr@IRCMT_BK-ILe z+{-^scsjm`u_*wzPp!nthleXvzV4~03w6iB&$1}fCJ(oTedNYW58_&tPW!375Z&*$ z2sf`d;BBLaj&;A~$@y(la7C#iZH-doRqrd=-(fRhLgPIa|4-`uNzAj}H%G(iS{LEM zz)Gt9riz#h^C9?nFyG?jP?4SGM^;FkkGmEM)cILF-J_s^GHd(MzV}G z6G>)>%*-;A6)kB`QIa$ynpUaj+}DXjWJbQBK@?dTNw(kl{RO>VJ?FWfb6?lz^M04M zGW)4{Y+&dwB4>Vv+13QI?%*Y?p-!OsvlVgge0g}f{Q$YY*N%KHJS`X~JtMWE2W9== z$IPiugS5^2%jRqq@96J#lW&u3u;}~`?w5TlJ9qdRy}vPzWp#%Toz7c?lfFtG=e!ZT ztqkGk`CV`-QaneU&$6bDa2C;9$`&W&5q;^YZ1LH4G9d9=)xJg9bXF11y9Z@dHO`lT zuwB(eBU2)@ravKLCR>8TmzDT>YA-LhRGP`u>XCEa#pHs88fq9x;lnR7P&~Yls+^SP zo=yJBeNrifLhdHFw?0yce!QOCY1~ZKteGrmA5zBp<>n-$Q66+^i%Dvzn&`Zx7|{KX zG{y^*uSz3}jh)H!vfI!bx`H%)m?HS}PJ_Z$1J2PqQaETZ3xljPN$ye$=sI6aUIu+) zF|qde#!4Q(*59Omdao1NHI&?31kA6QK%}hSLf!8$&BzLsvnux3up6$^i z-UrsgoZ^1$+1@H;}5cm!fY!)v{SS z2H3to3{{2{fL_c;p_Cos_T=Z0uK_#30nf9`A)-U6q*XZI?haR)M7EppD;Qmr#d&JA zgZIriq8{78enhNBQ+0LtBWqYaCl^Sab_&@Sa31b?`nkwVSpa{245(IGa0PbUtK}q5 z+8}wAF+7jXgLkXP!kNJmrh3xLMQdUNxq8^3`tE?yY|{=Y?pw)GP?^<2YTZpxWwdKG z1bu=>*%Oe z-m6pJa6@u~6YoOb!f-<79$cJO!X%By=t^ltY#1I0m!=J)n+DBc8yjZwL%;qew>Lfn z-CL<})BX`({3e>aeRewTiQY(DXSqS&!EhY+qXLYF4RqDcHYGK)e-MReOZs!pM6&(z zGSXhxM~0kUMEmV(ged{qWa403@-Wp<$Wop{{5!NDK6n@Nmzh92&MkDE{(T+>-rNhZ zCifxBMg^x{C?JY)liA1}Sx~n7AN*C1Cvm^}2_?}c!lc}>%s4%rOxv$Yw9Br;>(Lgj ziwBD?rJv0ZU>!-n(dZG-BIc7y)B^e6CtK(ruMG`EZTtX*bUJHlZAM&Iw5hC~|Xsc7@UGF6_ zZ{s0?L^fS?mi=MY3XyoEX)QQ(Dbn4!=kckpIuuOvfS-e!X!T$lFu3PMR`oj!N`J@E z-v=C7({p9^-8op;=VdNzjyj2w8*6ax=$TNdxR`R0%WzolHB!`b4^MRrb$w1JfJWXH z_}8AyEtOhLUyK|KOATJKljoGG??sLmKHm`UT<%gr$t*VvX*f+ab{V04UK#7{NCNFK z4v_H8kecal1dq8@82-MsPz6jp_6uwJ z8GxPW+)%yN1Q!#h;PSgyiPyggZ13(&N#z@N(tm6g2@W+7`V4!y%+n*m{=j+Gt)!0T zTgepnbU!$4PsTfkBPz zUFTpDT(5z7isdYGWC6E%ff8GIE0V4Hs4Zrl(!liZT#}TIeDjR!3|CGk>Z=CB_T}gC z&Ae1nnRT4Mp4R339wN|aK`NUx{gyaqN@CwfS)mA+WP3g>5t&VA`C_}TT-?sFcxR?9 zY1Vdx^jaRv&d6bR&tDQF`cE46Sz_dk9yT#&75Vwv2xWUU;nn15HvG&a((%um-}JVW z_^rFf6c#2(GQ%90^4^mu^ zw>6wiwAI0!h6+{_bs1YH55yHOt%y;+H73At^hzkl(u_(M^$qDb@>LoZeCa`}KX=%r zdQDt;pbuW#eq<)Cmz{T1Mv!LFD|BGQFIXgrLDw8v;os~sa6Owzw%(4wp4ZAaeB*k! zQ#77;wGv~xg0#Jyu>B^t>T8C58zW5*RmT~ugKWpQEY_&Kvq*~Tya|Ml`A=KIcsTxqjMQ>$f zna>zZo55tfE7@Hwe`a(31wJaf#^uS)A|qW>NrA#bHb&+Hd`Xw^!Dg?BZ+$!*{d$~@ z+5ZTXi^Tk3ycx@UrvRE7yNKPo0Q{3AkGi=oq|>R0&o!P3)f1bE?c!eOQ2XYRJ9;%4 zpSzL9mc3>l>t{o-SqSvgJ;BQQDZ=u1G35D;dHC*=5jG9@$zAa!ti9fu_%(~(EB`hK z+>*nrQtXLsMJ46R$xpGxan6yRUHtRdV zx6u~xHYgP?Y}3LyCN?;B?<|%kKZIU&n#As?@XYo37&Moj14)On_$Nl@yz){F(Lt=h zn2RoPEqcM^UgX0eg92i0p--fa$l(LS7-Cl+OA2n6@v{!Lvv2jvY)@P^oauj`Wzbm3 zr1i!mbo(HeZ0lGyQ7eS&P`d~j^bq-GeVPndmL__dYg`HoVub^K_j#Or!TFlT2BK-M z4>tSN@NQlvKe4l#G|Ya^#^0z#lZj3s^2h1Vt|y#@{WH@3L>WtT8I$v~sJ8IT<()T$ zLED~O7Ig3@ck-GJduQp$Pgy&RvyHir!;8nE-9LGzop70suuqdj^*>BpE0r-O+>+&( z=~a(=n9sC=6lj%oqsxoOpU9KQQ$*f!5NY^tF!4Ke6_tatz!XQE6KXs_aQVzOLF3p4W2HuAaQrv*)orM z>em*`TS`O+AsGqZ5*&z9aFgKdcal@up8k zY9k|@-@Kg3cortg9!iTV8Rd^qEcavd#g{9 zxt*`c3`aRIUfIJJ&evqG9%u8zlg@GG-`;b3)P_Q|Pk+3c>&Hw6F8*OsnmOtNb9gvMp_a&i6 zBFS^TN@6}goqyD6O7wd}c^&nuTys_=vn;tl{8C%cPh^4h%xEL)hxxKy7bg=<-zM^` zGKrY|DC1X7j3mjn1kP5)@N2yFx#<&HInVFT%w)|lTrp)N4D2!$ZZ*thJ?c_ee@hLA zj|wC^LE4`WZIa$KCW;5cYHI*$Y3vs!znQ)WWq|qJIuK5RRAewBcY@i!8b+QJQRZ?D=v^fcab^darv_X~&a`%}KJffZUF z$GeFGnfH;wR7N+SSbgs%2USyq(AhR%q?X3)(|3VV8Nip?%WP5oG=QH<{OYa&@?Me>^2johTfNN(71BbWS#`y>_-x-3Oiom^BmX9Krua|zcRnBkomuFA-t zESj!O;v*d-0TwQt^@eFI#jb+)*Gz-`f!fyzV(}U9MR&>DGnpoLS^y(7GGX9 zMoyS;?kicnaD?D>ay;6)x{-0$dq}O-53;}EAJ^$t&-?%S&X2sELyY@9fD`-u`P}t# zTwIkR?(z*_i)5AwpZGWk4u}@IZaCqMJ9=E0!Zdg>d?>V!DCIsSC-H|LAK{M7iKr@6 zT}jWK0M^qyftB=>vU_>EiT~Uz;o+>eL?xt9@K8-=4!bmAQvJ_y^DjOI4F2f5+ zm&t~!mvKb;Vk%u!z)XzoIlb7M{M(aTVB4o-g8PI!M193E!MkBPi3-klsgfB&=O5XH zYo8<#Y3s#A^OrAq^MVLvLH%LJ2wA)~rJl{iBc!7$1-4&5i0OHD_#s|Oc(P_X+>|@Q zqK+hj(5*|>{?Q^YE0w_JjWfT~u90PV}}HJJFkHwSHuQ$#wh~ZAH%Uwmm;DZVWl-V@|ZxEBQ|g{z~3%jwQA}kwoW@3~^nZ zNnG3HT)MtSkxAW+>~rKHa!D2NsPu7{n#%FGWmq+TaIh*QWh;Q2O)%LpQ_s1jN7 zUq=`0tQ`tJu72kH0@C?^=hws6gTBK0h%aRJd?$82-i)|grjYju9OUY46ng5_u=@Kf zp*!&t`=~yjw->#ZPph)X{(kq#`qArn*Gk^H6hY0$H+}Myzw}uO0F=Cl?U0Z zksDyci3ISs+zvCPZG;A`&9J!qG+gq#?($_`Hb_^gicDoO6T1)~Ch8Pgkj^W`9}jO`DUxd zbf^F3FJ6DZ^^3A2zt>veE1uo@cmt@J-yDlXQ zW!Z|9T`b_RCf_y9gD7XKz@*b7x!JAyEJLM^8GrhZWZ-IMY2wF^@LoZDuRh>|?^hFZ zS84M2{3o)vGKbs#XBvAE8bUs<$|k~|cf?`DTuDKCFA3>5$M&f`<8-roSh{HwCv2)? zDX|?@W87RJ(JzY}{#ro#inef1Muw6zt!iXXbU0bMP8v>Rsrr487Htdz?_zmYeJk8lFzf7{kPsF7hy~Np;%CQ}${h{Sa zEr~9h0Ix0>3;K#F+_GtXD4(u`uIp=gspb8_e?TgK@Z4t7E4PJd7#73diD828)&oqY zs)oO2*dI!Ny>Ri!xdU^H?1W3*>yaI^6mD?kENc3Hyl%o|^59rH3+fsTZ*B6}%nM1N zPfiM%%jRIp-cM}9W3jhB+MGRqU`Trd<%HDcHq;tzCL9k~4hQemu}gEhaGCN@4E`?- z5@J{2g&=KSK6nesdwK-5t&ifbcgf)86_0(=>*>bJ-$8v{v~V~=kxGsIe@>u)X*{0_ zx=xmK=ctXW)Mlojte1#=KBMXJPk}=6zlX42kukljE@IFsW-bmLpvTRI;gAJQ@V?px znq{@oc3~2ZUaSa?MV07Z;}2(NJQsgwdWc<_60{cQLd}~PGIaS{Ov^n08Dcm2jO7{D z$0kCj;}JGPJntG^4aJ$X=}o{@M*gL1x}DuCh^u zII9l_(&Pe*jl}<<_)zkwm0=0E?^zC|=tyU$*@H)d9DUur5SJC@;cp{3IPy*#b^O+ge{&?s8hM+T z1P#Hf57dOE4QEN^nmb_N6h&sgxeq;M>*&Sob5HP0jq{0-7id_r zM)ZSiW^!jrP(5q_?U>L>HpV|;dBKG&PJ_Kjh5&TmjyJwV9%6in{y zP@=|s6#ex_L%6xKjeB~vzu*(UmAW74B$}l|X^P!F_V(Frk}R^W-hMkwq$kf2io0Jy zSmXt){;>k;m5x)P!X2Yjdx^}33>u+Z!R&($qRhOJSb0R6hF_q#aN}A3DHZb$z;WPC>$+hbcvj29)buBR&?b)pX}Ss9PX zvfub$5Bm-Ux^XiaiP^O6 z`G=uAVFN}dJHwz$(^#sxo^WB+V|EP7L~q|15_C}ftnyOeT=-a;(qDy+c@l}n#(VK- z(OP_33-AUzF19-IB1Kz#=L(E?l<8Qa4Y~WrMYBM^H4f=Z)wi@37FNX$5i+K$T zl@7Clw&7SfW&~7YCd(S8K zzElc!#wNqp2bTqt2f5&7A4_FDrJ;VQg4YXx-OubqO;1XaP|x*e#l%f!!#Png`kJs4)3&sV%X30gBU zUA_erv17qDc)hI*?yj*Tzorhs?1BVzOnwYTdba$)&mOGo&nR@f*~v0=TF8=l%R!}O zBt)mLgnz#W<2#Y3Gh&@8_Keq~(%Ytz6;|b>FQ^@}PH%+x+Q+bX-B4y9B1?9bIg>qu z21AE?CV6?{E?6j^By!i2aNf@X-t_BqHu+m3cnmtg1`Tt^Jus48ff+n zfgRg&K}Rxxo~_*m;~z;=VOtG8yEIqGs~L-dU)AArmN@sV9*+531N$>q4ubXXpu9DY z?^PA)#7kSruHmAq>Xinyj-H8L3OC^&pW@=XBv;UseS#WdN1&wp3LW0t%kDXg&(k+~ zT(M9^a7u6$2CSYBo9>I8`hpSkymTCR>4zexeFToQTEI2KDj{{5s$e$#9yIv>r6XE? zqLkD?LH14xJ{V#k{D}K3m@cuxcujF1aN*-J9lBmm3Qiq1qUsNgh2xLin7!g5AtZl|P_@yU7JaE9TeHsNg}bJ7R*;P_ zHeo4llgMMoq(Km68_pg-_lB~_Rcx7Z54$)yDOxI50F@NTw&=B<@L9xq9uhAUUAP^y6jWX8#DV9qz&g&#Pri zbrZ$iur>8xyn~MEdq^tN2U3G2ws>Cs8uYer!-u0|;fC=}&~tTw_~T!}@ZU*rHynsM zIb+z~y_Z<|DJkmhzZrZ^r-GUEP}ruimYNMM!0AVe&~HZ%%YXd^+fQrL2Dgi>`-d$w z$2-#O)M0{A;b6SKq7*)cDNtj7J2;SE1~(jMkdeQ<;m*%nSeZOtsJ7Nc+3BW&qJ0kS zZ@&@$@n)h!ZWwivi4iWYlEOy+q14i6IZ+Dw4h^GU!Q+xI_+*egN%Rt1)D7*6 zB{*qOKlFKO%vvAr#UK1_GQuJjeE&3)m0NnqHqA;1R5IdEbj71(St8o3dBfIJq~mDO zyEFS*BewZ2#dXupvi6uwAouqSIVf^c8nwc;qmYk6Wm+Ws_E5%&eL^~Uh|6+ z(qHvpnodgfgFR{VRjW(2?ISs=9`FSoKEFvH{nsaCE^MIe_(a#P?)Rv8V~wEO6hR^f z$Wt}z94dK#KnO7(Lp@R*tFy0dp<@Cj;HwF`uvjTl*l<+eb&*t%u<(8t{c00Ne8))R z{f(c<=ogII70-r$$@XO0A%AwZp$ZJl4zSOw-mx?1qoH&`3BFVuCVmE6Ky8P<@GE#c z+?cQ(44b-{SEwBN1p7eJ30cbd|7At0=FGk2226@P&JX>#0g5D%%yG?T{KmPW@grqu zPQQT} z*GX)=?gY}4sf()9Kg{V@jUW6n$e2Ux(PTlI5g6lnuWK2c)i%n6a$t8WOT7949{8&xKye0ow!>jFYKE#cc}c_UH`xdF%$V5$VuA z(HlPZyCK=J*#zTi%22<0CdPcM<3I1rAS=#qhrga3sBF58bUkTcQdAP>Dq0WB;P?suY5zc2cN}< zv!>!GaprYSk}C52ACfnXQ#eKAFtYq#BwpI)jPl~{_ri~v7%F`M65a>n=8_8BHUn@+ zqA^5{DQ7L06#3=|MZD$S19E$P@MPf$ewhf@keNoAviSZhZ7M}2Z9H2w!3X3Lbn!`D zFY|u1!)0OaPW1J#6t+Gn;MVUc!>O12p!p3zzMKQ<8Cb!L!G~~;R2wdz%){shMX+?& zASmFZp*i~?DgCAAdh*a)!F8ay>!Qk|^wKIv+E(?78mKL!kGIO8SH64oI*X^Y;iaML ztGk@=K4le*&Wm;(*E6yDbHD;ui;8pX>0SrA$K96eJ#&!`)8TPvxE8rQ_Nb6;eu+G3 z)fb9vrCeXoQ}mftjBvp1fUrMf8BBZe0?lj}(NwixWaX1$n5DN8*6r1yh2z^;QR`XK z65fH=Hcg~WRjRlJF5Rn_uK<_sXvT(Jzj45Ze9S&0g}=ML!J0dl zaonS)@YLH4r@Re?I_(YkX8$`CSd;1mC+_Z*h%H!?x%Fw5!b#f*Y6#B_6i;nl)Q^2tzSdd+OY zmv2^(bgC_=>@9%Dd5ti8fS9)&f#mD@Q}8-?m|(Si5`6745;kO)lF=g9=)qcfdVZ4} zUG)TD=G8Tz;rNlhOR~gSyJe~JgS(()GD;X{7tb!KKV+-+?}L^%vUKV33Vx(#3H0+x zg&V22jO(CcrD zedd?oG69qa)EPzI{vC~CG7ip9 zZo)^}a%4}HE2#@9XBWmN@WC;SK(-str~yTDa9sygo;V6t$&Fmv(`NPki!n_Zv7`;P-dX)?%J*oO+$Oo}Y zJ}95q=q!W*?HN^;re}z%PcytU?P0f)E5LV^67ABBBJW(S$kGjKp|329WxO||MpN_Q za{FO)an6SBflo+Q))+`X7Q(OB83}(jDA7-9ChWXr0yv5Nug7i6p?v=Ua&^Twm_*+2 zpQ0>fq;X(cpX1f=OI%!cvH2kwuqb_(9RR zdomfM0#mt3H&)OJ^#c&KISJQVCE~w}PUxJw5^oQ7L0)ky>JD57YrizHyMcefd4fLn zh4+DsUJdh^T@Tw{>%!LjDKtUk-eqjO#?-CjaoYY&V!h{6Rp;~|9P(j28D$?1-`A#) z<7Ey|aW#YWiu?X0-D}z8dy&v#?Vg_@8L$DRCJm?3W`^tKmJQ4y zi|un@+v)*8ju{e%>~mn|rA4z`OvG-oB^g_(4o}ARr_V*sl5=06aB19qEN&|FFF=@W9RHy8FDz|J=f2%krH7Pv z;qL4outa7Nq&!z6Pye1G`vype!PED|!s@yBPId>MEZ#*sUA$pZ&H|_#B4PFh5oB(^ z$J}L4MY^`n75hGHg6*Pb!gqTp7v>!Xv;HyW5fVc_?0Ny6eb2dt9%b;svX9F+D?n|X zGYRiX$7iZ3T=3eB)ZpA$7|IGG9gpI!D2 z4I`Bkfzr4EV6Ur>OS7MG*Cxc#KIhd?6Co$$7@Z(e`kP66;02=i(;72gCV=F*3e_d1 z`Rlb0Gx?>nz-dITb7CMk|r%t%csy3nf=U%`9RXZ$ymP_K}%ZRj1 z3?KD)2>aYv!8@}zEa>z?Qjz$A1bM#T9`2t*isaW4Rfp;9{geN=<-2acl=T64e9|qf zlIbLF&Uc}lcjWXl+gXv;M7S3igAWFo!1^jr+$YX%CTm>;^Lzy`9H@f19kJLvUyT;# z79(vrAf)N1i7bafRH5MjH$t4XxlOx(;YB`z_Qo4R@}UDnYq~R)+57`7*A9Zk;%=hi zatIs8^@j^S;_S7DhnUG@@laS18~kyy;H2}3lskLFv9#~xr)~)uU$PnQEP8_KE1$yJ z&zm98`!ZBa*^QU;DP6d75RK}XP3ye2v-FCw*r;oUH0K>Rnud{Z{W$6-&MRhGS(3>6 z`|u+zgYiG-5KY%;sF2fVw?g|-XWKK9kVh^wsOTM8Gkg%rJDq{%`vUG9{+Zl;e}XE{ ztz|aHRPdqC2w~>#N3b$mm)z?s;19QFu=%-V^uKu$a0!SOnm}1UCguL)RsJuyVrzm^*I?S@2{y8jmfdU!>#VQ(p^CANz>Y^6U=} zwzQKqdV_?SgEXn?j_LH^Kn64A7vpYs2iWmf2L20-sAN66pxrYS9cRSSQ7=W0*CZ(+ zwspSPr;miya`AYkJ{L_|7_`Tpgt4tQu&;CqmK)xJtky+nw6BF-Z%GBu^mN?OD{>=s zw1qj3ym4OgDLx@0oMg&;V|qJFP+}7ex5t{I!jG9?ku;7^YBUC=p(VKFXdaPiOGVd2 z7o2qH3|!lnhGs9+g~S{s=A=7V*tIE)+>fZk)olnwLr++?y-7U75a*Un$7d7T8LZTx zn+BMX)~_+>u>Uv&E7*~ux&pyySQCH2>J>H|+zu9d?qK$~S=6Xt6&-zgsG!uYB8*sn zl@6_#>iTy59kR%`K#*QAtU7cpg??uggdg5@Lj5N~XBKPGKxG@DUuraHoYr!!dgVbc znrD?qN5{}{D>l)jk*2PP3@^LnEt*NYyDX}$+d`pytH?~htV>@GyCF>3Ezr5r>Tuyd z368j=O=W@;p!s+Kcm48nnrb_jbk7f=bZ#XCyxU3VmdjM96~6$(*btok(uM8}Xcqp| z<K3rhmtmNBT~k>0b||gbd>(fm z)x_OvX9+Ggso=lzh9vN=Jl(~&a_g^;63&hiV{IybaX@=H)D~VOp|-Qxe&tK7CT5^u z9cWBH`)?I=gh{Brb(Byr=mjjc&Bo)_y7XV!RkpL>Ax52!#U0}Frmpe`UTaBU>f!Y+ z3o3#{{-2RBt9~Bsjhrvczu3kv;@yO{O_#x=L4uuL%jv(G3O3yM4B0B5z^dOXleNtj z^kBOp4Vga>d2SCndW!57Re9Q-bRH*0TjSebhlH**Wn9ub7eV2~6?oWhCI8M!i7s2} z4Vf|lkaceX&52(DZ~LX;(f@RWA)WW>;5aGQT|;+ZPHhIcHK1K6xlt!F<28l1r{e^> z-M56O!->@C%?=Fxa+D7Ew3$-dIpl5YV{o4I1Q%)5;>eyTIv}V4{Ui#spSMV}xnH*L?DM*BUo zxBZN8#(S}NC$fj(^D0=8x~woY@(dmGDGAD-{)NA#0>tbxMJJ;OX1%2hrL9#3LEJAb z_rls*K!o~@!1G-q4X${MfDSP05jjp$ViMVLSGFuSij7tR#NvKKmk8K;wu z%bmC2kpY)G57gWR(5#2c2nB6D^W z$X+T#%YQsEF1*RIBElfnVj*^`rI5o5^aa7+0Jr}M=hJU0LRE1%`?v9m=ssLds#l$1 zKNFsi)&;8|>ic&Lf4&MjU;UF@sy{^x+K#a64MSmXrM>WcR3yG%dI7h|9OVbmK+<&! zs8QJz_C;b3>hIOLE|))K@UE3uGtkxf936+12CjHN;wgz-Ax?K+FB9%{7zzb-1B7Z} zGkIS=8_dP?wCKCoO*j?I9bJ+R%3CeDs*fEw|Li(El+nn!-%rFTRF&>39nU3vIwGtt zd4fN}o}p#L7)-4B4BoA+RI24LkcC6w{+cxA*J?yZeGRG1@rdGQecma&du2ykJnjh{ zzI{}+bd;b}R)Ck>IG5Uijn@gM*Y-p~tCk^4@$L?I&`1a%M=8 zU0$8Ix@0%`y1`sHK|3NRW|rcL zJh14=W1Kg{ge^@B#b3?cWdCO=`tgw|9^n#Tpw0*G+Jb8=-_Qn}FIDrC9dD49XKKQ> zc?-D1<4oCI3w^XVDZuW-;qcL64vuNQNXURK(BoswYCCv1wQm8D)wV&;#Q(@1H%q)Z z!V+|=^@UXha$t6{O}y__GuzD+qt3=tsn1p9{*~$Q&TP4`eb-Gg``~b@P<$Hwb1L!K zTzjEoQa0yv1K@M_RN|{?ho1fAs`s0ogJ9LUY`ujP=!P^3XTB-B&T80A>9YnQRzrvE zt8B$P5gllmU?j*oIt#hiTu{z`CkYL56SkkQr~PY0r}|x0;fucxdR$KsI`h6#s|zV? z=j3g|*MEb!(FUSVDKrGz?C!8xAFi?cX3=2TdK%N3RG#z0b;CeAyiCC26gYl zg4(UOG)-TMH!lk$My-bMe7Ymj>N#ln+m5d3E+;<1GdQbN&ROTa!`}-t=-UlTh|}=)cSZaxjHu*Tf|(x>iz`1yHCmc zW9k^%c>@|X-*UfOF5wq%ZAxsW-~h>29Aldenc1rRz@;zwKu2}{fvE=jHnNzmb5n$< z7e=)6>QZLoc89^15p=N311`nR7CXia0lP3=$=Fc_Le4fGgx`q}EM_hJH}yil!hE9q zFo*VZkAxKoTJ+VM=cM_9ws7~|YT^AJooa)yEv$0)YS{VCPB@^iBW&FL8VaA^ATlp@ z3CFaj3a2WQ=-Z`rpuX~xgeEK&&#_%hDnA3nK(gR5tB_Tvi5dBhOv$^D6x`9@T^KfF zDqJdv#vwPJlSVB!fw~RF35R}>gGa>QA)~=?C2=8C$-dw_+Wuh5sa3=%Zx$`-&1Ywv z@8OWgt^AG^Pl@uQ3ohfV^+Ectns5#;u!w8Auw8eTKrbwX#&a3)RX+}|%fL}|DQF*u$D;awNmLF@y*nJ0a zbygzxI{X}j`G|A7I%%OrL*(o2y-jNRIPmRPg0t$~;LDT~m?^o%4F6d2;{=f(lwbiX z3r66U+IYTtxhg!jYX@cVJFl2fikZINu)gLwS1HTD?79wFLZhMfKSwqr-=D0_KEpWw z{wS|>g1;^NW(T!j5{cS&2smd#^?u*Lj~R)WQc()(NiuNZh67;v1h6@q4cDRy$x)-* z*@&mB`_pW<7;qi>lASOOfjYl< z^7(InSRpbbvR~BjizHj|%UC+@6GMvi?D_)@TWtGF*`UFd1B%q+p-wQ2Iq_ zB$;j!%$yaDgTu8sSd!p^N$s+H+^Km?T3(#P-aCaSDpIk~a~?VM>o|8TW1_FGs{XiJ=p%izgcUltpi!s)HBW|9Ba5ovL6 z9agl6oL=%6H)LeusBV9Zcs~~Y)+XWG1y{Kn-yT8tfitYKJ{3M$?1n}ULnd32$hJ5> zB_R!(Y`hi4EuogM)%7(SI@lS9Pk145`Do%-~M@iCfP+e{wiuMkochd}j`Ha7O* z4w~9eRnQ(bAI^rS;=g@*tmUMI@Jr0CjaZh$-aeA!4K&Qi@hNY?aM>iX;;|OVxxNzh z+f=}2r4dAA8Bn{~-&paBg}C-dE?Qk`=3}aS@Zr>AJgXt_gN|0gs`7mpW@?WOx{t~6 zC10G4mKWk}k!jGXX`c?ezq%TClwuWW) ze&FXWPo(3AY7>5L4muW|V`y;;%-m9;<=g{q!}qGk1kB~IL=2|EQ9+cHz7Xy7nGPq z;RN!X{oZ4O2|hzW>qIJE*yczqr;MhqFYQR$PJeuE{FHrvV)Cdj_S;)#dx?cI%Z=n5TFi}xj7m!@IhNh281Jq90d zO#y=#ZPsz{B5imu3w9svloaII<221QR&>CbxGgEbFX0lADdtV1d=fDFdMCNDGZ%Ly z9bn~KDHtc;fiJ$-uw!cvTyMDrx>KeJGn%zg^56qLnlOwD(jOyu8C_r_E%a&f?iN0H z_d|Fze;Bw+i*rJanPe9YrwK~eP`BwS+`e~IP!6QD++>l^bw*Rr92bcTj~#~gW7nuh za0$KVctkMm)}g&x^HKimLV7CfCV)XKEVp`ys!mt%@bNK%*3>?13anygi&dfQupy~h zGKD5T%LZ9J71FEHjz1PS^7C%b2CqNyaQfFpu&7DG72y%9 z=$q>wSU8dTqNpN#NJrDO{s**jabHPKdtO1m^vRL{9jq@-bQNoMxQCiMUQ-}S0D zJw4}~`@XKvXPVs~Sh?gI^U(f6^uOf_<3Fu|U5SmbabzxB`q6-Y4}K>8jgiDIv<$zN z=Qw2Oi~ZwlP7>EH;OQ2_*-5jV;O*2wp6y-;Mu%15=%nRz*rgAkZ{@(whiJ217jRROl#n*c>a9(SOUe*a`@11Rb*3q9CcC3 z!of0q;1BCZW!pl?Xq(f-xcHs0rbr!R=bvP(M;$9%oE=4$9Axq`mbvySNV&(er{ABG z|4jSPZv7V|HE9v#%F5E|wu)juZi(m!k*BAszLH_8Yb5sG*)Y#6pDa#ofr*w+h~d@| zIOx)1Qg7l457`lTB*q@{qlkEyJ4nX9xW%mFQXq151;~9fgDs~sn6#k^1Z1ZZl|?@# zQ@riTE%E;!m#!uyNB)Ct_rjrZVva!9akI9zQRi%n`W zI43xtJhGo6GBiK40b4$^{;Q&4Y@7#VHT#e^Dlf=G8*N~2L!fxv14p$tt<^??KV$_> zfY8w$l96JLSExHI7!-6$TvLL{Sf5ek_~Ur!x>-WJ=mL_|odRZQi(s&p2V7?1lB$o5 zlAfP`AS}QL&dEH6ibZp=|BMDnl351RYUwXA*&+{R-Wx&1W{c32-bmiarb5`^dXV^N z(kX@^P`bz(SzsJSb5Gi9*GaABZYKA~D>2)_Q#sQzX6@fh`DX1U(4kNS&)R~7CUq_9 zXBtbxUsRJdy!ywBH*J!JREbjPH1+*ziI zMm5@!f2vC{qWOd%3=F1U&t|K0|t{KX#octX(7Z9k<>3Mb`e(fcHZ$<60#H=GK0T zv>a%FJDY-t#>f!3{>Fur?>-MhBI+e)9|w^gGwWel|4Np>&l~^zn+or%W&?gPC2NX; z1>*;oBEHVyvRu(v-yDSZ$pEHk5Ls+OTfZV*H-nuHVfj$}`Y(wTe7da|HU{ER&P zNM0x^^7#YniM!2Kk`wPjUmJ|!TVLz*A^X0vn4gWHT0I#j-?~n#l{xG4UjaUZEQBj} zS%q^CUikhWHYl%>jIgo+t*c#7dMXUQ&Tq#39Y?wU1P!Nmx~+I@zX4QyYJozLbC!`P z%lFGSfW4{|mFAbp)skKO+Hlc_s%|G4ST_OP!ZjT4=&4h!;&3!ZU&%9fJ(N1{2PyNS z;KAkhShVxCr0Mf~STTJLJyI!6WiwMS$yJ4{=(`GH%C*_NSMrc^>mwX_DaC`9S>ZCf ze{4jXA*)#*M_yLA!QhEMCB3>sp)y&C&i8g_Z+oAUHxE~mBF9RoIUP#wb?zlbCclX6 z@9TJVdnJ}c`f_03hVEBdDg_sEj2Ei!b%oNQba>w%wI^+~2-0c=rx={@xQhbo?o;_E8A$iT_v(4FUG;@b*-#_#2r+Tk0$dRN1@S>4stu?kK|3j zBXL)y#y9RB2itb#kfG*fq^n>PjG5+5es4cTM!nw&*2|6Iysi&AdWuZBqJCsoK)Ix; z@hp0*enM=Hya%6)WB8We;%rIGJDiRCEtu67LvGPba$V$q|Aa)LY=VrCl4{Fl{XKx5 zWfRfi$x!C_(uOP7l)&^54bjPGN__`pLBHSIkZBFVlOygCzk5#b_mnPoo&Hj?$WNA* zN4vq+i5J=FHXEm~3Tw5ExtcMX?ozFV7LwxX zODLQD9=GlCgzh6RA;Wkss%lG7yQMY|VG$|xl}Z(R5iWv@*(l6>ItQ%68gcZ>D*EH? zN_tb}Ei-7DC4BsE7CGq$@as<*Y*?0qyYMUQIR8SB4G6)?bHV)AnQjbKZstw3_i8ol z*IFwE28c)dYP+fxbRcY~}pnP^B&}*!Fwo z*rekxM8_t;=XbK0^z;R}X!RY6rB?78Z)AAD%T9X9@C3ZlxP*%}Cp%8EJO=tDWz2cD z8tpkmVS_}>;)F@@rCXCAazG=R9%H1|d;pj)il<5T#`J~KBwpF>#3xRW=W-`E(YK?G zP>zI=ijU59tNJ~}Ua|*6yale`Z$IqsyPA%WIZg8;i|ERy`c9I7!|cncnLO0Wp44t1 z%k?XQ>C{%SJFvuuzTEkcU)|q87Ytbm>UT6jg`DLVhuonLLMW_s4x^XexqEGwE%$N1g?w^@hayL~l1(D4Jy z+BGF_eb0c2vouwjG7qE9$1;t=Kg`4T89P*-gSwk8lHk-tYzQ6+w|8{VcbeAV=xE8u zeZI^$H>&Z)lQnrpML8_j@Z#As`%@RV%#Ayi5feu(`0;Q8jocDPFD_|?&^=Kob9M*J z)Sg4rb{{~eKVEc+)iau><3W30x57FxV_0ynftDVUsjJheqd8Rx^kTLywmnK0PQPDD z2YGpsZzB86y1taU8i&FhdVxj!45IZD)8PA;rS##eK{#-SF_o&+2?Iyhir!qt$y_BPcd8UPwUa_RaGeoQV`h1CA>I)FvFd1Ti5 zc~Ee2B}-@<&nN1&u-(%0Nqy-__V;oz$ou_42|LE_-D~FZ0ijI3L=hi8Q^k-<4Q#dd zV@YOu5UHk(HvW@{%ep0evb-u8@1unOrCJMve_kTLwjYDL(~jebowJxn{Tw0fNC#V& zv>Ru7SE5KQp%rtja7~y4yvmkF&B?y_YUgh(-JXJ8h- zR|E6ZYGC>7>&$oC3~Jl^81G-G#=*zx;ATuIYPIdbfF3i95WCN_cb>opYxU@@k$JGJ zG#Tb9=aLg1Wt89S>r~-Bg%=ztq?zmY({#&7`uxi;`eTA4U81a17xG|3T}sJQQs^*4 zJac8}{JA%%{H!+GI;20BD9xm^j&b^U>w0eON}SF%SJ2~S>P~YPO@TeRMf6-k74>gF z!4InYQQgT>PB$);;ee1b{{7)cc+NJn79$J#YV9T}YoQ7KTMton@%t)UrJFrl7)~R8 zXx4^52*rRQ@A*~hVNM$>=Fl&rH2B;7lrH=HjE)-|fwf;p(>YfpU|ZSB3ie(>k8ek* z`pzpb)Ab1}U-uhdNjOL!c!Yg><>^&P2AluZ48NNUq*u(((!AeavGI!>OiZ;V*EZZj z8JR6S`dB#(Dzc=$+vWMOx=rl;6-y?Bd7)x|SN>5k3zf@ls1#WW*A|=rwaf}kE2|`% z9Io@<9u9bVt1S1w+Dtm6)?(t#ncU2N04!Mki)4qJ;rlnO=>A8J4~|`ri&i0+tayQW z=|kzldjPGYs!*OEz=K~eVW{?0kT(}_DfOedx%XM~9C=z1oQCnQjrjA>4s=#OiVOZ` z5O=vrf^p19IQ^e4FIxN0arlnL8s`Vc;r+Z|R{Sd;U%u#}uasjjZpS=!{8uN&jIIIW zUmKypvz$db|B%>RkAzKe+t{6?X^vJdVkc+C7wpbEN!Jvt!X4+^&}H2Msz1DebW11l z)SR(AXOB_XjG3*Ss|u z`Gw_)bh)J~%&q>#_qU|bTRUgtH>qeEI>($3+kBjvJ{yOc1NES4?ZPC7sc3ive@Cv7YPwX`6l+xulUo_NW{3qlRZB&trE{IlWNq42~t8 z_LnfvXEA!2&BsT@Qs5!N7-Ac8aY=g+OOkejWh>?IP`C$tRRQ_u$FOGNKuo_f06!gb0hfYI@ZPr&?Jach&OwJE$>SduBu@0jUsd# zI|mo2<_Q&jo`X`TCYTdN9+`hJxx+V63(w%;il+(vx?{u4*_g~A%o}~TkV6QkMjlIND8+6etM49xvT8>+jrt-Jp zE0}d&0;IUC6GoSq^Xr2nU{akk(4)(tX?hU5)fGh8utTNcYY-%1?i{<`egg zW%oBKIqB%7^Vow4^og=2YJ}a8{QM!uFJ>jNdev#Prq~hJ@mL&X}y)Ks(BC_e|!=8R;2LhZnT5T<&)M4K z=fd{SZ$&2mRIH*eRy#YyFB$08@Q!~jennk-)*PEyi9*dscjR> zKQRyW*ew=zPM5`+r(*Db$AzwiYem=EEm-^e7xu9_0S}6DYKJ#VJ63D`AliKtseP6* z`C6pNlp8FBtBd|fws*&3mroh)4Bm??GXluq8$V(2iw}?*d0S*BZzT8r94A>BZ^*)v z{hdn3_QW;MI4+J{FS`b4X4$Phzj%jcJNLQkzU4|p6x7jY9_U#db!ZmGj$ zb0e^Ec}lkb+RKB7R`6?~kLY)P@#vyZws2FEWRZ+KJPA=Dk$YWX$k)-(Gr0weYZWCs%HIj< zcJFZWXg`Q;tHOt|S0LH&m}F+6H``DujlXYhkw^^tp-s6F`b<%PVf9ZTZ`@eAELE0! zX^w-OVTRDHr-I!#WhDWl2ZDZ)F*tlEf`<3Ugkl|4GM^dpCk}Bq!S@M9kBq3XYq$>^ ze+cwz`3U^Q#GT`dXeK(#K~wP@w8Y#e@huC5-t-925_uw-`H$G!Vr0HEt;q3(?{KHo zI^ts84uyMX!frGmK10$(FWOf874Hlm%sED_JqT1I7=8^7rtz8Le(XRl9-JZtRkJ5! z#LekA&388#xtY+X{fyv&%x}^*#+tp|iZbPRP3H#{yi4*wE%6Q)TA%&h68K)1b zIX$ra2rUdHG)JkLZvCk5^so9eTVXJQU%WQeNq*}?Ix;Pnx8;kz-FeOAqVH0^sqz66 z-0bL@Gppc)Y#wvo8$#{nC$a(YN^r~75>#g;<8?NcyZ`4;2R{yBH^1s*_VGz{sH4bI z?{$U8%ERe2>1Ja2z=E}$kb!609NB04A=KsaejFR8jNjab!oOiQ2$75TLcH@uNStH=!BgVc&Z`G-MyJTwJ>rB_3sWWAQWcrch-e)A z$ec&l$D;r9E@pXeEL`>afX71{$-pjIZvJX8^^m_x&P_EIHrKl0^FkX|eCaJF^=RPP ze~X#-#6pbtt3&P2_2XSPM#AR1_sDw}6Ev0mL~1#$hg45*W;d=2u*cAU1{9VL-cF+{~CS!s1g?VsI{wbUB za15mAh4Xqpk%3yOMBVrce98^5_Hif(qfKyoSpqRh{t7ogq{1GTPNEhtvv!4RFgv*7 zC7fR}9k-sS#W|1Faeq`D8M<=?l>QFHyN?%A%@x6L@`fh2{n8TL+W>R6dfqCHoB56*_*Vd5R>G}pO+5=D>F-29xBZb4jD*;55{nnv{4Y) za0X}hUdIpmy`-}2KD2kKQ$?}WRZyeGzYS1?AAu^QF5!@v-QGkk6hcVG>uLC*_BY79 zn8p`mWJ1L71CYFP8>F^A5+1+RqNkIR;cc-x=1eNVo=e%nhIeCF(E?rc86Qk{{S)1v z#=dywWjBoTe~b0D3t(W=TR2ddA+c^gCs9%CBz2V*;D0WhBuG08whv5Tvy`XM*5rVz z9!64yDIW0mX+64coeG*oKQQU!mMr0|#?!l@s>_wR9 zft3iduBNElokUOC$)MG!RD2m%S(fT0kHv4zjKtcS zfXB(>Ap1Ot6yHAxAL>%58(`7}1={8w z#?BrYLhyPen{K-tES(pk?0}$Jy;p~5+Oyx7IiR1|z?6ksm8$&fn5Fpe3lsnL)$n29 zbawVqvMxS7y5H3j{S;u%YGBe692(xT|oo_R_$+_%uA3&QSVROUZ^1DKi%@Xf>!Ca$hm}m#AYS79F8M|ZKJlx= z>`On<`S#t~lCmTcms1Se${w(-i?-s4ZL1+d>?};5bOX-2$B^918)3v;DZbM`iTqxd zLR3Fx`sbig(Az{YOvdK|+$}Ul_kSY)#94;Twz&l7r7mEHpBKLo_Y8D5nbVZ!w_v>O034ScL8a%R^1l%Zdd}X4=#|%)4m`Vr^FL7hv3)Z zd<51NjRC!9?d-5_A+S$npu1}%nf&+;uJ?2z`u*L(z{LQQ?gC8s@ZRx-5WqaedE|#R z3C!(S8~kXAXNe^Tq1$tg5Ud?8)W5q4dyD#DqWcflDRTC<<=a5HP|X7DQ*mR1n6Z=j zL0k%tk=;vbATD$>IOSO4VwWoT_1g&&mCli(x?Hf+Y9v|KH7r6+7Akk;l9k2V;mQUp ztP$m7>6P(78io?rqfepbMLF~?+l4=>3&G@9A-Pd>1m4~-fS4^2q`oACxrA>74f+qC zC^x|3R0YmYDDb_7!!TP#WJCIo6Mkkk37s*)_}e}n&|@T9yZ(o8>|81&DGrDGb!Ip* zx(w9NjN7TW(QgynF!jw-OtOp;@?#=cT-P2+n`;w^uT#T4eSMkn;$X*$Kj|#t*+o)c z6bFSNezrghREkDIpZ+OjaYUB``Ne#klc^A@gC?6ls zlIHCinn=PXkP|Lnp*q%&uKv-4KUo6(Z= zzT9rBcqf^(6}yM7r#H7v;AXCVeC{1>+#*|B8>Z|_Z#_vP-Oce(D%k~%CRXHww+^kW z$b(!HfqRV2gHeh~^ijD7JvlrA7C);8+v}t0lCEBKi79}MJs)AI=~BtX2w!v@{ugdL zXNar;KZw&m3b`*QAt&~@7n4u3vOg3}hEhTSyy8J!6ZCZfao?c;IUy;opkMl>$$T}nIa z8`;w7Ls79I2>qPzfSELY@zbX4iJpGUwhU?gl@ z7lLfSC_44V8Px7EqYidUxPmy(tSLwl0+Y4)u!8wee)SRA8`sTN9WB7{E)y=*-U4#@ zPx0FIi8Sc_UyO)}fJm|nmnDp(3#a(-;TN4Loox+oV?Ltcjz=VALo!bKP=h6rn=mEQ zgPRS`hx0DBIBQ-e-D3M0mjo|j$?X-mG<+((c5(*4XKY6eXWb;zg9@R4LtnfVrNFCY zWw`0DaBzQW%9C6_LYePwB&Xx)B#l!%(6AA|G=`$7gXngjxS8A80fkg2mbQBky;eY9Z#A=$KJ%H1k`NXx_nGQ6(2-hA+^MSqR;QsgsKB40$ z99g)GXqj0GUn7!vPLzcGD+&`f>kLMB%__X`tD5Hh%z|xuH?z-a$7t?@_d=Gp3_N*n zz&mos@+n3t@as%8QP$VuD@yvHf3!UeerwHLpULx;`Iq?;n`ru1W+W)+KVpZb%Tn5~ zl5Ogq4^H!RVA8=0_(3m?ZM{2}eW@+t>4&GWeW3+V<6#T#&o85K{6B2>$pV?15hS_j z3COtp7IOAXlgPgCfm@Q(j%AA{W9IS0*f-=M3;tm#cFW^&W&H%AGdBqwy3gQr&38DV zK@Hc}sgml)GW6C78M6DRBYF9z5=?8Q@#60Wk}<%AeW=Yxi_^y7ZtsoB_Ln7ZQeq+0 zBu32Bf0XpPe?;;nNXRgsMzj6H;B)pu(r!N);$v6hWd8?nXH^^d`85yIPdSLbhZBws z1Fo7UtMcTDQf#2hB)~uEq;pDtc>6L<^7F}i@>_JpEYO(`l0~h| zva3Y0_ii?ej{e5RyUIfB_D9&YJA}md?M1hL{mHT2ete(u64*Cy5vhK4!12%6=YpK` zeVF)k6g2u2z*Xz5%(31B=Py>r{=TNrA#%ah3qO$2Pr}LT%%QC9Pc~1yIu=^wT?q(KLYVb(7GaKJZ~D}GoyZxAKt>|5;q>d;yVNmiyKD=3hro_&~5r6BsfBO+WU1mE8O?!{Wgiolp={Xp*yoOVY z;~;Bu66(IJp+_0ur6aO%dRrG>SgOUf6S^TKG>>QnHFLu=CzxNMDR?@Lz*)opLq(Sj z{Ou2WdizZUblcpPBwd~ka~dA7pZ!EWg6=jv@v0w@)BVGqMy8POpS8JahZouSB@_lf z^?)&%zRYQ-9pB?v4HiyU$(Vq8czNw8s~@q5sT7nGBh3i3+;NYLn61diN1hcbGG%C= zNz)ytAKC{i6h?qH?FUn5^y0^1BGc5y8e&Jw(UKjVwH2))V#Z_xc{_DEPPRV^3K)TM zlF#h@f?!ya;Y|!(@4)2XWROwJVRLow;goN)uwdGCGCo7>Z{E!mEUWwl5_*9I$cN(k z|8%HNZ4!B@ZjVb$jWKq>PZolkKqpZho*sXQAFhuet-qU5Wp*kV(;h=6xA|g@tk5j5T5USsCJ{`IEc{o1Igx9aJWK|Tej>c=FeNu?A{0RDSQkL z+G`^8f4f5R@vZ^vkPO1L@9MxZDH1!j{R2O_2TWBfNZ38N10CuH(QTt2lbHN$m@%OM zr!8@(ttkrpL-QJvOk1ny1 z`(^4v#wcS-h$~q+^#n6~P>h)@8^fQSgBVG6?Z-!>(5=9c#{RWn@wPE=r}YT$_bM6k zePr_j$UDcMLvvrQH79y6UzS58$-u(tr-;833VeV}E3LW-ko*9vvatUyyHdIdi%ND(yLuMIH#pOpG$nl&+ zNZk4cmt>8@74qxZfgQI%7*Hy4yFXE4VBG4^J75a+!b1?ECqp+|nnBo%Yp|f>9(ig0 z90OwyVCcI3V%{(jjkFjumUbgw^b0Wi^fa{4S^%CcOYzukKXR}r7N$2ohauylg{T08 z?-q%*ucM^-(b{#wY|%UP{Q7yWB=rF zfASBb`i0Bl>|#67xygmbabo_!;1)BG72mp5gL!S>9CG&9Pw+Hq5ekNtKtj@Rysh>S z;CvV>AG-~^?ERtis|G!zXN(!~ls%Eyf*sONUaYec(W(&QuOBd%^+cEb$jcjT`9oTkg(47Ac5~fuKF>g;p zmsJ`nbj_3ORxiOPX*C#p=9&G-s{!yQiBr>ced&{6(X-c8EauXsMfThmhd(}NAYNpN z-pnwfKh7K?1xX>i=jsh%T!k&kEYraxm2d3!#d1*oaDe_8CIu@u93tiu%pC)xgK6Wt zQ)E|?G4;w-VXv25qG|U87!qd3^FL@Y<%dq}rOiZ8eL01XYgPMEjnO(Q}p#i#1DPKH5=3Nbcc=G_&ov!TEwdmAX<(p@v6w3C$2_5^WL z1{2n)UFjyF#H4i?YPQaN5 zwTNp#5+?6ki4_TH~8Ql^TWw@%3+b6eh7AOY>y8`!f&o3Yq)mT>WvB4oQu!`cVigwHRU$*4CA&}2*; zNj(<`d3KI)|ARHLfBam$3r%5`!Zp(0{|W@<%to0N`q*5$g!spfBPAkVv4)t^F^(rd z{_0_zmrWp2VIjGqQ7IVCPlU+yIb=^nG+Q<82AQLJ1NJ4H!7gm1Y!XX)YY6xY2)@^|)S>Ktx#Y|E&4&bBAZFV|*BjahKn9UOtXj+(x<6FP6HIKVM zwY*I-=+#vGIz^nVe4h@o!a}_k`=Xc zG2w+XQwWl#-4@E^yygfDn7xeqYDqTj}9 zn0x0Ud6?6WJDKlitL?2}RoPw1go4Y+m6}6FwDNoBh|$C({;=A9hAYNZio ztEo7-P7~cSnHAJ?YK=o* z>7%6C!PbxQ!gR^F*9l@wavZQ1n4{{kyH+J;J`ZH0E1vgbC z*Q};M;Dpb_;DZY9x5tM)lU;>ljKU$y;{aUN)f2ss*<{m;AaY{SYG$&01+-V668BEa zaMt1?w!+4jX$%n0oflQ)@s8~fqF%|KzVX2mA(=2*bPQp5CCT1@76$xyDJgy8FS)Vo z4zbDW54AxBOtsDqzgs!8+Rh+6>aWWkpLMg|&HcdQfeU-LYaCoU-z8YjP9*c9?~w_U z-mz0P5n`AA390Bj1cx$G*tXKeY;}7qD7SR5{l*&nVOB8dD-4F*J_BIjDS??+wJ_Vx z$$WK81?yiLF8)q`R?=7qy%S0Z4Qmssw&V+YSN$R8FT#c1q5b&vs6lvlM+oc5T?P@M zDGo0_9%YZF#PUyl8GDjFymr?fU%V4MjK17>i~YW2!Dk-KVhf5Rz{&fQq<_vQJh1UT zwa#Boq1o@@Y4c+%hjo1z7H@}8m^b6)=qxB>U z)MsPC3^TH0S}i%TU=oDh6?dRl&cmnC1MyCrilkQT>q%w(hiMnApz8WG+TSIE*ty*& zbuFH7?tZ64tyq&^(JR5&nXk$F2j|htW`ywh@N$^v{ZEh$)#SR(FNnobKYR%nNXP7n zVA3-VGQPNi$=R1|!jr#}zE9l2+sG97F_FFTdxx0C^sVjnRHqMiUjvto0vw!nnte94 z1=GjhN%*Ms?Dwi7#ukpCoAzEIUdD0`;fr69?{jLw&z7M=$Xw!JuY;FbQ;7CZ4czDH zP5wH5BsaF`!MROE124m0qm_- zg$l(uI(wWx!K6;y*`a3iSp{=-rhSJj&A!4SnmQ! ze`Gn$FkuRiOlwx>Ns9Z(@OU>HzFh7vkB}9(j=^<$`9>1IHMat`cdOADfjBKGXo29I z!?a9x36~yrg)1b_sGA~p)e#p3aOrYmUaNE#U&|#i>Fs93Xvf#uvVbk@tm+dXH^BzV z#{B}{`Ybs9u^8F|Wa-#ZW_(rEamPMWO!0C;HCZ|4qGZQMb-G;7iu|jxh0)4-d|ze| zyICMbe!a^l;eSQ1i`N4|bB-x`7N1}hCS!5l%W#lZ@MM#-KEaxeub4xOESzbag7-(& zgT=aX^eZjEzVQR#Wt2M(JDd%vS(Dl6=WRrxSOrgY8<1a8ed%`nFwm$Pk3*{FgKhmp zyw_TYGp?t@;ksnlyilCUNhCxeH;9;wDuk|ytxT)BN3!TbCy7^4B;&rz8e9tHfdXqd>`&pE1zyze?fHqmv}7;U#%7Wf1c+*F=l^7s-!L$He!m9=84q zfVye!tbBH-B>b`Hln&WQwkr&TCl~%=zrm3puX~LA^o?d3>5h`wmq(z=VSNlzu7zPQ zACZsk*U02KUtk9LB`ML7hrmE}F5lwC7Rj2@06RZq$K=S;sNeG$!4(8vccfxi#-}()U^_nWJXJ7T%Pm16R!fhtm;E-mEW6=$$9}M;1bu z;$gbZ;WCbkp2H4jJOG>a6L{Mun6GrX4FBf{&=tR+*~XFI)9k}yZXD%4#%E~%-UMo` z*^4P}#kctU^H7(l;q+{q4NtyeNKal{%rC2i@_;!;e9M~K@XqKAuMH5h&Mq;iQPU4k z=*PpS#Y6exbK_y}fzfE!+f6o`52VKf2a{gUAP7`xXVtyuF~u{V9PlLA;oFbN9d3~5 zEfII8$pUV9t3+ds#v`Qu{+QHHnFU6(nBxQ3VnE9cZuxj@(lDy$28@JXDlKT!3 zhM#wV4JMJ$_d*tG^&3E+ysri2v!=KVwV}J)05{AjVakK|km|GY;5)(*Ug^XM(|jFS z%GGdCxv~J?<=SFTb`$KCxx-xInqY;oE{%8bMBiD}WY1C+($BRo8TB-hT=9)1FRw%j z4`$^H$t`+dGSRQG?AlxWPL4$nqDDh3;qdJRsy*YRL-vS*~Z#R zM{?b?V2lcwh>ic%lbh$nx6R`}@b+e3d^sxxt|=*TWdmc$-%m1d-ZKzt3s;i4Ib~$T zacjQj>`jOgJ&5djG>e_?$g0*uIWjC?m?tzlImk!|Up|j8} z>M*(Uut)Oizd-cYZW7X3#6I2Y?_gsYiB;mvYVP;_uv?=qySqLPcHM1)lwARsuMs1t z#p&YLnBzjbk}62|pMghAcj3Q)eWa=01N`r1!r1^Ox%bN0GIN{eJZ)!$eN6I!YfGog%Yt6XCuT*}6qjq;h7$Gm)Io+lp+~??{?&TP~3e z|3Nx0D)LF5yKsc!e3%vSkgWXt7Y9x&B$LmYaVh^MVM6jObP@R=;-C&ZG!NmpARTP| zUL-v16UE3;15lgaN(`wouaB;TN1q>rUniuUUx>^g*mGV7F`C1P@8o#==Z8H{xsj4-rAQ>O>X_AUmi}Uzs_sIW&0whp6$jw zp*oqj?w`*4|IDRlf@SM6&h4awOZN*y*UQlz%@&vy9SOcSLU`R{b8fd>>`@jd^6hd) z@Gl^a={*_@#xVnMR$o2j0}6QI>soXIEA)+ygUi}#7_BrBTwWcQY}~BNXHK@}KTrF? zDf1TMI6N7w5|%(v=w&jzV+fzsw4AYNYhnMP-Q;idOLq9=C1PNxjgBLXMcv*=lI)?( zB{sP@a!4jI5<_I8#XFmBX(0rKog+81#xXtr2*5c;G^A6GP8~4|A(EqPU5`Y!XA8V& zPl10AoFFxN4X!<0E)*>@K|8fV)~8&b-qC$SuIrjJ$%PZF`)(#SsWwAEh6HjYA7@13yp-CfeWPM0>kpDZzrKaLsYO=P>W zEDi2fgsHo(lEWHLVM6~cXp^W%mF$zr4DCDc_Eb93-h7m9UPMj%mP)E~Gl-A;NM_wq zj*V?5P?Wy~iX#U?M8aAy44uuB#=pai{B5u%*ML6UF_RlLYO#VT`n+uPMGVrNh+Cq8 zs$32wPogfux3>#mk^Vn6&0!8~bQWhi1`2rMnwXo2YD5PIkzc5%Pp97!S^B#s^N^Lt zi1o^Pc&juTI=&|{v)Om}=1&@EB08A%?AOIjJ@;VQibtsQEDp3oZ}OT^9^53eoT}8G zhSS<=Tw3uovUo8gm^=u=Z^fhM+Rs>aw22N2PeXIlpIp`bBwbk5Bph0IOcEOy#siKR zV?QNT5oae4mBG95#()yZk2x`T^WQL()b)d<`^V$WhsziX)KHJyAF%)Ft%>UJrb%c763C0 zA=hpYXzlw13;Q|X_{g^y-BK;izz>r3cDAs8ZwN-c(q|S*D{9+(4uWgG12q4%6*&Oi zpH}lR_eH-du(CHhEzBCz$bNrRINfV)5ynpcct*=?CZp!QXix*8q+)avN->poTO;} zOG)L;Pt5S^ei-7`jQ)4}kO+em(05$GR6J&rinl35E3XNw>;y8r|3l*0=tC6OWYDZv z7s$a?W0>`eSAycCE(a+eRV-)COz+)Yus`EPTKi98X~Qj<GM$GQvS zu$2*68Cg+E2~kpb&V96GgrucOibz_NO2b~sEV5OaN+=o6xsPZs4Jsnl+n}Aam-qJ{ z;NyADIrshjUe~K9o#b|*AAWqaovrg-N-gC7BNybxvc*f+LaO6Ak`)oi6<5e((UK}y zbAJ+3+Sp5u@Xw5!x{3arkjG`FgXn)Qck#_P8@&8uAhWJBhU_y(Mb>Itz`8t9>~?Ds z?_T1A#)mYZ-eoJ9={H$)TFCSVR2`tBD^Bqtua@JSZcWhbRHstI=kvUbCam{Q=M7SOEP+iexkp6C&gf&& z!GiBzWJY)8Nl%|TBnUn7vXfcjZ9VdMGM2LT?RgMTmId3Ydg@yox6l z3J>u83~%{T=AB|mPCR+e0%n(xjWvhiq<9oHJ$4V}M(<|z#+hu%3L~6LyJk_@IfoV7{+~ zr;ff0NBvjxEvt;Uw8GSe2D!EL+{X887%OHE-6HAMS&|Mx$=?O;^8qR`XD(b)iH6Ub zi@0;4n7oY$fJ|Nk9(H$yJsu;yU!SwrKg7 zgZ=xV3QH=!;`L2l5U8_~7VTU?@@gePG1Y?V(u3k;iCZLO@E3CP6KAfIz$z;|m!A!+O zVGs0I^r)a2S_>bO^@pd}zi`$8pJ~ouCF~ssjVy(H&;cv+MbKoc5AmB%h?#*Dj_1it zVaz|WcK&P8DeXv-=VD8*7#MP?iUzUExVcdC3_mM4E3agHpON@ZQb*)IEI6;pm) z%kr08s6Vr81k4D~MSBZv*5!w+M6r+gZXL{>e*dyRuxJ)NyrNzFc=0fPdH;Ecym5#) zug23~f53rvFXF9LN13mNHoksQkGYY;yu8((Uzl})DTh1(E4krp?_4)H z@puF+Hj$=l+wQS3PqpaeEtU-uH{U^uO8{SA8Op^i*ZJe9O|(TwPxj0S#4^t`8WdVV zZLeHmT?-{0yv}=pnWzbWUmGN@cv1x$6PNSGU)9htFo$=v#`4hXW_bSi4^r8;hz|PD zA`TUaX-<~}ZBKCEzlLoE&yy3N@yjFp_stF)T22dR|3~;FIThpgJ`$()U4<`|`&qoZ za9OH1ohRSa>6dnJyu4%v~Lq_a7&8#1Ni6p$PKDols~o7b_QP*L!&C|uhCaTo*dzhses>x8i6EnZfo3F|x+B60)?~ zMH<-#Fk#$QyymaYo{b4XkK0-}V^#s!-`fdx>&J=@3!j6*O*8m^3yv~p!BH^uzj*j> z^GSQtu49mVstXqQx=;rVd6ZaioUv&N`0dFqw6d_KzSrcSX=^6&dP3>_p^URTbD$zo z#5>g^;oFLD;-|}2!EO_Cy7k>*nyBjunhtVUX7Y@j^BjX^N2}S8Wyz4V>pFbCcM-OR zr1PPQmXN#bD@t!^Vf$kyun&2gU~>OKh_BQay0}qrxx@uujx7&1B&I>D=Xs8V!ir!%hs61 ziyz?W%Md= zj3V9vvAdczM z@KAtw=jF{JB`N9z$9@&vq*@2`r-IiF)*rxTdQ z3>Q>7Uxa<l(R! zmEn=-WC$xh$QosZ-PO-ZCUfsOvEDOWnCFcUw@o=qre7Wown;}s(Q5MIj~8nJ63EX(#ENsfGR&n1m>QW zBHq&*1gqr^iT6FTWyf<+^wmS~NebXXoSoSXr+rAWb9Y4zJuN?Rgl63JN8OJw;+f6{ho5u4u<4yS6v zQQt(J7+m=%_Rc@Z3i|6?9h}s5R~#pJmt%-OiPWkjvdU57uc=z1 zt%fIso|q}Pi%=wI_E@ZU*+k$XsKCQbfnuGjTiC&~E10y!>|#oDWSMC2 z8Dg`t4Bq+m*EiW8W(5JNBC?U-m=|Zno0O;5M;qsp?s>|X{8<|_maa#aM*@ZVx-LtT zO%%`T^P#C4Jv6Q&m(PAYoEKb~2nxgFX>Pn7H?!YQe6QK^B_j+;@uYHG^fd-_g5H4Y zt|Yo+lO{bnM+0vBh@(e}J4HoH9Yr(NhoJXRUHH}810f~OT;0=vE|@IE*ALJ|6!u;b z=2yj0?;6RU@V)e{@^mcGRHS0X|LE@BQq=o!D`^Ug1vT+bBD?1R6&pPh2Tzoz^ic^< zvTUbmUmqhmZpjPoX5;VY7irl*4Tz7MOYPTQ5ii{A#I%kUFzMJ{XnJ`OHml~=r!`x_ z#Tp~_C$YW0?;wS%1Ktod+dm@rcuVXLF(=Ali?P=1v#7hYov`^@P}ci}IBhK_scS}~ zWBOPe73>XBCph*=M~mjTp23~RM-xwN6(P$da9uW!W70R0$%8S+aCo6TU#fe6*xsJa z(v7ppzvYVJCvH`#PcS$iPkhMsp}qmn0dTVpvzl@8N}5j@+u`$^s99YOM2f-PDPcAQ<7!) zK7R$#^63*WC6_`H-^Kc-*ocR`*e1?+6luHAHAUolegj;K?j`$%#}Jj~^UQa!zu4pC zGPqw;z@#?rWmm>j)+wLaEXq2t2$FI-M9zh-U~KGw5^f(v$$RAK?IopHo%gstVr2r^ zui8&O-XDQo4mZWG2QEhMFUOz*7qjV!Hc&ZyFC8EA0Au%F#wiVtQQaW{rB{t|Sdl)O zfBjIwJ-3(hn$jM2Mb-&x_pX3$rM2v*@VUQQIEI>dceAT!R2^h>l=vjy9#|!5OhW{o zhDGgfn5$-h2lLhVadl@dX}AQGJx{X8TnoORMY8)9=6v{~F?qTn!LCD#x??n?!d_TTt9xh}Mb8Al?2N z|Ff25#+Nk&E=(2fJ3Ec9yHiJ$1?OOG<5X6ax&k|s)}i01`_Sc6fQh0YA|E`5UDCH8 zXFRpZ=rOsNB$v-Tqejtd=Q0r{OOs}!6!c!4Lk13bBJNrg$qr}!VVyQ!bVT1fQMvI+ zQr7OrqBiz2Crx+U*f$PuZAaXE(Ez6PpJ1~-7Qsn{C>GLP!zTQWX1@0V$?*VB=(f2A zDi)LByZc0fzUG+G9fF_qd|7Me2KMQ?DttOC$HJ2hnaoisIN0@(d{Qey1ru%D_FPeL zh-uOYlLyS?d^Mc&{6>E6tik)b!--qIByoP>ig5x9{)X2Z_OvFGk9Dz79~qPeUv0 z`WQmjYRaKemjr)eBfJgLQ)#?`Dum3rkE5k;VVA{WI5Bwv@6N8lH&tG=NOCc~JX@DL z%IVV4g%8PjR|RVHFc06zCh#tyKXu~RQ21=ofO3Nhabf3v@nPx9Ec)&(wW!!&DT(k{&1T-IC389yxcTRS zuw(c)aY7M=CGk?AH)bt*yzvn7wyRJs{VVYp2yEi@aeT$RLriSYO@8->0yRiS#RfZA za&9DlYqNkkrwdt$%3AVrTsx6pQHd^zTA-i16Xo_e!i}lZnAs*No?n%PmVE-7|F`ft zIvI}xtYV>0oG*BmmWy6lr{TGoXW@i@g_yq|3Ez|Bq1ru*mNP+ZMJFHhZj5~`=;6mauY<9AQH9=xKidK%y}DHM}m6U3jA0A@XC~QfsW(Rf` zz~5&o_F zztovrNIwe|>bgR9-4VOnwu5+V2D(4}%GTCtg7u3abYG#swD2uV9gw8NUS0ujVS<2l{3k-fgfzz!J0Oo&_aYFV4>eiXa^(EHQ zoT^FuaB(YkKli1X^1d{6j3oV?xdEEL3VWsV*V(L@gLumK#qe_K4Bo;T>E(5)!pts_ z><<2mDQ?Sy&?J?xt`9xUj{l==`iu(O`)5! zRAe*TAC{l47koc6urN3W_ir1IVS|nFcXcN?E_jS}f5%e0afe}?;eTum6W;ogLrHks zNhn?FRi`}Q35gDlXBd|ay_1)*->*iBV#|bk=7f8=%<2#f_Wz8ycm$LRUEqF&F*xh! zQMLkR^DgNyh?JZMv!;942bopj<5hvsz5S@zy>0-ezO^O$EmH8nu`}RnX3Q0DuVOiN z32@VYCehMuWEYAi@m~h+@LtAHIAh1wyJp4VzNi^+*(QM`E|SOc#%z1*GoNsX;TbSI z_zR2M$G~AbUD3>92QaxR1v@bp=Wk0PNgf*@SbLYKQ^+?5{dL5a=p^(!k&ONGUNVvJ zHj2P@NLuE^<=zzHKcRxTA=V@G8m3r4gD+Jaf8Ye zwD?S!?EBF`ckiV$R(xWGuB9;M;&xbPa2S4VixzFy380S0pCh$a<)>*J*87a(w;S%! z4^68fc|ro;oqG!}E{dT}PYWT;EJ-xJB97)C8bG6GSc0+DD6U^OiB8;&0#{MsWbMtO z_3Pt#;^}<)$La#~es@QwTeJAyd6(&%`}e5G{WRPZ+&{Cz6e#>?BkYnQt<$pw#|tu; zoutSeCv{ROF3r(w109{}3@hqe#BZyAApQD=POi(NISrrD0Hxr-LVft~LJQiHOzFOp zsvx~mhbp%(;5Q>K(<%5~yvdKjA`Lw(O@DxOv-9vq$ztkqOqw1xSHj=}av&Cef@vFT z$fz~XfvSY#ZqlDn-e#5sqZ=rrY9 zGnRstfd}57mkG<=obmcoO@8Rm6*wcdr1H;{s6vtjO*MLr$4m}leD^N8W&T{MDll=p z7iZ(4Od%Wc(Vn*_UO`i4Pu->GLw(*e@!Gs<_`F7eMu+K8hqUEX?oEb+tIcz2YA)4q zVpt5n+a5rF?aguc6?_|Wb-Q)9Ek>nDmC6Gn?-iWOmP_IknND-rR+dM z)E#O^dgFx3OL#a{i9WU!m>z}G9hMJ2#*bOaQRCDjeDvM#Fk5>GK2!35cLSGDokMyK zm82B>)MQ{~`WZ^3&thzb9anbQO=b60KyvLRs??mrACJ$YE038ra3*vpm7fT68Xf-d zdLT{B8{<$P7>7N7W%w71c-nJP7TnVBV)f26`fA51i2D*lgHCJnUmb*Q=z7V6H(J8! zjYlDRlQ0vom@l3HpW$DD2Rc!S$V2w8oPEb6?93w&dE;d>*h)ByC6 z%vP8$k|zqa)!f}P70krV^thb6z;Jv8j&{GW`Q^C!Q7?3P!L&LWI8=pBTc^NNwjwuf z>4D#Yx!A$C6WPI`tXS-=q7VujE%c)c8`1Hk_)zl3L7}OE30Vpp&t{oEe%98OubwE_wVwLxE%t)$7>9Z)Uku zl|gBI$hx0!=KOg2{)In%Vy@z#5-mne=dmo`UXorqycK2yAE)PkCc~azLuufeF7CG2 zmCDF>;`IC#%s6N)e6TK}+i(5DzW75_!mW#H6rLbQ5~TPnVV~??olh%!N71C_eX!6t zhdvsAidS^Bz_RT!G@*V1e_r0tVg{HjRnYIRrI#xY@xasZaIrxjjy-6_kw>oM)yE3-NvJ-b=u|^W(}vKx^=b6apUWb% zU&7AIv5#y#s|H_g^uwH@i}XzXPX22AVQ|~l1`$3(;I(%*YVG_As$5A)1`Gd=O5H59%PHgNUv%Y4dX8syJMePK3 zy1DTzZzsM#^So%^{5_CSc89^Kf&6W;9jkag60=HEXw=U$3>QmKFOw=NADKfO_dXV9 z2DfuZKTW<;VH zq@MyK&1%SW6`|X(T$Ag+7MLRTtDr>7kv?_{7TybIQRbu#f0J<J9=ZD&y_~Uis=rh1vO6#KH=ap!7#-h_Yfauj zOO46Jx$*=iuqJLA5u}ZaQmVM3w@B6sYrgamcdF*B;31>O+3gMSm$gi@U}?R85qwC@T|pFNivC>$p)jY;foj1J$E=|pD=tS9Xh zLr{My(eNoao~9MAt1opzD2@@mwH%JcNI6>bHaArb5PlCfw!$9s8jNBnt3Xc z=q3JxeKLJ)ibt*JYv~P)H`s;KR_&pi%?P^I(pAtm5=YAi?>cB z;Q5y;=t0Q`Xc6`ahF?Dk8+OIR$$RVhi2_+}8x@8RE?>r2VIQ;b%1}_b6iaW8Y$t}^ zYA`gQ7N>prjDs(#Q`zYiJkDw&PP<}C_m8N+$3rxExvUYFvwTHt<+t(SXTE|-y%V^M zTR=Up)ZySEHq_>IJ7x-JO7c#9>b~JN4p?T5{V%4Yth_FtymlQ%M+EaCS8GxD$_jqJ zS(Y03^}(MYADVE%7o+bva+k+HurK2t=1Ln;qrN+=BPa=d*6iR*r`*9a?_aac*Q|KX z4_Q9*vsy#Q`f;@BmnB{DI+{i_9e}APYxxG~l1IE;6;18@wl7jS6ezg36JU8F5pZz|00{n{Clj6OtcsnJB zzHghxJ`=B)P2F8iQlk08MV0Y_8rzx--@nkBSrp$juPMAa*`x9hpkSD z5!~!@cuQc`&L=In^p@Ykx%RyfKEplw5m1zDc z322uCPFQcsXAS}0kO2VIiC96u+aj)fRRvMQAQoHo=tp9!tx-$u0Zs=o)-*ZT@r@#}o zx(hPYP-7JyYg^OW$P}C*I4B zRF8rW!}Mr)NdSGf%MN|WYM%JvImX9Wg3p1cZ@u;hwh!Xe5P{oJ`n7y_DTcpEq%<{L8?64YD znuQ#pNCtPtuS40><)G2%Mct3+3anofQDBTA?se@FuQ$KNK7U?J>tD5tMpYfd9c4B3 zW_vtEF^!41AW|0|dWPfl3o#hFBSmDfZvZ^4)dB-&qBMuxnzhG$ioFtR6^ zlwL4m>!uXf=Z**^tGZI~U&}_OY(4>9tz6*gW^=TQ4u(TZR*)SD>+5z;x=l6?Zzc|c z_jzlF27DIw|G$q+fV{>*_+iO^B-Jq)QX-PXxz&fyOlg%CZWvD39j`g0{ZT87y#E2Jq$gwEgGTm4 ztpGM`3lt4}w2YK7p*wt07R&|+IjVP`NJqteBK_JNXB#@=2K`G+4HRIK#1oiya5gQJ zsK@5(DeQ6jBRHR3%nq$|g;(k?LAyB)K{gB4jW@wRC*r7%Wg(Gocj6CUCZgPkNXSde zrDtZIp*x=s=i`FYaGUiNaB3H!VNW;p`yfRJ$%OMspDu#Kf)U6|-VsGlS5i6aA|`mx z;xi2YV)~JN;55SvKAQOBlK-ZF_7Hm>rW*~-pJvkY%BlEG=xn@C?j$nP6!D+=3&LB? zFt^W%#@gJ22XX3XlJ5-Z!_!1@SvPTjszMzJJ%-QL=3&2u@MHVD!;@pL)%Hsk1C>(2 zhz}0h+6X zcmAj%((gW%8E(1C#)fF~v)oVc4z`f5IakGFF3a%V8e6PQzr!$K3)|Rl0ok_~h@K0c z0i|U};N-A=*m9(ZSl_%t_FSEcOEyVi;n7fgtH#aZlk*~p)OK%p`y&XA{++{~pE>B> zmks(m?ZD;pQi>B}Xvx^*I@_^1?1gCrsNQ@fwhK5e?B3UdjL=b?I42SIeQd!`mBmCS zI0*Gp3;94ILo)}ArV%!8sk_BPx^svgFL5bFr))Jkv_%z4d@jgq*VI!}p z3g_|Oov^^Tf=AOw?APb@#8XiVuHI;?cXC@m<5sv(%Z(q&yRRzzz>jpX+v?xqV;-kj z%;ViuSZd-}uZ^gCZ!0__T{vXLI(s#l`*41N0&hFw43?AUp;z)2_~Y3@-uFcD@5!6& zdycOm7g`T7tqgr;>}E~+Z`5%CD;gzuvG0KLE?w3<$AZf> zBx2J{Ejmft5dSL81Rfg8{8Xv^&FNCq(KwoZlbMR5EjLKb zid-46gWb;_j-zW;;h$L#-rpMsA#Nk+`0Np&(w8l8V()|9o(`NOKZ!crDj~sq1lIy( zsyA;6ojz2KCQMS{lAT4Y-C2q&dY1D+#D=~w6VXvQhvnDpWsL+kv~l*Ht(U5rX4srIs^M` z7}ZjG4=*b}laX`J*l);}=I?_QL3fNdT`MEO=T=N7OJ&~^+rc8xTlE@JqtC$>rCOL9 z*GMeKPN%z1Sn(Cj{Y1iZArDYYqQB0Fu|SxmJ4{g~9Z&PbNh*pUzw{IfNR5QbX@B9% zm4&$4p^1$Dp(OUI26|$u3O0{@MP#xR&^|?t_7o~pkxe{&U*&?W7GAJPPw?Az3+&Ix zCfM%O1k=T%aH-uuxca04)drt|!)lC`RHfm9)?r{ctx5FIa~mBHR|vaTKF28oXVJl< z+HsW24;HYj8KwxVFfKC@!zJZ`%k|@WZ%JzM@qpOoz+SvLvIXTfNYdr*26Wfg!L;^G zJ&QbLLC;8EA=|D7v*TNSLesYd_Ul3r?!4j#!Jd(LO0?K+T7RuL{MIDYP2PkbRb*)7 zo)Rb@q9XEaeox*l$%hAq%;PCBUR{-)^98# z$d$bx=EI}3j|%(*f9TcQ$98P_N{qzKq$jJ7{L<|r2k1q+eXUwp{-#u1MxTO@yas5V zYohmSOmTwVYbYJQm>UlafXFvZtS+#Q*ta}pd4od)zuPVn95RnC{A9vbU)aeP{M$xp zWHS`%tb~U~gIHnU46c7#k1v$eqvbZV-bTH(R`S*{xU#^GCdbW$m=JBeTkIk-YiMJK zC2FB*Sr2@l`2h`imFVTi;V>j_BYi#H676colGZ1y+08u#5dGyWxf>n`^3P}BmfJ7v zKYBe9P-y}KFpR^#o3279zyVDPEXeYr-8g;z9BRY#nEd?X%=C2@XlJd1p^1I)%=jaj zUGfQY)`3{6TNm=Lb-~9vEvliU0+&1%qRj382#)B++HX#@p(IP(^!5UpIlYB(^Dfj) zt#YErc34BI`!$pj{=fcBt-$zB1Q2H8YhNvbLyq}u$vbJ7BQ3{Wf|cnkn*-wJnn+xA zKTV|M)dK~N#bD)k7P>dfpv;S>#PdxYK2Nd4F>AU&Ztghy;B)sxKenjChL{fazNLk1 zaJwdc64Qp3Z%xrYvldDxI)h94R?->NCmuX`GqJrFN1BIh!Jm@%1lNEq`P5hhONNhx zA_IZJ(lD19d>L&oJ7zW)XjXNta_uC~yMP?8aD%+eL!x85MzEd-f5i?~DeTwUaNKh0 z2njy-4gRgmhF`V)@V9OQ>r9npH>RxQ>FF9|Qpg;zcqRh_#uUTou_dB4AtUkmx@kC7 zV7}a)5`~Q=<|I|ih;CRY0;8r-df?y@QEI+r*aPw#ez=3sh$o`&0^};TS&s*=xj1MO^I*afiS7SwSK24 zg}Gn30(na7z^~GX-dfX39M-Awz{HWF%S#5qc;yb*?)e&Q2KWLw8UXq${}8hsD*VCA zD`5UHM%+*>ysbCr(!}!N0uQebzFGJ{!qXOvJevS3%1<(hQBh#o-2s~mRzSo>3y5>S zO``cV9A>^By5rQuM`m5Z;n!b5sW9FN|QVZE8 zdcvrOEN=cW4s)lbLfhf<h zJDprI1zxu0quLh@T(}|`bqo&^=cfC_$E{FwwjvugYfI8cvR=Zhg0Z9*rQBcpDjD)D z3cD9cLGHkr)N|MfVQ%;Z`?{1I{OlB|WNIfJu<8z7|F{@@p1j88DnH=U!4o9=sTUV| zN>ok%2c!`xJTkBE#H5S$gU$AlfOm%UA{l`P zpOr(S`7w~ct4h@NTJgX~VtBE`UYs1D#P0~-4*@DkbXLi7a7*weF_V<}=%J1&M=Ru!_3r1icJECYf%adYVTno zWh;5v=q=#!FOXzzD1?Ro6!%S^pYquI_{dIi+Nemw;N(JPOD6 z1+f2)hmkaK8t;!7OO^bDze#Vo*t5=#UKTtD+q{PHnUUS}daB^&_}~tcoHq;0R%@Pm zP{hlf_u#p`=U`s%z=kD5CeWFF9jKsk83ue&;{`ut9HiIgbAt*sDDX^!8-t9YV{bLQ z?-@be3N?AH**jt~EgIL&`-D!vPGG>)J&+v#kqpYo!-HQ=@LuZ`&=sgEs)=#LFbpNj zzRQ#2<2BK9#NYZbz7B$>ogr~gC2>>abR4NYQefhkGe3uitle4yGZl4N!75wW+A8=? z`6^PUW=X`xI<(Fu3Y#)c;?GWHxUXpmXHHLm0Gs zG*P|#4ff=TG_&zYz*xOpI#lgBE>gbCT74s6URf0=Soy#w-`nKl6K_bNCXnN(iq}5) zV928)RQ`Dg7iRqwtyvg_kt6qGe*RhNyrK_}?-aPDwYfxZn-pF5u#SXX`v^Y9(_q;2 z^(J3`AB-K(3(&|!lV=8B#nl`3kXv5ye3be%GW*XDG^krhO{^s-9o2y5pVgf(R#c8MFKeE)e*^7{1(p#oi3=V4^LC?31&r_+rL5e0%*llghhM-w|czUWM7yk zi!b3RtNLRHd_n;3*EgY;9)yDBraxrpmXAnJe-?cmv30d)WKU`Mab=J6xC zLHe?UXqlb?%v&!oOU5VT`NgBr_fQG@(o>2r3N`6nHHlN3M2WVKey0hzB^A7t{)Rkzk`|T zMI>ib93Czo;P7{dkS%-_3yBeheA-^5nwo#9KgNxy&z`~;%jfbl?`-+Wj9WZ# zSTTRIJy!g6KslanxlWJw7=qL7o9yjcY5Hq=4DRSL;Dy1%=;}EWaIwuK$Ss=AiG?iP zGs%~)v8*9p>>ylHTn2rLGr;VC1O^(pLeouo`-6k3;FME2asRrBp3hH&N%M^GR*ftz zQgg*uSC+%tPI-Q7f+qZ0P>wHk5@4J|0yNeC5hZvf)W6otg776`vf@uO>UxVE~3QqvF!k^;I-N)IlY%7>OH4;AxcgLH@l)z4MFzkCb zjOr-YaaEB&Qc`zR$+uPY^T!bbw7eRq;6`oE|fFXy4 zPIp=$ne$hPI_|T?3O5N{Zg?6uf4)ZsP8a+zchup>)-&)^K7gdZuVS92C$P^d6}D(~ zv3KoLndr4LoTzw49xr#IO55e|{_9H!c@c=!#^5pRIk@Ju!PPH==wPFBn0G9T9onHF zFjeM~ML|(GTV9s&iwA|hygxXX1kvd)cEFq|THI-zEO*Z|9ks`qR8L@K2Qp<8hY`7%M9 zO;%IF)#dx~*i^=ft!yDV;VIEI8qPuk9}$Jj1R}1|CR1pF?Tia`Y{0RjZ1}qZw&qJzhtphD$>U0QQCNvISMv2B{$tLu zJtY$O^ju()SCOULLin+&7jUj1Nwn_kBWMX$r-#@?JV{4!%{v3o8ef3p z!g=7|vI}CZtZ4q36L5FM8e*4x3H>xFG?pCZy)G_vOur8`yfm2hX%T8N*pD0z|AeRP z53(*W-3{;D{t1vMUQln^dHQ9dR0IlvwL*>97IA}>N7HW@%3Co_dogt3=?-40H@zb3C zUE#yxhDp*1Z+7u{+r4nvb2GBKMuYY?JZD4C5ISek6c$lg!8Yvs$1I~`eJ@GzPsaNGa;yzMgg>&5vt8;*V0!%> z3=HXo5fBOMXL#W3ldUM3sL2LNb(6-n9k|Z2jeXd<3%aIwzyrVAVzccYyyB@Om}Lsz zL$(*mgl}4u3Gd95)^WIDei8rGtW5Vkya+F6Sc6a8NjgzOi=SShMP+3LZgAi&7*T2= zTAGna!=s#pch4lc=(+|BqnIbKWTTpqB^ChOtOmnr1by#Q?g8jJP5n)q%*BO7on zmAC9GAn%RyaL=XhpgLZgEWB+%JwkKX@63lxUVj~AKQt5nDVCryOInGwrxkTt;);>~ z*+OFSeRkyd7(UQVQsk&o1`%r=v1I;B81&!@Yn!V;CIrdyKYya>g21C>`u1Xo^Ku1~ zDbGbROV5#`LHnU#q&&YltkKR?*Pi7>he1SjF&idx7}T#H!5=TeY8K0FvoUBWPo$_iER{h;eng?7p)|CIBB= z2qE+L{Ri&r-q(G-&N72NBu0e;oVT2t0ML}_K7Bai?mQOs;Mel z%>~qUd_Xt%4A!AtD)G7giPY=wgZ$h%$HEA1h+=FwlZAUmu ztm#L6yRWkjH!0ea-iOz3&LHDIcH^8g0^QlrpLWqDFdpZ;(f{D%D*e;fvDOkd;aX{M6et>YQ#&-z-*~ z7jYBRpWT7QiwsazxCP90FM0H4cwbm&QM=3!mNTgyFp?ccFHX+bov_;3k~&z}Ob zj%?hwFPBGW`@yv%t*Du8$QR_i1C4M`cw#G7REpiEp^6J|ZD9k`R68X37G5GmW&dSk zWIRB3!#k2xR9t0p{333DHV)q(RA$p#7P4RUkt}9XKBy~|!=g@GXA^VUI zuD`gvs%TFQhQ{PTMXoLn%<%x%*>TMO^HugL#sv(U2E%d(ZIm^CPUb=}=G<4Im;cSD zIXmN_*zi?_ce>IyM% zxnn-cqY->K>qD&~l0j!tqEPPi9bIn>q>h9Cu`+Q6zc2cIJdPybix0(;P6JnHJv~xT zjy;OkQ?{}3e%0(x<7yZat404AZGyMU+=y3uU*0@wk?=fd2C?1Kh@P*KQC;gUCJZ?T z{^t###%v&C7cF_t_Yj;P?um5KGTb`NlxmM&ORU!F)Ax0Ad2&q}KYaWaEOhxPdj6>B za}l{ICxJeTJA>X~>+q&YKdu;j8Rs}CW7%0FUcXD4*f}R_-FAnwiM5(ahZkM>rm*#dA%#+!q;? zmhpsB<2pp1p(c&`5z94{#!$mK5 z4E67ALSu2iIai!_U;9MEqpgh+_i--byU7INTl{E6l+TGLQG>ykIhZa=^cr zSKJPYhktj}X`9O~GX0f=REX`BNhJzU*Q*TaeCU0(>j) z!qY3-{Dk~R61Hs>_A08uf=&hgdaf!T61yE9j8-P!Ybs%n_9%K-(Yci?|AW#Bj~sCD17^|m#y1O`0?QRH0E1^ zU|;->@Q3B(xyWPDNz39pTD-W<_oeg?+Yd()_u_{Aj_7JWmz)g<0voX-(WaryraCqr z^Ed0lAqFp+1KrwWZ~;s!UQi3`eUFO z*G)9RwjW90bYlcbvDtzruEoQ0k7C?AW-@fHjYU2011x&b9nr7h4pFDQ@pJzV!k?Q% zB)#(OTcCJFU)}{%<_kk`y-f%c`GRh8;j@2U$*V}L{`^$2F|7y zu(unhu~VrF@KER+n7wczA3dv#Jo`6*?)MuHhGRr7yY8CRVreHS-5E`T-lmh$XJ>=#gP+{( z(4uhTjVV0jY`G-{q(tZ;Rqa-{tZ^8 zM3NL3DKXO7O48pi#X#8^sOs!TLk}W;-g^pL1KgltdEV5VO=MBRoR`XDpk)#MSj0a+=x*0i9AjfYy_e!4pX=h)` z-jgS*^CYX@-XQRFk&q|XPOdJo!BH135|#L;%mV_*#<*FisqvmAe_M{<`kRmiHP!h3 zubIs+wKTT$IR9`d-mts?c}1QuIqI(9cE=A=S41+^HCnXPV=yoInuf0|htRKIO)xmj zo3gvdVB>c&njk%dck}yjk@T?BPPzK6AK!sblMnRwE7xtUDLvb zWW-}yo#GH*Cyd3X|TPhB7m2F)AgUY*UiK#3394B;WAqU0(qqpX<_g_OuQlPlgkDNk=&l-*9CiymBlYX!>YLnn^ z#zwZeqqItC#awhA){pP=zQ*SMoyILc&b3jn+0pbKen zTTy#SA}nfR#AC899gHL3)zLhrIaZ4PKD%CW^_D#G-m{$jk$YidDlbJ&w@=1^fwh?0 ze*x0|XTiSHoo{xqLD`B(y2AD$Cf(n{OgzTW4We({C9e-pbX)-12P?7K{xIxlEh74E z@fe|53e(md;B9>sXheJjd{(q#m93MpcI8f3zvBw_X^`gQg6knSr45|UZGhX4qD4-4 zBVJS~!bP3AEc5MBQuOpVA9XwzZ|-!5F_!5pPi_oR-yT6mBp9HJ&SMfhb^r{oQzyHX zsw57NOxWl^TU>b05c73`H7&>`(<;01&Wydd*GbGKhS)LBNta07PAT{v7H3`i{Vn_1 zp3QPLN3f4qoN;KLJh}W`3cc3nSIJKdVBPLUaLalob{MAMs|i`)-e$|b?biaS$04Mt z-c|GmyvC}@hgjH^Gwk8UmBikqAJpgBv8dq{m2D*z%vpTLz2D!LP42syP0!I3{ncSi zbE`dkXy46RT`Y*F;tOmar%jH{8^|7>$s$q`dkC%jPg3SIg-if-sLp%9GB*0Kw&Ayh zV`Vd-{*NA;x@e)qZRRW1(EgeXX|u#DsaEjO(p=JAcS*<{cnEEWlvXjjAfcvfzL4tI z!gehV7tYPQCJ^@-P*CzpGK^V%W-kjNp^hiAS|0`Ph2VuF!Gx=PEG3zDjj8H_3y*r zdc++bO>o594%HZA@q;{zjKa#g%d9m1DzwI_(e<*SkTLBVCXVgGUp%X!yHP!2|?R$vKQe4$bD}wT5NulNQt_Q-o z<&O{I@l!N!RChV65tr6c4tDXf=6h> zWpiCLN)943$BrUP`_Cl0w{Ekpl?k|Gv-qCXbj2~U+SpWhP}HQpGV}M!IOw|!<{3SL z_FyYiUXu^sMQyIK?k~AnEz2H>J?r;+)nM16CHQS!5%EwT!$zA~;hg^Q?5Up@T0B^R z`*1GaHEsg+oDz2BaWK5DOvPhGd4y=Lfr)(x2@D?u`+j?3m~IzIwK)bPEdh6KQ^b#! zKbS#mF&S=YAFn~BKm zi=#(r+YqM=#MD)@@^G-7MK>(L?5>Xrp;mB0a{XaYdb@*h@K^I{nPVg&(ys z&U_L-35P`PPbvmA42OAFcaq}K0i?W9K{D%zEZwrNzwMWwr9gAi`Rr-S=+D>*y!OF% zxKQzm?QZ*mA0xl;tcx#TK{A6E>AA3LOo`wo(@ym}E}*m59(r^fwVmVc1h;y&^FN(= zHj^HX;R>tf;f!r1%+75HwdtK%9UJqU9k5A3{eqVyu)+WzS8Lch3sW#lwuR_ZX2kCOZ%IHd|fJe->%6Q zJo`XhQ;Q+x=N>xkawvT};ygUR7RMw%!-Q=9j@5O4V@s3^AiB+qrET)6E?T6CHy*Zw zn@Sfe3~t8o<_fyySATlr*?G`EdkT6q=fgvjG0actO;uz1H%b3>MY==Dm6J_4;O45(bT(8^6ph5yZdPvfBzks z&b@us<1~km1$kxg_sDzUq>O&G+iYu`;?zZpXT7nJ!qJkkIlU0%=LNq^rK?<3DRT%upS*RLB#H7MJXuI=#FP@ZI4agfpWg$)W% z*|Px;8B_cOEx%gO;Zip(GMNaKD|XY8)=<1A=Emwl z%I(1exzF)r;sAQwv>wE50j4jzDLh%?KnCo;4@cDeXnJ1@x_sI_=C*zvyfYd}4&?nI zYsTKk>;HC0_A2D#=ArEvF@GJ+D<49YvbwYkljXT#x_1hAs6G9096@Z2mOL>vM*z&^Ahpw(YZ92zM4K3MyITR zsv{2k&Ie!euuhkicHJg#{>I_$O)jv&Si--INyFN;L+GU3Yoxr!7L`h~`N_asd~)59 z+P+VK%d6GksNyPK?Hdj=Ps>(m_b5Zo!_8Rca2JZyD>444G54|87ugdDd`tL6+@-F^ zRZe`w_L)cE)VAlalx~LYSX=3OBdAe^@4jN{rlY`aT?5CSj zwPw@`ToYBmYc@~fr8n+FwZS}k^u!73&6~NRB!l}oHelwN;kI4VM)RuLFjy`VM@=6` zg6f|zVNKRgmia~2R@qaJTIEvFw|IiKPnEZg3C*Kb`>VN9!+K6M;^@uR!M0b@ZTPDH zKESz{FcP%oG5tC93mLp}6wgrd!0*$>(9fO;VxE@LXv4>3!K!0$z}~ z?Zz;5_dgtx5iYn5_JE7>UCj5t+xUIBGHz$%`8!29`oy3bSGN}n(HU1DI&Uu#oqlL} zJ(QfT`$I-=9?5&xO5y4YQ^}4QkJ1|hghc|X3CFiFazB>Z(&PFOSOJ~6#;h7|lfAQYaBLNy&NK4kYHj8G1Rxb-%0 zMN6C5XpLgmPpH#?{;}}rOfl0PSILI!Prx@uAq-o*q5M|?sX1W64DJM>LC+el)m1I* z51U2|-^H^z+VNo1l*Y<*t6}SZ*&sXM6B)E{5!z`SL8C42nQCe}I1K3}3ntjW%(Q#> zvTYup&%~YEOG_B>dmCa>5lETopuz0~kecL*F~^$OyyL30jXJPRA47z`w*WF6w!)d) zyC5c`FQ56!iMzaehUaWG_-U`7*tVn}J$`d7&MT;u>>hU#wC}!WiXNeSv9mXSdZ0h1 zJ(Z=aD&J#&K7{Iq=JDZj^QnR28SEebg*<=IP&FhVn08;kF6uMsbiR(3?d*LC^i@U{ zI!aCC1DpJ)_mT?gbi|%d-J?o(9#^TJoHX24<8K?xvG!(5bM?fYiu*LWsuHJl%hKQ{ ziR8K4MTjWrX1LZL^yjC*Mo|ZN*U&7VOO{1`WP!yB zOwnO2-u1r9zHLh*ewxPw?|OAms_MtriM%J-Mm?gsG94ZAFG)-GzMLB7nx#? zAbhQ5Yx>)f?L{5fuCkCjJW%);#zW#%?VnH|935HIE*#JHFY>ROJa z<5v<(zjT~BIe=YMizSmzUbkM>aulz=a0LJSA&@3!-*yEbmkc1qEIx;b9T5HC#e!`( zg|=57iSoh^-?u{1PkX*{*?9Qr-w)d#S%|FlLhL%S8$v_du*us9swQoPC$F=Fon5)O zXY)~7GG`J5U46jf^9$Iy$gBK^i4%Q({|)x)?xXYBp6Y7LbMR&V02u41jUV@D(RGPl zv}wm}zF49{_c(*?L(&T8gLcw*-)p#UT{zyl@qnJGIz@!pE2!?izSV8+qim(`KE$yk z4yn8^Pi{R#4{5~UZ`XKQcfFgeTDuTvP$$lDv8F+*BI%b$Gugxiz7TZYkF9DK9T>-U1bf3?)AQ{3RYP2pYbE|?Yw+zoY5LOp5R97hlzsNGBc5$n zNYJ>YWYxV8{ITPbq)qJh$h&IDmQVh{HguaaA(diyh&|smKSxsep>Pp zfQuZ=fNfMHD#@3~xF4?2GS>>dFTG^})168ALlsP4u$^QLW@LcSDg0b_iuma4lbn@L z!e@<6*nDRSDH64>wc7-8Z0&2w`m7#uOlt-2=i+-T8ds5Y> z=033hyRRT?`WaJ}H<33+vms#oJNSO-j)3#y#oX{hvSL#Tj?F7Y;}xEu?3alBt%g%Y zg+o{|bvQYe(~B0{j3fhxnKJrP)%M}E1T5^xVA}@Q((P}7CtF{paZ;lG`(Gl=zB8h_ zE-x*U}_*@I0uQ(j<9W zu!r9;G{C5&_be!DHMEWx4zr3j3xb{wNatOG!hyCTyKge=b_iv!e&x`BCx8*210->) zr$gEKLA+>DAxht?$D6y~APy7HeZ{pT;d26*^IjpXy#($({6IX44%p;BNyh=B9H^Si zK77@?l^rTxMoRPs^R1p1XlrFoI(~Huc{zjNEzQ7MQTt4pW~8GclU0OP!tra( zEO+ii5sQ(}=6||D%2o`8o1K8PZw%f_Q-;OU7qFq*_rh;ITf9Cd4zv~nn(s5jt~u|S zg~4;lx!#%h$_A1D- zd+KSB;k<}U7l-|kZL+-a`c?4XJRaU@l)>PG88AI0k8F!tOJ^k&(Jk$hx$8AqXg@QO zK6O!?<8y56z+ZxSNi3Wey-s7NJQ11>9EIlj z@x<6~JWbS}FW9-Pz^m~WV4vIaD&6`9W~RRyQv#l`ZJ$#yvd|MZA2>_aO3OjL(^*#S z`xU3&JWA$IE<@+3q4b_g5wX8mhqr(0(ahV5xZqMOJEs{Ad4HF%9mdl5@NY7keku*G ze;ALUfj+3R<{El7%A@&PEi{|&Ps4|=eD z>u#{SgKYUpaWBlj8ezWLYgU=(51pf8A*3@*=o~*%kot7Xrg57(4LdoL_2!Ap#Ku|l zz_Y*1woH5jnO;J@0rH%^POnOwEJe+hJZAc8gTS`Ai#@7uVbznY*@C00Z15Ocs5E#j zbe}H46@N5g*Y4}=!`G`=+2(?sy`5ECRu2aA^{wD}eujiw9|bAT7Pcn21_R~}f*&r~ zlCR&)KySw_rs`c{qb&5tl_jI$s$~=I8I2^fqyem+wF~zQ6kxu}V+yGsGhU%A3izg<|+s18#nS7KKFQ5e?cN}sFbke{cr$W#j_xZc48 z9k!V0q zsfxXtsdX3@-$fjDNr~LzBka=l6~H%`(dSQ-Bs=tfFw>-DRCzIyeDNBB52p6RA4?Cx zsoASo=BH-j;JY6+%~vx^tz~d#X+PR&QNvXJYlX1&dug4b$W3l7WI3#YEx9s<6`ae& z@d^E4cQAu9{3VQhI|||sO=D8MdCa!Qm~CCLo=(ynBYg7=B|ZBr>ABjCOvl9r%@5xt zt_mfBf+U74ogNC7k7r_znF3~CbAmHe4~e5I+gP;-uPqOvldrGCEW}+ce#zbnfuzdh}ma24|{x!*N{UCVu zUn)AK*x=u@>)`RZ6R^_Q9NOFNLO}3WVyzgBof!;crtietV~cR(753b}VE20Zh}^;A__0V-H-kc-+h1uru{P z@OUAODOKwredz!=v-d50c^nUML0^f_{sr{ZzS(rk*->K7@fy)LH={;e3yv)xK$8j_ zd0=cI=8eqY!lrR_(XSe)Jb9f3MUMo@y#%74`4Mb4Zvg)T$0WN(o**;(PQbI$gQ2c| zm?ZQ-I?1(4z`o^SpehN%rVEW#u{V;jXhjS2v(kc72c>9j!(++pRC#Lp;|x5X??VO` zOv0?(36Sr7huwH#i*nWf$njAxLEShH5?1aL^3+nu>!UpDKKQ|0o>) zFog8KB6@(7t3<|IG}&zaj3xa%g}b9JfVW~TEcM?9%T=z!JZTl!*sI6B?pRN@-1LOF zKO0fi`vU3dSA~9}bG6gVO;}Olgs&xw5mKaZ2kU}T{Vwt>`zUl_FuY8+MiHgOc3)qN z;}cWCe10u6%^wLfGz4tYSp;rJY++jNopySFv~50b+PoWR8o7mfcB| z>d08aTk~b0(sLCuH>L9Lr8^i53Wd`RBdJY=hM?_bLhgBQf{@`6Y*%xuaA`(ABDr%F zt}HJ>UCAgqsac&?+U^$pS9&l^%u4^|I+9FBCEUAIfDukL5Y^8CGPAameRZQidCCSX zX*?&n8!2XA3-fWjj{{VMOas>kk0i3w$3f8NE$Fx`q{>6&*aU5|r_l=1Y`4#Fz9oBa zm3Q1EVaG=u{!g|A^Sb)d&OgKX{8X`1McN)tiM`V^!kZz=_XJUS@Ltm9GM)|lmqsHL z-MQ1$c>eNJ5;5pwD>0sG!$;Xxk#ps<=!)87`1_?SjQz3#e&pJ-2+3sXC?iEJd~T3$ zkClX<9;0cjPd>lb`WG)8(1VC8^=MbA!iW0jvce6|Ao}S+{IO>_q`XCPFD#EyhwISy zU^|%P4k25Vld;%9AihcQ6<&d2%3@%V`eBRW=!H{i9HFRE-FX-?RS=1f-+3I+EzVV~T)6$rLuWY5!W_UREF26zMp0If{}6VV)gyOLrs_#Ex%9vR_+pUg zofNzCj6^19wyp~}8!5qphPCW(pXKmmp*&CixgVz(UuAFaXyCe(I@oqB0Ap881CN92 zi1hCyA+-cImh(A>F{C3WvpHEFtH0Z64HCK z*}w;LASQi&2t&i*3d*ElPt^TCMA zG-rZ;ryaBvr?ZKZY>}QiBJO|wBehM02i;WU8&7LM%L6qo+kY>Dk~~j8YYmng{=wWs z&$;Vik&AM`oZAJ}!5@!gdhYo(@@2|NV9TVraIA)G=(@`^WnYl_%5C(kTsSF=HK4Db zPGR5es=>X)nk)J1@#tP1UTG`dYZj$=`ecj5Y~fz$lDkiIR}LXMiq3pi`gZhPn+qpC zEGHj!ItWHC{YcX`e>S@y1V1jCi3iL6u;1bOaIJl|kn1}HI$TDv*mwGNWv{5r{Q&3 z3K{)#E~cE>$8MR3?>kq-UFWo*_`x(BKTM4k`;CI5W_|duPrc-rOrcPqeh(Av99fUe zA)J2x3LGku=lEdln}e2BWdo^B{p{+b&|6F19)M=F?7#X;n5meR8`NHFLUF-Vwcy=7+cA zc^4NLzh$7Up8Y!rtX8E1!#@azlbS&O+${dIsJouHvXbnx;gaMud!by6xAd3bjOub!sjMdw%WqX*Tdv}X zoZHBH8qi(ok|e@@ADjET4z7s*t@7nc7T#|ye(xPjHAgmKzZ0jJ&ExYZ$lKxIkWi8p zDQb#hE;2DM7A>@W@bE@EUbJF2hD^@|k}#LcOQjJ!#BgF3(3aza`1adMbo$t1xUFLX zDo9-=y>gA{=O2iRKISkT(Jx`NE(xD2PGZRx1d=1|xsU#1I6O?BPfC6SWtukpzIHzJ z_?6+(q82j2Ya(ph)xm~{nbTWtSA+?=_L#l?IXNA)loa$tVo!XK*jay1WI;IdCAk1} z=}`>-62J^Kcailg<*8TW6EHLzMqd?{pyN=2rfCyN)QG2`B_9HNtu~_G-Vr!a%q_~V zmZK%s(mYGsi(V$f_}oTC>Y{WHPfIVMW#wgb!o_52Y4j1-HP~>u*RgnOP=Tng=7ZxH z6F6|AjT_r_lk4x*_zb<3eA84j+sR3jXmPO+qfJ{I-yN?^YoB%geC(EP0{`M#M$V07(fTBA9U zue4U6(`9ahl=DDt?z9%K$f)7&BbK}^?>WH9{PY4A;i>nlg# zxJDTq>LV>Oc+a5z5`Z0niJ15MB`e$f1Vg|aUH?93RcF=l@pL;ZI6s;F*YOX2#-&(y z1ttk&J?hal@uH;msxnSK*u$!pRFHqAA!J3PH-20#51SVEXD(9l@IiSpd1UN_GDl+J z&I}hiTH1}Qu=i*CJ{#f1?A?;F4zGn-^GjF&n#0E82}13vt@z_o66`tP!EC;BGC1}! zvx@tUUy4`4tn$Tl*u7}-;(aSIuKB<|4c2CdWy@IBrW@o}_E{LOGM0Rj`bvuC&xR4B z!|-;tJyyQj!$J*4bHj)-;x)oT?3_6z6uJ?ZSKZ6Z^K@|l5zzU#JIR+bhh=|DS;b=u zHa#kdSZDoV`-iQ=&42CCG~0}SH%cWN9fr{1UjF#|-Y&_#sCH&Ma1;iaOv4?Yvm|Oa zzDVYYc_homcCzQ`k@EMMPuU_7pcQ*B5}MS4#s2yEY@1>=j|;jpR;{#(X`ME4l(eqbY%sAyry z520$jVI})~17ZHt$B^Q$#(h&K(Gxl*uyOPt{!~^4m)nfO)Ax3umVyxsEmr5h<=Ysf z&0||Thrl6~2gH44EKxpoNB9_V07veePwIO+nBnQ;Y_-1ytDorYV=G7K42){%69+k zBT0SihG$l`ik&UexX5rdJld0EUHU1Rw%5$X#^yH3qWgO#UzW_Yd6^asUxp84?aB(U z<@7Sh&k1K!{zXf=c3R+xC&TCf0kPAjPUPC(CP&gw(gzl~*m~+YVfFpsQqxdYy?hhA zi7-LAgiMJ2C+@P(jfB)~!)#W=bDZ~9iRB#h#o`M#nBVOq$x5lDx>|`?du1{4X$~hI zc}7JoLIpK>Boijv!{x*(;k4m*e19J{E1d+Z^}e0GX1j?qKu zeTw*f)fr-1{!$3gxdnCEWw;_Y%Cv|H2K{hrqgLF#f%MgV>8bslEY@usHGv8PYEWm+JfA9`W-tgZ~PpW42Wt zZ;$7}E$gAP+zDmfchM6m*`#{T7=HZCY%Ei?fb@*lOwX_YHV!qUGseh3V;`|Qpv9J{ zBupXxyT^m<>ksVtst5QXrXEt(&0yD4r6jA~*;Cy){$y)i9dX&=#S3T!xONp|RJxHw zdXBl|(w3V$7%dnIhT6tH{yocnPjxEg&sPyT4FkK2J5kR=lRRc zpur;_Gb?q-eCd6-cd7ztJ8OaiOCUK?%EU-DL!5&sHHk<-sU@5((7pxZECSiPVNT>% zT^RG*vR3%-?qzm9U^;9SnGlyuU%=u~DPX?sw@tgq4!*g#4|8wZNp*}(G5BO33|e>= zf^IZ1gMxDs$3!(q3b%*;MjCii<0cH8ISA3svDTYQe+oEkf=TBSRG`IrtZ-7-&Ty>Xa*5k?&R(6 z0Qj!D4zhQ2vfGc3OYUpc2m>B4_BiGiIj=Vx)L&||I$aGqW@sppx!eS{dE#4V#6kSn zkp*fGRIkSRY(0CIq+@z}_vhIRyMKX+kW(Dx!50(^Mr2#c7F|lqunr_R-js>3Zv?>_% z>L~K%MmQ#CC@P5_#$Z;5{--FeA1On3y>zCki$}qoY5(x%x&){@kd3OXqhar%&FDJM z9~^D_)AdF6xNG$!oD*=CFS@BC?u5*V>OmKqD&WI^qp;O}C}t$a;1Cae)M%c8#t}F0 z&&6=&x#JTK_9y-e%!8j`wqh;Z-GV7NB-44XY=JO6KO zI{Pq24Y%%of@8f;V(zsRQOmr-bhQ;BZ-bQN-LGMyPGU;EpA@mtK1nP)>XKw#>1#5} z>MN$qUdPSM@`NKVJYm?gFL=bM1V7InivvxTvhJ1BM80VVEMDn=mBAkLwp0}}F4V{O zBX5$-i_z?XV+Q}D)1QyF)yI3wcfn1$%V=-Nam6=J+(~}3){s?@yDuC3kA7urt2cdf z`aiZ`c?fPvtcERmyV;1ObKLyYc|ap$Y-ovsn;JRzpMEAAFtz|=78K#DV=j^ph0b(* zNDPjdSU~qJUx@AEo}v2eTYyAGd@nm3vqtZy@u}C@mW_IJS?Ch{V5u%lo2trhG>Say zx(0|)9*utzK7d(?I|O)r$9SbZOio-bCp!l-)94S-vHdeV+aR(XD&^=ZHbziOE?{Ys z%1P}fC9=3Y4(d$4lE_pMm5wx$xw`7u{&pOGbUTNyo<*_B?1@6-c}?6) zLs)p!1r|A?jNA$N!bCgl#W(XB}G)OKKXz*s+Xh@UDI|WY!(TZ~q$DyH&?n@bpnI&7zc;?GI&E`zPQP zK2b2qet{N!DumzD*J1QdBV1j+9?E9+l4o=`Xtge8Cc8@U$9xGMKcR{-aRKa{%Ox_r zemFavs|9QNDhkt04ESa>IS3d$7M)v5v1pzx7R|7vp>fqjxm^#`z6os3^wU_n?t40tHd2Hc;=UOYWXLgSk%Cv_w+^Jy6< z31KAY_GR?^kVID7-T|vP-0b6im`55BLV*iq{V?U;BpKdJu^V(As!Z2CBCt;r#FQZbVD`UUVzcnV7|#z?$*BA%7Y zs!Dm9iwdt#WAURB$*gyO+0U&Spz%so7&>eKA5_*@Ieg3uLCRzbzPc&FCw;xC*P=o& zOdV9YP4oujW}D*bU!5%DjT&};(PiPjpGeSu=Sf~`G+w_U!*3^fp>$0W=7_ASTLUJr zxDlbWD)cy*PCrAA_2vkAtJAPM_-fVp?;4aonI{hK@sPbigT-E(%`+Zd$NBfluyes7 zl>XU>6Q7@w|;ym~rA zJGg`@ep%@3X2-)ugu(FlnW&gJf(GZQksQ-3^epqnNlhaI{oLua3Pj@wrq#JeM2^2o%|eA+~SvMHHR-tv}atA^u} zF`7K!;b#my7SE@gn?xVfdcv;{#i;S)78zb$0sGXZlF=(vsIl6u%7$1INm&rV=UXlb z-z53qGWsnGof<(Tx@*a)<8>Hep$(>&vtZn&N2uAJ1Peybhxbue*|7x%^zy(^_GnQc zwrzb#R!;0E?6qrUOV*rXCZcyt{Y(tpS8u{q4)UNAU9 zMd#s<)%(VAdz4+tDn*)zjBxJjrqb3TB_$P7G>!I>tb|fZDv^{_2!-d|*G-|4XlQ9t zX=tf$gXZu2{(|RuUaxb`bDjJ8eBN(mn3LAx(!L^(4IYrsst<;tcithq`EoYXEBhl< zxaeWZP3fGZES+QqWRYjN)_8mAZ}43(fE*e+kA%cc1o9?F%ug&uleZBvuV35Hv1BLD z^grgJHSnj{rtXVZ%yj9@OJ=C@iW0wN$C+b=9DVoR3!T^4QpIh$q#86~A7;ik^M?AKpk( z;r`Am>6X+Pbn@mc)Ok%G`snI2x;LnpuHPTd{qv%^*2x>(tKR_Ez*n89(j3N5_8(X| z$DY$kvuk*@#93Hy&6aE0CexZ{7pb4)W@1+W{%@8W z+<#CeKJU>Nqnant_9iu#%e{B-evKM9ac_v&x8XiCmt?THKlkthryt^(v0WHhpN?(` zCV02;0p_UghK2p*#od2e1mE@zV3nOKTQlyFlnc9oVY+Rk+muE!Wy1!1^vHs{+`I<9 zW^3t^PhI#uzYke%aDuhOu7}+09qiV!LAba`6_OsFAfI#Z3dz$lF=JA1JZ1YtoZ|7B zEX&^{lyp56Mt!y?B^wXP9==Q^|@+Re(M01-Z%R3S!zIu~Mrkv4YDIbGK zuJI)dY%(QHc>KcZn788OH-|}T({w4k&OmDB#B>0@g??!s6~#yIo*&fzdLaX%QWY6aO|SIC<=f)1RUOD&Jgg+B-9 z;oiFKJn7^v-Zm+jo++(oFE5$Xl?^(TS%>D*4eNUGP1mzn#Wn?geuc#R+uoOc+K@_1 zd4X^+tpc9EEkv&;PSk5c0n7gIk2q{q;c5dGGnu?`N-q)w?FL zntVrCRQ8wYYsK-&F%0kcdGkGwf3vO2+Qr)jqtR1;Jg8dkXU|$?EF-Co2%5U$wd_pj z9P5imY$L&VsVCS6?7)L#lToow8>%|AY5oHN--jzh`K^m==cZmT>uI^@ziTT_yV?s! znMn+rm}<7&GYeaXXH_&d{}A4GcgM&RTZA4*KMLo6Plw@0)Nt$BBse8s%m$v`FFLep zG1I?u$@GGGXxh~%j9a)DW50QbHug63@g}?#X`1Q^&MHWXc69%xP3tz zRdDW#AYtNtwxdl>3HPT2Lm%q23b9Am2+DpD4h31tfwvX%-pI5H)asm?G!qBjjo zG#}$wi&XS^JD(Lj9{~aJ>R5J2L!1?~3g>&TC(kt$D3`y_JP&)|raB8Y?57bmTX~U; zEj@@?EydLNk}^%+nhtM!R*`A9J6ZZ0WTU-|_=88QsAGXi<>(i4>9Dh|eBkJ6F}p~O z$IkCXbz6<#L#_rba6U@MpDTl<6|?ExZ<5F8h%XOnT}6(rs!u$UDn%l+G!;^UU@6^SP?7suvq|lKVos)dk-qNp#go}o{^vDb$P3=)Dui= zbg6&5R$|Bwr)zWdd269N9XaeUnQ~wUHdLHtX4*2*VyEN}X&w!ML7CV;rW>tooJYDw zNDd3jle8`Wf>7OT%H8zR@QYCr>mZk4@W@N7*u$Im-<^RU+XE!-Rt~#1Yc!dqyAGe~ zY=Jd%;xJ=}1q-|Q5)3u|6Z9l2TMGCa`GTmxg0v*6@1E8?fPjcA>YMf24YA$4;k z+;5lO2b3nFVvpHiuU$bM>j%S$NNYYKsK4t;|6gpxwJ18+y*rq#H-cx4U3B1)L~>2d zn!oYtU)j!LsE5uKNUZ#d9(E6j_rU`+QBfBQ=ii`mR}Ry;m9w}v#L{=Up42JQj2DIM zqkL@@-R0)SHw7QylfGW1LfQjbd8&|mkBG(#aF>?8uYxUS$I?FI4zmr{e~KmXkJ+dm z;dJYdMm%Hpl4P0(;=ZCvyxe0f$t=r;@DAzSuVNqhop(~&sVtRdmJn9Hz#KX~Xm}A6JyD>A zXKRF`5)Z*9Qx2ww_JxYft(Z9SyErj0ja6SVfTRjlK73FC%1Id#`)nt1``AZl(eeyu zboa-VXAnY?PqMhQ9V~fN4*2~@Cus&HSaI2e^;uIabF->~Sf%?Yl*xm)NilY$Ul4}W zp2wc6HPKu(5-#W1KVwfctyJ8+>I80%OcU;SMc_Zfi?ZDzFK|fT^<<}7HYU3J!;R*AHl&9U zU99Lq?;q_1tIV_PR+tA_dQ}&OW@H>;s3%3m~2-UU6T&IbBp1>NPf9EyEPVd0!u zx-uyYZdQjvSkXB8bz3?vPD`NaLuzUFyumQOt{&#aJcIUDN8(eIK+ILnu)N{~n3V7d zXBvfok9Q3WF6jwk*bb><_JmAmo`Z{Qmcy}oW9YXhCPMeAlfnJ_Q22Sng+-2S!%auf=S|?&Yl9^$rS|{Zpb%4UB3xbIdvVVX3V4~m(+@<#-%ZJ-!$@{({z$KX(cq4je;Ff ziSVxQ3~QE~NBWNU#F25O@L{zf_ucXxjb{&|ufAMzNgenbPF=~tzmxY#UC;#3=vKq# zWyGNT4>|BvE+p;K$78$tGSV;mDOOI-fcZ1BF_*Y=nq3Ot*Ty)r#J-pq(vR;AG^H8; zma~8;>D-{gmh-Q#z~%NQ?3i)}?W9hQL(MNVa?T+J|Gj46x^WyVFR|c`B+_@3CR8nd zi)I(IX?~R_m}G3iPu0u#tZ}+D)5(>aKU3k~2K~l^uV?Y6YL{6r{bXp)D(BsNMHZW! z3A2d@6c&AyGN38E;^9^2UzQ!Lm-A<-N7MmbX=CWF(jR<;<4bs~R?7-o%xPlxqx5>g z3k==Sfq54H;g0%p_+Y0?US;ftn3YdS|ImlIQs0a}AO6FD66(^`~C5 zzq8MSyq|BJG?#Ux8!G4!;rVinD2C4e3BTiR}ee#CvV<}|Ugh>8bAr=)>&%^jLed)OQT6n~4Hjixli^m+M z^PBpsQ1eFy{iQsL&RHl=!+Rg1xpbDyfT;0Z7ILmb&PluMY-lh z%0KSD0oDu{1zW$YhUJs0`C9EGIKy`*ZaXdqb=9_{RC6RdA^BDmzDyHJnL6k-sCJu|okZXqITW1uyMr**K8^>g4Ph>*t zifDZG_#wUwGZI`w;$YJ~Y5usYOs(>onDrbfvnge{CM-(8?^gfV;z12$T|+bGB?rU2 zhlfF~#DvC4867h`k49r^$xP#BSYo#V?V1k56#GmzadHnxP>F~1ip{9kqJ%<$KWMt1 z6P!Qvf&J5ukz4ET!;`*dyz1o`G+Z7AvJ0y8euEF`{%#LATX^GE&jjN1eK=kEDw+Sv zG{-DM1u7bJl4;MZq1I3diAgzFefHNo;e^ zpl_d*aI7&Rvgi(wi(O0RdlxXdUs5S-&qx=!<_g~WLj_w*8{qwL6*7NK6?Mq{${dd8 zviKp>`4({}b?Ci?pHzMe%eI=*XYZ28MRx_rd$<-I-;Ks04*&Rn>^q)I9}lAyE+g-< zb$yZ|!(tOn=j{Bm{P>y*y46~a-}*k7?mh4tHhOE)g`z#!d%S|}^Nb|UXc|??9a=fc zE1vc7i9vUq3Z^G>(8u8vieq!&vf(aneKMRnoXp`jrsiYI(j_#_@g(`XD3r8S+2JjB zZ=BRriX&xuT<33zOtwFZ&AFQmZ_2%0jC<%|wx0|p)x77c)_sRTHU%)XOqWb5=mxus z@}T`@Im;Qeid_6oAi!`OW=B!EFO> zgWN+3R#o#kE^d`vAbs#?_EhJ4zddP-%?DyPZVfK4aV9OnF1&Hoa&AfwlLsdT(9Pd= zLZrnMEbO%ss?W&4t!^I+e5wHd*4ko4%oVcJK#yw7?ga|ICz<(<&m`9H5jyc&EUa51 z))*<#D}67J2N9EaYUwjJI^#c3_B8@HX$LZ?lkGDk)n%Zq2Hm+ogRC9+joCU*!@uKl zVaF2>I3X1%2H#a?+n1>GmkPuH&2SUPy$nMymo}W^br2jE0?5|y z#*B>pV(2-2`sDW_I%bw7adFnii@}34zZc3+Dn5vNG$Y*XgcbO3u!-^b~i zEc)wiJTa;3kB?ov_~TJ7RKepW?0D`6zy2EVVpB^#&2$`JB6km(WVU>jk2ZZc%Y=T( za0h&Sm|r)I=Z%#U>2{labj9hNIRAMP++9qGT0#^Q9DPq_%{wZr%=HqyQ!?08zbK-V zV+_Gh=3|@87@Yfu1JrkZq8U#`a%G9}>pap6vxeCj0Tv9Emai!5j@0 zrqjZ@4mKyPA5?c7!uCNipk{o88Euj${a@7Mf+2*Lcl(bC z=zkRzOr8me?i)p)rwRCb@I67HmsAf(MQi7LEU%H1jX5#>Gyfs^tySq zkfT14{<(6S4n$wR?6fOrPCv){fA^*@yJCrHTpQ$H^pM3Gc7pfYV_bP}9O`~Aq^&MNF-^xI+J8neZE+4`IZ5N1rXCZz1#e?U0od5s( zCo8zPo{XH5$_E~y;IOkB9F+XgGiyFF4JCEDxm64M4V{k{G%cxVwJ)BKm6OV`hR}X? znsDl1D;~+7E(@M>3Z5@k#|>stE^}0k=>~6AymUDMj(?rXTALMEuvsb7dpZcJC(eLR zlU1NWt{CMkHQ3Nk%3Q8?C>rg%2i5AjXyA}W@IF+0zcCuu43u^<_R4U+@(&qvsFekJ zMq|<{M|dc&&lZF#^2;CM*^UNHl=q9lnlHL^LGV;W*TW;zws)~gqd{aroH~!3;tm!S zU1ZLyi)`SPHdZx587`$CVjf>sVzTKUHgId3i=*%lho8@dgvU1!76s$sKWAn6$2-}J z>j#)yzdi70|9kQs22?}d`O_rbbgiuPODFc^gTVUz4+!%*g<%PD zTvH_$Ump5~BxN5{Y)FB%)pn?*^8w!`{UiqK{OR`SFH#;a7QQvrptYG7oRRhudt6M> zsaaQITpplqgHB-F??L=8)x%#qM#H&ozC58%x-g}67tqir(tAni;r{eF&U zId?2Ms_1}2Ae@!xFNXPmepnmRk7;{u#7`}9Fc!?3Y@fS7Zpe5>&gun&;SVn|c8`f5 z-r8JYGyRyf7U#_2bvft-gpy8aoY__!N(vl~LrY0Fbh1n)$KUfXF zBkr)8OSVGdRVqgzm)IEz5-K%`?2!oSd^ppaQ-P7m~_v?_nQj9a(OXi@!!nu z+8HK;Ci1-W5LTTom)Q6h@NIoAP9CHH8_sDE2sC86sx|D!5f6;Mrc7U-Jb>>n7env% z8}RP>Z;Upuhi*?&M3pV_+-puB7ScV2nKp$(;ciXpr_q;h32rCLYR1sbienI4bhu%r z32m2n%-fs}QaSszta8s$x^Rb5<2`{p6qS;su%MR38Mvs|_u(Eug=CKKh<^ zB)FjuE$ZrnsVP@U=lCUfRjW`q@_Yv<bzJ8qg@xWp$>%md0u9l16IMI^NQSdV-BGXKu7qtSL{&i zBCCGf#W8($fx{p*T%j`V|K3jOJ3^ z6u0j<#g;cAHgFv%^qndG`&Y}OCK}Vg*_ncI_zH+Saf$SG7>?sgognvi1bG%cn^Z2`MH03+93B&>_)u zgFJS0&W0q%bLjrZi)@bgP6m(9~OD!yU zv0b*w_zE+6CBW~GPGnlhPo}f*jqp+bF_ zerE!*!K>Mx?YqVNRnu|vSas4oZZ3|69+CcM?IuaG;EPOe;^f?CPx?3cB(P&i<`Y+ST}ZcjUzY~Tg_;JusutFDv^ z(5+;!`z%>kxe`o2=?`;OZ5B?9-b*$g`^%C&Y~e<1Kd`UbM$#)y!TjSjJYlK~Y7aGu z-`+NO8%pt3sN{I9?*h-u$jW-HK=nTh68 zGf9x%1Y)~H0|$Gnll5LrEXdJ?KAO`gF6f*>^lDdP%7M*nacC|3??o@ny&5H`h}+qK zB?aI#ON~peMH2kGi}bC2&zd7E$npJvA8%iS=AbrNyjiKJt6#>FXWtan;!leqlbA4T z-)14e$&8Fxd5O@%<1YE0HL~w(|1tCA6jp8ADIDy2Co}6RAqrdmv5OHOSzxvySvogc zaQZJ?n$22>wt7*8Jl#pMLvFbY9BKjMbIu4KFCUe>>O0uK!+J8mcT%nO3NZaq(Ij^K zMRr2%4cWV^T=*lu5d97PWep_-LV2JSDKT?{Usn6bvtd`rs!2MSb|^+HW=6uqE55MF z{~f3gHKDKijc4y2y2JCHp3r(s9#)?YMMeABXkyez3cSYCmy_o}{Gx~WcfS==%QyuO zz>>K>-beOFpN7k~q`k>&DKGi(3Lfb;hwSKDf@c?>V150!u}SaeLG{31)D$T8JSWY^ z5B!8~Ph)ZNsSmPO zuXB0iz~dpzbJjW0@caUFi^yf|N41z?mMgW`szJ&YR*Ly6XK>dDLl&{4m397W!R^~a z1l4js;mWVmblKg%B=+-0p_FRvh`!|XedQBl62b0C0-9y;w6WwXfka9dU>afsWFaYU~2v*g<&1LVrY0Tn4 z3b^+Jm)*-^1tCxiN*^4SaSOthJvu7-IF<@?CZrPi7Jbs9A1aJb&k!ao(Pbl*cd?$; zg)A_spSUesi@5zKWn`4(*u{Dicz;9(Ea%>0U*}~r^|T@(a7!tv^?6(Vx@Iao%Y0IC z=hhanJo7YjKA(haSabY?P$di%7jzvZ zD%MHFVDu|e96AVG(lyEOu_tlXpCHIK8$?ZfQ$hV&EiO+|;608e!0^>oFgbrW{}{0l zH&2kK>$_~=S>kDYYV1wMYPX2X2Tr6%_vaI*ZK}e&%4}Gg(F|%*hAlMzIDQ}8D0;u^ zWTzeSu<>*+_SB&pShhDnQIRE2vbKP!C7WfoF8_#6Q#G-(_`fM;N#aRC^~Vo!%CVX3R{I_CiPlNV z=lVmpPYM-ZxGML)JCVtLUJ)<2@5Wx1+TwEki$v$g0SKPB1Lm5&VA`p%;)ZjS#a3vr z-$y3nJpWiaY>*4|oVr>VrIs#T8)jHh*T9B9XkvbwS}GRkO5TBWj`YIIyF$pZB63r! zRE%*jVnwfJkf)FCu%9E8X;z*e3!POgY@Dg-vg>YNi61tE4No3J3Op6b>RyJ>U2;hI zwJ?_ZD2i;GsxBI@tQVT5tSXPt@6FmI?tI1KCT6myL3nf|h0InzBu4C%K10o)Tu_K2 zvd=m&I&HnnI2{AB{D-5=%_*6D%$O&e(cHjZ`!95fG5scdNtqzcV@@tg_wz}DsH`}S^v(Gr9C29_wYg(viL1i zxvUAt*Xlx3&m!^6%Nba?xG(HoZB158wPI;9N%I6Nc`dG%a$yf2#c0m z^A7b`7Wa7=L^`$+L1Q)p;yQa<4 zcRnDx!~er2&63Y@A0ulHQFuPaU#MHri}w7y4<;$NgQR6Zh1G^IVX-Z|*b#@8N&Ue- z*_e%yvQw}1|B@GHr9G6~R-#LzVej8#u;FqHyK)L>d{G8lxcZ>rD`n2-ZLeVd{{_J2 z?-s0fYZp;-t^kYr2Ao%Yo5Y2ya4~PYSn4nUqPPD8gE1a(^N$FYQl`@9*I^9Zau~Dq zM)HuHRCsf2G8mrFfUr|hG;fq1E_tBKUZ{8DONDxNyka0!wp!7z!_?`W?D;TKqgZ;b zNnRokX&1b>5QD$&gpr1Jbc3A^o{JwwgBJ7#$rgZB|7LJ9FBUcGTEsvndD`g}MHgSZp=aMB9`T>q00tX z(mcxw?BtikpuZYiN!yQ|8?_gYUf&KkJobZ5&v$sbTM4|x#=wtasw-VT-W*guD{f(sU4aZrgT+(?klQa-a_?<`OnGJ)CmTT1LB z(%8pa%2Z)aJns4G2j>yv0@Qh*82r^1?iBBj%hGABphvE5^E6Kc+{y10ap#8~6#6Z_U zu%eE@QD;56EusM9Zdb7@Kg+SFjWtQ0z8I2hl;{KX9^gU=SndqMH+^@=Ch7;Xj0NXN z`^eX9eB}mlcw>s>^L&p^!O3idMJToySdqa?Qb^o|N#xhr(fFmL6{cACqV7+F@Ib{T zF!_}T*()qCYGNt7IY18M2Z!UvCsr^eyn<@4xDKdz0e(3p;`6vF;%?)_r|!rhJ3T(* zo-0X2YqS@y+GIiF{Ih92yeCJ3>fu9@4vf;sV>jh`VobCrt1NiLk`yoDj6ZA0irIhJ zcKL0fb3TFD{MQF-=eUxg(>)-#7s0eI&n13pBCEJEf_&Vlh^D3*P+6QN=-rQYo|qAh z_tt(V4%4-<|G52dy(UjIF`fZ6X9J<>yb~%J+Mwsn&BS4<8Mb9VA&1Qe2_fqV?Ao>- zX5RNime?OHy2S}UF7(F%m!6T9kU-gznm)Mb?|!K2f0A6@w@66OSS;=pa&ai`!U2oE zk~F0u60>Uz+<#et<*8HfN@WGxu5E}u<_S3KReyH4csWLXs{*@q9ys~xGoqmB3!mt3 zc6&}flgsiFRSMF@P?acH_qmy!>3LV`p4`Oa*3r;mv=To&9EzFO4q)1d(_l5I0`LFo zNj$9NY0_0jhH5V+Cz@)Y&;Es|ZBj#SZdY*DF8)YX%x^%&R1xC3EO4KH0PZ(b#Ow0% zs9|sm*E_0{^ZVby?&Y>5^}Qf!X(+?o>h0)oVhMUMfWVf6G>%p+3f?TfyA0n%R?=Nr*7Uf=8SZ8~k%#`2 z=XWQ*piPYdJmAJdzA>zdM?aItM8y|S*nS+6G#y-zk1V7MY{FpZ&01*gcR_exvl30? z=CX4)dULmc6ZoR@2*}faV7YAsjkxg%Yx~_NTQ_LJ0F7|aJMTa~oMTzz^yj_pZH2{4e&yjiJ{Q0mIn&kuCO7W z9oWRzW2xJcQ{p+{6A4?7ZEb|7c5sLqR&&ZAiM5X(~ZE6@7_^ zGmm;md!b(Gz0k!pnf_@s!S-A~w5hhixXN+dUFw0~k>=Y!AAe!bN5J^=O;~u@l0F!F z0}qVSq}mESX`@XgtR7K_-+Zr#y3>2`XZ!kqL!kx_9Qy&3zQ^O?85Xp1`#Zdv-pLkk z7R5b}%2ChwH1!2J42bFE|8g$TEqY0)<}6^&hD>f@U4`3H`=FWGF^LO0hgOd*fwTY8 z`J&z>thRLz3E~ZcxpgCZ`b?dU-%vyNhyu9MKM-!0?7%*Cn*5xKJSCCF^hdisFUOsH z(^L~SI>Z+Zd&lGYQWY$#RMm z!YXjv?ND~j`YPV@d;~}Bcca}hV{-0&BddyEL*7kU1AS`JMe)iquvs<%Z+tDlGo?ww zo7=~v|Bs(AX{rn><3@v=`fnWdu|HLjdLXj{8CgAdg0QA+E=)PwpZ0UgXB%#tlRCi} z&-9AI9i}_*#H6F(b7np)3=BZUPwCL}UKh%HDN5npmIdmHl? z#l84qi?v{)UWLxVNurNi1-Wu#71YgWfYr)-@yw7@M0c`3&RDS&+{4^TCI%<|$sL4~K}Kx#k00#h=?W`i;|@!28q-K7jxD)BRy^iF5* z;yDc88^aVk2IAz5KWxvbIXGoT3rtze(XD6z{VR1zJWlk+6c#2oe3m5 zalOIIOPUQkeBgkf~v1|dDWZiXf#`e4smb6{F|w8!*dM(G_D9Tma9Tf(@k`A zLLR3(xAQ@fx4=cpYK@8CK$qNkL97fsX^oeR%s;jeTh2}b3y*_Lc4rv4OZ=vmWLFw6 zeH1;k`Wy%eJz1MmsBqstl#K1Zn=s=Pdg}UJOl+=(sLV4gWREV7{p2n&G$e1|-8XQd zB8&ML9ucC322soPUTpb{Op=iL478%6N&e=4F8VvV(?{wCV>VQ?g{=QD6})fc2*t5aiPHUBQl3zUwC))Ni83kQ zF~kbXqyDm@r*H7si50NnWiH$h4iP?C7FV#Y_0bQsjPr zg!5On;VP|SvTa5IzVTO}@+rl*QXvBeb-&6S_EzEHz^`BxmyOp(_M`uDux*YO_p6rjc4yT2rL=GGCG!i}^ztYg3ijM+T@9|p*$-X;`FM#NKZjfN!&OsNT<1wxIGenf^{oIGU4y zLT)WW`vq~SUIETle8iG96CgcC6XL(_#|(lb)Fo-xqcJz`>1CS z)kB$$-57)BLIZJWIRfX$j-bIS!XUQ4Dd?3g##seHxU5c(--iUydN5P$tWUz0 z?suT;*lFTBMIGk2K46*kVa!~;0UVwVz|;E8s5^Zz9?>;{y>5!+=!^5xz5I?j=#3?W zkA+}wL$0PjjOJ|GE+{rk!(B7_aaFZWR=;1H*XKQEH_O&y#Qi#!wWO2mXqZM$yfUNn zkG&vD{}gHYsYZ-=^_33nKbc0}zl& z(NCYVboD;8NzWcW_&3AtEt>Sr`e=I3BOhMO(85p+Z9e-#G2a_)L=Hqtok?#!9uc|- z4eI-H#SvL}@9TWbT9iO`uki!->>Nz**-SRgvZmYqiv_Rv6#V@@5%=xw$t$~C@)6bj zVaHx+hg?>OS%*YSUs#RrnyOi5?@(Gc$wZ2q^~RB<6KKTXT_{-Xho1TlVu`_7=`5|D z6qc;!`yP0rMc`$)zu>S~&`+Jp&m4q976)QP##wM^>mpk#rCylo7}^!)3R{kLkOgmg zz-g5->hmsu9+2a@#ioD)@knh=fkgG49#!Ffv zd16PGOQf9$m+Uj}bvHGde%GFEn^Q`PPPUNQUD~WhSz@iOdQH2^Z0JfVW#Y!A^4vv+ zXm2xwyUdWo({e?q-rJ2Xo8`>!T7Aa~Axm7FBTsAh^<(c3tfx&&ipi4U8uVA=FZdpC zhyM}oz}DCbP@4H0)}?!6Zy3(Iq})nswLsl#CkvOY{?K@bXOLlRi2kKn^j4rMuY3H1 zTpU_YLeB(KH`lAe$AR6cntnIVt2rL~uFPf)9tZ;#p*EEWP;hGi=p*Nv!9_ z(#{E1a5nN7=3g_1pqlM8=Dj?*pb|)bB>fPZ_MC)I3J+3Ejc=ZMyE?@ z#gBmh8i%rhA9mv=Q%!iTQ^{vmErLrO-ROVMWni_+h)?wV14@N|Sn^~ws#XbX+%Ica zb@eFTe{C`>{dk7%DO*p^O-Z4BOS2@dk1Ji}w2FLMzl3^a&E+EwWdL7ZPyS^rg@Q|x z6W*vNGcs(WDwq57&_);9W1Sr=iFyxFV*_Y)s0_MY>wysys&VC*ZFJt69GqQtgytla z!jGy%nz`DX2Tb_~lO5MmL;JnZtiOX6KZ}I8@=no0Ckm44QgOn@U9fCM6ZSae3v(vQ z!&&@*Hb0K@r)?+bySMiE#ls&{Z4cAV=MgyB)Per&W(}bWA3&#g3Jm3yc+KZL+9g== z^nHKG9?d^^^R)^$idn?3etS*7OqSyx&X4BH;|^hp#!{$WH;lTeK7=iA&O+1ieRQLD z66QVirx)IyAb{?9u>Ii?Cn$9}`ojZHjq?H%&%L~kxkbfLFb z7PDg~i>TM{-6*!D66K$_c>R4#`g-tO{xGe^C3uq|d!S|pUuN$|SC0ee{%a6_D)o|- z_DEbw`z>^wnJN|sw2%a?|48x*d;WIXEN-g*fbCxPmQ4BYBRg#p4g7W_9J4PaH$VR& z0UF`>vMB~-R$FhYQ6^=C)<(WzBfq9ge2*{e z^2J%OGUN?=I?0wMtu&-IdfWL3t+V{*$SCe=ZNksl=SX?SV*a|T6`I=RXlmCP`f8d^ zrIXQLTu`XZ$BJ?^*g2Xm3UYHjb+rg*+a7}M^6p?{yNGK1sipG#M8%`?opfbnI}>1TVdsir0TAuqj^-!zR@i-13Q@tB`aE?hd~P zSEkJsoMOMA%FEtfXvn9yDtH~4rr6>Mf!^v6?eDMzt@TSlzI z4$m$0KRXM4W7R;4_Tjv3Tmo%Bq0CQ+_0-dZ^V&IyRHb_#I@2~p6z7LRkLp|4)vCgW zC!2B)-@cU_zT}bzwtl?WAe-Wym3-9i65992MGXG(m@j)!!$1Bhr57NER-HOPdz||T zb0VLx(SPExKG&5;4w=Cs`UyO={yKJ4_oinpROz}$?P476g^}MRkI`C{%9)}$J!G#( zkB?c1W&uHxgERr=yEwvsYi#J-GqbS5wJ(2C&?4}Km!Rd;0@T@9#D}+Bp+~;TiH8b| zDqk-u$GTzv@Tg}N4^FCtA{xrdSH(c^s-tw~`0Zr!@EM|7?+UzNHJR_pdIc-YrqSMQ z1L0%qUV1cn746mT$(7n(u`$ZaxtGOkzIv9llXt%*7{BQclWW3I-%9G+M{R^|-zPx$ zw9m4wrQsy$ujG*Tx(37U_)y2bb`nSBfy^!QlUVrq0T&+sMyyfb5ta*?(4mDsN*dDq zD7h)0JRu2_cjL+L1DR@O3Fuy5Ck#kzf^VPl1o9vrd}619L~_TM{Ti^p#9Ho^GMuE2 zd`iX(0r>E9G?*EGAibKMg=T$sw&mGcIHu5nXHxn><<8#Z=^=?}I>!yq*SBNy2Y(#; z_ak(Lr$CQx2C%|mJ>DX-i09w!F6UQOlc2v5Otsk+3pa*i#j$d-yCehVY|bU8&zIu! zm_i)%$qx0N_JAshU6%WxMa=Z&c>QOp*mg9H7>4bK@H?3-Tk^u)Y%;~{V_QjCZ8X&1 zpFr}X?XXvUIgYojAhvd$WJGEMYx*BW=N*sL`^IsStZb4QkxELLaqjDA2$i-iSD`6jw7HFrPr$v%WNm!srw!V^#+5p z<8~VwS3tU6WRvsDZlc9UFFLaSE%PtTnbh>&EZaO#!)qN)74knqpX*XN&a?@~CD9W6 z?`N?XF63?R)c>ZUmy4Lxwj4}(;mK+rnS+f}Dxkxv0?O*nVP1t2eWEmvxf;-dlalvg z_Ow+bKFt#K7wO`|lq>i*=pzL0zeJBF4AMLIr0`sm;Og4Dfz`H*1(|bc^o!k9P%+t# zn=LgU;pH&txaoj(ohlG<=MTml*ocEu@6u-VbyzlR&5e7|Mx6zRrCD<>?0;H|*lvcY zDU;xSO$`mdJOX64j>3cUI>`B+DR8N?oAMhT({Z-WDBq@wi=L~Jr`tc1JrV?duCs;A z(RJjF$z;?|QzS3mU!&`X?MUUynP{Rs6STZ{;;wJ{xM$m9qPC`)?5!&${$`0V>x8Ay zg)@Pc@ehfn`*Mh~E}~8nw%FX}#Px{=6N7W1MBeusU8t6ihq8OfgN2Di_RBx=%xok0 z_&=fOqcllMwsbX5Voti)In z9Yhj>)>H10z#x1aPj4l5Q<=X>K48{h(skGstT&{R+gU3><>CMnv2c0W4v(MA-zq!$<4Fy7w)`Lc zIQKM|;AWWMat&8e!HctA@F&(;lWU6|Y&Hewq4(|GRNpHU<_fzCUpqUxFti>e<{Kh7 z@+7p`4SG_t;l%y1khfz8mg#+?o?mTHy=XV8Y$>Ltw_czc83h~GXX5^q^PzIon^Ml9 zhFjxyp1vtozyCfH-zc$hvKO>pk`PaDKC1QN2 zL>c(Cd?tl<tQf4iqjl)kP3#n?1({lLQGt|Odm(if`Ic90v0tbpO1rHn0^bt_-b|7rjv*PcYYIQ>{@J29s|=9Y9Ml5A(dUSnvI-4 zhL;rlQeP*x@|PZ;p;=XHp!@z5AX{QU)@VP-9Qy^sY8Uz8^UAEmkU8WQ%CUtR?re&{ zLotl+hp71PBzt8F48%vG#Wra+^kp5*l9<3unB|EbZe|>crVxb=TXyEE%k;SHB-pn8 zKJhgh0~=+UxH~3W;ji%7|9W)|Z0?yz0#p8@?p>AG=6nVwbtF^I|H?4pSRz&gjb;rJ z58@`t+aw@OoUc;%M*n59By2_kl=)qN%$~83D<8}3x01x$?~2jd@C%IYd%$IEKZLzi z67*4xEUzhCxB4CK5SOopn7VW&wv<1|`~#L$OV*k5@>>YI995t>*_GH9_#+Bkhjn>Z zxjzS9!f(A(Am4l(Wo89JyacX^dMZhArz@8<}6FMH6J5@(YpaYV_?5saJnLYmriK6;rrU*3BLpSs7v-@K2d zHwH@K`?hb?MLwT=%hjWCE9ZiIUK)<<&jdZ2ccAKHg;N}^K*DD|X4Uly9PfQsV5U`J zoc3G@P(1+!DUG1|@;EvkDPZ(3hmq(v23RQM>r>>t(Q{M=SnAv){f(O-$)t;Hp0@?3 z?2AR4<38}Wr@gG6_F2Df&xU|DaejkJ83x|(AmY!bv09=pvD(cYZd}QN2xAq#QRf8w z&=6-=)@Q@xM~875mqT>=C{+AbX1CX=LCOg!xUYAK^(xrN%SZhpN}C&<8rK8l z-wL7o9Ky28?EfQCrTOR@`;9D{bB-t{?S@k`?LeW`0`Dy!1t-IwK+%cSaCh7pRK9OU zxch=Tb9@UaE;HmFp0j3~#Z$2NQ5>H7wu)>`>!Kz;y|n7@PVV)yVIBX5(HZbyxpALxG<^`G9P8JuA?o$;^k=e;o=o|#5fpU&)4F^ ztz(&ULWQYs_ipB_oiZ#;`b~~ion*a6y`s~C_rfucL2|BWBrD%=fvp?i5Bla2bbYQA zY5P{hjgdCN<@*l9*O_N%;qgTfs20t6)d^YrGewY?y__X{HO@B|`eJi!U~J?VcKw?( zh}{p-{>W>3MY0eMoULU-0;-5k(_~;4wUJ9!31IA-%cSnVU-s#5B1i^(AivHIku9ka z7;#U7ti4fd<7{Myjt=%P=YBGt6HCL^X*)^Y9(D4@OO;-?Phhq>1<+56dbkk9L~{3P zBo=Q9LDD}BGiMi>vbrJkz3Dq(GN!B zsMXj(@~8MX+5f45m>-^m!x`g<=FbQ^^1T9$)sYq)_R%QuZy{(G5&G0|2Us**MXo4OTeAtd-|W`jkyU?V<}6t(r%5GTNx|#So;b=b)?6mgdWg zkV=Vpcy$yj4{~i@&E(dsa90AN+}K@|~b@lxNnV2+lY?j&0HZ zN#piufO)tdUYGs}=P(D`!?&QPP_PQlTuasjFBG~YZ{W&KZC=XOjc<}1fMu5?*pFHM zwEV*swnXw2TKFx8n`|ysZuMt_&g#+M{G;F-^hln>NK}^gh ze(QsM*!U_B2Lvx*R^OCEPq&HLS? zuP_i|>vurOzYR7L4-2tJ%?qsRTfy_wN5)vKfDCq|puvWvM6_=seD@!L`Mbta*PFG} z;~7V9{n<>u9}PwRj2I-V&cfSav2>cb2Dv=z1?>+=v-xK+2%`dYF~4Adde`3JHssym zwiZuEB?$?#eakBP@qRnUMmUmzEB;{FA_^x*IZ(sYujEmF29f{J&Q!>Ikmad2h0T8m zyxA><(|0`Me9cyp@}JM?&qx2!PhuryR%g5+K ze1~j$(?P2iO0%?dQbv?{$jwKW<8T7^p>xV|MK$s${GR*>&X@B6XZ5yhs2;tC8Hnf7G~*WrJNV%Ib9wBu_8#Js zqKb>%_JOWfYnfA3HG)| z61YPrgq`o)MR0M&XL@Po6ihYC0uQ0rc%vr|TwVZ(*4*nHR1eGSM-J~-E)m<{wSiRzve^#>wJ>J{9v}(Pry>+PHVlL7iq|!&-=i%@B9FVmz6N{RC`JOzVWzPsE1wM9Vdj_E!K;jH7nK^OB~h ztBqTY@N=Cjl-^v;w3I}^nxa18Q_c?t8>gD|TuT@v*{S8Xs z-#1A27vwTMOV0q`sm#{u9N_P6tin@6rOb5OGJ3w~742&{#vTfc#vc1kn7zjcnoKPC z5|IyF_j7Aju?}#_gHCExuTL%*>EPH>36`Jk4Qsod1uoE8^xB^VqlRT!g+J=7R;CM+ zbGRIa`j_)BT{Yo_Q3&lOrFgX!VD6)6TBD$kl5d?suID1C=UBqu5@~R};+EmY|h11%#sFbQN5IysARFH+SNI(QJQ~W zP)Td9jv`AVc(O%F*c(?Wqf-2KcBo;!kg1X*az7NX`1DB}Hhl;8?k**HekPzE84me# zlezkeU~E$n@5D1H@vB=sT|D>?l#~bY?3Y)NQ659OMY5?prQ{MPjr}`< z1n9#s9e*U1+OVTF5J*bLCF-FdJAhE%n zoSWx^7jDcTS8l#%Hps}bddCwXHtYgbZw$t{Nffl-2Ek;nN{mz8RrcR+b#xmSA)G^m z?C$#05X2m#Pv@M+QD#lts#&)nZ|hBVr{Pj|#+G+vP0e<`PN5E--QLLl$vVnrb)APz z?zd4Q>^$GT?HPIU30R0?N*{3G^KxEoP=pzac7ZVF_b{?evhHvBc z6~mApy`Gmd92VR}l*Ck}0S3n7qc7L7$0>?TmlBeCHmB*k(k$vc(}>;KB=GyGDO}w- zOw8OJP&HNyL~iQvZ$=9|HP(Ss9X`SKp0~lzt7pN-pJ}x7L@W99t&Uy{k0E19lGrs_ z_eksYtN5gOC3@dgME^W#F#PqIt}GKFGirZx+e$j2?Vk;<8~cvv>Wmit$7<|Boj{w2 z>y(TbUd5Wc)`5XRKa4*)R&WX*pjvs6q_9kfD%H(kR=LQq0vQ69j{3#4+nU3OG+EO1 zIRU=%ibSM-44Q1#hEx0Uz%_rE+6b@RvaE;jUp@(Ssw7G;+8Cc(Hg3G{z*3xd_n3*or;;j7z`TBbJBeZIo2 zhI&%%@*2AC6_GE?Rp3;Ziol$?j}|^X6i-ip&;3WiMWTcOrLjoIxKRq{UK z1T=?QvTU&`Yd$`a^aqW^s1`APzDqRK{~U~-LU-eSb0hM_7WB@E4&X%Gpgms>L~9J- zSEd5Crwvo*;z;!G3xVH%Z(vc9987gn!(*K%INkg~f!lbSS?_!h*HmqTVQzpvU!G0( z7Vc&HY!#s|FM*5`m|wCti}BT^AEff+e16x#T(V(bD2-kx#_khlq&_n4SpLTlHy5h1 zZ%0cDe#uzU((lIp`)?Z@5_US&Mg|XYttD@Kk%!^8Xp^ zWkq&wlQ>n^P-VaG8%ICL{-N7w4_Reh=iLHH}QGM4x(TnDDI{UBl~X-lVZY=QJMLBQwe7mUIX; zoz3#0x2fWIDby>Bp%!;!*jEcO;q`?AVj1y^%lz*-p3ik7eIvJEMawqSRzE|okJv~` z&7VVS;b!m=a>I-6JtGU173h&11ME|H3}4qxgB?2yV9HYqT65cj|CcVp@PAFnMeXxK z?lqmryxM|OW!2bY>l`qC^Knqr&EyOUu4A`}If{B4^Bq#p>7Ym+*iY`J3$(*<#Q#n-?J5_i!xy^1(<&F=9{*tz zQ!^Lcwyb9j&5n?UKMrJ}jRuKFS610|y)fI71MlkNGgYoBp!QlxI5jtnyKi=tJZNu$ z1QkF0_X4>m_BTN$Kbh59bq(rG9?}U-y@ns?WkX-;)~bsHbJ5ZqF!o;i*|T>Kac(&xgXds-?o*<0OiP-NN?6 zZ^-dbKe!^SW~%GF+4XI1U^%53ueAHnfvf)PD-&0cS*^f6dNcudRcgT}<8V&PC<*u7 zypJo#G}6LG19EDyknwjJq8>&c!GGf_vQ1Wvf8Vg3j&sps15f7wTE@W_>qa{7@C=-9 zBhA!poeQr{ens2L?PR>lBGe3$VehS$=ATB4gjR16n-+y3G&V?~tkMZ+tMvn0Jz3WB z!3laoS(y)%N~4DRo4`;z7h~SG5jo{tJo-?QZTjuS4=id%=jFjTpeJA~cgE15!Q*Hh zeI2?=w{oFZ1~_N0OGs}da@zOau-*k>wgn@L*upQ_{O0TRIMeEgklSS0tHav(@0=(e z=o`!5+9kp|OAGUdrbGN2jRVA`=Pa8Sw~f{JY=Q?19BsX?ry?)^7L(#euwQCZ*o{O3CQsVyVPZ$ry=D(;6>qE`H~=RxS5Q4WE1+2s4Zd9Zh- zHftOF0oSxQps4IVx-#V-glc3^-{Ly*$MPyl&E`Plt_87WN3)Y6=kYOahjD0XE%4ex zY|iln^{e><4@a)SKP^stb&nl8xH*VzY&cErna}9GehOXeHjiCgCQWPSyaTI;mw4wF zNAP>7Y@q#CKU9gn8p02%c#_HtxuKShM6gjP<(4 z!miWQe{3T05z%26e)tR{$BBZ%rR~@krN~O`k}D6f{Q&kYyK(6ZPuS_9%%?rHW}B2K zByR%joOoRD*Cs$p_6~l@&}4RPKo-QEkAf4;%6Mi=Coyby;d_VOVEfuSY+0iT^;hR{ zkB=?`ud`D?Y3egfi*RTEnONhUCmm=y`Vc%BB}OJDNw8M~EE!$r8Sq#5P8?e8PCthq zVMc%0MM`Bpa=soa?B&=onDuTf{_*i(C*fh-?ERcZ3QXFko9EK0Fflv3pN=nq0`Pi7ui%i1T~s*@GP_rrWcN9ENgA}i6ISewq!IrH(MGO=Mu6Y;Sany zzNZ=Qz?i%>H8&t!D|c!d|2)xjvwXsBN{heR#+ftC5Apz^|EYASc0 zKJ~uBWy@C!_eLAOKWdiX0R2E}r=EjYZBZzld;-&Y-txDmzNCsj-q5YpE<`^r3A#r3 zK!#E=t$y~A?t1)+n`puh7b| zhPW>&0*q>g_kml<>Lu&3*T{*Oue#0bG#kc!!yn6 zRs)syuHjV{sq4%_s?N|FMI&JzQ{44nwmM?h7e-7TmHYs+p z%O^UP&wVCcK1OC28&wd^M$U2IgO&}j`4+d?*^WVI&ZJuj>cIpgvmCR*WYu-)W z-(3Qq5)(FSjyfDRyGKU+86xe)QDll!4BkGt2ii1W!J)Qu{J6}~Y%We?UBp+Dp!$t$ zT(c~=_1S=3t{%v3j0BU*3$aDCfY=|pNYiSYXphnh`fO-4q%M94qsuqZ!wq#X2a{p& zpg4N(lV*1tY@-tXCg8W`hLA;?1~CyQF!R=BM()K=reZUPxeXWSwytyJ%llK%x21tA z!uycibCoP|6~P9pR{HpW9xPFPOtJ%GA)@*YxfOH*Cyn%Gj;HBBzE(Ins48T6RTt7g z_a~sUC=FxgZ3o5ZE%c1?Ji7Ue4|cSyXS&jUkXZuKsZA-1RG9u`rnRmHyHEFt{*w}z zY%&rpj|Xx^3Ucg~)?@U?Vjoyh5`b9(>uUb!bCgkdN{;6iGqO)o5c$_+rQRpFdt)xx z9@}NDvQCNR`ZaJTpH5e-72fCmSo)_T5`ur;=P*Z~elombePj0yqEMlSj(vOhQHh1* zar7Bz-S0=7$9O}EzzrPVs)gK-B0T-H2|NOTWN(QEdFd2bCS3}r>Jstp&e7=IuWb7_ zU!1jAyOC@X{Aq2b@8P~_FlIlJ;xk|GWxM^9fR8n#7j=BN7w^Bo_>S59ZkT!Aa3J^zCt!uila(jIy=epNH+f&CE>1AdLKLPI z?xxQ>kKxOFdG=SsY1DMNNncua2tHAsjFFb$zg^Pg?-YcR@e#MlcMBT`d#4Nzxle@i zR36pq5qi$9`PO$^LU8m%;X7Vok1`)h;aNZdeVPA=ICJ^bf8-7%Cj^E`X*rRJOQu^B z4Z$eJp18g{3BErUgMU*4*`;MFWM6&Yap+u}EVqW-nUaSR-{uoCkzvl^3Urwi&0JM? z22c52*kxHyJpG#)wIxxIu;Vk`)OVfq#LuVdvo8`2wQw@EIEQY?w8PoOGT7$fLH@cQ z#(XPDdhfwWQaEQCE!~<@~Dd_y8cY|(-G1LD*>aSRCwl7?~zc`iJ;k#a$z z5IJuH^KVwXkkgz<|4gi<&7SG>z{CckqHciU+s82d{>kt}Y$u$#5=!0frIOy}wV?Ja z9v=NUT6XTHC(3M1qcv+k6Q9e=;90*E-+iKysx1FZ;nHlBgh$-A1A44TMH5^-e1Zfm z74kKm7vPVhIi~%!=gEW7wwD*5VV}7k!8qHqY;^W&(7Uu==!wYU8p#q8dZP}$iHft5 zA$!>65>vTxEeH8gr((&C$hS5_rBk7~wjIpBA7*FR{3J!?6|h{sne5rR1SG$I;%2zi zlzKBeS?itd;3B?^ncz1GTRp^3ufqy8e5as?z)M;DT$6*>AxC5^s_OQlO?)USRH|`bwPaD`;2NBKGL+o>%SkIeV0u(XGEOg~!0&<|+z^ohJ*x$blwURZ^7f{%zgH_W zXpqOMf74K|SsgxH*g>xjAA)7Wi{Q@iZ(7cNFHJ2Hg`48{AUISClX7>E4Hg@$BZO|% z?HiF$*=vBc$G%fAT*CQa=n z^79{I!MZ5!=ZjQO2%ALQh$y;9o#EWP;>gnR19;C~4OdmYWVDyLGRMWPkdN<1(+VMP znOXdjs_K3v%^A9U+=G;|w}NLvCvFA2-E0Zum%v{6{DMl1xj|c##XwDb2HrJzM<1wr z&@s_VY3@&dq9e8i{!7{mzBMs8`12E~xBCFN@-}sIY{ln0KCxBiRbZGf6-xTz*k^y{ zg4T^AkgGJvWmS3z`ND8IQ(*#YCQBi6S{6FY@!_*qjVH`67pi|a7!{O_Nk5aort3vO zalQhZd23vmc@Wm#FyyX(@ebXC_U1H-z(V3p~p$(qxdU=ic-*(Q?^E;11_$%-Bf2N@^aTwd*H6 z>W~AU{YH~VoAv{5a*NrY_YJqi|79`?&+(&fCs9qaU98?}Nf4Rji_&i2nf#FMZp^ z4e5lkQC~gFmbMqrx|fyU3zNw9B92$NtjfytE#WL~5f zarv}^KX7&tvtCS*6`lH(TJ~*&=+gU?yEYE$A|AnywbjJadn_$_n~jaP3}}0r8ak>d z^8=H=TBkj^ZSHQb0RcJ%AY33wrNsi=y;B`$O}2)Yx7P@6i@BVh`*C_lSq(A+zu>Dv zC7deE^2aXwjJ-ul;OEOheV87$FYcwuF%EdTbtcB=_#+8VhXBE=wXR_cp0l_}%S}>< z(`q5_>6c5Zdp4mG|CzsGG==RaDo}m?Jk{gYV6nw|I%7pPm2p{ue`^}y{mczm__0pl zghp^8K0Qo}iV}>zkMy#fH1G2H3IF}~r1;O4ZLmH5yG>u`JQCjjn>@LeM>E&o zCcABQxq$YEprRc`em>enJkGq}(hNp{zxYDjyhn__??~li7s$}dC1Y?wo-B8xx}5ad zOap}r5}2fWi#o5%-IQiXrIZym7f}VD3FzbanS1+kKKv~H!0c+iMpk|aqhgzs=)!&W zFZYX=eGwoFW8w>`T7!=?RuOHY(I)YC-rdX(IG}q%aAiKzS0x> zCUQ$I&OwcZ7l^@c6S8kt07$PJN%O~VrZR6H(bMay3F~y4P8jh59~T5uPs2ZCPJs=b z*6E1D1=Hc^^8qGxdIq^(IuSR}hs=SKd6;#HCBd6lf#+Q#{A{g8#%Wg2=GiCF>})GF z7o2EZ%o-^18Aa9CC)o^Ke2w2^RbY-}3iZ7#Nl$;=KwpaOhq0b_>7fh@ocptqzH1qz zvw~H4tu7b*5iti9MytZ(n>;dm_y_=t+h?>;g~Y?~LN(W^CBGlfScKIcqj~ z617XwV{S=aq5r`o*fcOiit8!0aMeq znC|g2q5)+i$e$_sm~k+s?4?UI=Q=FGb(x94nhSy4&g^5jRosoDt|eFS%mg)U>|lOv z9+MJWRkkLjm>L%C<2vq-B#p0@2=-B-dm}Z0e#@H3MPAGX*#~xHgJmN+YRw0q%bjFi z;W})rFCrH8#zZ_Zl&c8Xj2qOZmbIme!|%!cB*onv@7_&^)siNRnX?jZblJzXzY4>B zFJCjegH(CdpjBAhc!KOc{G3RoTH)!uR=BXGmzWGlk)1gkQGdfLGC|vn-KdsK+;*r_ zzop|~fzN1ayJ$T<(9nnB*++%@u?2a%@)k(@&cb853YcR13BxnQi2Uwbv`%&kv={V2 zxxNOBe-}uDSWViPdql_&_0m_$dwJ8&GtApH!Sq7hEwb;`2|B`J5|bJ#4oi1OGk#wt zqi*{X^wKk6#|(zi-qhIAR};U|9o9pfTAmz}rMR3ws8(dN`Mow>X{>|~{?4RTeGx=n zWFx(_Z$jC>^8O?%xdEMAqyuC9OGs(?tHD3H9Y7VhwgI@bCDmH!H%_u8HQ7Y>whh2 zap-oU9ASnRf@hMl$w%k~J{>&O^_b!6%@}>m+vfG)HSD>&f;10)5kA+*+_bN!_mo1b>Q?y;rBfHfQFpSCQ>5)oVEEeZnn!L)HJ$h z^T72qvu|V;F)ciX)i0Wut=$q(-s^#u7katBhkjCKeg|hhAdWWgW^sJRbE5si8vj%I zX*0EBEsY&J(52?Z>N!8uJJjr9FifGykBh( zzSC}&E$pu=`#fSLNX!3bCZ95(S1rtORmM*c$-i%NV&-z|^qY6NbrbK>pIhdUtz~xn z^3U6C^mC7w43$voLE^YBZ8>;zn!wrW&o*bK1d$+vW>j4)$*NO*EZwxs`uc&BB>8g> zS?GHT5;si5E7d#5{7i3RETV%B`;Fn{ft3)t-kXU3%jdQlk3h*$tFfZkhh!&B#FxKT z*eo*hBNKL&!unA+h+%O7h^Bodsw)?gT;V;}@vDV8r|l$cnJ#foOQnI+7o)~VW!PWI z(;?+cbO!&1lUygmWiF40O0JA<7c*jNTK183{k%>6op`3_Q8HNn`pX3SO5-`h6xzO{ zgi4AUk?Y&fl%4iC%Ix{jLLXW!B;D~<%yc6YqAoXVbILoO?EJKjx-J+;-gfD8o`)ZE zRYj$wT)vDJS=vxh7oLWhZQ??#H#5t!|B~P#TS6>u(dR>bGgAgHUy2wuf z2NsI+wb5FbDQ`wbyFW&S;R$4sP8}LLMA7KLe5PZLEMB~Lj)_*E08;`pc>!etN7hP;~+<(lHYg9l}{Hx zVWYUb5$uv|$@d3wFw31~6?jVoHA#|PA!N$-oxuH}?nLTZBGx-Qu{|A6VfXVMNQ&N9 zs-F2nV4dD3k0Lk-6`nTb}6_r$Ss}w61w1{obxhBl!^U3T-PeCti48-mIN3YvGgr(hI zxaC@P5cB5~Q5*b3mwW%k8@|(6S<`ydduU2@q~0)Bvr2_*lsXo%ePl)QF^HQc>N8J|bvI9Yc5 z#7eRSUVGS`P9;-@;(v4)W7@6>qz1A&uJAO9!r>ge7u%V5ecmE(^Iy=gZo_ znaxFXy5~ahusML9dIuo1ehS?`evjZ^&xhpW;do4P6hFyO0S;Id<0b_i)PWlEtNa~Y z4-P<;Yc5cknNFjv<>A=tJf?C=G3a?kQ{PQj$c|}S!Jsw|P5x{oIp35q&U-psGMhl& zhpXWDm=kpKm})A)WP?<-I*JcWhsU$$K#6T5_rOUJn*)~8m>K}B-UxbVy*A8Ux&^i8 zSc1r8Uzk4Q6HN_l!+aqxUFp$HoWs=lD{mahR*xRI^=T^3-aAZPM_t9SCogmV4(x#! z^MaxKwK{*$E)MdJDS-NzFz`4N#w%1d!jsn9^n2<-UcPA!ehC-$vcJvon*Dg{wC6FJ z?k~eR{4?wGOA#V32jj))ZrFe2HgT&kr;>Zzn5s_O^3i2_?7PzA!kKIa8~L9M*=<*Z zvDx*d!Jj4B*keKL2eWW~vQ-0q50ZhJd~5i8L!9k!Tt}qxq}azFqJ$5LqF@h956syc?I{efdvRdxIxP><>n5wNg^`;yHcz_o2{D$*0HLvS_SlE86BM z)9fS3Q04u~+EM5#?zKCOPX=U&L}C+i#|Pomh8y5{Pv~Pa8nkyE3wJvfVd+&39NH5B z=BEw_9DrHSEhfo)8j%a8+rqJHQ41c7Y+^cgD?y>AB-`ozgw&@##fnhgI`X3rx9LPK zxX8zYTk$CNOnm{4$W#WCU8Kt=#IlH8!HJq+y)B58T}Lg+3i~4&QoZ zTerT75Li}e_%6Pm`cLZz>&qALyZ={W`hjCkhy8$p&YN_JPChA8yhXS8y|mFbiouUd z@8MuXnBbk9Oh?!4A<0!4IB-)0Ui|*VOpLvOK@NLpPl5xkIx!!{PdpF3mF;9@@M1bi z@aKq^zCZ^!Y~xa-4tr~#;;Ifpaqe|XPuhF_*;X!xK+>uuGdST+CziSnVbwaXGFutAQp11_4tQ}8p-Pso0*#-`v5M8 z@u%)AWph(E;MJx6P*SMQU;CDTkClvA5uwLz)}zQ*-G2`m7Yo4g$TfJqC;>SsmhW6Q z!d71MGu_?kkJn-cQFl@+!`=VEBp#W?nsgjy17x=I)v6aDuG^BIrEweYG)<@9k9#qO zO%vFSCeyL!i5<)C8wWbh>)`LwI?^~G&N^OQLycxQAA9B)oksU# z?x#dL*HF+fwk1Pg@G)?Rt$-?l#WY<^t?Y4S3?^q`Sz-JrS}1l6KXS|H*n~1TdvGfh zaj^_98AjD2o|j#X^2a&$2xDAb;ckr)+-Ww2Pjix?me!%wpB$VtJC)|APltg9QTB_v zEU3gFSezs%=n21E3!M8VAe;d+8_a{^S^V(Ts=NdH(_Vnrqg%IdtsTWAN#^nkzH-~ z1Rr-P;`41$e3dX;JpS)8yDmJQ%{{EdxBaunpcx7L$~(ZW8q><3oqH1_uSc>wA3kEA zY1NjkXkA0R+5@PmyA5969LQ_n4ER|cz{-x*q3N&pVDo>+nC^#;=&ex$TYBwzHT|== zO?wCHJTII*e!Gylpb(1>Z>7^~F5j%HuQj8Ah6b@}Y=X73FJr*PYfOHvI^H-fPRC@Y zfd9J(D7NY`BVY0!&fWM0_sCt+-y??hLl+=b9m>poeX)jhMdQWY@K;#_Uu)^XsDuAd zO)nc|f=%JeHd~xs{~MMkRdd~1EL1&AfZN)VIN!;fzJB+D@g{2F^~xG$9kOdA6MxtDRuBSEMj&9&RQ-9t&LKwh|I~dIeN2KTI0lSV6=! z1+x2|4fWl935$1n;54NY@R^#8;{&GSc#}HD`j-lQtzb{hXKuvy_1VnX^(uH*S&SOC z>#_gk{(<&nfHTupVDvfze*N8ae4D4w+6@xCUiO-Jr+8!O?ps91Ukz=u-QdF_Uz+(( z0+;(l;M_Y`+1m!+S$<(F)Ce8A8*&Z&HGP49opqZvoiK;j|23UW*}scly<;1Hr#6t6 z)|w6Xvc&n3DdF(><6%D8b&0KW&TQPOFkj^Zq$5}4_SJ5BR@;~ zCD^2C@pBaq!(f`mE;a!ctQbL-E>}l=6Hi{v^9yyHIGr8e*nl%QGq9dA z2DjS_IsEI7$p?ogSmBoiHZnTwL1E`(6PQfOOcl{qdKs-AfkbxYNBZPS0p78eWydtX z63&Vh@c8mNdZd30KQ#4~&8-ClV#YLqqJug-c-98#PS#NUn=<#``+}^`D)M`~EZ3>O z8O47*fPI%-sHOH5xUA=lQ@@_Ww#$2I+EWWih%AB9uNSGW*EZq(X%igFSIDl>XSmO% zN5D4Rpsd}^702d&A!k>{)3%%qP$ICPH55-F_1D82#?!%|v!2|Dzk-(yUFdF=L0Ihh zmdJW1VxP2{^@yN7;B6^`qr@ZVlEQQxu)aawnU-?1ZN5rY%j6VxJBsWS5)3) zBm|}2f%1%unb^Dh*YK97Xw^TvZ{zZUgRHlT4~@mNdGaG#bf zu{PJNLD7F=G*&p5NjqMo4dLN%Ymyg;4laR!!Guq_BLc@neiKaHi0-B!M@(3 z3V(BL*?FrB_}@p)@Ov{K;N9XN+_LX4Zp!Y&`~P|H-sM$nOZRK)P~*sZCoSi5HP>+e zW9ZDIsqCUSj3P;fM52;PQG`_Fo_($%l|~w<(D0>EQJPdLLo$TSQv(tjM2W;b`yh%Y zDM~7(lA%QNK;?V?vzE22YjNLu&fdS@^Vs+Z9{H{Ul&{Mrvz!DEdPEtljt{_t!nxi? za2DV7i>9*-;>f!1*C6NT4f62PKJwhsfVXFEH1U;&~t4KM$j1F{;mxMR9H z<}b@4&jW%=K36nJqGSFsztvX>^oHP&w;i~-aTk`PerG;Av*4*XkGymr3Qr?{LU-bK zLX{`uF^QL`^QWxjQ}Hr3E3udvz3ESqi^Eup{7pQ85Ag7=Kn!h9#*g;y5Vs|HAJo^CuZGDEv#RK^8$+Kut!71TfZNy!Nm++jFK>k7AmEUi43<8s^+g?B(7y*8cYPphuQy=gB~y47zJtltdSJ=Rc)CbN z74{Sl1<{2!Z1kmfOey;?o9y^m1bIi8sZW0zY-&X(XGMVatnu_xE0S?S#((aJB(UAF zPvZM>F#T^H$FHXSMZaxTu%iAr(<=^SrUTo+)$AO6{;z_?R9n(!R|nWsR1Gm7=7F`< zdNQ{C1=)OP8Jun`gf_(}TwG*JS`y+g{CuP6^P|(ue(rzJa;X~17aYRmA@1~L!FH&v zt_D5JLef-fi%ZU&5S5-;OJ<$g2ksM(;&NF}7`fRDqo3xn)sEHd)BRHqJV?9q9Y66NjH{Rh21ixk*onb#d);W%wx0~^j;mvFv%E-C`z7TN7p{| z3-4*K6zR6)K>4P3B7L=^qW(V;;7qnTBsNJy(H2eE&=|~4{Jx4?G@B)|8e?&Ub$_~B zvjDfN$Osd58FU=6iNtCu(-})vV(0_|%x!s2S`%9>KZZXhg+GGH_!c$Gi>qz;Xf-W1 zVyZOeZ@ma7MaH1^w*cLjt-(uczTwu)7qEC{3Yzr%V8ayNf#$ydSg*`r8lr!O>NQQE zzeaoG*w>$kOU486+wh2KemaNk701bFor$H766)C%A_s;mUHRe%i4Z;XGHuyv#QAw; zDkq#2lAYwJ(x=C`exw%fay$Yzs|4Uecq0F9_2`Wj4C;D`T-glxsoTVj$_5y{V3YfgtJOwVA_f*cs70{ znIbUt*1aD>x4Ica;%nh=IQ+XL>ETFtXY~N>n=avDlW;uT+y-G@nRt;5;ywi_Bxv0< z>Qu1`Y?76*v*8Vvs3lODD}ZAK?&H*hDX5b3l4#jdOfxoP=UT-$>rx!m_|k}aGgff* z4?kdYs}V#r1%q;fG*|7Jht{`r#F-_=eBf?3nAm%dWqdnLZhj5{gMT{I{Q5i$u#SW1 z^jE0qKNU}DCer2?5%jS0GTt3m$K=cv=+?UqFmUZt*4A;9i0`-J@;mWxwx<^liyy<5 zjyNHEkP9h0zrfc&S7Gv0gcMC}Ok6vY?+Cw6rUu-?{V%@5K^wt=zW+WOGG!%icXFds zl?7IJX$MT)B!*R;-#{VU2hO+pqua>-G=WG7{OVS8-?R>^&;3E!rB|UwGX=9N{b1^d z2<{M|OJ@lTlSipXVXoXWIOC{E&%9TrmcksZ$bA<*9%cp^_LMmu%3|xUK7kwlb+Ah} z7Jn@XhYgcY@%){FmvML+el0KnKlcJKt6xD^uDK-S0n;#f`WdME5df=%u6)?{+n64A z8s-@aZico1+*Wf0O!tTL7gNXLs*la=$kcG?_&Jsuy8IR0F&qjJ(MjxBYQEt0)56ih z9xt5Fl{DylBdHJefOE7Vc^y6nbu;X_?O%6%9;hN&p!Hj_WQaV?5g0Q`v)s}8QX84P zu@3jjA7z6UFJbN4OUdf}9waGYJB!J7gQ5>&Xo;E3-N&B7h3@^J;ZZZQkhh0ewFktu zHw5_;Ja6X{ToMvXD<|KDvtH+*d1)8djV26p z_rmjfHObOX+04Le5S={iJ4>-K2d*X~zOv2_GGhCe2G}c5-y|9FAGckk;eaKIEwY6C z%3m&@eGZl>{6sg|zp!D;HGJKjL+_nEz@(>E!7_)J^o;Xv+?OSVey+jPaa%lz;}-O} zCMQ~%4z#P`1J}MifX?tb1e2u4K*X2i`eAUEDj6Ikl69AI=bE znHa%p$ukg1<`cKOt#Hrz8@_sw1rD;$(d?58{2Va^{kmo0{_-|lxJQ#N{wzlq+ug<; zYvQ5ID*)R64gmAj*+j)V9eaCrK&h4k-uXBYS4C-XD=#tpjt>>R8FHEVY3{*8XvwbdHl=+(xqE5r%&K>zrFzS1Dwfe2TLrA zh$lM>6H&h71Pgb)LUNzW;=aaC(aMlScv&z8Un$>#RY6JYl+fu^{5=(4oXlc+FOp$G zmx%dys>5_yU-H$^jL-ipi=L;iz`c+J$bEEy%u}2X0Vxttdz}WXTSua(a~i&i9*azu zF2WnL?VxkG2ugSThmPB`0Pk3E*EQFe>Nz9$>n6~Y~jlh|ixiWd#~V6^#uSQBwl#D4X_`=&PT!>ws~ zc)R4w6J7Q&y#jt7=!8i&?rin$?Q~P9mc(5gK_(0_=0Q!HaBLhxb&4W!Pl;sdr{;rO z%xyk)%3>0-mrU? zM+FCN7PQ_dM>4nH>$U6h@0JHG=uv%llC%4b6VP!mV= zmxcrR1~@`@5@_jez)9glOP6^RFdq*+KBdJ9)tM^{+WZe*8s)N;LGsMdc?AS$i+I$~ z>6H5eOjOau)mE;2>irFL{L=mS$9Hn+_n*sg&;A6y!)G=xalazCg@R$wg&$D5QJ>$M zWiNEEL+H^&50q69^Dd=@@YpYjCN~FyaZ3Qg_6X|HlnilpyV<5hG5TI9A-Vs2L1p_Q zIcc0Vs6Y;Eh z3f`=80P|0dn9wnndXyf5a*at~KWv<2tE&c=XjYS}hm4@%LoPgDz7^jHjw-{W`{13L z4cj8F#lbsNc&WEUq}i1M$FKf@){BWmC1Etyt(351Ee_n;EfTbAoWRy|DQx()A3KI? zK(X^PHcOcKJ}_0s<*O6%+SVkpCTa;R3G|_}{`f;>zzU|!?_mD{`M58~gx&J<19c$- z{d&WFEHG4sAvpsj`LAY4N=jDZAzwm%_5Bc8Yb#33h0mh8eipb%ON}gDC(MWg``D&| zxvbpbIN9482Ysgnj{Mg3@bPWD!0e16RV9(EIX0a+*!jUi#|YNHAc%yXQNlh&;d~SO zgH?XZ!ql=@)=%y^`8W6jd}%$#`W~o5JFCI^=S@WR)dq_vVN1xo7OOA)rtpp#!&vG8AY#r}?4c+9Dd@LxYa!84P@Mr1TXbNT@xb5)11LV@l) zJ{gWr4TRl$57W54E3hhR3Vohxh!1>{*$CS`q~PQ&Opv;X4^|634!I)y`*982Ro>3q zyCf{pPw+;RPA6^7=kR;YTcNkLf{nT946*wwEmaQLfy2#c96HR3+<0{WN7!cK?;$h6 z#WoOX;x^)h<6TV8>p1aH?3T1Yqu5(HO;q~0v}8@-OBR&)g!IIof}766S!UB~HsVks z-U=~5uXZbFJmC&OS%S0UZXHwBGlVA7C{cPImvpM#C%fnMkk)v0(oe`F%U~1iY6pyI zIEeMPgK%z4H#1USSo~w=5xCdU4|y!3fz{K`5p~~}Z2i~sxOdt=@LD?-RB+>v8e;$3i7#6oikGi#p?bQf@k2jl%(?pml3#9So;l?b zrvD6*C+VT8{AO(0W`=3U?-8A|;kc>h9NAtdc&^OuF^gYa?9E9fVXwTNl?6*d^xzv9 zG@^^09x@i+cvmyC)M!|EJCn6|A7m-!j?C=)C`|LsB4Igs66fNlqERy%*}^53IP9=L zsrH%${^M#arDDTzc7-i^&R8qT8$JQv^AK`<(Nc8&UdTq(D}iyLHd^d*!f9IsM{C(t z=AtLE^!Du~MLSMGe&Gwroe}5R*3vq5B0C#(Q%{f|>MAh!n+$dm4O~~tSVe;tzO;?P z?_&jSlR^sm=H4#}Hg9Ij&k4*4zEol%rtGr6;GdN~jFndgiej4FgdBi8zFKR73x*sa z_Ww;|KP`V^d*EX-cwYis(v||rHCdcLI*!C2xIq@Zxks)%|H!I~&!fhjkx&(W8TNfP z5Se8Qcf4Wa!RGNJXv=KC5r4OmRi_`o{FQNJsJ*~Hw-%FP-Y-z3{e=Uw;>Dyl-BdHA_ zE80S4^);eLMg??xB(eQ0kVso;^48ux_%HV#9G+lH@~>_s6^T0}C+*F!H$(wvtW>4_ zHZ_3ufJ(AzlPPR^U%}6(Yx9t>q4b#QDdw9ugg)@B!@4)YFiqt+AK7!%Qe{8~nX*fZ zCjCqxrpEQ;Q}-*_hR!TOehN*!+sC~7E}(^PE?YM>5iQc*v#awOal?8Oh_!A-t%18> z;Hv=0?o}oVe`Vq8oGNm#B#m7Db`zZ(&NIo63#??UuBd+JYIJ>N1u;o+%zOK9bkEI! zqr4f~pLF4+E0>w?h%CX+1t9z27;%1-3qEE8_^jRiiAUFZsI15%HW`D+mGYVRYIrF- zw|_8|U6_Ow83!aad*t}SjCA(7JP0-8n@MACpJ;eM2z+0C3B9Xa$T~+YEU6bu1_{re z-fW?tzG4`5dP)iBFE>yUW;;7Kyg=vOQ}N@uN$A7cBz_@JiT-Y15NSoAuKadM^=5{p zbq6FqTpOIcw9r;=6*idu1Errja5Bn{N#ax4W^XIFQ#YK&taiaJbwIzoJXk(i8dVNS zF}?C%g4a(4SB}UgL%RLp^}xCK$EyM6R4TyL&aaG=WJ>P27D3LjX{`VG1$>u_J04RC zhYN*Qv9a?wgwCOS=G!V3(HoET?>CYMfxg)Cx(P&kf-UF2o{V|@r;{*y4=S^-mL*N= zAbr+@`Q^P4FjQKO|L1-KzW)i}oh~8FTGf_6c_g6xBUE|w%XzT3;UgI!JDzG3Z)O3V zff!?{gc@rV=|1BgR6bVAOL;x?oCskD{wnb9%@@)4<_TUu#)enb+@tma7kWvo3)Nex zNsW)YiLd?=x=`~){I2X`RH3U_&-xNpXSI}Qr`Yi;mG->7zo|$sDTHUtN#dtJ`mjC0 zM_6Nsk?8e>i9$~)lR7V$ifmVQNkZXM^31f9?W#+M#JD8r8yNs;`HVe}`^bU~rFcri zWjyw%Qv~ZeMeC=x3LTyPG)rBK6J!-}b;b=~lfop??iXSG?;{X4su>!-wh4i;<*>DA z3+qZT<~H>Wq6>S2h~M=9qPn+B^29&^l9aNTiCH7*c$Q3JevhDSW`UsCc7&CvY=oae zkHG1K3EaC=UNZ7m9%^lDvz+fXnOxC)LJD<l*BE$b`BcNO8>e3B8@ zuj}S#%l!C}LJPV`*N}G}v_Q7+16{Urp}6gw91MSH&!^g{V|&6>rYks2u5JEO^5Cv6 zcMUCJ4~Ylc`RYDbo}|UAepr#D6ggONW&+v_?a68|f6EafNtww*CzQbIoGnCKLmw9H5biW-+F+k!MyqPm zp(8k*)isR~Z8{)BlRqS}(#Cu^)X>R#k9&&T)OM1>O}9}+(+<2=`V!;8Q^-YO=D(v; zABX&&1$>Vw-70t)3e+@s*OfLB|Mf3BTonO9<(7CeA`tx+mXeW$D@fOKP>*t#i#tubt6er_R<$9LlI z#J^arXn<1^l*pBngnZX2m5_h6mgU2i!O4r!3^s>gd)IMRlpllr=dNZC|2=|rjmP-c zs4{Ns+N7k1{r3N`3m+kZpiN zss;!v*hqX}-j7>8*5T!Y_HkP)^U{~Du@E=rHE0*u;UPAkk6v9(w*{P`BZ&z;E;+*` z3mw3^xq!GU^um^vT69LB1lL9?V8_OCR`TvVpW++{AM5suc0Nd9(5l6m*G=#hcxGoE2P7D2*vYY*c4&pR0^l&31275qR;p(?u)bbPNup?NMUj=KZ-Q|e&;lTuQ0)(e*1{LcP9oC(u5?S&gV$MJz1 z{}cUQG=!bKGz`a-rZaP)gKFhUP{~k--bi^UNlZ$@6N%wy_v#_LBPxKIBNRw%?q+r% zYY8Yf6`?rDlKprtxZIR$NmI2Zgf1V(cJ2+sm?g(?VDRe_`62Z&N*WM0n5)yvNreN&X^Fqm$?qrekxK& z86`4BZW~WK9ch_qm`eWChk@B~Ck(VU!J})Uuzf`sUd}P(Ss#%%IQ)X{Y5hbUV~^pX zCwBbC$!pXpTSol-;#BrvSqOjG^NQ>;l7_0S8gMLO8vS)ZgL|gAk^d%yqFb>mA7|rF zrg~mys-GA!XaJbG||EfaP=vZ^bI?)JUxv+;a%=|2W5M@yl?jY7O_X-^CO#)&Kn zzF5lIN#U4BCiv^65B`Q?2=x}a=L1KPu~+qBY1w%GNja5uHz$j-^3~|D#U&Vh?>xrs zG@wHkQpX_1+>O4=P7@e33(>ExfiBAZ2q&jUaIx+);vjUD zR+v)phM}D}eU2(+=S3)2oyM04JzyR@gDC$@p!S`F4*shF2C6dDSJ#thA3G0ouMdN> zD~mCya}K|=)JQN#{lY6MU!h$lOf>D*eG+%Z7}~wQgZs59T=B&)jhpvb$k;;sKV>p!?U6k9oD}nIm4}_{LRh+4EIM2s0uT4BgOQiyA^+|) zFxmc=$Pd~iJR?@2_U&6_&kbkX+BgI&9xr4c#(%}1JKb=hIF)?=RnNM$9^wXSqs5f$V09x*5soVHTaoNgSlDn z2F~Lg=_iXubhW$$8DtFKx@$f8RkW3_x+u%OSGi(#`XWr4dlw)6)}S&>2gmn*K~LQe z0-7lU^Hz4Txmg}`)LdP1>uwr2#`{A_mI9s8IHhzq-@%W*TSnXZ&ViIxB@P(=hMMkD z<=y9X=xnDtNb88kq&UG}n@q@^gW51q$Vp}gonoY);00f1+5lohbp$pUm1PCgzbrz}<51((zV#8vg z7j*U-k-NJc@4udgdNRQfwb>7I58WneB}#l->|VJ0%9li#63BX`LC&w@FmUBP(YJ!* zF!qQxE0X;zsl2$HNkW9)r(-4#*|eDO^0_GT{cf4PaXOjgaS`6!-3k}{DurjStE9U8 z3VAo*lWf0`%?9p$D*B^34?^5r*?!+}e7sE`{aZ$G)fu^XAb%AsOTKNH-SUTA@H1!K z;nU&N(?86lbvVmY7!8R#7PIM+mt=xlEorkKfYvHg*x;MS_;Rrg|J!jL@49E8!C}ED zqkmO$ahMc$TYDP1cCW#t6R!oY;Q}JwGMTN6G=R`aC8X_BItd9oLkjMgqy3Ew@Mdle zeztp!TMfsdw~+!aSzL;0ZT&NQ=fR`_gBF)aL(Q}^Q z34NnORa*+NiB)3dwHqcUl+BPiGcT z&sF!J@7@vm$U~7Xad<6sKgRMY4v!!=%arFY4-;nWm#D(RBr@lO4SU?JK-+@P0~vaY zkGX0{^@^s$g#Z=WGT$Gco*h9;Rt}`=_w_+gPYU@a8^z9fJb}#yb}(zyH8}b@nO#@z z6iM$hpzZ&~;dHOTmROaIs~&`4@^3|S5(hxP+kNc%kPl?eIDrKvS0k~{7!21(-DQa- zYVdEt0XSHs4N6N(OM*PrQT z)$(YVu%m*Ei;xn0T#s1v&I%@ba0zZMO(vC!O>FiX0~q&B7Z11R&3L=`jAVF5p2Sl5 zEuPbi!Hazd;FDWm$#~TTtZln2ey)3C`7-f5Y15_XAH-SW`yKc?@j3B79z$v~Ldg@+ z9j0SY$5sanLzfTdF@QU3|R_#bM@67~tja*E;^@3GQw`VzZQ~C6l^<+<`I!~MOmsqpc_~0z% z8MX5n}BodS=ir-^ug z3{N>OLq`vt4a=vwV*g>kMa6Q}?2@Uq;FtQu4rh(PJ%1W-{nZ3)JS#&F9w;PsF1C*HHeLPoPsZfIbo!71eV9xh;A!aL5`L_n(U&aDQ^jp6_??cd>NYk zr3q|)U&aZ~$GctNI!F;0T|U4T zdA%jMO(%Jc)^)yMQiqK@>9}HbFjppfZBa=52Nrq27!25MM(t{@!VS98B z-PE%mm1+v0??nY2^fD1r(+x}C+UHPuF9sSj=8>9P2>TXY6bk60Xy0mS-mq&jZ}T~c z4u)@_=8+fmeC7?#zX#H|WPf^p;Yy6x+QV=0qqIcrEa~boWp4VGLhtUGsATqIayO|Q ze{TAO(NW`JJ0Q27A*#kkKX!B}a90Pt@^JTm+xd>sO}OxgA2ryulv%#`$8_&crI!u# z0AI=SSh9qh}OjQ2M_cd{|WuNM}T{rM`Wn zSLFd2uq_HlZX;AZ-Vb*llIIV@!t{3)Tr=xKG+j`-F@i54mM8i4*RpPRE7E1{o%2TP(^B5op+Rse!kkSnaoDF05 z9uT-vvz@Hjl12i5ykL72OmIzV3%OMq4xSO=&@7k7d~aBj1v7e3$7>{+EBl2xP3O#R z$2xj=|3{HptrU*ib`6>p_k&*Q9cDY`F`B$e2G@r7WJqEW$vt3Fvb-;w^n9Ge!_Qk0 zx~vd;M@i$H9{x{8v&xg)7V%qTb%Anf2be&mYB$CGuthSGhGZuF;Q3d%`M!8(T~ z7`I%BE39z9n9cFv($SB*yip;$>aFRVQ~r>UK9ctNoAQ883L9ngc<84N7;3VRYc!`) zt@9&!=*lY)H{ljNxu^tAe-y*ecX9k^ye?Y&I);w7V%XrOEUx{o518a2X3nh)`4uYh1kif`}LeV?nEPQ1Pn?ElI+FRSngQm$; zb^H)Idf!8dU&%%uF*6dCr250QA19b?{auV3y+ZPQpEmv;DbMt0n&8->*I41h(Iw$C zg5Y!Z5x5X)44H|qiBo!R~b^sx}FIVxwe;IV?pLY$p+j6oe(5N9r7imsgx&Mt4uJembtWd|s>N{KIQY%C8KhL0>Mi?u8REDrO)wO^b#; z-wKK2jG?%|?;<)VWRhW1W!d`8&tO8$88RY6j!WKf!7F4(t~ooxJZnX|&e}-Scqtdx z?fnFgL+qhn_G2OlD$)J1@XS1#gUwgRGV=qCaA%&tP}pe4m-gGr!)t#MkMhyfFs_jP zt?$CW86lQ^fgGZC8^MzosbqHN3|Ki-Q*u1_@{H+KT2S7*8R&?A#D308?AcStpE=J& z)o0@cMy0B_v27@~4-6(%Eh$tg;VZt(Ia{(+q;liN2J6 zkGsAe6Lo$l|=I&o52^$iG%Uv=gGiz0- zS@bo$tq{TQ&pJt7Z+k6LaBT(k)Z3)toHlJ9?#er6HnRFLVW91mf*u#9Nvvn2%}ANHE`A0&d4- zLA1<+H*Y;9(LdqG_Duf<7U>4m`Kc|}Yj{h<9@%JLvyvX{|A6V{STU^Lz*nm^!12Zb z)J10lyxz91q(&u|owS`y8aIfzc5?-OooWbaW26PIZY;C zkE*tFK<>;}jJ^Fnrl#k*$q%N%HbRnEF;=7yj^rW*KwXzAX!r){kcUgieUb`0LF7!ZV>i z;|#LHH}K7_bNR4IH<>tdKITo!q>b-(*O#rN_QY%0X>b7}gBOyP zZTes`VKHXa1%v*fV`y+JjSr*Fyx~-T?iE=>9sj*xgGcJ#NE16p*`yu0~gq1R%LcvM4;}WwNRfa$QzK8Vh8{o*O z7P4ih1;3g)mntu6!!t=M;Hc$R=>6ad^(RuXH1RXqTCOCQtwJpSmW@G|+zOHsS54MV zjfc5CC)md~1+1WpfFo6+>$@Uw`eZ|FY={#jPEn%?F`HO`2Y|~ z0H|RegWW14VY|LBsJA6x{IhE$P{|f_{sprXs}rF9Um)J8*~eruT_H87k)-%HK>7D* z;yLp+Y@c-xJ>B&%bwm~E96tpDUm9_}{q(v8yUI**b_#yH$)ngQjxT;;q=edl&Q< zEoReh6fr(o27aEa5j7lNigL^iq*mxt!}|VIdx^l8y_W-Ny+!0wg)u$WDZ-dJN_=Xs zg6P3gS=t%w34MEBv2}J=P%~f!N~ipV)2nT!aDZODUbaJy5n6Be8zSKzQ=zJ`}?-^S3aL-!!bMBGly9;}n)*e6fy)BRJ zhGmw!#}~7gLWa~}ej;0%p$IwBRqXZkzbxruElEqCPtK;S$Jx`ISiRIB((%=vxE@j| z4(#^8Ut`N8Dp?btqD%veq|dV(_H%Gveut}5Y50a7D(ga&aqEt%_ z^K|<|&i}b5`m)4}w04<5=)NhKw=9JfCr!oVPg;=N9Lfw+<#FcQXbF*TW40Mj*yFY9 z$bp0-xc~fGu=%nE>XTLIg!g77iwzaBO5q@`?_{_C%HikxYoT=Ab++UmmC)-NaOKQA zT=R7d?oaO$tw?A>>BEljwOg23h1Sy+QYg8vJ_&2$cSy>Q)QX;sAAse)k>r?+B_>tK zz>142;D~geXvAVO>?+*PoN}#jm-HG^{#gww>!Rr8c`8QEWy_>g&wK1q8CS3pk>fQ;@Omgsa)_C$4`OEJwSV$s_=tj z9Hzeh1S04D{L`suiRkt(OAAeHzG!(jT3^V6R=KA{!)_q^v!Nf~bGnw?_dbfV7u$g9 za#@i19fL~CHE^kr?{&D*CZaagr0OljeAt3^*IR_y+;BEJF@@}x8HG0I&g1&tCFE&r z0Y2C{h<&|NLmpl`jAvA`nQdH%`C|)rwZYYyU29W4sxZy7(8!9VM_4_;{E;&nIHTeER6lh8RHnV+%%DHXA1beL5=72 zEru9VV>quHDKPw8Vf^QxY>$VbNTu2ZQa72Q_Dvt6GWh0`A{|@}=_=onx9q zvRh@iXQ>sxJtj}2_*aqlE+0nGa)qes(O*=vDut0L*NMv+ZSvQt0_<8utoQUhEI+jz z&IIhE<++NarbqCYj2E2b%Y#9|Zz-?ysiMVgM)2W4E5f?#@Gj;i{P9v|zpfOB*Dfu`^ zNr30?3FRq1#_-?7xjd&$5qRH!wBF?%9n-_ef?GrAmRJcnlynbYg>GiAi~UelEgTIr z2VvyV8KAXv5WjuU68DDPAX?t5uvPji8#Z<{{nmdU_~=Z6`uNW*r}!Z`Z?Yes)kNYl z8y9kTu`U*CXS3VUp=3{rJ_#}T$Xu1LL+AJu+#`8q`Jb~by!|l{+8%5LpIwQ>?@cgl zIT(l4FQr()j$yFgB$Z{n^TW-f7fEgzDAS|6J@MLk}z&xf5qyh0pxYI&`OsI?jYrC;9qhdK; zIXa9__cx{YFHXhmV}k$B%u19$(S^$J!KiE-MAjU<1KX!XV_^LWc)Il@j=|~B_ArHA z>x`s3ouo0wYaMsru@N8abt5|CHuIZ3#_)HJ3++F$fyu8I?jM(QNIUwYZmcGlUl@q! zAb4!mezV;9e`ul0JT~3RpAW5`z~{yUftO4eZ}~Krh6*_`hr9sdnN$Sv!u_=1dJ;~2 zB>Z2>OYr$55A0rlkXWzjCw8;{#wKl5;}WeCJU?+dm=+cDXOEs!m3Q?p>4!Nr^7{f$ z7e>&}+sE)-$?3vuYYDF$v=0Ur^^uu_BWP;)LX1p_<^K&`hVkF^#P1iq=0<^^L>m@_ z@R{k2;_0N7S2jzFUDZ=14^(u;|Gk`BIzz1l_s2T(dB?oO_b30Lrjk5?#hOhEcO=2# z={0=9moYTpNgMBCo5b-uUh;=;N5v|pu| z$_G1&bzBh4yW&t}TtnHUw|tn#V(~Y7Pu@DKm>$fJDt(qTQXJc&4Zdx!Va3y2>>vZh zGxyz~`%;q7sC2K`CPxejRvTgV;Tjq@=Mi5Qs3A_CI+&-vET9?2ytLy>8l70108aA56^hkf^1L%ouLv;&shg^{rR$D5B)4yGyEe_F*V|SC8z1Bfu1zvcsrY~ zR82hwUN4n4JObIvVo5)}ometx2u-+2`8DIe;C!bX&pd9Wqh;o!zugFQIOoS#)#lSP zvNhm$Ta7j+=h7Q*;!59?y1?Agf=_zXVRVR1q`8kX`K8UX@LGflOnYe~?wzrQF4Z&T zq}PWRZXfZFJ#jNA))+SM2dLCaKZ808b|lcvMe1ocL1HQsm}+zn#osK z+VR|AOL5KG!KG0qbHxVL8R8SO9;3&aQ`D5l&?r0u;I~>l%zG=uxBJqdwgIJwZhF%g z!)Vy^UWOMvU&L4Zloofqzrqy)V#G7cpNNM%zl4F2GwGV=t#sar9NIo^nfODz9G$vj zDt%@?pwv_^gnEripk8XDc*pJAoQ0jDs~#Hgg6SdR6}1<{KjujAN##d)dh;Ykm^3koe(_N#joQ`)MP`TS3#P_Tey!$_f+M}r z0`Q}B72f_cmtBckgu4wg1h>ox_&V8~)K`oVPs}!>VO7^)2K&di72SoC!+%4$!eAcI z8pCyrvUmbZ#?h@$;LqrQvUzVNpRLH}_s7Ug!IarXL(a zOrqsW-Tt%XiN6$ZM9&`LH7uQPiEjaipyTjvMipP=ABhP#vGicyFtNKMh+{%q`S-u0 zY2!O=F^Yd?H`Ww?45CZdjeZ& zo5-!aLnXE)CumyS1(>dIl_(Ybf|%2;IH`L`*$D$xs@W|~kID=NpW>Nh$*(qvqK42n zTOTgCT;f@N;Q_8!nkRZX=M^|A9RP>z9iobgB#7x;FJw;#m%Tsx6Fj4{MIiY}s*Ey3 zlC}WWk~f)*$d=`q6GEVVp*^49tbsorg|G8(5PAI}5H-i0X?$XW_d>2L`M58OaHira;WTQ!JVto(3s@WAOX6SW+1#;!`RW$-k2Wz^zgpC;anc-O18?Zr3|p;Wwyk zq{$kl>*UWLE!Uw}1K+W-pXXWsr-QJn@(=b)E|bLFH04udT_q)Q)smXRH~4s((08}B z;@33eaJKb;vcTU~=z2oAbn+5AD*Ma~%zMW0$%?D+wA486qohMjembJV$qd{#YXCI9 zMm$jBE%Xj%acTWt7Em*?jBbAe$L}vFZM(NYuw9*lpHj{EQA3>xJX`+qV1!UOdV|@+ zzhS)N6{vkb7k#-l->`io4|!q-y_-$SK1fC(wOvwLBXxmhcgH~0M}3^VdD zBKkz;L3p`Daz8i%vy^r4tix(LJFpQldzFZ}bw19;Kw3Iijtq#sCGmY|O1rKras%(j z*m1xPyRNT>)5{_;^7ckFA|~+7)01Xgm_Qd@bA^&bVQ!%`4o$o-(Qz_@tLEKD_OCD& zd<3>uWRN^GJsyVYa>~?R?FkwQeX|h_dNAAR2rX3>kxuPVD0NrhCtt0U9IO2EKS$>s zm*e}s@rIW6))Z-|P*&r<&MP7HK~lDcNJciPjH02TqO_!t2AWDl-Pd`il$q=(Bcsgh z5n12+_xtbp=XqZD>;B`p&g(dj<9*QltF^?`dO7;@^7Q4}I05Fz)5oPTs2E^Ib9;#J z`(!t1T@nTRuIkZeN;NFYDGqbmT{)-3MOd(}nVuh*MI^2EW9XTybWfX#u>WNob)9$> zw=Nn_2gth#EyjNE?}HqjG+#y-c-qbJvX{u22=m0+Nng=L2Wd~aB#C+NiAwo~&eyIE z#oMJr=-sVBLcD1aD7b3~PQwuL5>r6`;4&d_={s^uwhn(uEx@wvzi@$VAuayN$dP~; z?0+Qdd{*3jT#Wh$hk}AIHAD*n?`R6jVV|6=Cri*X#wEhP2nP9`pV_oP1^VLL7hIEE zPS;)s_;K}aebkUV`gPGEc%st}b)$3WgO#&k_1bvhWuv~3<046a1V}cFsZyZw!WUOYDqQBYhMj zK_x89Nond+oId0N4k{ZAk#+TuaQs5O=bU%`4SrFSnU-tLDUjLu@-acf6Q=pPqvi^Pkku zFgGTht=e#)%K`0VAFy>|)@8=9C15%#mL$9|W2$!6j8h!O&RSe&i>}Oreu*rY9QT}+ z&)o^if_w;?C)nnK$5STM;5fRyc*vEhv!{#mqwl~GM{XUq=B$&`Ub8S8M7P8Ru- zHy_=~KH}{LdoX-%g&z)glEyjz$b~IcdcLezB~A-u2wPbrPSI@SH$6;XHAR+odb z>%{!Uj<1gKtpymg@;ptL9*_QC@*r+vHfAnW7A%bZ!o+v}LdJzTkYxK5PPq{JGi?FP ze`rl7s!I!>gO*dn8d(-)p3cqgJ;BarEWzY5Eo$n~1vNzyL{Z(E)yB2L*oSwxPv$Bl zt~v{p9GX$Wek#mNRVJ0AL{80yx6I5ek!;D|%O+}HK&fj!sG69^&Awkl3UZT0R{T%s zvN^*$mMnq?FSnnyY>j7Ik2FJdmlPOPl|uZTHMm@}pIx_A7Vo8BaMH{@xG#1+W(E3l zRelNF9%E-LX zmOQWxl|OC+ql1COx3_?J=I_SQT`}kxphL{_hEuC^T2$4ikYpGfBFbl`(80GQ*k}oJ zG;Dv&=1q{p^|H+s0aA zkYro#W~zT1h+TmX+`f{+oa6L_sF`7G%f;RBUCcUHPO0XH>VE1N4j8Aw+PEC3UxP3g%RT3FxbqOr`$vT)Z(-Aj_Eb^HZk0CZ!0e;T7 zj3z3w#3^duxEJJk{ujn=zRCJcV1^I*v+g zEE1+&Z-8Z=44_qa8GXI~INh?>8>F7j#`L6gs-c>QKMoyr+TRc?)YhKB<{jhdopm~N z+jI(LJ7q9ncREg9qY0|jT4d_R82H}wm_!_npqt#P$>-UF171JDr-ik6 zBzhcN_*ry9&{nZOa`b9Qj^6~|Z4}|7 z%se{7*q_Y3bq3WQU&WqlhsloEIIPylg7EAba2s0&>!18)W6G;odhl`nvD6HD@^K-2 zZ1rFRH?}%0J-UU?>X2qX{a<37^?!Kzpg$X27Kb*KbBSE?b#i!+$l%-gf|W=N#4G;q z&s3faq+zp8z+n4xcx~^N`Ysc1(0!o98SjZ=AKxhBBJ=fZQkV~1uQDe2Yc*KtLPb_> zRKrF*3d5WCBDwqx(sUGbLs)4o?&=vq5!i_am(EHwj<|tgGh6ft3%{rD@jTsJO?Xu1*K?~1D zI>X6Bfr8~2SHbqqM0&M)8dzMbC-Wu-{>+_h?~jLXch&3Xl4QtS zv5guuJtte$@4%teiP&2f%jUiwg04;1&|uaFFnkpD|6Q@6LzG1xNGGxLxXZbmN~H^e zSJclfm_}FGoT8sP)Q< zvTa}m-z~M1Ex295l*;>PT<&ouzbOq8q7wmk4{%=FFboc@9VC2rnv_H))sK3%d1gHnkuBk?b5IGGjL9^6QfvA!+Dh7-5`B+`c$tkj5d{E-k@M zM%v-0lsQ7!i4EYi#e)Vtc}A8%k@&u+GApe&tZ|eL4l?_XId#t@i;Bk!iKFDOx#2L0 zDJ~~3sw2tx=`V0VYBk84`3pAVE3sn6cy9i&1GvH54Ab5aZ10@LlA~7(p$}ScN!?eJ zd^VpAN!>*{%I6D5dYXvo4JXL`HJ8>rwi0Bm?&9UaBJbeZ8NBFQ2y0hQfTQLs;cTRp zP#s)DemaCBiCV-`c3vfc|3Zalc9q1~z>%uFnNJHB7zvgKV$k*7Op+DOnD!k30@gb* z{al1i13d)Z@K62Is6?>~ZyT%lE|8iL=POzc!3AvkkfQ*)*LifZ`IJMsoGBX;uGk^V{+Vv9I&{IbKwu!lT$RooC z88c-dOh@hsX{^`9t|$Xo(jd*7b*6))%N-~6-}i~S`h3XlpT?Z8=?aPuT9{$qU|hCc zg02>GnsJ*Qz}sIN=FKT~WQP{AeopLV+;oN>mXx5IT@~n>!->M^Z+lR$vW%vwbl{Ju z15`fMv%&OC7|piWFRZ;u=zFgk+@vN)Po$?)({d$nS>()}DH|$u6?9-xQ65%1Uj>8Q z<4(I)i+<%N-UktFqcpKG4wfi!4|9~M|UTf9-Ji3y>X!5FD>BdG;Fmk;p=*}gx@=UakGY>fYNzZbh*N7JQ}?L z_4}vblBu~&a#9~z`D+%}ccLow=SH<$S<819D3 zP=0(0d)bu0D{S<@eOo%n*zH@0y2x?cRdZuU1 z?FihFX-B2CA;O?dCgfB}yyz>hqHEf$8!R6A&||>L-@T*+PM7A>V?~AZSy};X zIUG%%E0o|J-w^WYlLOw8+$QdZKRP|+B7{#jZgWd+1d;RuZe&A=s5O-5ljVJH$?~@o zft}b&7UnDlkF)A5TVzGr_63p|lm9Wfa&w=c`Jb6Ml;idvA*x?BD4G-8$)!m;|jDY5wO$y*ml()J4#+}k(Rd{*1Y`W5eIL(iqFu;afTX1lbR1hPmX zd)k?N5Oaf1^`4;Qiu0V;NDqGOR|&RWM-3a6ML}WO22QJA3UiL1CKo$<`QT)IR4tf~ z3k!|my~tfJk^e&y(~TliOo_u z3>>bCUT4?vgO14yySBB_oP2fmW2`e(e>WB++ypUO{f0hHQ>OX4NToq)qEC%f1l;MuLQ3r?C=q*Buql#W_OO&n)7R zn1|)dH0h1>byzp@4wl81(m2h5H1I(ePKh51{WDeA-@#k!-mMc^pSsuC!RQU_-;sP$ z(m4lJ|9b@1F#^B3aXXW|_7a1(y~5^-QnvTPbt3&R4K3%Y)b~eRW9HMvX9*ISdK2$E z)(s`haD5F~9{Y|JeESS16AYPW_zYMY|BhJ4rwQ+eeB;*EG!PfnYTVIZ0Mi2{p*+un z9`+3fg~=01mtj0xzebJ4`hMoV#7e`99$z->_7N;>O{Vj;YcSekCOjJ5=O7i4MA}b3 zf$~F>VMW?n@OyRvFFOR0k-_uWu1mjgruV7wJ&tk^9q5X}few`S_zuYnuR^^b0V%Q# z+=L&Qpt@-w{o!qbzNrQ*`DZ9zXnRMNq+RAuJTwuEOD2QE%PvxxP==qXQm`iX1|RRW z3=9TX@DFEBB1OwyaD5v2NihR$y@yi4e==O#{2%U+yN_Sn zlxan)4u(zs$)crextO{kbaS@`oXMCiWRSaTb#W&7Xv)zK1IoZ#GZvp;-%jR9%fRJo zcjC8KN!Y&c7%ja&M~LKq!-LNngl^r38m7(cfQy#E9LwlozgVhda+|J>v=Q$TZs5Lq z6|NI?pwch%XpOFQ!@G4Fv`bYDTLPl#kEw?A%!|#=37?__#ngrLfRqJ{pId}8SI@+N zZ%x8_Z(}yZG8i($4I3QNv*-y|B=gkH@-ioM5ZW}DBJp611_}> zr+Nd@>2~v>xU9;B%ISMyWs({eJ}hMM=escMT{*5zyTu2z+fcSE4vm(aBg*xP3@2V^ z&+FxAYtnEUxTr~-M;&pYwhLVtyAp=>-@iWSrtaSWas&Sijg)zoI$; znW7f<*NWNl`YpWiCrK{waXtC!ol)(I z(E#VV3Bfe?(kJ>>sg}5HIWAb&CkwNdOolVlb7;_>Lcy0QI!A}dFy*ROc-BL{;d0bK zup5{oykBk#4`eTZ;*&}o?&*f^_N#@uZM`__L@eKZeXL-&(urRBeioaPFOly1>FoDQ zT|x3o6}Abw&hY0C!ZbZ+{QwTQMf)+{y~io|U8T@vIRrl`9b@RDMhBm9q&3+u*gThX ze)5OY_(JXm?)~!_Nt=rE(>-t5Q_@7;t-5&EM^UJ6SH}iDb{70+C}6mti`%3ess9QE zc>1H0KjIh61|&=4i8mL?rbEloiAXumQrgGfd6v@S$1|{c)fZ;>L=L|O%Axs@!ukQv zh9Gm*qw0|(*}P@1`1a9rVAyaiT=DxKc&krdq|mRtEYm zOobaUN1LHKi0=F@WBZt_W z$K{Yzl+UJbmE=dtX$f5)g30%f4d@@+$8HX&he1o+Vg1@^g25Yo+-@GnWY?-g7M8`3Cys7||;M+ms67u7b$2$Q#D;kUH?{Gnwx zAzQW%J}I5ST`GsT;~S>q9A6)lPd?6k>L)vY36KyG@ao!J!Y{=67SP`+leQNB6<|8}>LwTZ%rux{s6` z`$6T?Z{oVFiL_(*LhK$c-UE}bqAz(s+6HApS+yyq-kJd4)+z|!bC>Wkq@TYt@4VP^ z)&mVmd0>`$nwp7sxX;#8>3Owg++p{-zC}%17<8+eEFLljz70tvnmq-Wu(uyS?ssM{ zS|#9H@hmWSyA5>K+JKza8G6#TikNKp3eiPl%iB59yA>G0UmOya>MR#$B!81>G8MXnVX7r2|1Z*hmi zdFSBnGAp5dPdpY>q_U;gJ;|i%p)4|tgT9tBGCcP#NVs3;hZ%%p?Ze0PWnV{@0Vf?$dUDDmSj-{`E&VZQK^&+`dp@(I0g@d*M5}p0jjzUS%Ro zHqfPs<%g(kr{Aa3aH%f-C+ebNq!ztk5(<-akHe^@C1^5qBQ38QOZkJQOfKd- z$U2x~_VsySuCf=$M?Rx2+OoJ}vnL()*-Vf*<%OfnE8**=VmMtG11l^vaP@Wrnjg{$ zi=Jt6+qY@cgbM>%=c!e6*YoS#iVffB>)NYWAGV5anKel`>Jp5)3EfyL@+STbD}rZV z=HsuDY!WojlkIEwacYa-4~>t?>j%vv)NIc!FmC!xAB^zEGja=P)36ZXf~hHsvfzXZ z=R2TNoIexMh&9^P;D{}k@y_~%%;w-DXjza%<~R3%acU6wi~PrHzekd6^KWps=Zvs8 z;1LPjZ6_3tjex5&hlAQwg!hYi)LVLqxo*+HJ(rr`qjn^-o_Y}Qx)*%jyMz9*4`(U< z(@}e6sNi18*I5 zh_JoP?fO&7r{9f*GghN;_sfAO@oEtIRk^Z%pC6MM6Gbh{W2vydq>(+^Tf|3K;tpCE>DaxO!&{Y#-3doYF6H&K_e(w4x$cd)gEYF_@JUix`8}=jcJQH0;?8ks$#^vafGik@!&;C=;|JH;_89d@XsAYg(**|E?Qp2r%y)4vS zzv2BeYtXn>$tze}FpWPm@l#+88@{2IyR%RRw|~1 zQ~ww1X$->|34Kj z3Y_oL+Y{zEhkDzxsXHFxXtUuBX?X`AaE2JkL_9#n|`fsuD)No@OY=gtuuocC|N!2;<3VVsU-gK6#_h&Pb|liF19PM5@4 zi@H#VH4<8uUS?j8-@(HmwZY(~yrw(Hdx$a(u5Pi-<30v_06 zRR3}kI^rU$b(w+E5^u?`1v_!!H5GKIoDQ;OnxsPNcHI~|L-D>bmKEg40zC+DVL`r9x)QIDyUmX{;inhb^>O!akM<@Z6Fp z(i@gZ(iYr9soYa+u}%zgJ>FP@Te6&gxxbj~1perN!#FYmpB~ z&pF0mU^y>4Oc^?gbwCGqv6;PA{DD&p?Q)XIP5r~{@bjtlpDb#5uQB1=VNE0c^%)s< zKxqtXKe7d01bO2~^EIqLcLScXDILR! ziQg6GR~yHM9#kQVL)D<>Bai3#!Q4PqLwa}rJCfh=fK`ZI*RUG#zryq!S#59ticYHI z&iU{7BinSz&)rgZ!7`WsTbT)!b>^@xejC=>}hocC01MHk%VtTGSdtf)b|m0 zV@Vp&tcpRSbJ?H^L%B)Y#^I>%pX+}%nSj|T8#w9ki2d7jpM0$vK?nT#47sD_ao6+3 z_;Hl1aCq4?P>(R7t`RP5khBNxZ1~H`uf9OG$NwY4^_pPU%$aa)rUoDAsSQW$hS9Z4 zfIn&|K{kE-3qApg!b=r5w5d=bod-VS>0Plf_?8XZoL-2UKVIV=`WRw@`(V-&_42Op=RiA4d#r^u-v?vqwiU!@_7?6puY^zSx=36= z3^#BY$7 zYqK+3pWDF3ZdGD-SMAx3zP(KSGw?$@-1&2=d1R191HY&*n>%QHi#&D>=96Db0IupL zvksr&qOZ#0C57FjcDEL0Jyj&GKj$!)XVNT-bBCMNKgphd%gBqIp8C)FW~8{-3f@lf zVE$>t!C25Io!@jwh;KhDKXZAFV+J!%nA1$F-@O;!d*t zW*Z5X;_A;ID62p4<^^%$jH!FZU6P!d!w%eEMTVWe%j#4kK>g4>e&*i8+|BGuczHhK z-aMQ}i!R8KHal5vpUfU6lPk~S{gvUH3P&3?&yuKS8$Nq)E@{XcjXO04gMVfVEBkFs zuC(Rgfyt}M!GSxew*GAP%6C7Xe|H49Mp?64&h~IV&yLQrRfPLHa@gc!K0uaeFzK!G zka_wmsT?u_bnS+)SAPG*-g|#~(5RjHz5hspygV3Y7L#K`&O*eUdbpVX2XFEgY?SRO zERMUzuFOX?v2dezHb%qrYw2*-GXqwdtY?E7Y?;gh9g#T+q}Wmwvo2Nh{lQDnm`_4` zheYUD)yzMER@QYjfmD3UW{+PUCj&af{;V0#xFNsO*o&d6@JintcLpF+&?@46XHG>0&Xyd@ zT?bQOBQetW@6r)Jm|4!msqz=yS zgA()lcpK}ztYG7xW-{sCLv(D}O3fgHXymMcVOM9Mllxrub~y*5H_X7}Pad$~3C>{k zZUEYwOol^~dYOJ=l2bvgDV)+B!#RDa!6!QJ;GLAHUDwWn#f$flaX&Nab2O9)jq<|p zwMCdGag)(2)~x4x9E8_@CX2S^kiECEacRn0mh~_PKUqG8(e0UB&^#3!xcL%Z(F_C| zjSJ+`SZ9pBl|%;Y+K+bQlW@bw$?R0!nW(0!uV5q!vpO23_#|F>TfpPaqcQ7* zfyXz%B)*A7i~hp7A1{zar)J`X*DCNyY7ra@Dil(^r^Cn@E<%0YNv2aMag{8gVz)$Hku09yTWtsV+bd)BRcXs_rV(Gb8=)cxYp~i zoh)U_CX!j4iMvkBW*6ifNO40H%5Se`nL8}%4VJpYd(jUWq_>OoG-hDsFh@2(%>v*} zA9vgA6c>B;F_F|B?bLd$3x~y&V)>S-@WO8uDxbW|r`;1-cs`>*QtcHMS=TV>I$2>y zqaG+J_`&{-I~{|$XC!y^K880Got(t)??^v_R=gaZi2jX9dz0|D@*3uMKnVxN1mm58 zMff{kUl`r*0F&CJ>RsCEiCU!%7|L8Fi$p@&)MKNBoDub$QmcSh{uu~oMSoW4MGdC1 zzKZ{?t%&+s)o7(RUO3F6Kqbi@UB5>Wz0);dQa*s*88eR0aB>&yy5EvxG7E&(xi4}5 zxjN=;v!2CGQ^dII;@05vSb-{<3)lFs;4##M1uZZD>jSkgbC@-~-#ZSw4mbz~rq!e) zbgi(oY@}dXm`2rFoN#Ym8S%bu=J-iy2kYuDXr3y13WL|Mj)T4Mr}7ZSk~pZDs*iK* zcf$Fw{q$e#dO<}!7QF4H5&kOSqsLwtu+InP6nw_iXS=|;q6&>=>_rdYbO`d#;?$WW zo-(k(@IGIN$?_EW7;Vhpq&!{sVh=e!?lz7*%aiCQXW5KsQye5MiSd$OS=hBjc&_sp zX-G05?Ws3#?5+$J)OH%GdXK^Mmmk@=t)U_(Y#DRz`0b>3Rhwk+BY5?PE@+&33CDG; zz_)9232t9aRQq$uBg;$N6TL5I=Q+t?_@;v_?V%xy`XpfeT6uITif5V`S;VLA7h7Vq z4t*v+L7%ZkIN^f}H|Dk>`DB{US+^eoy_x^9L(u00!?d(Pvn@s(_AP6}r4 zH-LjJX)LZ*orFJ85$eaqu*3cioTBkv#+K|NKL@Yl&D;|?7w--{D@c$lLBm(Rm( zopv;qR~Pt9J$$_Q74PAYLju1{7Oq)5Vx!IGvzYUFC}}VmR`<-so=|8?jhNW7sK`BYX_e#Cv9U*nN>DWm{%}t#ZFeDGBEs z0z|&0`4(K|J4N_jFi%ik=?v}X#tT(*KVV6k=oq>55ysAG6UyY1*s2jPNx-0RVewcy z9Ai0&wpK7+XL=$&*lvL{t*@Zba4%u&CQC5t+$1=j9)^LJTiEBBX7ulYg~G~|I@p(D zNJHP0!^NntyknB5@UvwSw>+#KrnS1!Cz<2XaLiC4z0I4kJ14nWru#7E$w$JE_r|+l z5kn>_3pxLO^RGgK;P|-RuwPe2d|!biPktAuBvwP-y9_vSNs%wvFM;0qA27>!C@AzC zVNYMIArmqN2>YFi`Jv}5&{SAR3PPJW>7EE&-u;4WIf>vs_a)i8G8qHcC1FnD9e(11 z4Y=4Kg}b=(Gtt|viS@tJV8Ll4v@x^6?^|oQWwYy?ipQmr*DZP6^`bVAOI*VS|G9+` zVMRF1xslJTF2eOM#>0af`DB^we|V|sBFyT&$4a{USl^ki zUDhMbVvp{L>7+Uy>Ep z=t#hfkSc7tm_t6FlcBG}-?9$}+VKaMfJ+-gXl;hNkmIQ!Jdkp$f8!R$N9J3j<%lnQ zT7NAZyBCF$T~3&*wgor0YVrO%T8YUHIrg(T4IMh<1-Oz!CG@5VWBld{E}$bgi9VZv z7h(_5@sIFSc_3#eeF}H=840&corI8r2;y|Zo%U`m#YNjXLG$EN;c8PdO{&}}*y)0B z%g`NkzNQE*2lnt^LWc-Kog_{4I)<~i<}#&wD~0NtpV*X4W1&-NGksrWFGQ}iqaO^C zz(M5nxZg7+{)xxQ&zhEhcs`THjF;#nkmJ$fxNY!saIi_>wTlm;}N zlo6CIT5(Zi9~bmUPR!YIa9wvdITla}ZXs&Ils9So>)_{b?4$`q?cT?RbUH)ptWC_X zsh9lMs)S?4DPZ62Eu7#fvU?^zB>DHP;nQhZ(I2HvBm9@5^xA=NbHHSFWXA}YGqN6s zWs6?Mx0&pPe>VZ)S<_-jE0E1ccNYG=%bDSqd1 z`fDXN-K`FNlKf%%qjFaCG9B*L-G=5_b=We+5liVnL2@|Ft=b$Vw|8b91Z1fjMyZ|Rvy;zU?MQC~Vf#0ORjor#r5+0PiKnz!z;UO_aAZ@@mXnWKP-tXz=+*~v~e^Xd6YZ!gqUIp6>BB{&Y zLU_MSR!CVX-{7ROLWrN5Cfpv|2Dv*DAvwjD2CvW&>wRVji~pEW|EP9qX4^q->08mF z&${@|?h5S7pC}mI|B985Dunr37g*}AS~}Vz0?O2OkjWvDkbcwxLt-6-vnv-<=P|`# zGEZbimfS=$zkAGqy&$`HiobJ135p|cv56bzk+nvNa8P`vq7)stywQN}jvfeQ12;nW z=!x`9q6AgDnQFi4O*C3spJu+V%5GpL^Y1Y|rHiM?&n_+*9;3#)TrZs#9xeKsyEK)8t$mV^s8H^kFF zlg$LDQ??*C_&OVNy^Q+U$k5S;447p=8)&=_hugKY@%7qHvOg)4$n7m*k(Gw9$p~=J zx2eKgk4<#$4*_3Jc!lG<9PrPTPt?!118luBnM>at@V@;Q?!!~F>!aBKm zVve<8;!?r$>@z&H+>@RhISpTqvqP&vO6=2e73T$y7Q^t6EYTPJ2y$H;XzcRYq-msq zkQM!#?9Cg%y26JG(@T5>gX2jUXf=&q{-urbIYl^VZh(L( z3!N=z{J|;y`a+gL6@>cVK%uG^vp0Q&i!UvN7_r0j9cLzNPMgDyJ1$3^I!!vha;Wey zK2Y>qUlt<0Kaq1Qw+L}hpTnYcQY?g-(W~bwg}F~W(Q{uS9jzyW`oRb2HMc^161WXk z)rLayaZlRvO5_QR-^-30?&3}b7ZF#NV-5;O5@Ep$OV|{>RPat0z%``+H;5kX6+tpo z+u95wibJ3vPoADid=3*L=aHF$GsG0EAQg8a;k899RnysydK+fJfsyV)&tB0#?O%$C z^J5|GO#_&o=p_fuuaSzbWa99CAjC&ji=BjDL3W}POwAdJ`q$^t=Fnln@Du|Yd2$ch z9~nz#?>&!8JEp<G5RN@NTwMQ4Pu+7(03O0><5o7nHK55nfwP`1bTN{8dxJ>JwuiEFoBU z{J5Gw;87$L>Plg2(j4J|PcVEYZZQ0nI(qy&$xYajkDAG@f=|x_+$zr0YN0*wO+$yx z*rLsv4q4;ikaX<0(jq7n{~?V_%LR?BjkrNR9=5OhgyyRkll?TBdG61~?{Nkg_Te%& z@$e^DIJN}3mJ+;IYla#5Yf=4(Q$uItB8WV2UkH%55he_lhdtv$$^AglyT5Y}Tet27 zKK{@K+ZGHIEd55)A&)7U?BFAm+Et;$(Z`^sp3zW9vp}swvcaJ70x7zd!0eRQ2!rx0 zgo9#k*Q(hH;%~M<-;q6ZUr!{xw8o20i#P$X!H=NigS_*oVK=aI#%8vux)MzO&KJrj z=fmL$2dZ~Z7c9+XXh_I$*b$n9HkaoK?M1zy{yhcfa?b$d_Jj8F**IAARQ^|11@YcJ z-0-TCg8H;Qv~*Mf{(h;_l(j+brPCQy@NZ7WQZ#ro!(5R0=(X&EYAqu>#r7 z9p6~dw-z>P?k)C>4#P#La>4`#3I@MB>>MS@9-^6=_iH`+5r?%8T zHyZZzItsCBZT!#?>CkS3_$aDOoE?6aXYuPfnP?NhYuk`!)v zzCcB?9*q88fi(-;aqyrzRC5?llMf>9nHI+%J^TVrkMf}-R!Io%7G1Dwtt1S z>s@F<{8sQS+=E5K0)&ARJ0LEjN;thl^aE_WEc6+t3gfn{r_(DnaLu5A`u|+tGm9z9 z>6DHzVcS1_*61>lPH%LFgP}{Pvh9AnI<_9Oe}2V=k=9hjMC=Y7x<+8qPsyV`En$nH zkzhZt7m|ic3cEvWgxS*)g{<)Tm^A=FZ;K{<`Fs-GS-C{$cH0M03;V$`h{EfRF&NQx z6685$fYRICi`NmjPcjY?O6^#_V+%&R%G0#MRYK;m4v0A+W{{pdO*BAT9 z!Zmx@KSdMRux|kC7_UO`1JAFyy^fe4@xT|>8KC#-6YNTQjP9O=1XARLmrLu}f)C3; zu2T}5vMVuRts7gv?lB3LYiD1VWs-&Gb^!O@90tpz^l;P-b0%lN5EE$jP~ zQ@wfcW=<5$Ts53-eszG@-dli%$#Y2LlDA}B!bLD)wcvkX7umE_ohAJI!e8^54Ufkz zhN1I5V)(jGaC?rHlm4}PaN0mhn06~1K06d*kJlJ5&2@lpwxJ{?cL_dqly&9|X3*c) zO&UVA7Q-lR5e!&+o7}oHm7b_#B+eiaO4{{c|BMQV8(od#mMsz5o}R@o`+t(FuMLH` zM+d>A$(0W1y~Le5Bgcxbyo6h>qgn3#6y~+?G1>gCkThl;Wp~%evD_=W`QDGUIMr+? zm)DU_g1iI9>ICLf$djv7sXe+j!_*ubqgS@%BE+%Cu5dY1F-TQ4VPH->k}9}H7p zzCdUB;Y9J*NphrAns^*_AO%0nSg!L<82ZM8HQxI_?R_HaJvxkp24$0bo4#@n|74K- zFHRVDe0}}RNy>OYe)Id70C@AVZw_gXZ4lPUa** zu9Ys~8zzzMNgi13|Fk}8y);g{n@TDdTEf$cku0X~GPKJ)L{FD^B9Rfp0(9Py{+s&H zJG-A`B|d@XE>-k-QS3B+e=yD)wiG-?FML8!J<%C*2#Rhha_`Fk0wqM=(?XGx{5KQ5 z*Uhcp_dOk!e$l}A^;RHvWi)TAWXw$|kie0%c7o4%O*%PD9_kF=k=e1&xP~t(bmbaP z`h3PTG9#*+ZN3_UdMZEQshXT%Wu-~;{#xSSQ^(=2-T=Y#=LzCzdIEp-9)fSn#J-8T z!61)`)Ff2woH<*DOQy8a+gqe*%G)&Ig7IFsGg{=_Me9TEra|B~`2w+caFFU~m0(s{ zAv^Hd5~a>{V_Q!GQF?l&KC`qFBh2N=_pE$6VpuVn$qvCgQJLVVUWl(03z_ZLeAZI3 zl&!n00?s+7*vpg_=Gy#(<1gK36E9klmbO03%=CtL^ZOy_NE6W=9q*nmXWH&!2ezLAuTxl#^9zTvt3TB7vW*Tb*_*>Gr$rE@O;$MAViCq{ z*2a>1aEE;; z;#v#1XRhfi{Xz`8@I)8#6CW@`a}UVwNPtt>3UrB67r*#dGK?IxnspzF$29vCvZV7X ztbB}Ix>YuuuP-B8T@FIU)Fbr)nqe8G*Wg*ze zR54fII5_vV15KtrW?vR>V%L7;63rSZ@NU0?EAuuIB@0!|t1xBbFTF+C@$oF}-X~Tv zkmqEh{4nXyZpZ7Z5|K^G$HpVFqCNuZ^@Hf69Dp-=M5s zKC}G(iB(`i z3-2#x|LxpgvupaHOf&KuyZG=N)7pI4ssFmTk9lMYcDp{357&p$hR5T`AU*}1_eT7}Y3(APXb2Q{h+ZobdFP-=2b`)bG7U@^8GG28HnzKybcLHZ@9|vWkIXb0a&rX8 z8XD8l|8nW(ul98Ny)GQPuM?+#m8Lhc6`gn9)WKn1L3Hh@Fd@({n(nSRMmD;xz^BlyJz`!#-`6IigqZIze0vgnHp@AOi$0eXV%Mg&m>K)lmPTJ> zXkpHh!>pu6RftFk6za)D>h;!{X3offb!C}!$>cIDZAyW~Z(X2FL)O`O*FzYomPenM z`wN-QakQwW6gU2lqVsUa`g`Me2oWJG6f(-Fvq077$4;w>(k)0iv+sW zhVr=`J7}29XFO{f2$^$Nim^wC=}U1BcLGkN3jHBX_Vk zGY&5&Me*+1kr?Sb5LN2WqsTOpD&2PE7qe60^?_!bbI(vr?xj-G(bvek*b?HAIhejw z>_ctR6nLYs*XrZa!1GLZvBQh|;kYr^gxkVHHfrq{KJSGF?HM|nt5?ht1Gdwo>Hz2( zag@#dHyW?W?xY9y$?^WHQn3GP8R_^wF?eOiGPHv@I>|SZ6qL=UuZNAIZ;ifTgTN5l zYjv6oI^xPTH`ntf-$qcoBJ6bNBg-m?qQlx#Xxyt$_+X;} zA&0>Is}tSv*oW-Bc9Y46D@oJmT!s~n-3;y}u~U(jH2=jo@zJp#@r>gvn!9%eJ=lLC zT-5P|#>1)i+b;4z3NqRBs`myna_sP7v%ZCWk&@D z-f6Iywv$}@;X=;Dn!%FO>a6MZby8S(Ub6lMC7W!%Qs+%8Y0;rX@_BAL6Z@OvD$SWt z7I_ZGJsAg)u9|h#Nh2X{O)Tj+VoZ#h<5=hPUlONvWfJw^kCN%HYw4j0qiNp}qoC-o zIl8}ZVIOl^;K_@3_}L4jZWA&^AD^s8x%x$tXl-}u zANmhc=9Q6Vn`DG%D%f}~9ajF)D9bP;)+UZ*ibuF;1v|pp)ODe6vNCI& z`;EC@QJ^l{Hb82u1^W?ejw2qfWmWT9$x~;2?mn}gI6oc-lNSylLyNyMrELcI^jwK# z#7XPh#9m!y5-U7*eCknG(m zd45w-l5;;(vM$`8O)kgU-M)j+GC-N;%)CS1MI2-)m8tkGL+E*bS;{&lzQJ{}(OBs= zg}NVz2hl|zHt?Pk%&e&)CBYuJV9*;DkET;wxRn_lZ}VE{cFB>=BQBD>YkSF}Uq;xR5-qs3!}u4)YUne5I&s=Li2bL% zo6j7-52vqP4uexP@jt_0KFivUZu%z!AHv_UG^ZI*cjvd{h4T!U6s*p@ZpLuy>JI4d zGC_%q8JxGOAdZ2~k^^q@QDkQbY~)&~TJ@KVuvKS?9upCc z%1OWJ=7aULT-F>`#cX%$u=VTjla@cpEbGEA1~&$SX83U&-q(!XF_}#ISS!O~(rz;%b1JBZU&P)n11ptiPZ%nEi6=ZZZ-z9-F< z+@5}%RHcVVA_QIl{(eOcD$Is!HSS`2O;uX7Ko*XLHVO61X2R#pfyNLeJbbjC+^!Ji%T8q_<~~(>6V*%()hEpX#V^( zE-QBvg1QEaX>kOd^>G4ikt~J93JdwVl{@JDtp)Umz{{B~HQ>2;2X-{J@Y7kLSk}3g z7j2J2>#{rWFkMb;ct_|`Is{OCO;s2%UzT^Z6yfI^w?Hq&hjoqqEmF?j#FXY#!%c5J zKB&N!ml?03Zec^Qwci8i@j#MQeH716^d~dxBKY>#?r8V$4Sw$ZfNetm{=G>M_e>L2dt*R( z$0Y2xrI^g_`HBknyx@IY7<`&x4-dt5e9XdwqM)cq>PnY_{=SpUAy$N#x%BC_VbBHV1s!QWYjm}2|^*s^0LT;4E**FMrk z*Aq9e@6kn2_}GC>-*yE&91oMz9*cSFO9k*eISgVijKIFnUExrBI!4@o&3^7p0Rp-> z{@V-3V$Ha^^qD#E^?ta>@A?{8?)aJ%cqNc=(fiSWA0*G(R%6g^HU7zq2zv%IN%}u4 zc5K39b}mPTC@&oa?adY}+2SEy`P0UHlaisfs!+0bmoJ&{x0MZxt-#1n7Q&3_kf@QEVd9v@Lm<>^591V1zy|txo%+jr@jGd)I5KrQ-JKyv zM}IS-p9X)%31@Wa2z4s;Fz$r^&hO*ty+YqHVh+#Fb)|Do%7b6~9nk9fN#D8dm$;be z(~a`)nB0_USofupdRc4J{yB1D|DPIC6`ftQW$|jhtN&EG0pgiQQCx%XpeK{SBEBeVDD12_l)_@3F}K-z3@xk5ZWr5=_F#HUXf7ANV7y9jF&+9FcfUa{erJ_!<>epJnqID`L z@BzI3{#b}RMdbktiQFnN&)HKb zIeI@74jxV>BaI^j)`uRvJ{`^;O}r`E?BRjIZC3oG@k4g7Dibw74InaQh2*LKcpT}a z33p>(Vwhf|B>bqr$Qvs|hHWE}~m_7aW9jU#;28VRpFT zvnr}uKE$|@w{XeR6HG7G0bY8y*)RBeoBa$u1n>Qg==}DB%(ko#_wv@o7_DY<`+O11 zwU)BXma9yjMd4~y!TVEi1#APK;$-tTtZ4cPW_)QcxbNx1SH>Sicj<4Y*Q7?}U)HhE zt$M=yFhy+2-1);3mDFjfta#9R;OZrl#7^rsQTtg@5R#TJExP>*92&oo4SUUK`hjD# zWSh45S6K!Rtx2UGOFz*^I-T5WiK;l$a|^vGTgP+f{-*yzvZ>*Jv9usqO*(I&ym-%F zRdHhS4nFS83A#d}C}t@gYx7ar$qwhQ^`Wb_DvQ1t z*Gkk3W)qzxMUl656!$Kk#$`VJBX-$iaGQP)vsT@MD*D-2Z}Ec9yKD}<^8^>!#Bw(L zfIeREDrO$xxok{<3dXjElNsBWz-5U(PYxQ*pY@r5&r3#NsG=vUDKNrc_W5W$D45x6 z4WoCKe`bfjDr4rvqxdbl7%IYQiOg1AXqm0)t4}_w3GCnx5t(% zDzq^w13zW_6{*hq!)}aGLK{0*?yVjNr;&liWF-iWzeFxA8v`Sg-HEq+F6-_H#3|>e zitOywXrZ_m-u`(-Hf6uV3v?TLpS|b!;ZrsHlz=Q&U6*bhae*9pwFRGC`9?|x*Fd0i zBg74*#9xN3~lFkZ%(9zMXB`VZ3V7g6vqt) z=!losI*9j{&*o}Ix)}KAEreO@q594G;*;Aq(Fa@V>E(}qsq(%YoTJqVQ}Q?R_$E$o z8>aH=exX5yqTGGFAFR67?8I3yn2fo-I2Q$$!N$<6{DDu4u z9+iFQX65nl^rR-V`^@EMkJVtmTgHURZiOUWXL!=1gE0ex;rEhWvOr-VS*Q1kIX3(Up2wQ=OOR{(2$G@hql$|TCt^F%IiD6Vj=WpDo3p!=+F zv_6r^zl1CoI8UY^M+l}`q>!jUOY~oOjMWc1fD_zQNw&V5;8pfxrQd*ADn~Qlf+J|x zdJ)d#oe<{Z{n@;TSE8=Vr%CS9FA`e?fcQ_ZSjR6J2s)`GYW*lgfI@HIzT>En_i)yz zQYo={c^o4P+8yaAfkhKn$4-<>B>OekYRW3Dn=g-V)#d?wAz(gda7_sRUn56SzDqezUxN9@dQ$0=s_ z_=#IjFj>KsKJawstL7*2+1<0K`tn*jVQs2#&m2UhN59h-x?}nFRvjE0P)Z+!U#I8q zw~$l9?Dl;15i%zf@oM`Ih!cF@I{Qm$R8|O|R1r(dZx?Yn*@dWGyNt&ge}~B>ihPhK zrB60eD7Y#3?o9gfQC%hwAXy0Fd(&XygJV-n}rEU{516*hfVq22GNh{7gZA@@`Z z;O3~`#JIwlEcjc`O!^h#jtjwHzo{8?2<5eUm^kNpGB!J{J8VV1kvyX znM4WlS;h2!Ea0dqdKtB2%cw(KZTmwuE~Hr0@7@>5sCs!4qEyI6DBonPsY&n(CXk79 zV<8HKUT~4WL}UK|QFvT5uF=>4JEE*n_T4&`ZSBGygbsHIK9?`rJ}rin4Amm1%FBs? zy#$8%r;y5{W~}F32a6~lhRc#BDz9zH{*-m>$=|1v$B|KF zw_PpUao{?s-}hNGBE^kJ;>WPUju=s_d4CA$-a(p*bJ;xp&hd}ROi(^`lNJ6=Vpi^o zEJJR($Z2i{`EqC}4p`{`9d7;LSH}QwK0H|D_TV-NOt{Q`-}NCIPcP#S{6fgRXJgoT zCn56|ZvmZ-XcD>fIWaJ=g-I=y81dPNy9NIu!*85~A$kLFfAlrD`gkABv@ij~*15dB z?ulqgV-Y;IKMZeUhjKGB2fl3NK5nAuiG!_HaHS(U+{17ai?J76T?-!4FN?0A{lhW= z4L*R57rjJHnxocfYT}aL_rY0?w z z!{JTROLE}2p#;;sNu#P2WV+ddVnh%jhPK3ec`KVK?Wt?sa}~AyX0d?_24k4>cnI+- z!-Lm`!}GtLqI?}A)NeV;-u5<kMdrUgM1JTlK;O-V;CoQ;M!Tkf{*iM;j$eWhk{kG550EoIoIy>q6N*N{Ecmw zMD^Txbj$q>xo_meVUEk_tPO(m*8T$?tLsH#T+WxJI?!FNk7#>GGncx3rvG`z^13gz zkh5?o3+kFifAkoL=lmIlgylwh|GmW*SFCztp#nu&c)nhQ5^2IvE{$&!S~}Ohn3l`czV(sWMxEvtU0Z5Ts|t*%xn+=GAMf}laxnGm zI*#Y!yV&>qbfzKnRsz1|p^}pth*r#zL=VvC+1)x+Il`K(3RukL1lEMR&j=dUSS5Zi zE!&;HE zw>=rNR7D*ABm*WiM9}Mw+H_2#9^JkoS&}a}Y@SDVGns!iH10q;R+fK(SvUc8cT4Kr z#BbqIP(9u*u3%Z8#^R4@2&=~`Qooma&|W2c1b@iF<_`+o?Ac!8b7CL0dKHUVRtR#DTG%>EL6nE}Xq>i$dVB6oBuDS9=qCK`Re{*RrDooC# z9^dCN{Xgko_f+4pWZqI-ey9@eFYUu)Yy@X$>tGmCaRjRL=D@G{spNa_4H95Do=x{E z7gdKRV#mQ>pj@RSJ|*;$Vwa(sth6j^FE_!bQ3=F$+Fkfz?0~;^oF^JHcH&wgS1LR4 z0Q3@)C9krLg#D4XR8D%ZZ@)a%C^v!l>h=Z467>_KtShE zsxxaS$hTI&stsxq(Kl1LSMdM~wA=XCU!hc*YeCOxoAVr7Ls)%hB0mw{jb;}XO8bY; zqbhHg@bu9yaQY`7`f6ti9c$#rEw8H4`Wt=0_2xe|LiatK547c{_g%s-^Iz4y^$o<5 zUQZkv>LI-_&WI{r@PPLkwd7*MYS4Nf0JXXH5G(*0-mA%jIVyrx>R=2!x1FytQ=#(| zrh|=)7TWC#g}-{Y_|b*wFsej@CY-Cmxx0=)Q@`^fnQ?0H+UGM_AGcN%A1!d#9vI`x zn}hg?%`TAE`9LIobe;`;b`+{Er}LyKV~OJUI}oH@D=?PULgQ3Rhbeal;lEu;@Tqq` zUesF)LfIDGFK@sT0jLhKiVgPt$wpPo*}C~4re`2Hwhi=ij_FDR}(!5u>7!8Imd6t{Q)UKRG9 zC$06P1~nF_Rv8ID@-DDXnV;CQ$P_q}(ZObJTa3q!t-=eQQLt3q1_u1h;uFiSlNg&K zJpM{>k;Yp?Q|Mk=;+90NjJ*Ou4V}#Ok}C^PON3R*gK_%xP7FR5hQ3o3V1Awq4F4I( z$F%hkNmncKybT+eR+T4oJ(@;6bj_iuuNh2PfLIoJ9OU|#kzO(Z^9u5?^Zk1)-y!&7 zl-`n`$F2B+l^ZbKau5HmIF;JwD$|Ipa5{S(6})FD%=5_yR=drW&r8>)2ab-VM|bw& z{c0b&hUFOc$ZQOp*0&(>TZiDLplq62m7y=Ris z%XY)k-70LsjR_*pbUifKCgLCTJ~`yxJq7s{Q($7o6-PHs2^v4M6cv;{W~v9In z%M|V=VEJ-nZIWHAzloSwt@VR1ua}b_w>)sM-)UGb(?(J!eZ+i=^)0g^Z2Gw|7g zA-J&Py(qpn5hhyL@G&#KvSR;(BBP%cXmhlQq%D>wNwxN(>xqS6x>|57sdwmecns{yM7;UL6XQ#YdxR4tckR!#=*Y@C-7v@ zHZY%NOjlhq2l>DOY{;*RZ1;{_lDyiEZYlUG5$In&S^rKt#xd~9!}b+z}VW5 z4BAs&$nIKaGRWi%`FPbHyZ=tW>Qq16IL{oy$7qqxKp_)dUMX3YA{F`TpMeD9C8Ra2 ziiB$_qjRAf@yI2l;Kwe>;*RO0Vo)9Pk4cx@H&wwoUOBj8)Dt3plmm5se??&{QbgK* zE6JntC8CNpU+DJxPgEQ+o5aKyFdM%J_U@S%M*DXWStqR1SbCSGXif&%wJXTq+BGn2 zYCUsyZ?&JQHIg4Va6@wS)H(R-C$M!C?~9)EXk6a7nw?VfM9Z93GE+ef_gb|Q?NP@e zGV(StjnTk4$_qqu3LV)K<%wJ_WgvczQ>K#R*T_b-V1OGhSz5wP7M~+wk1CgeZ|O54 z*{)5@Y#KmhwSegLoWaCI6LwYVhF?lN`0$bp7Wyd)O7Rd%pIedewpWsW>+XnV-YzAR zioZjGw>s*5Tm>Jg4!vw93nTkEV07&SSlE?|H_Zj@tu$k7RPb zpF`CPZ5WtQ4X^J_BA--Bz!_sGO%?8z6*XM;R3vUXU@TU*h@+biq{CU)Qm&<_BR%2t z2?A#1Kx)n^zUEFMv6iaSj#(;z+Y3;xUjcEL*uu|hUluy)Pw6?eHtef56Sq#>1r}xs z;-0PAbo_CFKkD@ozpA;>KzSG5JFAPWH?8OCdA7LHS01mT1S(q>VBX+zqV7HhjD6B1 zdb5p?wVZ}80}bE{nN4ow&qvRm3Ao^A0(|Q5mQ?krL`xSF)@`Um3(TA0;&cnVmlXhW zUH?gjM5l;kw+&;Lf)>O0PiI7<1MR>7BZ-5@N@ihZLpBdAcI=mn5YSpIi5ct->!wz~ zk^*^r^`E`u@j-8FEleXX1pj6Jx(gEJtT8O(MG@I7^d^R^J`28sq~uyr0(k4&fYj;< ze*Uh=f4A04M(9+KXj?f_nsf$#kMGN_#{jV~&KA`j8OcV8x3lh>dax+e5_b&9BeI$c z(ff;{s608CDVZosnxZsFMO3OpE;N_f8JQDxi*%8XfhD=oS<3iiU6K0wL3Fs+JGSq$ zSzWMIH7WSs%R)>9m!a(mvdH@&h>y0h(Fe*eGyxIj`bg%DRJ5@$Fh%3q!%P_=oFQHeAUu$+|jQd0*pBXo*l;R zw?=_}*GK&GnmNmj*Ebh0%ZcZPmLb8yt zJ}#q2`&rYw!uPOU$aFJyCeZ=qxgxdf!`NAH6few*?h4)mz zti7zRCeVpCZ@o$!yw~F77Z-_ckRrQ)mY}L#BpJAQB^y{!?VxFKlnnVes80M&1Mj+? zVXwSmYOj=5Ko=J}ztTSR(^CqqKizR}D?$0zFf|sRp4J5Q zNJmLw?==#1aT|N<{?T#iF;&Mt@AXACam6?;XA#-xQ;C{e9!T=ii}1R9vS@|S!&-en zlRF-(CE4TViW=_PQqdJXUT!s*h_4>Ttk<@*U`HH$^7f>Gk(ZbVec45m7*vR_!uYN! z^j!5hTDmlWyUFR$sC{L;V#@}a@Hvdj7RU3aCS`c@&}=Fn`hmXK7t62gc|@NprqPQr zXRvyV3Rj&y3#azH_xbZwG!PnsVoHc2g}U_Zcny z6^u7*VzAHG@qEvFBQz?Th0$@hiFWG{@E3MiJ?Bdaxjhwsm+o~WmV!S$){WdqYIAhj z=ZLZEo-@N4bKzmbO13F@2#lAH6c`N+|BAJ1nwd4H6n4sCnK@X1~JxVU?5c-C7h#*5u|hy}x^y+2453 zGAbie*4bmilqj~&-iPhh%w;PN4WmYra^THIOBg$*L-M4kg?P6J-kHV<_T11JmYlsJ z($k5?ZnGIM{)9IyGLL6&C2)!n(j9IE^bG10JBL8B$|!*b_3y_7!abncj_W{(9`-f3KS zYo#?AiT;wsH|22B)EtSy{T1cTFFbZ|Uhr*8VcGBG=VIi}d@T2Yo%&j|#(?0Gc zGg8jL%U)%+Ltpq7yItk0Wm~|=KObXX-K1k53vP?t6ZE5h3_f`^1b_dq=k?p7DF_Zr zOW!8y-@BE(39m(dvyFYb6~$+-m7(E(hKVgF-{AY!gVU_k@H|$@oWLzyJ|364jaJ+!#QqkpbzhsC(^yQ!f4IeINlJ> zFs05#JYCM0q}YDPH~ova&Vxw0TvHWi|DGe+?lFU}ePs(@y-e_Tel_b9vd1(#UG~M$ zlwXZVMB~SqqC=AhU_!Hv#5-dFo4+OIZ zzm+%$y^EhQiCFG@1>RkHMU)Mkn8As8tbO@YW*z6n6!O~Hwh775Kf~4WbC5TU=}0D3 zHJeyuV<1j;XeSSE%p^nX;z`IX9~!2Z4c1NLg)e;P=tS4!18J!CkLSY0u^h;C)gVzZz${m@4SN#R#52ysTXZN>n4(WFz7O>;5QXA9?BmWbIDIja8{Yj%ZprMU zhP|&@!vis2w(k+y^~{(j{~iFxr!GXb&8DLEEmMV)`WFvTTZr4dtf=`w53&CiP3hq$ z4K)18D^jZG!DkUAK5oKK+7Y9o|dR4ML~xao(P_~X|p(&1xX zievWO;@Ov;@!GvlX?xEor_@(>xO>YfVLs47pROJ$Rf>(_-xhb{&CK!A&42pyh&2u3 z@C`HQww<$iMR@_W<2i86F9wa4$I^8+^=FSh|r z$%;(|)OPbFwk#@+?}?a5H)xHOy1r_`{|e5a!ukW^+S6KWg|-8jCU{6+%t+!vTI2Yc z%i++yI)M*Nm;`6HI7vEO4C$WmdM#WPiE zGh{DlZ5_c~{AA%{iJ0%xI1FEws_-l!?<=a$;~SwEqe2eyKc0mDRhl8)F{6*ug&KVr z{@qI4Rk=v|?0BNU7*ODq4J)aueH>QLz6^(iPNGiY8a{FHB(6I;4t0?;{29lWOGUa9T+kI^%4W|U4g3jh>61IBZm4>~$L}Qeh`26u${;Rs2><-SL=2v2AO}7pE zP;0<{N&KZlvUW=67v847v|_~xS(BvSU3|rT*1do};VRNMvkp+{)-LMvFN2ynAHwKm z#&p~IOT2~+0_j&p95C@Gl3xSi?&jU%8?o<6VR;I8p3)G18Yg(BZtvq$pUOyFZzR(* zH&baz)lr;xsUP$?+{5#|cEk6PS7Bqq0k&9}3)jZ>5x=NTB)i`4p=I$PZusGj)r+E- z0m|^_#|>$e?^?R>-4sdLl@_u!Z?rVTPX0iF7`2-0Xu@g326L$1%*I_g?)2Xdv zr3)?k&@;=XaFys#amck~Y?-$Z()-S1t4SyJeTJqN6?{{N1N5X+@)@oLVhfPrW+k>XxXPU!TP;U74K$#$FZe)Sv%K`lZ6iKtak!9bX;Kns!Q#19-)^;Cp;N& znuLf)()%g~VE$MGLQQMQzYYE9#CuKnr}z?FpOlJTYTKc@LJjUYPlnm6FX5IfJt?E{ zxOmVM(C{4!de^UtE@#P!{vFy!{<|TDRwr3H>B)Qie%cPkj!0&UM@?o<2d0DP`LXoI zXA^$$xT#bl&<`)EQ(V;*NxB+a$w*%}XsFAFwCjvi3$v=tPkriUoYTdURZ3*#_xafK zF9Mu{>p^;^6Wx4!c;g2zEWajn*+Q&HL!C8A>{&o=58epBjD+8FAVcjwwxWdV#(cF} zG2`!6^NGRMQ2BK-s2ps^J6B|-Di?O(*^=>m+pej?enu7CxHKGj>&ZI1*8<1+z$7xU z@e=vjA;1aVFXSo;GJM{*CT#E6B01G|1$TGrNVCm#_|$559+0L=llPwjrCtBA%Oiu~ ziRd_$T{fJ4JVjCLWXcZ;d&&zYdP#f7?PYdq<>IZ|C!Ft@62z0b<-|_EO2p%8t)!p! zwu#@wWl%fqwLGd|lJt1cMl7*!_?XFy?aa0Az_BdGjB#}0)?Ta=6QusN<9CQleB%(cQG5Vdb0qpml%=&EzHs0$% zY0+@J+n`31r;Qeo^_|#$vjm(P-@@zHjFQp z;TNU3O#5LbY2E0I##S=a&DDw3R=t6l+9O0VLO0KEf;rTD*TfrJx_0m?$(*WLE%mCX6{wkx89fBurcKCW}DD>rSXy)r&=;` z>tXzRzYJ8*tc89JG^YyAKE6AK*5oYxvw_E_{TuG0l1ShkYvBPsP_YaHic( z*z9-$6W(aizEYtZT3|qrP3uEEzLpD4aeH7#(>veE2@whCpgXyq378bba=rmZgFBNopLaO z>*o!mHCdHR%j6)uW9oFF&L*hy1hk2=5;^aiK)?Mb2=o!vef9Efh;^JU}Pt3$xn&4Akm_**5KXy3X91Mg@+iKMo3x;7|Wy zq1GmP{Y(^5*OH>n9SeT;c`y{JpTuWXCrQO$4OaZ?s^nkkXkpg-14pn|pz0h!46aMy z^v#3(kaZ)G#LlI6c`9VRpUib5&3IH|B&MDFi$&?VP$%RcO?Ta(DJ~w`F8HHU>0!Y! z5`rIR7*mC)GOp2y&|0;ee(982@&qHpFr0n9(_(# z31@g;xaQ@_P*)DKg-L%e5f>p$&f&o{ec<&al|BmQPXE zq)N*r=t~p1Zfph&6ph2jmp^0Sx?Sv9&3TlB?V~{hhS0k^#_;Dc^%#^Iz=wYQhabZe zX_{X;XK!wU+1EEH?O4Zcb;Dp`zzuvnHj&2*j`@;V0q{ZZ5Y4we@6c91iif=zfk$RX z@-DlxRHm2VP#xHkTu9~D7Etkd6)LM=f-5B>`M%0qpw?MVccf|ahaN!~c|(mKnr@A~Df{4A z%XXq)U_}x~MA447p)fS8faWgWOW&n>(xD9#FyY{B^sVSeJ*so*&CXs_&7tVhnUA?L zLUkf}GTau~vo6D5cwHltj=LgD7mpo4e{DGik2a5|@q&}@;mcVVs@j*XmW!w31nx+7 zRx~@`tBg~&*$7OSM$xud6CB#yk3Zg@MRRJ7;g?T^;CM9&7Pfd()uDsItRW;lEToOo z0_dF{Yp^dL!mqE0gr5&R1lF7sd^Ck@i}2EOHgz0=vvmsikE z2xY(5TGKQA8i?2W$XYb(NHWXd8VP=)N6eD);Dy0qaJ;R61>HNzvZhqg+uk!c z?Vc9Q*!YDv&WXX!Cx3|2a2Kp|2l`)ZIvG__0wY?$(fD;b`>L4=X}SmCr1~KSt#@I| zUL*174Ka*8i9am43Ux(%KkY zGarl5<(bS6hVtFg-LzyRu=hKC@U2TIt_hqE0SU7)$?7$~Qn(Fm9)@tX>;nEx+6-@l zX7KE@ZLlS&9HU|%NK}3%^Pj7?g3|rxl9xV@@$}#4=&W^JlyNZ=&t^U0FK$)iE~5;7 zx4Ry2h@ZFNBbgBCYSh5M=%IwkXv*t*m zx3ZsTc;9Gzd`^$*9&mz&H>>Gsq32XuIRfRz?ZrC{eMJ{fCNbrtJ)p920!@woEYXKF zcs_D1UF@(9W9%L<{Y-WK-%LWMrT37Yvl{fq4Z;27Rt;9_y*TFdZ_y4R-zL4BgAu$)x!ob; z;%+vlrxPpk<4J~hDy*~VhN$QS`e*S++$Q(hu}k$7Z_3Z4o$kxnRz(TPn4`=$D{Igu zFC|`mFPXjU?#J_=x(a>yzxZKP1AGtc1mm|=wAsmxPb)HkC%Yc=OT!wdQ|SuwT<16z zTV(Sb%~7c+LU`}(X4>#}08jQ4x~!>`dye>x?_8E)|7Ck& z$XE?>#87Y%2U~KrZQaDxeJz4l^8zlC{I= zQb`6Rgr9+E{LT(unvZpPSIJV^L-qw$h`y95lcx?D(7kFAG|kP&$EEVrF60^h_hdbF z+0n?Ze3}6AwN^O0ry3O|{lNiBL&*-i%ODvai+gA7mAqX^;nl#~sP?IjT;Gy_g@22{ zZ&MuGY#R)hhxNs~F`EUZouaVQUgT&Jc^(sm-TjX(ff!^t4N3+-mTc`3b{=o&cmp4KQZrvvGkNGp&>K89b5h8(1;U%Ve-n=+()jCzR}g=WOpib z$`xSVnhWgdjx1uHXa*_~iEN3Vsi?DGEKXKS#H=mC|HMZ_(LT>gQUBMENQmG9x9Au` zj|fbKlR4XQS9gI#Y2Izm6wBGMm_nx<2d^L_lx~H83rE?dX7&l%4Daes8g-t zD55_lNRsZp59BU>#qsA(lTU(cZu>-`YoI=ZrB%z|#$OLvZBQ&eXZy&|3F)lu`g@kX zvx}^L_D?cg{-?mPe?@!-xx=%4cO?)0dkSq|?=gk-tDr+DyEhFvh)2zH@#5fQA~gvk z^Ve#zmi!R3@_0=CXw{K>d%uWM#~C>GTod6`*IZB?ych;w6}ms(uHa;Ng@p!vA!B;x zp{acW5yZx1%6PX&@y!buG`Y;sGJxqIqDEe!YoSA;aMa^TxevPnr_T1u7vILIO1qt;4aGS z67DO;=h*)!I`4R{zCVsjG9#pkq?Cw43-`Q_v@}%G64IcOtfsz&A~U0ejFc#qqNHKm z^FB04G!z<=O1nr&TlwAJ|NiiJd>;4SbKdXQ>-oI==mn;`{lNjrSKx;kfLBU8dle*y zzE;KHeEK{F(P+rX%R&v)9P!4fZl;=K4u5B!A+H~c(1)6{Reh^icIj2N_vupXY`-j; zz4M3C&_tZ^Srca1_n{ku{$o$3tMI{xeq%)QMcn2&n)3sbAW4761k4+9-6aj7&rAdq~`hwWZJh* z=6^&RHh6p^5AOZIxb>eT5bbcHzRQ(g+Hw`FS9-y+o!@crx*u%UC|xR_(v$w^8II$o zKZMd=!-;&SD%DOPpb?e?mJt9fpaTCsmv+1|8OT|bc}Nk#1Bo0a&Kse@(TO7{HdUG{qL4ru!{3Zp&O zv%Th~cr0NCsBfFchLnm>xhavP9X(I#To1$FfVntg!D}{J-`U!UUSN9t_u;kbD-8O? z5{tujxG8U#=x3abjf*wW>$DTRUF8GHbxR@o{WG#VLgKo(j)Rv^8mzx9x+lDxw~y6L z=Q!l05$+myhCHu##U`I=Y`sO5v^%1#dU2<)_H!ik{c%O=aQzf_d02t<+cnVp?p0WD zIT?GO9Kr1F%tfD%!y)ER8gY7ljD@^;!xrB^&jLO_#AnJ%P@bJi?v-29J8^fIQF}bb z+O?xu{!=KsaD%-PbU8vD<6L} zg8MIN6&1HQP+u!1y7Xwku0ytT(~DFhJA4uhT!Yg0z!nc@HnD4tvD__Gn;!9qhxYI` zJhP}bMu$|v7WG)F_uG!=&OQt9>J3pc9ZVl-`GZpBX*lAu9(-rJ!MZs~uKXqv^TPF!sA1LzLxEI^y3R zW|i;?|H=P{vB$@OS0WLP-T6`)q4kZ3@59NS&wa_>mX*-@nwR*=210XOGE)!QBmU}D3BG8k_AmpG&= z^ZzoAll9U(XJDQ`I;qWIMOuMm+t=@G%V9rOW_yZ+e;p?1O{-+%>d!H+p2c`-j0a1T zi^i>y63@Qa1^YK`2iGtqI)0}HU)_CO7^!!F=+BChI_{0^bHG=KY|kL+og>JYyk%_1 z!deg-l+b>xG1ydiqI`Nk{^QL|E+%9^&WFwTPWu@|s{~@jz@wn*e7W>ndMFN%t7SRO z--&9!hphLpckojvX9m>+=#OpkC5e1HKX~H>I$0<{-LO3cPx#cZlvlc@mmMGFW~12VX|s5WE4ZDk zDbpI^G`Vx{D*o}E3v9f;i1Ts}8@I-tWnO+WY$kiDmL+)ipgS)I5PP*GYE^NE5B4;% zX^88@g9EP+6T_;qlaDUh#9p=J4=&i@JH3tkQjMd{-LjAD@wX*58j2dUEj|;Y3_sH5 z5+%4Ey^uc2IYHG|0}rWJqUSEnDof|CHg-MRVQKb7B(4!$Ifl`?O9sN-lqaUUBxe!eFO z2~HNd+QX- z76#6>smnP;*N;3Z&B=>ExoiXfGv*B0S;@%Uwh7#L>RbA8mlBs*a~Ay)7eFNH+05{6 zFQw~r*VEsUpRaZJL7N4SYH{m_b!Gi+GHsUl3}?e07Ya|R+se)-?xbl& z-eB&unUei-HrHk#UC|X@_UZl(n^ilH(E0JrO!?(1D)YP$vQMw$Wo9YVPUbc5u4D-Nqr!vR^%&PO>tJ)L7wuR(>9YGH0L$PmLJ22TkC%6Yxe;c>{vx# zh0Z}4C&@b~KI0Az>A*&I!O;2%;$+LYyrA2GOr=LqSIryZ(&D8KbU*$~P65~U3a7D+ z3vgzN9c@ul!9Q|FG{iNR2U`Dz1{E24JLZ6p@M$Wy;(B7vMtk^TxdL}344{2ZOycno z4eYPK^mnhM;BxS1u$G^KylpT2*)x^THva_FR+%mul>^Z|M(|~ipRr^`8*19zj#o7v zKp1%hMs?mkoTB^H`kQWG)8pixU)73gK~h32u9K3znVOkK51R2j>W7>Rc2HfnoKy zC+{dLNIA!Dd&x=;o4@REO%?eOwG-Wc7eYyA0=`Qzpd%eFu!&**sCrkEe^a%l?MhA1 zx8@408hHh8?>UP*!uo(qPfh+weiZ*+{R4J5)#Cn%I#fkjp5Mw{Mu!=9;)0=&P-x}J7YUw{f1NlTgSLKv=SMp}0h5aUxeHN7|uD7?@5|xWx@vHFXMWkO; z3WGwL8S&|syk-okP2&AHh$nfkf~@UzGkryy1)x69s(BX8B^!j52f>_mkLwTC0Bdu zF@D`&le*2;BrkP(;nWpTWZTrY!sWnS7}RAbWg^RA#-VC*{!={}S>u6v1LWw11t$cT zyd>;#XBK2M=CInX@l?*wiP*oEfgSSRkoh@^_(fE)v2LHCZl`pwxO1Gf{;h?d19ssT z?{@g-w?eoz?=D6*>eKc6=R&GtJv{IOVWabCy5`|)QX^#r$9+DJDI4EHUGh0FS>Z@@ zYwp4KY%i1_Qw(*_hmi};eYsoHe0pZcbBM}a0!_bOF}cIDp{2XQTE-!obi2L5`{y2# zL*~h#TXLW59PtLW+Gn%on@3(I!zaR7MrGcSYj8hypgsd@ISyA1gTYm8VfXkAcrv1l?VmA#&I? zVU=m6p6&%G!&1 zQ#IXP*js-G1Wf%8O?8(+hW`PSxl@jpU;T#eA_w&T-pZ!zO6HB}o^;aZP~6m6BGyY? zRQ(P+TJm!jJ)TlX?|xR{Y2N+ll(z@)CVfRVZQF(`ZL6TpOWN})7UPdBF6GfIX?|%L z$h4FrKAKLa+5Tjc^xLQy^n&Kvi}xq8UsWF~Z%hD%uQSPih5KoHOK;(Qg*^@)JdbplI^dELKeT+ey|m!94xij> z1o5p_!l#mFVcO_MX8EEwDH?i&xR(U72h;D68zJ(rx7nSgm<33Vv+Z!)?*{4h<-N2O z`zBnS;Lg7M%ClBX1Z+N;&Z7pM!$W-?NzXcK>`1R6&OdeV`ixPea*rC~bO*90U!AOV zAB@|h{$t^~8;I8iRWdAR1IZKQaE-h&UmhERn^y-529ZlqpH~Zmx7d=!s-s1deP_rj zrU&xVG%-y@4hIGAWkr*Ak}7FFc&Mkk*r%(2J$%+1ih8dWZ)|rGPPfJ5nHim8-1i#h zo!^W7Y`RI7IF*XMoxZS%K4%erEO=n$|4kn*tZ>Iq4H?MG z?h{gI!AwgJU_jRp3>z>E@-st0$zU&Z<*A}x`71V8U4>q&8_B)wmxGJcxsB>Pjpvj; zf^6?+Sl1-^axC?@_jwmO=Vedo==>Ghr+QP1`Y`I^Y|I&P*Fn@lp2P^xy z8+HuZ!-8r9F=9&zFPr)b)^D2uak8y=ch@-jlC?4e1#O$(FP>Y){PE*j4r|$2D;Z3j zHV6HULYd9m>&W`YlWVfOBu9A#XCX(}*l|AO>FqBp(F#G&=cefMDxI!RabAR}Psxkeo&wkWEGg%M(JtG|xj4rX+gQH36 zW+n7GIucpAG*cC(3*+n}N$SB-q$B9MIQ!;lHaFlBu?l)5WX*{Y+d3UF|BD~mrWcbX zLu$zM+rC7hp`4k0_{zq8M5di^lPq3+m#7-Iim%mHkjGEb$+YYHg?jOqb)ZZEY3zu^ zEV=pYLCHgLMtOfhdrS(kGK?k7v1u&(zbJ89TrY@udW1Ms&LJ;7y_m__gP`oCi`T|l z!bqcVA|73gLF_N<(Hx8aRdtd}=X!&p%5qF_8i2kDOQAY-A#}MN#1iFepnYkTm`lHu@PqYIY}9!J%WB+&3hUr}~WC|&$H4;Cv& z@cxT!=}H-bnWG=zzj=jVGw~Qa(UGAOJN3}^qgvT}{WLHb(*r)fJA*?b)adjcGHj4# z0c|qzK?lElKBvhVU0#@?Tb(Q`v;IR&l%3IEE)Aj*?v}2*^PEpqTEZTUIZnn-IxV_a z=EA(=0vvngMXQ=GGTn|ae*Zx^`{0a>yQ-3i^-atye+^TL)yLWw)7igGQT#`qHdft8 zAWMx`vV`JY)_D`c#dYcGG(=BdcsIh7pZ2hY(9e32V3mal;a z{G3rD%M(UA!~oHCjHm^Dh;XMj?H%0 zgfi73*wT?fbPj(OFN8^)uXJ5yx#b5(kAq4(8sEpFQrd=&mvPFy%V>r zN+XBdr-Q|q&%*k1>fG5f(R$RM4Ctk`4CY>z`tsNMU`n?v>@N0Mvw&rOfn`JSGes~dvX%8CsJhOS&J`~qxql1yEdx%}qIA)ROh8Nc;;N^HzI^L^?IO~%wf0k3v ziYH8j+>8mxl6Bd(#6RNFqTe(E=4)?MblpHKtdpg`*0_u~ApUVMSVk znCYVlXRhjEsQgs&>9irSO1&Z)-T23jc2CB_hpBA0mmj8&pDxV*Z!0Nq%V7f!6`*^e z2`T@0QFt0-S*ohY8mPZf9NH`e>#7L%P5y68W`05T|2i-8kC{BL0=KrNv9xd zj7~)5;H{*>V*vXW<;Z$Ho=AL$%w+2WkK(-_pULkGE%Y3;7d(?=#4}xaV5=eJIKPT` zL8Fd*=%q;h>mGqi5*OmbJzvP4ev7f!Uv1_Zr^w#hsqh>!9Kwcm!URI9MHIG%fb!oURO+{!Ps~hU zNk&$D^TPqCRFW>5ob)AK!FynT?|s6eoO@*T%2qbpI|MFuO6>6`|KZcKqw(70{lbr} zKT0DJ{X#<#hYQjna!`>m?`Z!UzjSg@Qhwi{>}-LW{*c5 z?^H71S{s5L!`R*gPC7LDz?cplFspKxzC{sO6CTT+q~x=p(v9foV}xt#s>H7Y=0N`L zJ%am(zNjuA!6pqGh2ORwCu<}Q=eLzJ;Xk>rxaDk)aB0$D#?4j9Xy;}ovvH7^zge4I zt&t@k&K!juHWtLC=V0u+(vW?ezE`~VMVlDB1#)R?9r^F*VC=Wn5;FULB?rT6NM5{@ zW&hR6Mj!eqm_#%RrarE$TvP#<`q8L)P8n-QDX?7gQLz5>Ad+G|k&KYM*hi)F#>1s? zWMtAlqV`T1{66=?_`p=QIQ@b!$NxOhOM6fHP9Bf~qTV0Ihy`t+lG#Nf;VivW zp-cW9>WAJRo|BXH;dr+_)#lL?L)!XGzU;epD{tBNmPbVB+Q@1&aQX8Y^z@AMvMpWH zY?5pz@COI4kkYXJ5>NaQbvu$-Dmt1{3lmw)UarUe{?3KmS`(=sXhr4jo$tg(w z;xWkyW!IfWc8AZQA2ky2QjP=GJCDFW9Y65JyF}LZ`aJ1*dL~(`r3F=6_Thu=VPIRi ziLJkG4xvVo@aMA;seTuat;@!X-ntvm6pJPAUw>)i-wTyXirAiRTku->TTuQ_P2A)j zEqr#;2brF$gbBIXWSLnB$*)`|zPxLVCmg)Uqv_HaS}Rmsn3N~DO$`CZm#Xk^&1#7F zQ!Vb^q(Y3EuCX)Tx7hfTwxmGQ8Xi_%B_)SXh%ZXyar3ecw)^5_*nM#bOr2r_jk|B- z;$cfz<*#dKpa&z z%%`Ov-8@@H)Pf*#tau_kuMCH!C&Jl+S!>BYgK*MRGnn;IJ;{c&6_ML+@5PDbi%E3$ zaq`x4la!h04S(Hc!sC=I@vhBgQWJIn->mHo=Hs`M2FvlRc6YFKad0Y;|4zh#XCGUe zFO@^}1Nkh>E{w#pVti0`lPsO8E*Qu*kmw*)SgIM0E7Ql&ZHn2pbAKEY+_Y@?mWm|O*3lRDYwWiBm z;@Fx{;&bszarB+_Lg31$xKIBWL?~&MUaBl3x62%*uFXo)G4K%Ha#+o}lnZd*q4kny z*PMNEol4&PxXPZKGl65?vci9wlf;`3zKdTR4}nR3gkZ9uh*;e{Nq&7;D`**vV#0+G zGI*8&neecQtVmB6wiy<}?Kkr9=vpS6xW5&<%g&eftly1&EFY5~xnNQw`4?VBQs`N2 zCfvI_8VA#NZ1RdonDvMYP3p%ad`&BEy8MXU(XvAiso&Z9;v~7I-^e8DApZE|PGX0J zqWzdPz!HnCFO7@GEp3xfyWs;n=|2v|*~YZRd=`tVHD)^<7QmQU$uOt6A3Qm8o3S6! zq-1s?bbOssYLRvbmbT6!Gmi{`h3fO+$oIpbexOZo*GY#h`-ic|35VFA{@;oZ+rK3D zhwX<|;!nYH(j77Xr{s*xafPhzU63$VR$?iL;?2G)Ac|Ko_hzfmvpj>$db)}1`6PKB zU5;a4E{ZBWjA{PD4^qDOFtZAoQB&p(C6*(%^X-?e<` z>Rfi|fCrvkzSkz;)J$e{V?T8&+XuTgJ>kcDOFfjqOXwsafdqX~D>E((v|&5f*-X}Z z!Ve7ZqGW6W_1%?^K?P^2YKs#Z+)|^guMCwtc8t1YY=^%u-{I}3^SC=^E4)tJ4ucFr z@nQ2*3^*_qDsP8Nv+p5jlbi}oYd7JBygG7FbqpLh9z~+nC0FFiZ_-UVBvB#KF;|KJB9gTUpa3WUao>)*#t28#aHv@+Y7fQN>`V`4qy}ePuy~|-)`)JZ2WP;7LP#n870IyC? zXWe&)Kw!XC>j7RT!E<0=7#^s?`YE5pxJ-Q*ID0HD-28xLkE|~Bw5!F|KH=gjb4!U6 zcmO=_++?~c9z@+G8c#$WV~rUJSn%4O++OC&3=>PS&FE=yCyywaXtfzOhd)NF(Fupk$ zvPLxH&r5fO_19!*fMFZaxztGdwnyRtgY)2@zYrphDpR$m%W=cDRBH9<3^p%*!}>^0 z-CfaZX;pO$qJH* zrxPS6sh@f?hM$yvx1g8kZ7MO_O=BouK9JqbzKJu(RN<4z!)(o5civl4 z3dG;Z#)!6e*wFf(gw-p-rS;}KJtGL^-mJm4nV#tD-^y$jZALF8OIGMoCuQk$;p}HW zHf373_~)=2^vJ1TVvn8Jqi8JDw;wM(P@shMMeDGVE#YfzG+?}ZKHHty0M|?wu#7n6o@xLQ)$Y~9!AKGq-3GSzG=D^Ej+bdfP=oi3B=M>-x7bCv;fhr7oT91jt zOW?QcM_4;+0QsOUJx3K!*{2p?h!!qFuLJ4Ad&B)?=R4fAFr=gcS6WcF>ycP-+m3s|PsJDaUl#f)fv!hT}Zu?D7KKC+K3H z)C(aEi3wn@8cy#TTZ0TA#WQEO!rlNKzC5iD|1H}_dUd8y!><;sNJEy2)n{f7ui5=8Z)R%=uC0>r<44$Xh?rYfV2a`!4O!{+ZF4H&%)bCvH;T71o$$ z7{Fe+|AI8%WHfv43%$lSN)E_IcvYKEvc~-_{T?In$GSQG7dsVhChisaZMyvc@>kU2_my%q+bs>6kM-b>{+NQDhb_ zI2yR5*m{nBA>DCR#C@aJ(;NHU`OrZVu)}5#=Bt|04^dxXpnW-?FLA#1-JZhzD@$J_#=|A2m388p;$HoD(GE@&Q-g;6u|pk=W;AFiE4)b>uMh0))wTORkN;-B3F zOFrOr7QrnocEI92nb7;`D{-#uaaLzpL8kAGg{Nf_Pu=1&$f-X?`EXkv`9+QHc)X7t zi3%f6cJ?N}M)>jDfA3VgQOvGcCDd`o};$i976+RBm6bw4j6{7 z1-*c?pg!Rw{yeo$7~?KOm*1EMZ$I=RRW}}?UrQaF^ZFqu8Ezp}d;Y+d-F-keP?L8? zABGgUBuuMQgu%|%RItd!?$620IIS0bGxR@VGGICW$+YB(pX$KcARXNQ%_o0;eu7mX zPj~!NLe+H(V7Eyd%1*O~y8bg^^lKK6a*z?*n-p{`SN6*!x_brN8%qK>oO(*eZRikl)l_noZ zWB8eco9XeHKA2p+A9e)Wvk{x#0&^tMZ_@~cjGUl@U&T4t6H!-7{?&YGZ zn+iXbv7ebvwB(k(XVLFL$3Z^+J+>XX$28VV;d(&>c=V{HbZo^y$-NK)Bc*qd`!r*E zLT&)vYPuK0k5`Ms-Ibu;s2Z*4II29RFPyC(!du2FAZ(1_|90e|*7nnIrp65tC)a>d zvI$;y+(Jz!^(5PmKOnI>gv*1q z)?wVcJv8{lbeLM@O65o8Vd;`8Yx^e>e@gI#9?puWGSdk+=1!E#!N2)};dgMz`ma!b z(*gtUZGeIQO~46%2inv{AAztfJ?PtJDO=XOfGO>(XR433!ls8le7JfXu~#;Ri|^+0 zkd@u&k)%h5^nZf-cg`|3msqkn@;$wNLj^kC&!7Q$cMp!n zfx6A5PdX~_;N0{4NrWAB^f2W&KiWY5UllBh7tu-A_CV^Iee^_FC{K#qjmfL4`6!8J zd2rHeeEUz1gXT^Q%72HcYijt9>c`@}QgfcLY$a*W}8)JM##&V)a`r_obY zb@=DUWuehag+IMm#cmQU3jWs z5DYgS4PGji7`<*NJV?Gmf*b55UicjP{@ECuByqKi*Gc`V+p%OvPCssIG8QJMYs1En z@wl`_hA$VgaryV&P}9&C9G=8lJ#QZb$!)=y_;Ec|c@rpkl84a9xzao$Je5rAe1hc> zelTO#2x9&#kBwSAh%5gbgi||)!ljIP*7LRuhJ&+1>9Q04IC7RDbsd*WbaM-#V*3Z& zz2&~Jaeo&29^42Kk`MI5@ykpT4Y;!Xd%;sBh}{gz#5V&{NXHI08uEFG`1IB{i7Ocf zkNb(FO08Mc)U=S!s(D>o%tVB18T8zGh#wE`nK>fXt7O%nhm8YcVj2P&3Mi~;*a(>BfkDbOg3*T|xZZAgf9l)vgM!}}FPgwh$+ofkt zRf?69FTmTgQN*RD9Ip7jh3AU-tWv=RRo|{A2b)^h3H`@nTlXu%5vZ%;o#8YB~ubUgo^#3kKbGZ&2bEPkh zd3ge6%!;(y-d4ff>(64Q#&~O=yjrMQGmH;?oy`75+LK7tk>s9%9UQzE3l)1Ch}}eQ zJgw4?1Z>%FI7Fke*g$LQbG6B19^`v&HI;bA^R=7L61rpAkWDcV|tS-eSTHkow zhyR)vAwKg}pcP!2S=h^g$Ce)iw!eaO%U~vq^}%Nedh}fDH(|tw3GCLedthh#nB`oJ z$Hv5$8npnQKuX_;`Q1>Jy^w;LhbWb&_h4UaBKFiV=Z}JV z(tQh?$fp;1tnl3+TwbmP({}g3r<3-P3_mkIx7h^42dne&W=rNgN#b7g7zHaA4B;hR zCy0X7?{7EpgVnz(QB76_XC)mb%xylb9%C&W-eUzHTsA|x6JrYHxuTg-C)tRvgp@IH zVu#gsQlPj8G-m2b9fjc1zn&qi$S8^YYf2|R^Fkq9--)-DOu*9xFPY8syX@PNIH?nr z4X)#+i*M|sQ1*l}JZgOihB0PP;dz4n`Dx9pe9SN@=v3*fp^dP<-i`bGOTyY-L)a80 ziEsC2EW~S?&@72nzTov`R4ezE{9c_<|KT#`NgSxaZO7nZa1VaoF@h~^-2q9LB=>;r zK5YM|z>Cwz!?$BeOnI9;b+V`sv;HJtpSAm>J!v}BO7lb&k2+Qy(}Onkd4=8M-?N)1 za-nat5xDud@x~#k=o$SGp8Nh`1~R#zpr?WlM|ePJ$}Ai>bsVT}U%=)@W=nCoHgKqV zFFYMz$3_MAfseUE#UV*+`HX0NJ((0<7|NV_?NtL|$=oveOvbYZOU-}}Gh@iJTTIDnFCikFE)pop<9 z@{k-R$4qNKK=}m~Dy|B~1@458%{GRxBqeTHTS=M&V_@M(_V^xE$&v~Nlw&e>|fkAAo(26SH|fx5ccLbNS{z7<^L`^W>yGqEa%+u^YlC z+RkT8axvbC;c%p53c4Q}N=L39NY8r3a@l4zZa47-6c5sZz7b2rt%akZ!89G*o(Dm6 z(nO(R-BG-JH44)^w!<&Bf;xP;%iOZl;E=})_EPQ?pVFLx@?J7{()JwNdwn#w?7tOv zzFiAW!;;y}`D*ZV;(C0(@C;r$9t#4GhbgMrtbD5u^{q1IpJ9^3e7{s`?xIr|2eOr>YhmPFXYgKOkG@lNxSGi@KEzuabTh{A`xCBWaX~TaeKcVm3ZrbC`3R+0DseX1)K!+S3z>HoJ|@_otHURp*Fa>s!|N zwwW!65t)WcSS+6V`j-W_UV(veH`&6sCDx~QoFi=;<-xGCQq-E52ki?E;+2c( z!hxs|7BqYWj@~s=RJ!$!>4k?Ao%DPrd%0e6VkAq?=2`ZjYXTvu3gWk!QF5`I(M~`^iB51r55?U6%X(YJ%x|?}Ci+dHC?F7s#!2!gVVvh~tGmXlqzQ zhP~4z>sGa}s_J#ncV0QZ^t6Dsz{6sAWIb5ktRQm6Pq2F@vceO+=`FJww)4~~oQQu& z%7Lw^2z(hVD^=0NcEqI zEzTw=KkGj!AJ#x_T)D*Xt2&lOJz&G9Ytui;V_14gF)`a)L6mbH;r=#toDiY}f zr)CN$z1HB77g9;t&t5`+e{b@2o&j1so{UyZ8AGC{&`w=j)|pdFjM@*AN$(7Z$JJmY zvU3<;GMDFcj)lag5-jU|6f%>$O9Pt@3VXc9V2kG?cEP|76`KdqFVSI4G2ksZp`lOu zbdMy}4Pos0%k!k#$cPuT4`&m4YND=11BuX6MzQ`4$@tX529(vZ1L@(Y*y}cQ$WLZv z8QO62Q8aTaEny``U5J%=78$4T3%3okVIy-52pd=o1NSV#750l*mc?JTyh(?BbSlQH zp|;RRVFMezMG0!3Jr)jKac|Cx|#I~o)2X+WmINI3EBF!Wxr623|^gU+nK&}?u3TKf!yy4Ml7E2ObBedKI7 zXmE%-WN5Q1mNOu!Ydn*U=wRz@uamOoMWr@3HnQ@H!^B!?kC<#Vf%^Ko!HwS~#Cz&7 z>(j-$aLwuilZ~Ckowp@1Au>T!$5p!wWE1q)jqTAI2 z;b`(Tq7s?T9B=x7@!qNEGItHWkXRb}oA;Bf`G#oxtS5L}jVG*h#`IBu9oC-ct&!e)x^nIZ-&`h-)0*U=i2 zXHsD8F(iSxw)$hA?W#;KB$usKsuoIaWfb2wm4zR=Nv!H#CRo`k!Q#)QqDpWD=zK9G z@2ncERDV7pW!qK=`DPkY{;Lx6fA3?~a!=SXdwslq*nzYqC_=#ddRB3(4DLO+C;SQ; zDNfn)pE&x+1Tx3diESIP6=a(}fag*t%r%Sx^Q-eM@Sqj zsV6Jr4u1;!nhvSiP)m9{4B`0~ zrTxb8f5hrp88K3M#;$vRC5?4=$cSWjnsD(unPoc?jk09P$`h|(U0f*q>5?bPUjM|v zO_|_2{1Ex$<4SVPj^X<%S@h~rD6I8#<;ueb!B5@=C0=Ucb7^L@`C26VUa}b;wH+g+ zhR2xozcp<8Fi(1X@<4QVoI$*s8`!Vsr&)Z&5A1xpgqxhv0u8s}R6RURlv(5rn{B6v zhveOHS$+dqwsaVV27G62=Q62LTpnwh)`yVE8u)tKpVD)-Uoa~v3%w3}7OK790t~$; zWnrd3vGzSH&nXdjHEJF)xw{PYQ}nP^u%r9cCH6+;4{M3&(lEAUwxKy}?SHGZPGKE8H2~Omn?iK+UdMVV-2Gf&^MJbo|Pmd{Wj(}37cJgP<1(q|emG$=Pi*x7xVdJ*0hrLqIX`J$2R?^#q z$x3&c!&eP3rsNDuexO2UHMEfBIlUm@OAM4HIY5GzC7!q#hNS;@VlNkm<6bzhgzaX~ zOwF-p^W+Gbhs;cg=^cgt#`zcC&ycn3(=5W3^XHM}-+8e9smXG=F+V2><2*|f|tR5@Io z@7UOfPn$+XeqkTz^f?4;Z%46pS8Z`uZ4f^`{tMgR=P%5Z=JT^RRSToKj)AH9QMjtO z0quD%m^oSSA;;0WY@|BaDqBMChI#P)<7HI*PgclF^2e)sci6PN-{?HPihTF|&fE^Y z16TPf@-hDoN}>iVidl;>s-;Z%%K`SqSensz%fYhRP{}#zC$4#QTG-JZE$nvNjIQ~i z@Kt?}^xf=)9Q8OzV@GkKLMv7-uVy1c#&DCl%W(2I1(hyRY|8r) zXkW7&Gt^H*%ZHvUXzB>MQcf9+zn(+8y8C#de;iqumx}B3zq8@}Bt(Mbb{H|)7>lG? z=Ly$SrAL$Zve#u^sP45797;_@#V|uwAazuuiW=C@!VX|8Vj; zGaz3V@v;*m@N{eqMuiN;vcn^xD=`qalK=3J_5oP-ES*gNGS>9b@M#9MWffTA;azVIP_jq`?*yQNq+ zhv3XaXR+}0O_tPU4+o@Y?)tBrz?Y^oFR$~s#mok_j9&%+xeWs~*)!rIz6LV~>ywUY zO-$#@N!(r)O!m$y5vyIskegLgS@IA8e|05`O`g+1>Hqt=nt3o;dp<n_%LA4&;rTLcC`+D<6_h@D=d5MU2JhL>65N4I#wYG5D%bs_FV#i7L}c*oi$} zDS_6>BJA`pr~03ic$?=HC^GMd>Y6TWL9QYnKh%=e+nJJQ)1<1A!)H-Z<1u@FX&i?1 z+6f^(W0*&rIe%I>6gC)MMc0=ro+K_=7|gaT z?*|b*7n1n%S!4ueW1RUX?0)JF58@JV=%}&mOm{Y`l<$o_C#AB9hCA_v=@EFKo<~le zxrRC=p`v&l39Rk~i__i;DIqp+MJY&7+NHw+zZT(Jp;UbO>jnEfQAterP5JRB=fu}F zrqK1IRea;)zo^;^cM36lZ$|1bc8c^)3)sb+7dG^b=T8D}vsJ%$S=SAf7>l2Z$iwOLV3N%Qi0-Gw zCZHbK=NSgicgCQ@{F9LU&yr;>T#082#?wVxQzhT|Q~vRE8dN#Sqc}jim%NK79x`(D zQlOlkAOM6Bu;!+n4D;12C66eE6-l#NH=(SS{O{M`@kA?4$@Y?+H= zdoARFqhsm%rHQ;X_J0hWhhI)@7{}XDl8`i{M4~sM{ha$c4MeDjM5$CVlAS_CLwjg1 z6{SHtM9;ae6B*eNvUk}b$|&)kzo0%nJ@>iKb^U(dZ!z!uVmkg=JqOAQ$FNr-rm>G7 zuYsRx8hE5&C+Uv1q7Tn4=fk_6!DUTNn15v^*P0tne+GoJTl@aVAZk<)fRj>hqGePht1#;|6i)w16GxcC_`<2+a=VOJUTeT3 zu_>IHf1%*}Jc%M%DO5Pz%*54(qx>6pJYC(zRII**arRds@>DJ!daubHou&@H>iUrF zzJmNcFoIbwbDLY}@fD7i>Ece0E6fmwS9D?bdD>XIo$o3#f_c3Q@bByZ_-ZY1lH|7n ziF5+rj(a3kubOPnT?oUDcHqt?6ZWo!Dg^EDqIXNwz%;=dTjXNs+n(9bRriB5%+QCz zxrKc7egn|HV-BzH9wE2CI6&u(W|DU;AGf5`f=ib@r2p+F4G!0#aDy1$JRFNM83j=K zAcG9t(*Pg4Mm}D732dA54KivY$+e;haQ5drPAn>=DVFYN(rE=-8>QjiNu=W&V_@Yp zJ>2sm0<6O8iGkoyxPA1AkQpdq|pS1B?8Fl*UNC0d0`vTwib~o(kI|*rDHqpd)jqE?O zVJP9H&a&Traxw0AV9l8c2!bl!`1>${WnYNJYoqv&g|?6!(@x%nO=54Kcm=aJ-5_Sg zM*OHpT97IoiM7k?>A#S@>;>%xdci7=SnK_wy1XhUYVBoSNbjJfrwlQ{WjpBP=E4u{ zD>R1r1ZQ;45#8-?sKJSqyw#m!_#_;t#<_mp64SPSRp1C8lBQA&e@ zhQo>v9bjcL4>MQ#lA_xqA!9`c=lI*6_xH%g{R+*fqiTfZR_kf1X(~pNbL65;9JDJA zWlvQ3)6MZ`$iXe!VCLD~IHp1mROaZzF|`k5^cO=upuHT6O-_)B>lL^$hQfKi>Kz)I zhLNo1K4NP91$s}V)3d)7;A-tHXwg`YE!j_*^u%aiBNU4QYd4;Tq(hb0qG4b{bbi z?xEM}?^2`q2XM9L6!Mqlpx;M@-Wlr*yI*eQBA?C0g#%M?QRopibzdGi z?(v*v#T|zo^JhYNycusZ^By{uKgDfFN5LoIS>m;GGJJfi$)0xkgc4gA{?+MfJl2>^ z)#4OkM)*`-=0pR9@rURmw^}^*{VG_fhl7V-HOYHj2g%z5Aa-gUv!gJ8Ibrz>H@rL! zeJhmN*PgrZqIeQ?yX?lFF`oqFvngclPy&_cM9x1p9=?=!Aujh&?ZjSG0wNVkut34D2NezRHczMBfkV;-@c%s@4Tc)Vm5*`oUAun29lffqkpl3h@ z^o=)(zDy3m!mb@uf2%na7$GRV@F(T=MnHe}5~}k^m&nz6a9TkAb2h`1IgKITnAl}a zMDfLC=G?3*;<1{c_1b!@^r}1phr=;JieIT`Edu@-X{@R!SrFatOcaz6v5N{)qH>9X|%QdBOIN- z1SS&?E)o~$o3`1|_;nXIE!P(H?-s%xp(7x%@i%jSwKZ{<4#po6Es(YiN$3nae#49= zY`Lh;J^2<7M?Pn=vs3R;S(};Q@Lv-B;Vj8N3{m8jOZ;);2n#mUT^{5YXz?TZy`Z6E z0`%ptW=lC+-eTfb?5{dZ#!uS>QwpbI^a44Yx~zrV?r1>&rNIzr?Z(%ht|m#$PrUf_ zJ~`yyP4jo;QC_l;?KxHsp-FylY=QfUhFEQ-kUPuIz#n`emO%xZF+0XjHgE*Ljn zq7HdWG5@3;K1j5K((mDT;(9pik@7+41bl!W({^(kx`IhiNg!ho-#}JxucUszKhVg7 z{FYfNy~U_KZ4 z@hrAfToL<4Eg?lq594f|LS}57GFd)fVCZ`&5lt^EURAss9STNL|Cgu1-pkSiBLRJlimrLLD?Qdnl4+^ zm%=L=n6jK5mRE}g@(w6FYZ1=4=EF|ft%s}p3gE5mSR7aog%(zZ*mb{vmpQD=+k8HZ zrBMoOs8>FDIPn0TZ?uAa5|D#S^ljPy{KoPD!u!YRpu1SnCSs@iCGgz_()>uNB~Y>I zmT(trLTyVkUL|89d-UB8!E>d{#w+T=E8(tDagW91o}aW^bw55?>y8f|+~(eUOEUwv zj-f)ZD)yvpLeq1??=$))N>1-4VgF@Ouf4gX=f+*IT9QgHbX-C^b{$T?)XM!hexAOl zu%gZ5bXW`b0@Ud;;$Pm(LAPlkqy-~zs`NSWjg)&heVrl{+V?S9Tb9s$YNPqf$2MTv zs~YBy=@Rno#eI&on!wK5dI(dFTk<0&FNeJjsc8Jl9}^=_(t+QC2P9-H=@@$qI}UEA zFGh{yp9o&IY?(yRo^hNRtSn1S2Rxvvk= z$ZixY)wUqx-~5G(Tjyg#>3%-ZG#eFUC$f3(57LzKEfBKwFguthg(fR^GuQWLLDt@F zFrPm}++hu05ZFg<_HV@e#h*crUx8;XXY(bZAk<&2#14FVk7Ji+L#cWxE1jB%qAFk1 z2-Xx_V>4)!-U87Bdlmlnkrv{3c{857xrXh(UrQfOKgU-!PvDZj7ns}Q3ajIff!@b7?xNmYblMfj9ko!znMom}^YjDiWtEC1 zzcW#4>S3r!4J1iBeqrZ)!G|0<7N4xp0X4I&IQ+^AOl$2Uq1uLED5=7)@>xQhN`aIY z-zV?m6KQ_=Q}O(mIEIAQaNj$`=;jxKOjBz~tHgGE{?iNU9!_8v_nsmKwwnBT z-B7f>s)nIcep=EbF37VUOMjK>N=B_%Ku>K{EHAw_@W8fA%ts`EZ2Z(r6 z2`pI7LT0!gnq+Uq(T*C}@p=kb(s>C!nj}N;kOx#QPKUk_7Oy}5v*te>I1J`vE2*s7 zNm8R1OXCl30LjIQbp85B^p^TYhrCq5iEHNqZHfaaB2z!m^>NcV{ms9*4ONq=Vxup3C_Ay^s`D+ES?J@6 zQBO!(++u#h{n0q~VJMYuyh@TH6=?6AOt`cD4!PN3h^0ohAR}Zze^}&0-2M$PyJHxu z**C~-_fw^QBb7jM+$DbhnnZf0YCj%V5@uadCTP*V5Psct#uLshRB1;z(H1bEyHm~z zuI~bfYjfkiz2Wd`(k$wt(MPvjQiOqITi7pE2EUzxQFKL-uUT!v##q{8QQr@oa;qGE zW*DH!obTZ}WKS-7kl?R~fJ_ zD?Oq3-F{SAupWFRVu@@2c(UBLg6ngA&NMC2fftAJNWA0`ymCH)J6Bs|wZC@+xx8X2 zuJ4`$YCi>5jo%a)lbVJ)nnm=*e-p8OatPV?R0Xew9A+}Rb>PB@%S5{207^-ov79mA zis?Dk#*G?3lYTy?4Qp4i5!;+q;9wk6QsEkB8;Stdy@J0se8VHhlTcun>mpAJo#%W?YOVPNGy2Kz4@ zBrhXWA;X~+;_Y*>O=BF{HgYFp@V16tptr`25k5&()|EH@U=-s_RGTruRsc zI3>_rA4~_T4q*5FNT}a17rU$5aY;5p%ZJ;Tq5cOgOA?5_#w9ZT$89FJS09%;U4{jM zQ|Yh09-N&pwSL* z(6vnCLhU|?YnzS>g67dofAC0deNmA}k+zDCIrHSCxiGK%t_Qipa!6F`Vj9<3g+wQTzEVg>W+K{2GiT!AXz9H?2U zIXx4qFaEYf5_WZTV6&1M&a|qf^;`DA)NA`0`q>YX?DWayxiw_*%^0B*;Eba?Q^;}E zn^gJpTq?CnRdD$Xr7v<80R(p9oDu2hTNg(s|7Q$YQx*`ZSLPHm7uF$bQVh882pCjc5r@3IU;UO0kti-##xj`;SZsn?9Oy!HuRFI|seLnc;2U-=WNQ1?v zFu=S3M!&8l?xE_e>Ni7v)+%{kG2I-R?iW*b_BA@A@c@;q9K`h(YGH7BFd3M-gLDXc z$ORgb=rHa9d7b+gKixS(ou(NG&r)TU|1^v4TjedxK9;f7%La{JXXp%* z!qb0-p;Ma!OkR8t&wR9l7KfL(|02)G$oA5Ew=2neI}@M}QsBSqI;??9EbNP#N1qy$ zF{*3E(SqGS$UUh>eALzs!I6(?az`t-SM@1M6&GW8y9*ujGX@UU+#*j_dxD9K;BroN zhe(gf;8~SR_toFRK~-<4$X<#g)5Xvc+Deah<&!zBiKta}5r@9I$T`<;1$~|S#9~bv z+V5Ni8@Tnb>TnkA+xvq=9J!8h&r%rGhpPBHr5k+IA8;4X1d{)hzSFrmhXmGFaZ^~3 z4#=spB*nNIj|6#gwl64LzxIY!tr-C^b*B91fKg2EGH22oE%-lb8pWFF>7df0Ph>^i zbniwxW@HwDm#NNO$yc1SAogqV}hk@@BA*Un168ND;V$n2h z*3&HzChYtLr?kVc{>@g-P3Uawyz+(``fq_xy@Zy=ox3v_2gii|ESmbBz|c$K2CZp+pTaIm*uzh4 z97fX5Okiz117Tgb9Te>CgY-8Y5a=-sy?;MMTeEOTA99QgDEsnmGe=MSwjSZgDMQ;ReXPE&O3Vb)qC`(Rt zPZ3ueeFe--jBu{=8`NKRjy%|u$xb?T816caW`Eq&!rr?ELN-hh{0^gKL36u>HK++-|}w|&na$&aju@I8?_yk1F1N7 z$|CN+Y0|9bslD9pFIG5aH-&3$O<*fi2vuovR6T12AGSSLB)im+k4ZA;*Zy1z?RO=4 z`HG<=!1p~2It-&L_1)n1r8G>EHl=@U{MeO>!ZT%}5&OyO30Cbp$75(dy8jV8BkJ0` z?W&W)EG?0*b{oO^W%yx8*dBa7cNc6tsLv}nCPC@S=>q0+FQlm&^V7L*kUm#Q%%Xc} zxqAfs88IHTI!|MUsWdOr9t*R)r0JHdEOZ{$P7*Io#ZE^Xu#YYiKQdB<9SI(oJWZR1 zlr913w?p`br6#OoR~8p`Z$Fifii4l9L-2zZlPah2I5Nix>ZYwDO7Ygb!_!oFsE|vn zde-Cq{E;+#;cCHAxPcqHE)%;J+#%N{e`gfbnnB0;B%SGfM(A+JU{an0d_Oq}Z4!Rr z?4xEZ7ypymf6m9O0cBdGTtdFp3)!@TPw=a66?j}Xh8*GNFEcubFl!ZiD(*a8+SX2m;}^H#{jRG( z9{!+)OW%5z_)jx{=boB?3Nzi3$a))7X z_!R!9++jTA=Y#+BrJ-WuabmW;jj;^Sr}LLyg6iL6$rI5*I(lOQeH1>LT$^&5Updj4 z)cbvf)kE~@P6;3Wd&y&}mz0jl?-vMuxOe32BPqO_GYLDs%d(M`SIOP!WwfK*9+eI> zks;n8yj^>&C?;hdsY?G&4=EL6g4J~xD5%4+o;9c>ukk0?v*lXYvn&*g){1b9!+ZMTmmMFTF%&hvoPn-+ z4C`w-ji}w44H2=+A-k?yIJXa5)lQf}H50C}VKUhu`6YtRk=_QX8SC+KAy3|Htwbx= zBhb{R%>JI0OO#IzWfL7nkk%6waPMxIIDf$btlQ#G-x6n78uX6rldmUrVY^{!_$=;f ziZ?8JSV%pDKKu4rFJaFxNvfM4%l7)Scv(gh9{FsidKadFRKqj)IlmCQOiwd;a~8oe zA+sisMy6`&sAyj?oBUOtwu?;y2u&;a#jR$ZZZ zox?L4)7kl|6pm)tU{Og2blm+*)eomZwzV-Ro9u$~&I;`7Gu7a&SWDiNPRHczyTm#^ z3-n%WrHzx0p;z8`R>GuD$7?D3V*~BX)0X<)RK&9ztsKT3W zm}8iTMQuiGx8Z!MGVK|r8JJ*0@IB-_n;5@e`P9b3l|G%R$#xXpA#RU^%mVh4TgkOp zyYw#D9X`ds&9>vr>L>C=l85=z&Cl86cXF|AWIrx)%i?V^7qJDC7)U{*F4U70$4zY78GC9L zB={?C?dLN8NulhFhh&O@SR`Fx34iNaU~pePygzdaCJ6tJLo9B=F6{_9Dr?tk*E)8{sv>&@WN6@D1!6Tz$eOTk^oQrX2j_5=Pg;FCkSCLy22ShVee z`JWk(&OS?DRa>(CvGbYxuBL43Tn^2nRr#UIk0R-9<_p#grRqlgY(b?T$v!`pj~RWI zHV#@~djDjwl5>QheWUrNUk1FqXDVigZe_n~6yo{`*?8*xLR_Joz_(mDORhPNVKWZ; zb63r;fa%6D_&ZU9&+5E|+xLjz>8ul|trE-^7LDfp%8Xf@l7NL<`_L&i6`iI(Ba^pJ z0r{7j0%uhOYc}r&{4@h$POv6YkJ)OCrH7@;m3a zyB$(4oDgMrjf2h;2hmeQmk*Db1XlDv_Qyn37#8@FR`kxo$zj1{Ve0@UIX3y57Ws<+B>UAT?Zq;Dd{*>T@oy_P_*NfBx z^YP&YF)TWJ6W!2VRAv+cU9(n0Q`K7fQFaMCuJbkKt7(JMh?7i=XQSvZ6>`rHG|=)< zBmS=VM2B)&I4IoxsQL}e+ml8|zPUz%uZ@Jc11Yp%gFWkG`jq-6j|D%YOXRw%GG;uR zN{4o>g?z@nDW?huve`NBRBpk7F66^8oBrb_LOTU~S z2`!3_bj8mDOwIM@%*$PIqJouSWN@+zZZ+%{-xI0x9dBRK+neKv$u~_rB6|l_Q`a#$%Mjtk{{{%T! ztwZ0rAEt()tGF&;3PyB<0xKU&9(4U7XLqWy^};Uah4WLm(<@=!X48PpYU|hx?VW5u zeFC(c|Akr5Pb1(3^p1=cx`(6r`}_C9-c&7i&v_C1Wcg9pscVh1z5Y;zf1}vFe=XR? znytdRSND8>?FkxjsW~PK=ZV9NYDynP`vy}ez?R{ zDax^XdyWG?Nt2yB{~JcGlpzBH!)eXaGCVTh2hM-hgitjp^jf~(sa;!&i&n+KP(PkNjj}+JS-`Chx((xM zZeYvi1z6+p0q_#q;!-NkXbnf1jY3wV;36i^cc3v! zDiD%g2}5pHVdb|v)NgL5<@XJsqcWQu4o_fJ`!(5#N2bBCqki1d)LSSqUYR$ZHwT}b zZKPMM|HGQYDv&>5jjPn8n9tqA`2@>XblX2qIw@@mm_4TKv!1D}J+BUJ2^zeT(?q_a zZZ_YiJ{AIRJFyz|Jh!PU777g{c%v^#qF>ZyFB&tzUJM@nQLc7}*fRkNYC3;D~LO%PD9kiU11<@db~-~;VzVHRyBzMsB8 z(zaNlv+)w9uWW;~EM<1jt4?%ik0+JSd!bO$5hq+4&b{3=AHpmr@eYNLalCMLwY+zL zcc#PG$jOC;!{-vW1D15nrzJ$DW-ptxC?2vV zkA=;Xk7C!6ARJyXgI{BE3U@lz5N?QW%ftB0r5?Fsh{8p$uMSv)_y3Vnv3#vgqT;rtkco6+5L^A9D+m#q<3fi|YqK0%3$(RBWl zulU($0v695&tBA(X5Y#r^S6|&SjQ^0=J(o)Y;4Xm*!w7ozMLQ?a>1tj*rkSe((f*A z=($GdJs;lgKS}oW<2e3QZUno`UJpVBvia3k2N((eVQ5=j#cAXo0RQGpqCC@5BZ6wcMEUTgWH6j4MjsfqGILOPl2mdjxw4h7KyyxZO+HIYv+d7u0_8g=dW%g9Y z_XfGU=9uX9WjnMvb_>tuq$3-&4<>fkaQDAY1B;C{WRcki8gJUdoV9cZ)-@g9+-RZA z;k`8G-CJ_Q*9^;otVP3j`{OztcmA2tbtrvf2j6#_Q+>%g^2AV*>Ij{-MYUJywJL2k z-Ek{E+<6&YTq|*sS2MP6j;FWBk7A0V3^4Q8c;02;0mPcS)APZ5)_f@K#@BE>MceJ;silHxkF(FyLLUyMX^a8SB>9%FVN%=d$0l2e95i$@=M0 zW4?FdLwM+Nm|gdwmNick(}X!2AbWN#KkWWyu)4;wh0C8~&o^%%b2OlQVH5tkHIE(n zK%XtwQGqvKE|Lw^n}y}pA9$5t3&qN~UsTfutSCb{>ESd&@AOzKe`qcp3Cf z$5IK?EO??km(B8)1LIhEw$>;P-fG%1PiB9HrK191nX@b2R^Np4uVzwDKQGe0ON_}< z+aP=XaVAmd2db=kg@W0eev^^o43j#+M#!4XNLIzu8em!TM4C_dx|1BK5aGs1Y5HxK z4Sezr!{xWa8Q%z`rrpyau|*E1@AbsO4H0zmo%5ji+KtS5JQ5vCas6jO6d2%5&oOw~=NE>`TBnJ(vDSWE6CdELa*XFAbUDVPk1~M_a|UetH(awSd9;R&oQS) zOR${IL2>8#!(59ngFU!rKeUZ&B@z>o;L+6<2z9WA3*kbZK4To{`t7DB`sJ{FAOdZT z+-SH{D^6Iol-N$JgL_*>pkb~bOrP|K+nT4!J=EEZ5vIbTM(-xGQ|KRCJ1PNRpC87LdwPxB2$>AW z{#Afd-vDFTy9~a&r;|IvJ*cVm3#gS`VcyLKsD2fT>;DCy#<#EBF}^~)QPu?c`?u&b zGhJ3j2qq6|Jb+EAb(TzZ1GL&Xa#zfcL+iLu@LZ;c&$86S0W$IQqJ9K8e?LSW46|s{ zf{S=E^&<(|GJ_r5HW8Nm+7B z65$;(Wae0QX8C^9)K9_P1@Zi-OW%mcuUFu1m=9ieOR0=YD3w%9=IaW8`?tlkx0nT@6-yWF77`k8S3|U$OaJ zPg&jNLwFgpvF!T^4_L$*{O=d{xJBXaz_&CLrS^&Z_%Ykr!xv)ld=*e8b~8?2`3?WQ z5qxBZQLta|Lsre$fX_^ep{zR}ZcpeVH!?qSWSRz?`E`-zIC&tpv23|V6Rwy&Ti9Du z;xxUN{N8qe{=PF2u1R#D;~I0&IXnuJJ%)m_@Y%k#oj~ogYDvLYp-VedglUUT!bai# zvBty`a{H{H@MQuuu85Z&y@0nnQ_)l0h}+$@M2Y?L zm?`r!2)DZ(V~b1STUQ|&S0hKaERN$YdIZ5}>zO$AkraDlObOJ9oN1tSG(7x~hoM%H52KZCFDg&0|fjNJfUSqP*%GMMQ_}xLG@(T!?Xm0 zenpTs{lU0jrW;b-)u`vZBs>++K;Fun=637!l5^2pxDUsi@W+SW5c8=LX7+0ETLayp zZm$VnQ@;XNxO+oTdpylEoGSDzMDXdm9(zJQlkGj-!=B4I!VhdVW)-vV^Yd~Zv&YSa zoJ^aQHCH)>)wIusG3{Y&@8CxqePRk!Ik-cWT?w=w$!D)<^pKD5wOBu452a$3$6BWX z>J+YIvi811y{>Yq>MKwEa=ww?0G?9_XrYrb7O>ws2gpLc4tmzr(w>Deq)6i`-j@@& z>LD_$S7$mN6?%sIC8Zg{+=8L+XOo_^di0yD#=Ik?c<^&H^fdXB35-32uDi@U(di*E zav7-bx1Nm2IRI)2AJFKjGt4>d2S)NAasJD*Tz-l%D8*_*io-6jX_SDY)s9TX-M3)! zIEzVk)IvGUMYwuQAJJYok}Q1Cg+3PhK*4uBX}^()m&&y{Lt%H5xu*e#%6tSiZ5$Uc zXE??x9TxgqWgt2DkLLAwFcROS@$8NeI%-=e`VREL6SX~{P~1*VPZ~%4{F6wQe-S?U z8cY&L|Dc^#uW_qvy12b`E9oER4W9n%=}{pA{A-*XPJ6Av{0N%E?(^FLbG|AQ-Q0MN zS#$`hwf$jcdjjWdWQA8eTye4PWQ-0kV3rEZ2J=}HQ0sOo_3+gs4ZpK-Cb1W|G8EFF zl3Wm&Ir?%3;3|oNEsF$($3}fja5YD*=Qgyi@)|cjEf_u)7U5c%k^G!xKJ>r$GW_-n zf``27JxpBkhMF%`r+Fp!xb0i4$-a7X{^p(WP_#K0Es{?|_itf5(tDe2I3f?9q~aOr zxm!W8>pU)eWofoa0R{f(^`CNL!iL28-Qtj zNi;-9!dl^m$a=^gdvrQa$@`&6&?zy7ofEyyy8E#)S+!#n9rz&2M>!?X3s)(pKxj?}d!X zP93X2o5$!iGKEGi$P;JTt`eIci09X-PKJeF{t?@V(d?5a0dzH2N+N_A$#jLe#P~@G z2|2LUS|?A6)@PsQPGwhOyK*Bn+ZIS8OSFjS@lpQCmB+BMzlzv7UM0CoN7KC~sZEmHv?B*B?~pWH;@{BTiZ{lZbhZB|MCHrO3ogIwQu_ zhV*dA8usLkd9+eanKb-8gxWg~Svzs2+`XJzO{;%f@XwlqIGKh9oON~~c*Wl1A9_B9 z#r@|PFIPqSLb8S$#YnR&+zv7~&NedR4^8Do#Sg3(tAx=@4#$|bMusn(H4zt>yg`Hb za&py8tr^aJhRG>TR##djaK?2zacJ5*ChSur$>B0!&2&dU&rYXvF(=$WbGF2oB%fCe3bagBNMSO#u?z zOf-GT>lty)`#%Yp@H*M%p??d-`!St3ik73!vs!LiiZ;mpMd?9p%AYRs$K!qxm} zB!$9Rc~d!->^1WsxBeA2>peGyW1l8B`wCrzILwjnR4B_w5Bt;?p~1^VDGO&ZEvV9V5OGns9UVlDOqZ zd$@)iSFU2RGP!_r$-F69MDtP}_gP~+Gx%7Gj(_$;l#rB4+9NVZlCL$BdG`ic`GXfF z_WWg(^_FqpHm;@4vyai5f0jh+Xgj0d@QO@?5L*9mGL;B8CmON0SX6bcn&@|);1>6k ziWc~45Pi?ZqSin)vf@z==jOSACTrZMEByn>vhU?g(r+W~zJ)JcJFcI5m6S{qf~CYV zYd4Yh#`{dPwjBNJ)XJGRbZ|%fKQbTJT;S;FnS#eh9d%zskuZa)#I#re%U_k#1M2qF z#_>JfPSY91l^?`2HYJh9x8|s^X&FcS_8oL6?oIGE& ze`$xKE`Op%vqmB>JB_iaOJu_If6>IJGa>OuAsP7tryOmTnp1uV|deel5U9@Pu;GsXA0{U z(HjEaV1AD+ZMHduvnH2uH-DFkRG;aRv~V5nOvq*M+IoO2n-@l+b;sjCi7<02r<|-; zG_AW{#;q*ZgH->?;HWA~uaaOaoDsyWyZf7)DI-S?R8YEl=Xv;*z6l=rZzWbsJkj^@ zLlP#R%55mEq3=pm=#}*epj#JCMn6p;rFXy30qrxKL#q*We)}KgPkyHHd)guImOdLB zAr1B!LHI*1m#n;0D_VT;4|RFEi@U@Ly$5L|3VZWO#qz5(K3R({)gMo7wX~3QchCm! zH4tLt#BQ%#4-I?r@J7iXv7b@NL|o~lGYmC|oVN%T6^;bS)*|luwiuF_EQQtIi%E2z zDp9vR!Gy&*;KU)j*s`=tNc~WVBiklIk!FuozvC9V@Jk)JpShNC^;ig7{}!P7hb;8{ zxr=23?t(@_Avm`E!UAnAmJN^5@$3h6JiHNaza2_-uN7jC z@i27$uaMS1k)%z2V=*=2AyNDA5F^`<_?`1vscFh8> zxgQdCU}^N(G$VQ_@es39p%k}`KSK?__%UhBd2Uw0JCWCY;q7O2Qq#r{OX=yG?--Y! zAm+gJ*W}H3Vc+}Ux%iuX1KE57sl2x0%O4{IY@~=wONi? zv_%2kUAu6DiY5)PpNt+~SZKXj0q3?~fUvG8ao|0HZJxRs(}XB&hPr%QO}hay-H(WPcF#c;Ct0=+H0P8=PSPX8Wqrf&{S=PI9<6Ju^T?N=Np z8uv7ZE`R%)>nd#^@e_v#NepvRFr%4!+L%NG`|LsWks(eVd68)4Ps1S>PSNwnwlf8V zg+yaR6yqwYBYz)!q=rq2L@lITTsy&uKK{3wemVP)`+Lk+v?*z>;OM$Y6MuZ;6pS5c zAFTv3-4Hm+{(zV9pAadzej*)W;EQ^8cl-@%NTR&OLfWx&%%`m`X$P8$58u=wy<|v6Skj@qgvlD(c?3w;mSjwXl!^a99a^9VV7Kp$7UAZ-2O=ljIG&f zFMD_)Q-lZ7r9ckSnO5-@$iFJXue-mSu2~aEb>`o|m-Az=?!O|aAGE`)p@N&zr|1=FpX^85lfU0bXbkqWkSc*ZY9@^R*~ci7oZk$j94XwOuDHpzF=-kG?a{l9fZJ5 z=})63o@RJmrJUY$GZVe?|IFPnX(3#vG?m`-f!v+C51umxRJ7GrRPbjMdAMg7uCpBr z51r?bwQa?uZQ?Q7F<;0KO4^`N$^g@>8$n;Q3e+d?C)e|K1b6t6HR!po=5*9g!?ky# z$@ix!G_l4R#`kT3`F;W9`kzzuL9;NcJ~$GiPs{?hwZYttNlWq4We+-AUm54wjewDE z#l-Hr;AuFi#TZ^H1JmcXNs;zZl5k}>D&=hAK0bG+XHCngmR$@qh5iTM$Hn1Ug_|_a z+MSCCR3+tujbN}`g55Axj&Ahc436VI6aUUZ!oPoV)X;gtbUgV>1%77$5OZ7$O@sJ^aOd3~dxE?)xkAio3b+i)a#@u{*u88jx2SJ8UNx(u=QK9b1|@A!u*!n8 z2M6%Pj$cH@{4Db%J`j5s&V+pu9GN3{_ws6|i)^=*a!J)^am&tjW-vz<*QBI~YihM< zV9j%4*&h!v#}+|yRV+kYUfR@NQ$xqqSHR}frH~b5LS80olfg0*ZJ%-G1?=jx?Cm76uE-?vV$EEp*#!9(IgcLT|fn zr5-)!z@+pr`ITjjH|+fscoX8&M#q8kR3TSTGj#0-_!Fme_xlSST zA3T7|_G-b|Av&B+iaD)=I&t&!Mu?4>%8xQL!}9hFFksX{Nwt{0H%o^7FhP>9EWQT6 z0&}SELuv9+atE&1*&mYyCv@x2oJpT$hwAHM2KitLlljPvEn@V&4e^*#V z@lI&EvxAqpGu3+g(TlA2K2_H{z^_mb_Wa(-YFTd{Y5-j;kbDQ%va4SsAcd?jzJ_sNm7N6ZljA6xky+7a=TW zH$1*WVDtq5I@Xrbz)z&%=NpvO;9$K*3Lz;1N9%uz&O4mT?~UUsvLZXQ5LuNX8PB;7 z(Oz1VkyToh#<#7qBBWAAk&G0f?2OO3A4w&nqNOM_RiZ(Y^m~4P_|N5XU7vBDbKmdx z>y;fsn{T#UBU)9k3BLxq zVt<4pzELYeQ{NQWyzCXWX={_Uo9<%etpYsSeF}!#-6PId^N8r>ba>qy!!;G$6nLas z#P-M-JhZzP&2*=siAxh_D6kU#o!`TkbUT9gFd>%;#^j{fDhRCHK@9m2O!v0|y$L+@ zJidr7=VD1;hu{VEnaWFT+`#fv@)@_v1}t3k_($>YDpZ2*f{jx;6v!sRA@v(@@JuO6 z#GfHUl5FYgZ$s%h+{L=yhcn|V3;E>C_5l(ARTm!kuSS-0=wR-j%}SiexJ{=lEf!$c6e1x22`)&VyBW8K^$c zv(YV|NlQbb`3ZM*=zdg<(at%>}3# zF@=V;7ooL&CVf>^46SYp_)0^;W#aOe-4Ym8MZsp!GjAcPS4i-$wmxN}^WO+=;d?|5 z5^>gg6`F9fotW-?fwP{)g2haCIBqC7$tR`priun|t4fRZA1VOV+Hd6V z%7a6U4jw)qf$mj9VD*7MVmWFDJP7lAo)R=N8{hCv8>x39b;u3M=|L0q6m-&|A3kCLcHWW%V z!?e-uOnQ1XWKW8>z9SP4N2^@mMuj?GlPvIu%vI=>?HX9!KNK1p7xPg~;jsBvKEJps z3^SicfJ^l-x^VdpbX#ixcs`vJ$W}r7@wqHX`Y%S^bH*m;6~udoM)~J`0c^$lTsXOK zFZh3T;hX9|;9$s8NHA*zrFRX212qvq{GrHbU?g07S!xv)atTc*cd!r_b)Zsb$)lOa zAh0$APW;|Y+I$OI@VVOMruXhZ+^&t{w--(3n4Nusd&Zns4_LA6+90tBmtVOoY zLeIr?3yf&U0I`lyG_+ck&Ht;(8?SKZ{f%eSlZ7TUA|ZtK6w9*tc?U5mwT$v&1c!EgL<3td zbp2wD<1BXawhLxsZ~b{#U7<*A(+gOY*aiMaa55V$_Xn0I>k+#%5Afct5twS40AKxj zn7ZM3_QA^*dkz$E2YNU1mr`b-Z+05ay6NF;4BDf0v2btnS9%2 zkH2icfYsrrWaH04658Ks6_+jKi4I%xk1U%o*xinfio6Mf+thFZS-_XWkn|A zE@F(L3kwZiNPL@gAZ+SBFcEm++GUn_t1A>&%UScf-`8M(gB5MtTLmMBi{L+9Nj@ms z030qfqr0shzPLPw?fDo65~IH20+lfM*b@$g;UcsiD#ahW`w5$Gl#s2%Cnl0x^urI!Ue=dcMfW582O z4cCtGq#x?GK-W)exVJ`;-kf|2cAK4r@TVi8(s!aruRR8j%N_xfqeuCkW2!Lck&q?y z9my5s%t3?kXK=>t#Z)TeH91@I0(8<7n4-)i2<&ZS2Mxq%$tq29vLEQVOY+p4B*5>B zjWEpG11lax;ANdSjJffKlY70DTE2^5nKRhVIaEF0c7^uXk5K=DRtTy<|3 zJW5TW4=>H25|*i;UfW9E!FK7o5K-ybo7!{4hT=lphG> zb+1jPw==8Z1<|IDA%cA#is(+=!sS8zlBT_LCU01tQ$gO|d*Gs|0!n1B8cT&EtvqyJ6E;X;t=-SN4+ z-k_T44wyN;B9Y6B+!x$PhFSSVOWwGZ*t1SgPGu zcE4;Lwgp{dCF`tkmG2BV^~|0%Dk+mn4-2sLGY9)amq=aUF`QOu!UBxy;hRD#$tX)^ zVG8S6x_vkIRB$`L%1UDPLGGxw{0}*&(ZD|WUMZ`J8w*9o)7UDjcdX{uARFV5EJ{mU zM3;?gAU?|!MYc(!u&C1w5>KQGeV%{p?}1P}{^A1hPbk2F{nA|L@K~-u`M8h?Yb zJkOh$yp+NhTMIGgp(*V6AVb&2PvJ`zn$cC;=Hp^zV@hxAMtk2}NKTuK;>H4#T=xpN zP1X^3=-JqoLE*TsAx;*&Re6$OB9s1D&V1>#@=FD`V8yO&xMaDeNHe)nq*!0V$}i-w z8>{Xz=VKWhcWon;FMWc;js9?^Uz>^7f>Mr`J;R=9rjV`*;rXJV7@Dt@p!nu9Y|GmQ z)^jU?J(VjIMfMzKQ{S#9lauQq^4(ax6sE|WHrPSP3Mv}AtDJoF{Z1A}8^Px(nc#1v zOj5GP!@tx{mgc&X?O(d3JRmp|Q%A*+MSG4CI(Vq%C~5yPigS%rET>+I|OCG;Ero$^|eAL$q{7sEaz5? zYZW~l{)(JTSxth+{3NG6ikaTRR?)A|H`p!tM4T5lR5U8%G|Sp?8F~iZ5vdeOG`b|k z{_~v;Ef#Oer7Bv|N3M$>LnvRV-s2W%R@~6nF-+6A#}zcffddD6kQhEZ!MwR zhnp(L;gdNUT+rtT&@k_2zdz0=QUk-eYU%sLr?ZN*b;!bzs8j57leP8MwLc;H>~zt! z_6Blsk0yB|IgLMm_$ro-p3fX>!r-t+wy458i#)Pg1JBcQ$hTT4xa;2sUVXw0Y|(9Y z?#p$eus4}?uN@7Ys|B9cfmmLwdKXp}X!h>t0sasJLON+N9qpaVdbNLNoc}@>}U*b{7;!$HY@)u^Ni@4Bn)`lH zh1XK_1)Q}NmPN0I9lE<&o7YGPnS$^xU^Dc&ycWIiSp?<1JD{-t2eH!SSgmWF$kXx~ zSN>xkEYUlSuk%GrV?itgC6#c+bBjg&=HX=I!({GDT?jLk_d%7^B$jdGLB$$@=dLQF zZGB4RUPX3UEx9?_1G zb0k50fEDL2CWlw;r}KX;XFlFaxVvW)SvcLDpCjRqP9_RC#^Ne@y*mm|j%*W!$FF1) z)HgtR**k0H5)~N!tcS(VEg~|?@-Wn4JWeUT&IOR;MB`5~Uz0A40oAD(b$JDucU%*P zwR*DvzgBQMV+Ub%^+a>tZL-*11D)p!OlHXsSUhGonu&h^AJ3` zpTw?)3an$=2!~Hf5^K+7ENu@$T+~{zbVVr+?HvUH%m6aNk1?IP|6uF99-)uA9zIBD z(QkX>VMDnGE4{T&q&R92o(WFmU+&R3t>-a{^&R0>1w0g4jY%yp+bwii{wZSO+f(pi zbOE!C7rMIle!^MFiR97{PIP$pHj>a8PbN&Nmydcc~mw zLXWT+vQH~kPYopIZ|)OU$EA42cprN>LYKUKxsKRK$70>Z;p}y#yx?ISLl%Fsga+kH zkfG-YiG$Zk{)Z&|)a6cUH!fgt|E-4YUz2cT&3kg@YaR0DNibUaF6KObS5aybihJ{h zVXfevG%}T@z1L!4V2KnPHsKX6B#uy2D*+3VL)eb?`*=}gLCu%G!>%J5uvKp&pINdL zoWDOMs(#m5lif=2-M<#v77DphyI*LV*eslNiA33o5v!&oP#Y2lb(RmnZVkSuWIMehG8cBK)Vzi|E`Z?O2-O$Iq~?!s35RsnV>I9Di~# zf7i$x)h^G6k)Ai_c;!@RwIZ+m(FB$Ch8de`z|*x@_^`y(m&#ub{{6Q zlT12D1%72!F`p9$!E18~w_b3Hn#vy~%Pl1_SEH|@YTasRl}blXhXd&Bw;!%V926}M zbOtFy7jPbMB4W<6^j6^&T<$iE-HvmH1Cbe|&A*IA+*hzHvS}mt?i#Vzvo&~;WFoU# zp2{6P-dLeE7zx9dIzZIyIWR2!AzX95gdXb`GZzm#$Vu$Q&mGs;{SOV6hG$yHBB9?p z|5y{IM2NxU!d7ChugNXfl7LeoYS8Za-da_{0(9d{@c#Qh74xhJ`0UF=qt{1BI#mG6 zz_TQ6_ifBkm*8*uOR$|z+qkj+HdgeGIK#gGcaWql?qla(M?h##0?0VO=cWbfL)nkj zIN?Yi^$EY$=bbc_)d|5dDbbT0+Jwj$FoFJRL=MR@7s00jM5N{=pH z1fo`dcyi+n)0DZ!528nG#Gb>K;Q>gBGv6$B~{m695Jqo%l-INZQtz zj;H<^@KZ|D!Lh3c-o#gm-o3NqkBbFiQ&b~c+?7C&@0yQWg5HwO^J(C#U<4Y0@#wBw zgFCnEpjT?w!A0XVvg4sSIL$Z->k`h8kugh{R++#}+>(OQ32VtdH)9Yb_FE5{>I=SO zP4fDsF8{eV0DeuGhre!_!TgD;#QwQ4NPjjV?}z0RHBB?P;USHg;wfBAx;T~F_8QDv zlu*LLLG)s~B{`ENgLhXCf#}J~I9dD`>0260R_@b==#!0PSkMtno;aOxmA>4Y9z_^+ zr3%KLUkPV6USaW@DuGtX5<6o#7=AFB_)RW@Py3d@_tG>jtGO84&3%B12|q6TaF1y} z_snQ0%o?)|Dqid&DwcY9H`pW@vms{#x$rz_6pWSOMqs+IvmfL2KI6BB+oU6 z{XF3Z>JNXj$C9qlzWW=|R67pbuP-A*3LSgm zA}KvyiA%(VuAt-W{nWo_29!Jvd5_KD@E4VUGjS4_e`qo-A_ zDOd<2eabkqZ`X0w^D(?%3P-CyXTX9rx_nMeG-O?gCz?VpmCm|B-^T0H-5=h<>V`oq z`16Ofd}iRQ?Mh7Z2sD>j`x4US5x&><>fj}~5Lza}KI zVFDi`wbzRo7@ZfD^ytIK5FIw|pDbU0I~m{UPZhoscjMY!KBRQ&HW=MBxq_PaRy@(1 z0^=Q9Nqq50sIUrv&dWvM^J5lMUb6#3K9#aVp($*7nF$=K|As}J7fZ>RL#CD=gG<7G zDQZZ8z*oG@+Rx1dzs1s!%~iqPQ)%$^Y=x-kc_~!Z_Oh@3m7HYtblB3-Ms{dKat4jFvE*)jM+7s0)289RF}Ui4%#m(bj}e z@}TxFi5a;9t4-eEoCGVFm9&KaZLz&_;_Y~x@zRO~W!9sb!6+*4=}6qACD7}k7+OC4 z!fM{^!Hl7MA+d&L#9Z{P(B|5gc~{whKG z(jP4Db1EhnF2^Uqi8$)dQ24SYLg2rB$8#PFamy)Z>n&^VqtUT5m8}z^F=Uwm_jZ{X zPEpJ!Z_Q?rk7`Ny;;i6ll$Pc%j0+bW=Nxw^Ux`V^QjGM{!2Py;<;z~b!REywl^!<& z(O_i@TcKaZ#vGdiy{4#9D>-+) z9vk(&Dto4`#McnoQI_f0lMLMads5W^R>kjW7e>E-M`k~ADtteb9u7x zzccP5gOL3(|0(UnkqT>TqT5Oe=g6IH9sE$_M5g&9@%5-NvSJ z)kRW&WiP2;n}6*vdNS0iM)SEz>MYu*88KEXz32e%*;U1cY8IE zOutQ>`$JjMpDf{Mt&M>-tSKws5#!tGQyQ7EZBwwFVsFi0Xs%7VmsQ3n5@=T^q$_rB|9#*{&lX5 z88lyFul6XRq_&Z0+j&pe_c@64&6C1>w+~i%5(*-Tuprc)G!NSuhO5+v{b94?p z#cuACspyyIS!R&|>Sv5Zu?1&1N2^Sted!_zNw;R5@6{pD4mza*Y3VOTe;wqzXwsxij@j8}C>|REYQ}a9_ zckhex=Pr5>el3XU;3iJS?sJ9r`7Gik@Jpx69swtI{b14eq*>34;e2O&6w6AqA?w!t zBMxhd$UCd4(4bLHE?2aZW#8xErvPhC=EjF|u_Zy^{op)zf9)KYH^LoLpO_HOs)>C6 zWP2F3{3ubizY2;mNb+ChgXzPeY!f7sp40M}nbpEQRX9zK2ZD8~TQyX@+{WLz6NLk{ zs&uX3shBIgmJ$uE=--+LU6-8E?Rr~9#fS;eNUFGBf1Zl?xf5w@XDz93S7P$1Qsi3A zUS3*YzcugigD}Tp5_GUl6ysNd1#`y3+2!?2jOXBsku;P3l}*G4|o@}qVh6T+#ap?^SD4P*NwpdK#B#ZxJ6()ke>(?XpB;Y!mr{lvGgq$Y(R5^CQ zVg#tkIoeSj_D)La;iR#Qh3W|jvr3lS{&i$ln}N(Efc0XxR9?768wT4dbn2a9~pI8Y<6c4HNj@wjC^c=Rv3!dbYJY53*s^5u#NZlkmaoMtFS; ziS$H3&NC1~{dBSIj~Z6|NF_=3&uGkSG0Yti26lOg+~~tOf=|{PgNoa^*X7aN{7(|Z zecCZn&aM@OS{I_6dqxQ z>GxQlu=gu(v7vu0HgMZEk0j&FX0qs4Z%O;vA~bwe&wg6P!Rdb&`8S2NWXZFuqOC`L zuu`K^w8ZlwD~Nl>%HKLceq#wW9j8fT-&?V1J(4JEz7`%w)MMn`*DPa40tALV;w>FM zSHwIsV*%GTldS>9Y~)To2r1|xX43tHce+mRj-SHJBJYwp^Csd`VVBtbuMhV+%Heyn zqhKWVhxhv7OY(o+6{U%s2+gkI;^Pv*Uwx6y(_n4BDWW$Xl+`Z^{1*p-&{g z+zS=EW5D)72wrQk2e<4Iu-S6~vw9^?XFS*C9}C&Ek#>^IEy)Bn#h=GjJMZ93l^tk) zYYXjAUxp9ded#5QYpl9X6=l=XVN}NsxHtM0vz;mIN^Aw!#JY`Sbf+bnZC%BCos5FM z3*Jn7RTxw@d;$oM#!K$9;C)Am->X-K&z^iBmH!6Fc26CgZ%>5$R=Vi&i%e0p-WKxj zyftq)Q-MYucH-WTaHYFP?ZT)7t02)y4}ZMBU9OaNgBeY@Sg}aBTSU&#!6#pKx|d*#_?Sz(&=E^dTO80XL1Rf+e&sm}O*;dbg)d-l$aWDIpT?eK~U|K20GT$i1~`O8AEMSL9DXjlLXT1NBp z?Kg_Lr@woQ;ahrs5RtAMgX-7?Qb=uHEO2&t(o^=G=uOWulOC9peD$ zp7qd@tje19Kc7ll4(;NHxG$^>?El99{Eyfu?=_*DgM)a*vM}NQXyvnd zq^aLKEne-Y41c}Egb!0XMK1(BjqAa= z^Q+m^&kYdU@*euXd}8Z-9&???dLit&CoieI4FppQar!Onh+9T7S;6n}P0^!@KW{KRzheIV1TNVNTD1{=R^4;MS|44k9y;tT6x)L6JX8arzNxoN^WKWbvh zoRz3DaG2;$Re)n|mN24i9q!Gqg8xpt!4W0bd|d%ciE$@a zo`hrF5M_R~?od7=?;3Wb?gX(KX?UI;gGM29p}y}tvpe3*{(arb9OJb4%3IRZOj8#2 z9`EAZ+pZJ0I)9e3KAg?XNXDXT?Rb9D5cu$-t2`s+2|TFZ1fBA4u;%bt7Ck$VnE1Bh zre!C<``=rZ(yd4T&MGHV{XRJzX9{r+IyiSt6n=dk&f-faka^YdU^luQjQ6`@>lY5s zs&4|iUzwk3_le}ctYaaaoVN8vQ-o?+Di@RbX%~KI{rAmdpB);B}degir|>wI9z0WhP>L?jb=Mg^l*hV z%(gnt-_O&gV`oLd_FoEkJz^YdE|||oRewkJOQ-uun z7ii-cI%LF9{!T!PkP!(3y?KK;MyB$_h7Y zkpr4r$w%ovT%LD~CU&~=UUS}&xi)v;np`sK-E~4)qXtkiUPA8$c);v2;pC^~ebVcl z0jFoQ|9e)%ZrSm{&6cy)mTaN@T(jvE|WX|A>&!cOV((N0;kJEeoCdcV2NdkyKP z3qdw;={-GNt3&%1%?0;^QZ_S#&hnl$=fS>bCXLZt4uvl_p|hxk{H?LV?LCvJp7K=w z*=HA&_+-lesF@9w+LhGvZXAkqtVlwnES31WjcJS%hcAJZa4a5OuILYR~{u!xQ~nB)KOVt z;<5whXucxLyNBb+sV~@z>TM)7;{jX0x`AyKzT-aaXlC2DyMX=QlMt{*gJs^`gmu=V z@pjS)cs0Wpi{pJ=J+iK&P9#C_n>+jvKMf)~)a+PigB&95fd0!X2X94MK>J(Fe+<9cW_bJ#RX+Wy}0a*vz&`L`%tsRk-)y@s#O9C?zi|gUn<$h z2P%~_4Fc(;IeYom2^m;@Dv5^dlDDz+*X9l0_R}TP9>GGj{q$Q!1yXG@n2~k|)Hk1} zcPhpBjqiuiNju6=_JT3h-?<0vb29M$sj~!Lor1q>j$`91DblsM&pN7MG)*5K!yIj% z61QFhkagQk!=wXA-|hyu8#`6B%gP*5Lzi=H&)dm{N8-%!ia0xRFAV1{3udVuk+ARF zEjV#)0>0JWhy|81_~VroEnJvDI`);}&WIl(K0_BDh5NF;??w=sbBaZ49U(#Q1HkC# zFVVWBD`e=cWQfev!|F}qcxiqVnmqml-tQlf18>W5&^Va=EX-t~Q+bm7G8G&Qi^#=( zITp}n3Bkix6Mkr7UbMZxI6p~TtN1$HI*;fJOH@_x};yi+<4I=sut_^Rvh+|PnEHIBjd@b?u5 zmyX8M!cH>ySuL4I!pT2{v2=Hl8aMIJV$c;u;8G(4w%TGSuRSeMloNWLJ26h!C#URY z&FhWvzq+%`vi%yHyv>6&+?vV-j0hzs6;8mqa|gJP`rBaKoyF#s>vK|F z2g8)!vQ3`y?3Ke@!P_M4P}d6ViXw4({9_K8`KiP@UvPGWKI`S8r+8Ac9t9ic91VU` zz%871{2E{Wq=s(HTtHnC9^!B{FPbU3$v5iVq+C!l?>u%qd;D=6pZe_~O@5He@8Zj; z+C&ptSgHhD?hJzD-Da?Cv!h}UVrgOGP2_t!;LbQZep*`<9c`#j^Tl=0Y;G;L*x@AT zr#!~_j|Jx6y*xJk{0~r`*3al=4>s760m02KbeCxxIcy~G;&wMN@B08lm*0osX>;NA zpYz;!yDX-(BmtMlEkmaxTfsLg9-f95;DX#t?47xlxh^Agx}ps1+vA5pMfnUz7-IO% zN_g$_mAL+mA`gF;S!w@R50MuXaMx=YR)0DQ-u-kzyFzDVmcb}F;RT#`Gl$%PZVX?h zig^kV>{yo@D2`BtUfH?eJK~J!s?d>}R~5y6f6c{Xb2Opl(H3s*xQh^1NZJR@V3+t2EMLrZZk7DCuI9T z3Y_;ohRijQqS`<1I4;Ks$Lx;79dYN$#DTZuV3Q7U*w79uQ~q)1ZskCi&rN(Be2T5# za2BIZJ|OqL2e7>#)GD-B*x+p`iY{YI*%?c9{A1Zw8tV2yzV@&~N>A`zQKNOZizmANyUeLP9SaSbUTle)A#8dS z&DtXUnZIeGXl&C0o9EjL_!r}T(wW{{@uXfX4fb&4+Xw%{*nu@h165}tybKo%1*sf;YcI3IlY!<_okwkdnWX5%ZE8-)^t?&b-LT(KWGdXPfV1L z@si#{Y;J#@U=yrRhd+#d!*Ww`8hb#8ZTR{a_D5c+I5%*IWH;#Wk~`mnzVJ7K4-c_< zMK(f*O-RLow-Yhww?D+siKGgG({5VjW<1((hdB1UVk?up@Xn!Fm?t*}CJeRUe^)&q z79Mk;$^JeauozCqG+jhhBXO+X{vUD%QZ(SoTe!8Tgvpduk&TMWU{$jmCOkACId2?b zoYxTE`Gp%aj!}R>Zaux|T?cQ^jS;4vTA2ITg-xkm4SM^3K-pE{tTGZ<;az^D$L$`| zsu;?Tt+s~Ar@HWEpCo-Zr3mg?s?iPl$(SrVgdb763LSqtV@zWXHfA3Kr{|wY`eAh{ zvnN!P^4S4a85r}l>o)N|6^nn0T4A`be;qM39Zns-A=(vt1^2C*gXQ)=v93KB_tl;z za@ixew zNjTIY0;*Phz>V4*TE9?WX&JZJ(b^oc>Pjpe@G{2evsSQEH4FwHgkpti8+R|T72M*M zvD!p^RO<@n_e~Lpg;8>N)+`>~R7#2YdQ~!F;)M#k2Qv7oc07tkkA^kr`jFg_gtsEx zu&AV%-0fS>Jewy&?zf4&5|>L38Ee8=s9`Pt`NE5)wJ@|hjJ#Gb zB>h`)<8NF1BQQA|-w&__4jYK!;h#*eJeYet)C%r@8phgxFNOKy$s|s*oMm7K{;J(W zmWG?q*V^^O;Hnm%wCqmBso{IjWXL>(xFHa-KP`rA^W(^gB?72alFrnhsI1NWI}%~J6E8wU$u3mzEz zp8agoBlemqn7_7z%Wu^}`Gb@ATjgFv15d$bA8o?!Taqci4f&qt8{9OLR`Sv%NtnSt z=T`g`h`XbNduxUcc%K|(BU)5|j4@-~GM{i|jw2g_D$p5ukL%tgL0Ui6?+eCb5y7B z-D@Sup8Rc0+Wi8VFu{py|J}!=`u0HN;$`qkMgm{euL8Rp{g5`$$trryggx$b;raU% zxwf;He32i)8)a`G7Z0xxoE(B%;;1+|^m!qEro-ry;;Wq0uaTHHGK4&pxdICp#v<|T zX6y3Q&?upk8O_fG1NE`^)NroQ$S-AvYnj{owp|FQvRb-0eLdezJ-MwDy9b zzm{k~4h#mF@FMdeD3wrFaay$kvV32W_IH{zGiVw=O4SlS7xEC9-$QEdA7-P>t??Nh zg1W}_@L_XK#^YDvuAkAl^tl zohNB%BEM7UP}Sfb%LSm3DR9JBC%>is;WgELaA_ZRw?trx8LQf~-A*9$3rIk4YFmaq0-Q(;8R}cKbTH(B# z6Qs^7t`NAD5oJQRrVU&^B#}ee6Zr4$9W+NT2IGqTc{~3){%)@qA9GWQpEpaKZ!OV< z*Ksa<%Izq@1@(pGSES(U5tsS#XAe=Q{)v2IR0@6cSDAJtsiW$kI3IoeKR$Hk13a`N z1G+vPNB>c}uuHR?H&-sf^Em{To>S$Am;NTI#xrQgA}tj26T!1TJje<6Uq4)dMztB3 zTz3Ywb>hIlX#i)2De>gdaei$3bKIVP3hIQq#^G1RATQ*)&e}(UR%r^jzS;)sUTi^) zc}ny~x)`dz5+@dm%ekxV>g;s=B>qpRGvC@O^mue9QhX|~YfT=I#G6aOZRi3h-`52` z>YreDtrnl=uS=yA_1Wx_EbfEYcubjf5foda_$loRc;gZ|UdcX?`cApdcAAU?={y~{ zC43&bM%&Q52k)S=H-x_5VSgv|D+eeTk2Ne z<2ftn$e&@bbIKUlR&xnd#_=F|_9QH6D8`FUgB9f}p1ibH8aTf=iH}q=K!oo7F@v=a_+DxWd#0FJdJ*zB-qU*+5EVLr9gTzaB*=Q z$T#hv#}gFz*oCRQQl}yPx-uH7Mmx~D;uPr4{{#W!PY4;ZvHaZG9^flgO*T*5&nqQ( z@JrUW;_xv|G;`ky^jL6=|86^qe%vfZhiWDAEe?zL|02ea@)lR{o*+$ilKNm(S`pM} zq~UQINFud&(($s>Y1-o`SQ~tg1chA|dg7g2y2ovl-|-MuZ1w}5rSP`}Kh5?}98R)* z0gq-SkhSMSuqMiiI8+~lNZp%oVZ~gK-@h77Q_hof75<{F7q^gb$zNprZ!hTY>4n#u zoWVu8lGX0m1xxLVAgRU+ZwSsXiKR7g*nm-I?I~ak%2ZZ4IolGrj92oFccqwxTe$UGj#U)I@ z%WI~i#R^~U$!I_7Tq{KnyjKIWt2apJ{Z3*P=1kAeH;3=iV_=zxva*shBC($$P9tKr zNGnf5a4$_niT~7bhyh1J&uY=>PqvU}vj@r16Fs7izd4-sQyu!FyvwSpV>mhMHd^rc z#&D<4Zh=ORk)oEd2iaHE|3nsJFOp&3)vQ+=v_q?f6o@9>CNo|Xa({cZ(f8&rn0>ZX zG)DX@nOGQ&k;b_dU6Fr4qHH(YzH=+PT{Xyks`4Z0c1~8lCbwZr=Q`#;pbR5y%0%z@ zViMLlK#mXj#Pv1bBFQnEAoQRytku`zbwqZ!dgxDf{+J@^eH_fXrRzY-{VN20l%o}O z_VCkj1bns7qA^MF=&7E^dzxh9zYxp{)v5Xo7 z!;m|YpzKh{HO&Yha-&qp_nc%@J-3qX5Zg~bQ%8QMVh4G1LK0FxJQlhM`dF}849B0# z73Rh#ahcf_=xdWAo_b$#uU!HgCfmo39J`3y4%^V85?$u`?lyKO*>cHCA23Ppc+xvl zTr}^XH2Kw#4t)&;%*uEMn8jW$k2rD?4=kBS&Mp}XLk=0@PFoKcxURxdrwOhNlPt0? zM~uUoZIHL*sOXNeI2(ST5WJ_lVs`^U1=l3vB36W_^cq1t-<0laYhr1ES+M?Vq>u@9 zgUQo4wg7KdSgeYGQN|BMTHzxwy01)R?^VqP#%AK-bHljI4X$Ws!@>Qdi`k_9n_S`Y z5Rf%2V_K@KMAugUQ@PkdGLi#H^uhm8blw3qet#U-9z>MLC}l;*NIvpEb8)$S*T4^jjJzwI!$?*>8X-FtCei89Vj zFM-*9??~RWg`hV(28^H=Z8Um~syb<`C0(Bme>PN+tGy2k`!})3J2${a{f;Q4=P(Cq&OvO?pCPiiDN zw80qroRagt%XPWU!-Z7eAOf`gd!ok?>3=tD08dwcPXcl;GRxgHbb60(*wc0rwCJ}B ziRC_I$BnD(@`W#Azthebth15-korJcM+nn<_LuCg3sk6&e}XQVF@#*dN1n#k!8z&g zVv1J5f47D*cL%~I2Am*MVIDc%c!urnzK*kFrjT*^Hs}m!lUe`LyAT|bgHQG}mRZIA zB%4Z9V6ukve03z_)=Qb9+S+=yy;BGdl~@D^lkT#02^QRO%K+lLy(=_S{v)cce}sK% zWl;B9jog)Xx*aF>$YP!yVlH*JaGh}~IrjaS`109$vbG}z)|^0A5oE`s2j#O7T`lm0 zO&9dJF$nIpoddu1#^6-B1lPXPqMdyrn2ofjJyLxbHWm2EHh+IFXnGC-l~0u$h_;G^J#i}IyZ4^6PXi0w=EPzLAba5FNqg9kN-(!n0`R6{x zDb-CxZNpK%q=Yl|)cvr+PYKoU4TTVm=gfNHNHEhWrq=V8W7P-1lS8ht-Ax-L z_30Iy@NNL;ThxG3@*{r4+nc#R`3wK~M1a9#WBeTL342YW>9Uk_aC=l7wKC9?JWh|W zVc;X-bHY@Vbt>b@2W)B5(b3%Yg$cVc;WG2d>cuae-a?Jq(=a~wG5?a?fMvt)Ly44q zKPugyE@`ZyMsMXb9gqv z!M{%|E`N3yms%~MYpm0yOqC@rTlpAlCbr^+bxM5kdovinWIe7Q-a#%lt4JrIC(~DV zgmcOVQ7^g~^1AK9SSL$nn4ZJ#dvC<4a1mGcwSsGrKX7RG`)F`?4w-lTGw2oEVh?{> z(bwANM4v5MEICh|_s@I)TDuO=(CwilKd1@2wBE*WaRKgLd<3$}XK?v}%ixl77d^GK z+4aVL*rN3a+>SZIbcbwMUp*Cn4rzdvSy9x;t62CpavPkS=ZqDm^Kj76vqHBYYkAk7 z-cVO6#~!`f*`#F7CdY0isymBuRm)sf;@M2L|B8lhL7LS6^>y6-Rh=g0wG)#r_2}bm zhZF9Z@}E5|WeuY~lKC|yIQ4UjxOu$vUAO(s4y7zY_p|ye(kn`+^faNlL67m|B@6no zNE;SQpZVQ>y4b^I5bu1bkywNVikGu$vDZQsvSQ~cI#1SF@Gnas-$$iDzu#YpTjhJA zI{XnvN&cu+K}X3Yx21GR>lv|h{%T&>`kqDf=n9KQD}=E-T%f99F@1fffHsd&;t_UT z=-Q|xXf(E=4RQzWygZ(6U37|l_`Qx+`Nv~haVqbfQb|VFJm9Bu(s06{ILNTQLi=h2 z@?{HF!mW!|^qE#y+WbkCW zBMHfIrs$Z;PK7q$j@1a(2G>z`B#ikjm-E#XZ?I&CHb3`Gle`*`1i!B`c59X+*p7@M zI*w=X!{7qu>G%k|tNO#a=mtEycQ0O=5s8N;7Q)yGg$mW^ek37&7N6N3D4HkCqgrz+ zN%4^sSzr4o{E&WybyGcGr_RT( z9gntg0TB4?3Fh0y@uzY1nED|Fzo*t<`-y?DyN5moFav(<+(^l{Qo*ACFc@}Pswhq_ z#9h;3u#7yya|?s<m%5FumvY}{(_Ez_^o8cnC|#`y9I{yc4ep;huV5Mc;SO8H+YvptgZX=N}ULD(dIXNHj-mh z&J;dt%Q4B>(-SwS8bRBiSfcSJn@-7gf!+rVK|b&!@-QcKkE)`6CdKFVu!gvO1Abp4 zf;QJyfnHW1dgi4-x$-bJDkGO0I915jSQgXV5o?7E`(5-ElX|5S2@P)Vj;p+iI19N6 z)8~sAra6ZusPE@nt{21G)pCBQ-hfp{=;8YieeToKiC%eI2-RA;;)|@^uv|F{cN~Z% zzf?a%-J}#)G^GXkS`X+jeuHlhW}|WXAlR+gguR@*fNNwm^Gmm0k9o#PaMy;pn?XEV#cZ(`_rl@miy#yvtuuP4CVJ_zfX<_jYF= z+~v?kQ-niv=fQpRC|ETygw>C}OZvq=B+u3S;D(xj&Dzs2LSnsmDNLB%{Rt5FQk5T$ zeF`78bEw-t7pDF0NB)HS;W8(G*dAer1zN$-|LJz|%oZ1zbblottlYs&^Uq^!@j$%r zt}FchGLUZ>)j|Rv)f3$>kE;vb zm3jDR>_cYSQ3NqcPmtZ{g&Ed!p{{2;YjRRUhX!pva?gDX>GFl#uPMVKt5k_4x(0@A z55=>(o6-8@V0;~y%vjYqhzOsHe^r9m^8#gfllhE!Rn5m4+tv8J%ON;1v=hwm$i{}H z1MuXc#p3n#*N7l`HY&u2@#@ zuS0LQ{Ri(V`$Ljm9Sk}j$n8}M#Eom`^P;qR7}dibZJfU{-PgS_*Q%Ir&{m>urBcS; zgG2n%L$E~eGGwjQg3<5$;>y&QV)>-U!t(elwxtV);RCIS;2qS?x(2%7_hC8kd*w&g zH1;T&-|IMvZI&?lR%cqSB*4SAr7%6?2zz|}4mqiBPBe=3aIo51cs3~%)=IOL4@Q$P ztT2RnUQlMkMpd#Y8d>a#A0w;zaadAu6lT9EAse@3;~uqIIH=bjQr;%Q5A|>4L!S@^ zcQxVEr->{~rb|zIDDn6b7h0jw3uD^tVUJD(41MW=(+vI)J&k?BSnbQO)~Sf?O+QU$ zo-qWM6@9T`#U~g%@&a@I`vJ!5hFnluX%5zjvvEUf6RCfbM242P<0S28?96~c?D^;c z)Z?@j+K~g|m7Wain@UKzO^9sy*ak7afq~3Kom$Q)V;w5pFy;PaVley>)3`g8A07}4 zA0Pf8J6mPqX7x`ja8#niDc0dPVVGcHlkk%iQ$6aPc);=66vVM6dI@8S@8$C}$g4=7%96W<> zsXGq!nUQF<=pZli@qo1_)VNMyK9Jvz==H>sYUy}Voux)RPuZTW9a; zpwu@wg*U#^r1js=(L(z*w6-hZCl;&l5l{9)*6?q*!NQMz+--#idiSQPc~PiZcMOzT z^DydW4Nm<~1Wj{o_&8%V`q4HP4jn3%_z^}daAO>4nGiw(s4wo^d7G3+*dy~=hY^<^ z!nPO@iUOB#rGW9MZPE@-cIv2A8_qthZzS6n%#iw8L+FpE{S_s#2DmQ&zQnw|EzPt0 zqWo+-sc!lX0i9GaWY!3LvUwmgbiEAo)#bdG?OwWWyE{bqd}qh^l)#jujrjC|4b2b9 zm;A+1$d*f9oYq7#^tcV}`=lofbG?R5)kZ?pmyvLB_chEt9|Xhx#KO8y{Y96a?HR65EI^wVt02fRmR&oj%a=NQ0^O(_cA}&^6grw< z^Y5-0{`3T_UvQD-<=h7?i%p|rc(oYC6Weo`bzFbgS>Kn-MyN~dq%i*a z_zQ5Gxs|Vt9m?r0GkCtn5|@^$@-DV9Fmn6^YF4UUp4n@9x!bL=@{8#MX5>FW>Hx>pGr0**@nQ?={N%kB;N!zKgNdIftxs&xcpF zZMfV~liz)6in`GoRRu#=9p3|OFnq0xI2wS11mnj~IGGSTAyU`Hy z0Ju3hm(DkhBb{Frhz}M0X!iJ5B)5C3;>6fP!j#kj5O89mY);uoaP;cIN~KJP_Z2s0 z`9=%YjCsv=lqx}<)==K^^t||KjEz`*D-t{c`r<7gBEDO(pJbZ!KrO*USlYB%N&(Ge z9^xYM>iBM=Sn>jf%*nRd;FEiQbHcPQ?X$En)x{EbL%n%}_9R8SL1KFG; z6_R;u5DcH6&*rz}F!th=#4g%OTF)C1*{jjm-1D@;=xUR!K8AZ z+O+~YB8_D?&5sI!{(Z%X;`_3NN$&suUb6AaB!2J(H}-z~01RkS17tp921LVGt(9)j>!69y)jDVF+4u5_e{q z%jdl}C~wgl#S@-fhK|V(sS7zk$DH`XXHKf1c~#ZYz5FM=wXkdX(`DbOY33}t|7a%9 zSJp32*p>|o4#n`R9r5hz&mh5lbs4x?9odI#IX5wMn**c$@v%9;H=X#3i|EX3ya99R+Zz+>1<4B>cz=kc` zPH-JHVwdnVIsI=4PIK!}G#h7#zcyO4;zm8FD3ZL@15QGReUz}@J&$dDx*8kja>Yz- z#*9+tvVH9rnNo{L(x&!?9^>{2h1o^I(v@a#X6-Uhk%y=dqPf~}vzY)?tH4Ve> zZ3X)i-^BZC?QnhFV3L;;M6^P?5_OvbGVSj5xF;h%CMUSF6-s{?%L`Nsz3O$VDmzow19 z4>pkNU+r72zh^g{Z+(W2vzkJ`_0TUbw)+J~#@&#ZYg+jE_!Erix&=Np{XmW4dJO61 zz+Cu3=v#6Fw(mJcQa3Nd6Q_LfO}|Llz?_jdbL(mxbo?~-Q(26^7j!4?r2))*)^Lm) zG#Gv7Z)K*g{lU&RUopDyCEoYR6@uAA<7Ep^ajrURm3u1P%^&wI!( zf;MKx3!qzdUC8$RMueZ8;dY)5xfI|AZ=Ljr#>+vZInoNJ?q4LtO#aLMdvagwP<&>U z<2=~`w-@lDDV3dE+acVW;)i{&{A3H%quAB3tKz4OL~=QIpNu_zDaeL|u+1I>I$kFc z=Y!k9^Gda_bJZ4sZZLoWPIn~L)M$7RAjkAShB$YbI`n&K&$`d?A``uW$-MMuWW(xg zcJ=u`wtQl;C@Y!xYN7fEM#*XZ9#)kBE1#8WLXxGkc?CH(K%x<; z0z1846V;#l#gAdZkdfrXz;6heyRT*~Qg^iCL$%oB-(K`w@QJ%^nhn*X?qOW}QM&6| zGPfG|0}g-5gOKNQ@zokHPTw@5hWk2jF+T$7UYALs?RK6JrzO5RUJ8fr4l7qV)>VFX zwnll$F*81C&=Fde=ThFO(_VgN(q67*Jy!m0k4JfRSJ(1S7qsLDdUo*KwjSl~UF4L9 z*Ybxi{gIEBN?{%Q$g5{P%9|bslAz{i82xt#S*uz?Nuf1#-WZRwKb7JFvr~}UY|5k7 zf5DVh9r$WN5DxizT=wzbOyYFsv;rMfc_!u9Wa|L>o`YcE{_Pm}bvVfwno0YhoZ8JW zK;sz2i6Gtfzw||KBdCFkddNShI}W zd7ncb>?;)K+zDh^8*51a;*F5EW-Am|>?5Y-2BdTJJf^oWmdx!w2>w0VKthizqn5Ec zsdyC(KdZ7?qUs1z{^p4+d`~eu-@Zp;qNm^_?)9i113nKXk2JzW@AEtHs#;iFbkK8s2h0~&f{mn5Iy~6LZOZ(5kya;7Xy6lW| zL&6nrhDPC|ex~I!Htxl#1?TbERcm?b`&J&7(}_;H=}H=e0p+CWBDXx&0NN%DyZ<(T zP6y&(YX2rs8N3tboQ;HMpGUII6}1>>u!QQqokyS6t8-7ydi-wp9+O&XAoR>V=Dp$s zziK-kZSWNhnp(q_S3ZZ@t`(t>^K0`-A0d@Y_vyi-o0`eeB15*>Yc`zPdX44I`-KZLI$)NC zHQL5sCCgd@6xUj-(0ebEVwF@_?D|-!t#l%BH~-Xn-7^w9NDv*uqu^`B9`Ih< zg}a2FV0_YRu_3dbI3Aq>88+3}vcee_eVG7lg49Qyq{^-&eZ>tOz0olLCvy`2urv4O zDwaPjf%>6+xc9?_!tw?A3~4NUvl78qJ>qzxZpbN zFy1{p9)j*n#Xg(VXvg=n?CIt@#pSkv(%D@~JCAq_H$QKqFZ&PSBfi$)fKCTt(T!RX z6VGAR`iF3YJIIc~y{OG3f&VDc;!6$|)0gdJ^bl?CF#6838UKrV3PV(wzl@r*-GDuLeihHG>?-`dmkh>+TF_8!O^z}v$^xC|{8&B1;artrY! zFqA%RmbDE#Lk#D&V^W_;{CCO?^_BmUVT+w1sPA$jZ`+9zKBfZcY6;`^y(UdjahR6% zK;~vWkZ#g3ptgS3#dmicStv=vh^kpgj#}eWo0afj#7LNT>yXgBO`8tf8AwIlpKxR7 zS!rLZ$5-jOu^)BObo6#9{5sr#e)o65l-?V-*$)r??sOTHrEg-d{yFg(ce8NS59vI5 z`4(TFYQmngZb0a=o3u_=g1ULP(D|u0e;v9K(gv@>NdIb*sxqHvo~ozY(^I+Uf&Q?3 zdJ^rQDRtKj@|acLayaq+v=H67fO>7*3$>E7)OB_Y_Bfo3LxzNjdpkcO6H*?7aokM; zJ-Wl_b!Otq;6`>Bv_f}5IXmM{qK9N!4vvKS1U+=D2hi!i`o2rfH55Zsofu>nObOHVB^+TBvsRh zb(}~;rxh{yb%Z?}eCorrR1b?M`bpl;lOb>-uMi6Z9x)c>NV`8uCw-?JW+xxsB_TEC zqG!oo2zq2dGJ|VbY4AOGucJyAO7qvDcN17iQY~66-Y+rL)iC~Uj4ZnL3amF@OpYq4 zaGx&IS-PrpKatr>&UOn}=ogF)AwD$tmp?62TT1Bu6fD}GPBv)vB5SmzvqY-|nu_)? zB07^jO_{j#{SOkNYe#Gr+QYJ)Juo1<0LPnX(XRb0>4+~~ard~3eBrB1{(p!bYqs{AE(jwUeJcp0;}XOH)8Yty-2C0O~eH+&0UjZZo$^QkX;!?4X6Oez%;9x9r2=KX3oxX2D8|JtB-m*rSHw2DL<{le%=$slQDs}fX_ zuaWRkdNB24rOf7N0w3YoNAPWyJQIPPV9Sl~{GECKDu(;rtwq8vTN|$7<*Hc0 zTx&4L`L%3ux3>gc#z~%mcUW)voa{{2;PMp)bfouL$l939e?7lRzh=AAIR!f0jg8<= zh6O~Fd|GEVbm!(V>X7s(j5;_JK$?aFk8F+v#aTbT%=I#kuhPNXz&YIR*a^BPVIx(T zhI7&QFgJ9y;731((sP}pJXmWD=^M0{50~6aJ99SC&R5jvuNrIl_$9sR?EC9@pMr(- zckg0)@tq@@XI^DdwtKmu{W`LG$8BCT&xy}!-o!WdJx)X0Ur?{n)2UnWRq(v6#J}Hu z&94u3#v^@|i3>UeH$9=}7sQu?lg)xc$SA zo65UNUaY?j3CQ1drMD`AG2m1#@1`c*>*rq(>r}$g(fP9&WbsHAw`K?R*$_vD{ye}Q z8(Lw+gzdygF%4c%JpdPWUZ;-ct6_X-7d$&M6E<$IA--Sw!1e|mXuYp#yI*2X+|o)F z_Pdm_3y%!g(}Lc(_0bA=K5rWIoTDwVhzH{9%YE5le=U3vcA6~C&tQgbON6D}?z51Y zSJ}|H5*y1xjtiSLvGch&xc<)uveu+R$Occi`Ee*V`nBNutRYyJyB{vH0_Iq&DI32% zSy7SZ0{x1v66XcS*!s^A_&YzAz0~c-96qE8aJWA{tFM&}tJjj|7x#z*uVd4!2N9aN z2$y^;5+X`hijx|3(AV!1D_(J*9PQ!=Ba%YJ)`MTr>UtSF;<}#9Yjqcb&h>y#v(LiL zs}XqHCz$(6QAzXt>KLU_0Y9M?PaPkNzNrJ4fyCPVc`^lvMiEWS+yKgZ$HQGEGxqa( zT3J8KA+*h@4rbMu)3*9Na&Aq6uA9^D0E&%^c#kjQp9zJARF8rNC1R{NdNM9-9$KTxBEdm`yT=tQ@#iN`uCX=k?DmiDe%M}pFl zxZjKK!$v-1RlPKP(nj<;G!CY9^}v7)~~x(tv{{`^J<3528W-)99idVO;lxDa8Ei!2CEj z5MJf*Mwix1) zOZT9$O&=dc5SB84hj{A7>we=8J7e`Hg zB!I=!w{UpEA^Klt0+*DWd{JB}kmJ+ntl$~^uIdq9Fk?1Zl-iDZ-Rx+au?BUE$f8z; zF?^hAHZ-{Va*RI!#{v|*)-RstdJN-#u630^+@M4cW&gqN*Y48hoKe(!+FEKRK7=K+ zw&D+qwb_vvV%YE!fFu{My zzI@`0bBKPg$zkCP`HlVIQ2!1VcTC2&*NjEav5nw6Z7v`1w<~$obQMzb)M!PT4`00~ z9;UshQ(UpW4XTyBaocBP#bqy9p+O1UurDF0Iw`DprxrvwK7;e)TbY063!&w0Ph8s5 znzpAkBc8YolO>wsR2P#{_iBu41^s zQd09!jVZaG0LR!+$nIUQ$ahzxyT|H~84J6?uh=Ynn6{VLhabq#1Wm}d?8Fnd?S)x73BsHyy7J5Zt~5OA4KF>^i%LpR z+Ig-WUiEW?zmmsnW0ffz7NCpIRqXIV&rwW&_CZXYsW12V{1)@o)#==2mAF4lofh0( zMtnYQLs>x|ypmVK3=+e|_U%c~vAH)E%N%ibUv+#`dQoud9ER`jc9Y8kByYoH(CqW#^34g||K(f||=4R<&suntqsog_e>ctoAzjHe(-tHhsow^DeLua!d?i z0hoE>D~(}pIN{k9;kUXAyWsPTm>#PkO5;4RlWG8Yw)qij{%0%dxf~|5I~TE#C0T-n zqLOtv5iWk)BDqm^{GdJsDtKXg4jX(tQ+BuVC%cta4R`yG#lwER;ZI{c^Sb6I)S0d# zcSQ?Qovj2*V|TG9qkNdkS$(ODrY^sJXaw5bH~?{rgM=mZyU?spzO3wYE_3DWg1&{O%JxX*GM7FcO8vo{*@Q~pP!9Ct4L-S&pu zY21VjI&R!GaueyskDca86}Um7ZMi>x`= zXUR$WzAVvXI) ziSIs<%#^1w8|iGR&5Oo4wkb^B7S3#!IKuGhG3>amJF73Uf(|ned}3J6j;eHqZ@V4Y zbN?M>cV`=s39;d1V(orrvC#zPoGN8?euFS&;ap~YzYADBe9mU=SkKPqxDYStd-rhP zcpPX0q-XOH_ANGD@Q}CwC%S(VV*7+KhoMzsoPChE+GmYs&tjx_F`4hs`il$D*22)_oLV14>@m_Wl*i?k^u9-9w_>|tFXusk7eC;%Gsr9(}kJ&2NhrE`%8K1F*r_X4O?+P zk^C9#K&Jg0EF`bl58u1*AX|RjC;!=xhT+#@MW;%8k}>rOC{ck{ps)wRx_v z&1@t7DLBj=ugoHIr5vJuNT@6%CKEdRLnTf_7_l_71MjYD#pCg%vL)AcL)e2DHe~8P zam8d??5KW6a+XcQzLqwu(cMg#drvyYTsD#IF`pn)a*kcTyqO$*5ePOqDT3wAD#Ge+ zF{2-!V85CRpHL--#wLl~^RI-A|E`LLTk1r6$2zj+iz8MZW=vP=-gitb0<}5aNlel+ zI3Mun6R!#oWOo z9j}ts<%blZZ=aLZFM5O5jS4n#$7RLt=RTxc$81KOZjdkA8(3U>9@{0;Cl6LSvOngJ zMU{KXB+N3H=;S^iF2&KJY5p}9()9u39f$>BxCbi7W(8UKUr~EQU2zFqA=zN z^M4l0{JUg{HqN%PL8nyESLc*y_`6zSQucsSMK*hR-I(0_u{&?4Zj%ZPfLZ z%ftHFK}tacedxQ0`rG!DnZHzqxSNy7k-^$HSADCn?bj?wI%SKt-l^p?{+6a@p1MF z=+at-&VRO)Uw9+s;kWqHfXk9!mu_OJOI)e-duc!aaU{-A7~#)J5kw=XA6?zgh#Y?5 z#OC=qV9V>l(4u@48&>Zq-zp!7`|f8^g|i-s8RW;_zqktPq&t@%X=M+`KNDX!o{~-e znF-!mJ=m1R&)GIUl=s|{1e5DqnBSkY@|4?gm{Zh9ZCo#vRl846*l!fb+qD{CE4hoO z7Ddq?cQWY8?`Gu@#F2jc;w+DkyD9#s;|sx4rqK14>B94;`?%hKeRSeRBOY14gr1dc zrrl;=B|{?vkosBDJyJ(bdhuq1Z`*^V<4pNUC?flIKV-iL^#t>t>hK`-5su&WA7WcP zrhk8pxdPC-Vn@C^#2dn0E5x)f4bXeBIwTB{(=6RWs$rZ?WZ%xQ8*k6y@--KP8DGcq zbz22~&)S|$e0CG9R(Zm_bt3aIy-ya$yUFfpSw&nWMn&&MnyZ-~dzKoyrV$?}N5^8ALla8BO+%p`Y@O!2L7XV4oSuZ+jcl z*=`H5PF=b`wC*FiD}s5CyFy@UPYIc{S#e;k} zHuNkxRsW9ltr>?eS1o`UgYJ>0>cP_N#1~pGNxK!{C2@(@MBF#Ogv zqUAYHavDE^>Fyr{x5g?wkprysMG;hV`5=BZe}H4E&%p6rPsns(Km7Tr&kuBZ2!9qI z#aI2ES;{D7`oPSJyMBzKFEt+H^z=@A#f(z$zkUbIzKx<^{mpTZI1%<3+G5fAYcSt> zB@J4!h`y`ngWZOC;MGfc^vrNe%Jz@tTV@>M%?I5eU89U1T%E(Nj%t8q%SKUs_krBT zHkmB2TEagsHKOg^zwyUmbui?I4^7IVsrjZDVCv2=waa2U%-Io7PO|2f zsa|x^Wq_Btqrvq2LIS!sXpO~E?*GG%UcKrod3HvFjg-rOG%%97&W^@GmYUQm^B;tp zb;9=1kMV~~Hg$h60d$9ZNZHr}%rNi{6}NXOKNZ&w{|&W6+XbCquy;B#l1+nqN&9>A z%h2YS!cSakhLO8#QPw4w2HlB(gZfk8y60#XcqWcs8yHsZS7k_N7bM`gfok~4{spdd z8bAvJev=fv{u<#;qK9i4WbCCw5u>2N|E&t3l%I)7H-#x>jN_{%3T|DGKBWR;V=TYrRq^%mtu zi$ZAJ+^-OpEOofgS))#d#D{-9fyu}UeE%q#8`{}ZjPvIm4SQ&_mL1pWm-w z1aBJu@=;{Jv>RJUml*7%uJ^Oiu=8Bh8KXe^z%uOf{sz6pl3=9WjPk+hD!9hqRJ@#c z8oy>7p!v@o`LB*{yq1jRJqPxr$KJGJspOO|U4M&S`8A2YN=&8ho%+i=&EEk^r^fP= zVP-VxQajFJVM(iPQ3#K zHa!ld`}1DWbY%sq=39Y^=U_PKe-_3#U7!d50kull!?#!!@D?ctuu4;Uh6cv*$RDks zSo$9|vNl2MArdR(c?&&%=_mddULo4JL=v08GPvDVPiJHL$I_iigYfRCYr^fLeW2*_M{=asRoZ*w3_8qdEHAgs z;a37%h*GXKOckqqp#_Rw&m|HsL#`T0#97O|XPu^zQi$tTejvS$F4AjnCn{ z_oiq#mpO?4*(0adzqG@`f?fPeVdwIV6$)#h3@|AlV330W9z$tI?hvZ+VKoa*ENZR)6v~~WSc1}hx__c6%zfO2UNLNhWhsG}e5sK4RQ#dYPt@cKj@Zya zyI0WYw>>#Jw2;*X;&T-xyEq-)>LMd_9nlxd7vz zhw@}kWx4W|J+$lH+mOBC6$|*~O~(Wr1+PgOe0km`81U>X9IDQyxlRJ*8ymzm-rn@g z5li@Q;sV+uG?5p+s-vzyeAs{indI-uL&&#Hpm{ybXpaw;JUc^~4!f}#9~?hGKm1jr zTRQiri-!in;X-xVb&H(lnzV51A%(Qd(q(AeU6l_GTZGYtNwn!aLV2VGKm8z{4k=3J zh1aTSCmnrQlhp=>r3wg-ONWjpnlx?YZ*J$al5Sgi9o2SQ@?TT3MTZUB@Ny4Ng#0OZ zt+OwE^0|Z?8}^}>ss^CEIUKYeDX^+{SLi?WA!TQ7aC3(i)ZCqeiIY2V)q~$yz$ruS z5Y~d~ZR#lhlqp=WddM@*#`5LOPhqvy8JagXn&*aD!K?S3V3NmTP78Z*g_#kIePfC% zXLrL%=N06p)K5+N>PF>%DSjK$o!)P4!G32KLj2?=qw8@T!$`l;-NpW|P# z)`mmSD6Bx8sbjcBHpQWT$I+A(fvECfoY?7pvQV_rf-LF!89slhB7dWu$)w@S$a9-a zG`BrZT)gVpp|6o(;CoqIGW@OhETL2sM|y(Qodi}hB$(M;{K0O%l#%3EM|#M(lkj(= zDI0u#GdUP*$6BsRS*^sUY{#;>vR=cNu=KXg7YyLGgzqX)WU@Sbj}<72*jPMi8PpI|iy3SriU5$wXm z+r%&^2bPrPipnqlh^usVkipw_i?w}Tl8L8Mu%}}Q_W5o>vVzq43Q5>l+$mL>*$l#Q z=9<)g?PTFyixmv|?-Oi3Jeb_?WPE?KP^Oskhw=H|q{OcqnO@lq-xNKNJsQ~+On0iW zvW4^5=NHFVV4rVd(Z4KO73<8>pA8edO(ZtS=4y6nvo@JyD`#DgSO|}pcgEhj)J#75gTLF3UJRf1O3LuFMx|K6Xfz^D?nD)01t`zbAV?%az30 z-WJ~W{$p#q)c~h9+_3$pe452ZWZRamOJEAmbT;1``J*mBh-+#9aZXc_zlq(;Cdyv0 z+-a(Us#ZT@?eR)@+n_?Gj55Gkx~8N(*@S^~&s<)&m30d&!p}iw<)II(#F$Q@QirFT zJow@jk&7mH1XNIp%70 zXAy%glHg@u6sPeh4(qN>e9ulo&(d}5L+mv0s#Ky&yFX>ScW#Eaf+oy-piMq1_XNvL z4WL)Mmb*%snROll6r8?_rze|W)sNY1Lb)+?^wC7c%{sVwE=J7ruwq-XP2hpoL9*%k zAYtz07IwCynElNjPe!M_QiQL#FJ4}GQ5Lzk7gPF?!P@)nX6wHul66k2sf}Y6(=_bM zx(<3E1m^En=zW}8rj%gJ=+i0*9ZyY*6E!ciD}Ku{$8wP5ob zyRzAPOBGeRt-`pab7^|nROYltWW&0vDf%x8CwJDi%N)!?g{q2jwnKi2jO#pxCCC!V z2w?ylyebQC^9+14{)? z2aNyHSTU++VZH;}7Z_+Odx15S)`n$g= zVqOFa9s}+%(pTy@bvq&IYxII*2OZ&i`aEp*@y0EC-N@X232a5=RhVM=NSxSw1)GEv zW@$B%EZ;Us)Pf2o{~tx?9naPG$8jr^Ekd+}%7`TEbKZyYZST-fX{SNjQ7W_SSsEll zW+G(V^S+cqXi<_#OA^u0R{iep&(FX2@wxY$^FFWF^I0*#acSe2)URP|$m@G>bllQ1 zi3}gq8S@-x*Ip%I`SEDhtwR$s#hCK#R%^j4QUm)nd;W{_tbwY4W7j z{U7w^R@$mxxQElc9ukkLV)o>AAaOCaMa})oAWx$LyV7jnW8rz~aX5-3ewxYsOUi>M zLJoiEmTCNtum8$dITc}0-%tpUzr>_ojD!9A`pLgI5$E)B7UcgnWwTzGLvDSAXl_*n z8NXyW&WMpftKtnrZ&?NVJoY{-Iv|gI|CzH;qXeecGho}j@(fv9tIi!sI!qoOFk;`< z>yaj_TSWY}97(%h#5$j(vz}`?tj4C3$;sW}UJdPI*E6Jv$DUB`sC77t*w-f#jh#V` z8aOcDl(8)5TAyfd&nxEV~N14olF>G+Vhp75RKXW&o%O3y8 zVevL6$ovvna&(vvmpJttn|}Q;8~mn97FlYFzSfqoqk4+`d z52@j*WhXePAFFupoB%FNWQ3I$bcxTlPohhy9_2wN3~{c;Z8jq_k;w#Rkdf*4nB<4E zEUZ`zqU@E}lW}5fr~Fl0vvpr_i^}QprP8;#w2)1lc}xJY9yy$R63Ju7hWl)+hCbBi ztRp*ZgRsHU#WvR18HeSDGcogn5H(tztyZ{%m$20ofGgpA z{<_J$e3zu%U;X*GH0mI~()cX@v|gF+Z5_e8p5Do452)F7#VUi%Xgg4DY6qi41MqlK zM|Vk1=4aoC=l$1i$D4VLG;r@h-uy!xe~OFZRrL}_q(B-$?i{iBdhSNnyYG76W zeh#8fg4ULq^q;&D%`VP{hsWm9#e;@))8p$MUGoq;I+x*#cbPb0;(C7W zPBE%{M4fJM&u0Hf5p$KyAVmrf$a<-tK&xlb0Ok$*UOB_HzKwiMfE%dP7Lw;?7g@=p zTg1&&n}2zFH(3-Tg5W1keAR@#&}!mOcGv{qrPW7h!sLhWG$IemJ`Lp_mbmcGb&E-} zyFXWAIRT%^i^HE$L@vr>D2!ClTC_L21p;E&9A!RJsDgA;nvut8L z;upHl`$HOsiCBey8jdy=10U&V+|=LB{Jsou2{z(b^>YkvEM>5wsg;asZxFcT=jhUR zPV{y^q4)fg`KHwmS^aDon&qL)uRIsX?XlU-KQxx$tyN;tCGE ztH$}l9L=+EH~1$^$k|56PnD%caSDI|Cj9INreyHGC7rPMk-)L)2VE z8eXeE3F?{B{OXIszR*S((QXR`*=bc=s`WXl{A2<(y|ax@G;Cv;0+XZk(+~3JpAM~+ z@Wl}icC#!+Ro*RD4&oKH_@vs+Aa^Z+{OCRfw_p)Wcu@~6`fZ}~4^`;eJ*{}vCxHz% zG_lWDZ0PLV}6;3nYc{=w5;8Uo6XeG=f_!MH~$a5EuKw$BDTV~m(h5obQ+yM zb_S$#fxuP)+9q=A7IM>QQH5{9H3M4O)+Le*Z+VHU)mw_0M?t>TO7b zbavV)6~259gp)3MIL7}64jVkr#jDR{vU@j^=SyX2Uhx`ABip#%7Ja;uG?7oC=I0kz113+Pv0CscZC9gT1n1G!yGB&a;yf%( zy3F-F+W{Gwf%sX=l#dp?ilW7D;Jtku`Yp|4!CECyv?dCgic}%VQ*ePwc0>Jw341;Bn$)O#JqjY@V@=+|H4whSS5?hDsMmFL=h=cC?fCt-8GHE5UjA{vBjLR;By+ zy{KU*Zd*Uk5)%)Z6P3%~kPBE25>L;QhTb^%G42Q)D7yhFHTk@$B4?|yONsxmz=?lu zl?gi+Ytz}aV{k=myy%J72dr@aL`F4sVc@3AFmxagZeCr%J~j+O*$``(^_}Av{>(?$ zB14odiRK%)46t0kfG*hM21OTFk~h<2Ncm4Ku*iOZ({s+j$|bJYyhsOY54q9t_w8BD z$YMS_2r)5R@Pc1U=k-DY;EeAkh?1WV=2pYm)Z-F-yTckdUf+-VzFwj?JX-Ov=Ly() z)t07=U4UzQoB5{~N8d^muCh?7>7x|PnOCa7i>4}rk{Jya|^w5l9w0uh|_pze} z_OH>VsZ*VBdW$Rd+#W*{#;ZVhl{u@D$c8Ca{rD)-c6AWq9@e2gfylJ2?3F_Zax$HGSp6DwkCLXNwi)t| zL^Cm^B9MNIlH}v0?z43sABnSK4p+c0fVwv_aPt?TH;?Pmk*i|Se6lQmd#WWb;V(mt zz!;XUoyQNX(F5r}zi4{BHXr-y23oi_VNl{`6uFwQ%2z7{CXpX4E*?!M&3q3MvmT@S z>FI*od>ouh8V19Xrts49W{U3U-lDhf#G`a9hly_AnAcPV-a+~eEA{Lqzf`u;A+L53 zQMWhst3L!Ab=L9;X+b3DM+%-;MfgHDS@2D5rZv<1$dAb1Ec3Q1tnXREci$h%&$*Ta zRgc?=?#LEaydsK5N=<<22Q7Jre}em>&zyHX8_#Qd90w_r0BY-E0>2A$$un<7ew#xc z?sYHY+fs9A*TQJNbBY)pvNoJH?9=9djw<6#s(OjZ<%9gaw5fc}n+edTtVh+0&8Ua- zX_#ypN|uhk#H$yH!^5ZFAZ*M&m@_vo1{Fo|uCkF6A||)T!mu z401&J1RmA7Bye*Du5(lhaw+<-=htz1ZTAJ-nl=P#o_`>w^6yYPxe{wlzu@NRr7-Z` z2OlX)P@Q}uC=gsqSEdKe=HL`50PdogXz;f$R9h^UMyUi`206o+6(YCb+Zp^ymshT^e<8H_m&u23~rq zprvp(wn1xp zHMk=a|f@uYS>wP8MVr@xDi7C%sBBUn@A?%+USwI#i^Un z^s1KBbPa`PaWYI!eLa6xz7zH)%RtAaUes(=W^MoM`QW1q@z<(M)Df5ol`?+V?^(_c z4+TE#oGSI(6eM`aS76$|c*wsY23`AKpv)XkROrfrn?ttae-OiTidFdcQ?hYmVF(*) z8OgROCV-gr38=fekA(H!gXO{Em^F12B=0?h`?iYMqP%Lj@i~L_y&lDeY%3+#L(cMc z{p;}4;1#AJmkR5Rrs9cXeF9tk2N`l8o;ZGbNz^2Jn0?7Zrto|fZVvba_PVa1V8x^V zpA9%KOab0T`Z1X*FZ2xvgjx>~PG#Mo>$n)4ePUSHf6B1n$a5U(o&aRx5>a!r3hi|H z$LO?c+|F+T>tdNdanuqxH^Tz(^1vM!Z#=XtdCh7}+33qEhrA&p#{{5*-Bb3dIu)J| zRVG!I0pM9F1Jk@MsK|9|*%F6jPNnrH+j}JgJ_=cchyzQ=)_c2fxO4y}KU@OGfBNA% z)gbs1bcu)z3c+=(3N}~|!>j8pY5VI6xM-=w4)4^&x-aACHpCcxo^MB) z-OH>Cj9O9k;zvEJ#?KS-q2*8zTI_zq4Ng>n zOP^a=b@2^Md1DI3SFK?y3m5hNcMWD=A4RLCYw^!dcfsv%t5{&je8`uW$t&5Vp<1aF z%!!&dtI)F&3u4N5{Xye{7Pbee)90oOAo=3oL9WcA;E;yK5aynkmp*h-;%zSxY^mW%T ze5YXvYk%(r-b)g4eYTK4OU+RuRUF1YF}MBWXwCGsUD+Gw0H%6=997opCzU%|$=W{# zq^VOHvy{z1=T8t^yLo^N{B-0RKjy;py4&2>mqPb(syz3}{VzWAD`o2gRiI_i4i^Y# zM)42EFmP-;xP+KP`;XJazG^cpRv%7=guEux7hI;k?{*R1qKtfUPUrI0+e4M}Jlxd0 z2c8GW@XH0BsNSZdF#WJP-hK2RD8KF@&6*-`W8$_RhwI6y&`f$~7f<%tej|gSaqOi2 zQh52h2v=nfkb5Dc`K@uOaOv-LV$Ri~m9{Z!@mj>z#Z6$9caz!fh5HEZ-$>uddXTEw z>gc4L#vcAlgs;c8p^dUJ)LSQD8@7-q5$nhz?iKT}F+=T_Rpjo;2as~c41Y#RLimfr zqU55LWEnk&Vl_92?7Kl2SA7>b%UXO^eUN2n$kXAO;&8IyESqC$%?4&hfX&V-7RPKH`Z^&Ys&%r>l-b~8>xqyhqLJ0Pq|R(V1f1T zW+6YuUlgBl4?YbwB~Mpoi6+ONBf9n@sn7Fj21di_7F#2%P%^>RfipQBx98Zhr~e70pwVzA za1!<&-%jtEYXc45hzri7qDfLW#Qx02A}GLdP7<)`-d?)OWf62PXv8s=TIf7AgNSV{ z6p8xNL}#{}lf27mxa`jv?vB93S=Lj4dQaLw!&8pWurT1mt>R!_OC&uoW)zU7TCO|G z823M}0sH1Up-bE^Dsz2-Q*Tb^AC1!FbJMjUOQsj+Y}BI|J&T{`Gzk`tKLJteXOhl; ze?;GtH$kzcpIxf;a9Wve!GH8^;49QS=!*1HcKxyLJZ*T+9FCM%q^}=k_hV8NZxAn2 zG4$~)SaT%GZvUwtblc8o8qsW-#qXPohWd_7tw0o+ zY!IOl1Sfqx15513R-FE10HJd&h}Vi!-0rASd>l26)xJK#EGe~Z%Do3SY%)NsXeSO{ z-^Av=yhPghCNjli8%aytNBl-Vc4xy8r?aZ*1i@3&dJm1smZX}{*}PG zE+f~D%|g`!BAb+)x5WQ*Byl=%0yb7BK>S;tpXYcQcQ*b&9fv4(bIS=N)$-JHcLsYa zI{`lG$m8>-K{l+inXB5J%sdVoGq0Li#AbU6WSOW7j4$NhG>k{_n*!rFaTI!o+{bjM zFL3n1Gm_ys3#`J&!L+@Cv%KyMc{+a!hNUTBZA+`@YjPV|ePav^6qN8|EBq0|AL4)U z1)_OE-f6t4HeLVi4C@}h3C@HH=bWNZ1WSW)Qsr0lskg=ZI$31Az(4(M9U{6HBvBE& zs0VEACi5ewM{<{AyfJin2Xsz5fn!!pg!Q}U+KrZ!!zDwn;DKGs`EBEs(D0I+-PJ>G z=&XDPPWF!G4p-o|K&b)5!jSxa}Ge0Nf19=a3z>! z{72I*4$^NaggtU0U>Us7?w>(tWGBJ32v>UCLltV*f42Gl z-zhZRHUu+17}2#|g>dTlKO!wYhu$^3EIN5%8(gVo)s{IN` zSNTU`TP2`&N`+8v^W|aJN-4oz1iKCJi?i!iDpNpizDfS4w3G&q|TJ z%OB6A?oDQ$YV*O-!~nYA4?$hY2)s378fiu&m}%BbN=xgif$a3NDF@W^JcM*luhK&cQ(#_~8jT;1huc zMn!lux)86rkAtkZ6L{x#5N^No8|NzSz_Py)EV|krOY9V3#`eq1Nl^;Nc-O<&xG6a4 zyfwU1nJ#L``+z@^+F4h@Y0--z&xn(x5;;807oDvZLHNR}Wd4e5yo)*H-TtXK^^FqI zl5inWe~d&gOAQM-b1wAorlNf5}sbO!Uk#oX4PyNQnX zT_SCqj(wCt{i31dL~TA^HGjq3eSVp|1bKY_Xf-LVufqZH(R_qx3ht>+CsQi(ps#2= z^OtcUB@)BgUAYPzIIBb72TFszSszKBP>SvvTe!28!_X`#lpUXbPlOHGIHS3T9orwl z8ZSsu*K@AK@3RG2`z1*5VLrsLe>|*7UC9h1A;?w=<*-w6URfB<`*DFb~6BH|cU&^PUId|wh1sS`$ zh9`Jw&wToGe>m^#=*(7o2hhmHe_)1gCH=Hnf^Mpm-~)eOrgrsf_<^hE=u^LNUT?u~ z`u5>-{9B$4=Zen>&idPM)I1p-&YOZ=*$deJCd6rsjL#%VN-?%dD$?hQpmjs-Xcp=DSm^VJlu8~z$z1Q zdfw|aJJc!7KlnDl;5$OG$$S!Q&`A#cO@J7ip)}*ldGda<6%E@qS#;KoaGQfCK&Fw1 zSZ9ysombey#xNtI*Vc`rFJI%FHrC@6&E4qcqJWK+8{k(@CMeGcgZFA-aNJFemg+5G zOz6r6wmXYZjijnacI}f^Pa$W|ww`g*aMZ_6lGN*CxSZ%a@|hi;o2SRbCY!?B zS@L#fg&HJ2_auA@)Zo?Ywu4FENyd7P;>zaVxQ}}ZzZZ|BR|dYpuc{z={*NuVH~+x0 z$7i@9(scqux{F3mU5dFILb=>oe!Sc3IplGaKfAf{4tB-(;%HN024JE>gI;_R#Drf! z%qEK!{N9N#j|XAj9}%8xxK7h%T(KGUCYhP4Ir4W-^kdFYDYiMj7DrflvK_W=;56RoBTVCRszyjhRn@Sh8hrt>v8SE`EPmIy(UY3dKqnn{ktHJ#>Qb+p>;5frdS;Z_0Zv*?t2A3Y;QekEt`!2 zZxT>;z9G5(^8%O_55*`mFHn@)fw*=WYVr5cN^%pbwh4UX+krIt%zD60k*xlSDj(3L z!5T3Q6vag*_Tp9DR5u>@}nU4(W0Bl*mF zX}kEYLM|a3f{5TtGA+7tqb^(jTrN% zm}R~{$6J=Ygiq07C{iQvu@u=PqX|}Pz9e6TGyI%K-XL=* z0g99JasQ4as115b*60t1xhmIjQey#>Pw3|*ThD^(icqXx_?y)?yo7^(e__Nrfgiqa zBt(Vvz#XUA@TvO;9-J5fpWPHN!1y&Wmwk<+6|TX=DT92&#uS#}pUf63oW-_sN2uE^ zNk5hs*sLBNf(bD?c#@=9 z@#u2)0_3Ixee)qq^ewv@&m5H}EsMnA?AZ?tPa47babcJ?wu_Z)PiAh{JmKr$W4`Is zS1$C$7=hDso^5GhV6)nj&KcIl2K1)jZ~eWfJMW1oD)M33afhk!q05LYNtwZNNypHIUgcil)8fSjGi6CRt^H@}ET9X7AA;F>^Njl4~Si zYd^DvYEmHKD!8)N$W-*7R)Px;j&L>)zOh%P=b?J{ZHO4ju?RDFlr>31Wa-SLXEdAs z+*x$Jqk(%oK^pac8vr@6N^m$;@XE#0A@{u{Dn|pbKl&*=4qA>c7tF?nHR5>r z!T`enckIp5MwL;aqSs4*;C?qVvRL3Z6uW2eCl9qS?{$JN{*NpMXKaIoMbYq|$vX7< zGM-dcg;FE0W^n#@jeHN$we2;W!cY8RM;kw;qs^^Y)*CpgVvXNU+kDS0tWRSt#3vP@ z9oa~?zrF%1+vm}9P)g69JPG5}2Dx{8yJ5^gLb1?JiPiS^9fDmvnL;bm&Pl( zx$|vUgZO$jA$c|RDT##xYKBy%F@Y9aje=WaFG7=1GYoAI`k}j*fab^w{54%zL;Z93 z)NC~&x75NWoJd6XnI`D$ZY4bb1+aC48SSmLq$Z1HV8faW5-7U|ditf{RMj1js?TS) zo;4CLt!zGJk~ezz>q7}%#;)pBXtwDcY!23eJiTD(Dh-4E?TO^C9)(qMfe;~?2a|S5 z(w4iIiDHKZCiMmJUrqOkhW#?8p`JQ;BR3UaY278imUOfC=QKcbcr@Oe{++bGlYosi z5fC8wwf*4+M6SC*{%jtJB^5jQum6(B-zrDiV_D7hdGugPi7xKztzhb#4zaw;Q?YgW zJCVZIB>1~`1bkdJP_DJG9Tw~n_yj!*3C)b>4@^pDKLjt=_U(WN#EQ@=JW2HS`xRz7 z%TMqwDDYk#*6h>y%dpC~MzrUsFK&RG%333DUx0#*6=w}jg{s-!aOR~KWcM^Npg!OxXGq-F-X#7e%lVatD)7wi2iw;_ zg*};kms|{gj-9!uMB>es{M_~+8vCnMLPO!w}Ar*U1B|?(&DO!CcO7Phl(*MjK(WL4Cq8{x|MGq{f;qqCqIr1jT zC-AUYxt@K?SP7%llxfUoE6$H8R5&cZ1bWj>(l!2(n7`pVT+yqe@+XyH{*p!r*c<^T z_xQq@H7fjO?k3DxHwtC*oCU9^0gZEdPYxees%T8;2Gg2+2zpxuQipD`)&7~ZV)1;) zvt7uYxg&)y_SAxl!EqdECPn8QyTRrqdXp3x1_SHk$e0Bx6(i$IVf@S);CjLilHx#U;4M?P21jA0Rf?AK5$^!C^2Sw4(&RRlk0Pa_<3hAz$z< zT_CW-djTHVp93ocWVyK~BSmW#RN;zAVz6s)2@W6C4`T!;#;a3FxPJRIc&S`~e;;09z=g7yTW^SeKF?I%1f!Ce!2Rj*XLY0NP$6H5{#X@^C(Y&Y^OU#5 zAVQ6lNB8hk93Mg5-ZL<5YYEJ}?+hNo`}cQEI@wjHhpHW;scm;4#-F%Nnii*#Z$BlN zUeOs?F-$l+STCj-A7v}nK10&5#S}Ju#e%3yY?7oS_{>RRF-KR! zx3|ZjU`ejPkI09=CUwM9`4zkQ{SCSWCxC_JD^^{Tjq_T?`Q^*skm}ivcqV)#$jtdj zZmMr(oh>4$Y7N78(j7?e`@)NTf{$CihBeonLe1M=V3d_7ByVhqr`-;y;wjl(r;XjA z7O>!rH#l*&@OYgOIe&5?4u2etl?S6BJ3o-y#>KHv-?f-jQUzB`M!=zNExaji3dg?Z z5vi;qxNzYp*tbmq&D{YkZng%o?U=`EM^>^x;r#!!xXt!JlC{veKa5w?Bp`IX8|>UU z8s}Z#iRbQU!znpgSe&28UKhs`Nx23#fy-s|!E-J_${6f#hrpV|0a00-3as-#iTST( zL36Uu7d;V*Tk9L}YpRG$o~{A|@=loGD)bcV3`NT)Fx=nqnd{%I0PBBT0IM^S!f#pF zQx=8_4^M-SZxU+%6Q86c)P6uT&LI)2o+e$ zKbscdtv+=q%ejhYSO)}_JYbJ%Dshj84_|8#B{GyVVJcS#*ubDNtc^U-=HD)mGAJY<5uLgro@YESQgHFolfIL$2=T-^_FdWtA#&DTqJ{>A|7#jPjXIZ zV183L^p?CQ;tvS+dTF!#(C38vZz?>SG@H%N&OxVDhcKq+Fw4lhz|?zQ5bJ-cxL&WB z_(lOs*b`rF@%tL|t+Iy9ZK2HJMHw+@dk?QADoOjSF_05@5Kn$+W0HHq*_V>p?A(y^ zY*OiTJW)N3Ti>*uoPFxSrWf+WvrC~)`2E~hS~Nn|#+obwycA?`j5=Py+-?Va~<{>x1zlP4_MQvA|a12$)qlh zz`2|M2(!CbQMybw5i34v8+yr+IBvWJ+4rN^g}tM|)ldQH31J<=LQzJ+ZU`7N5_9={ z(Vnd@h=#--HbzB6Jb(Cda#?qoVS)s#+4O?V4K9I(3m4dfGo3I+LIPa>ODHAN4Dmrp z9whg4v3>S0g@r4@R&16Vyo`K-$A@H2I?nffdCaXasl>@@LGZ*eiHyyE3eQRv_zhr2 zQ@`E?ol^l2yZtQau1O{bT>~-DdKIouU5k?HGhkoH9o}YiI9n`m@;zteLEZXZ(eu$F zs(*b07L8v?k6gSDhsPd)vnEsN8}1Vn^lrdmSy^cFd<>slH58vr?%)r9|3o(2PU5+_j&H8s7Qvrsu)i>rm@V2zB)ojMx*xId^=hfeX~!_kUS&a4G&i8{A5{#u&k~jB zo@cE1F1P;NZgetOLF87qFj4qJAO{bUunH%*{C6r-Gu+4}h>n7|Wen>&JP0wr>oL8< z6ExCe(bwT7$=|KQ?1%i~EKA*CVev;6=B_~3-0&yfCk>z`aUuC7@RJq`yy%=(e-`{- zG?iA;BrQc_@%i!@yvFZwP+2CZb*Nof6satCPysDD}gp zrgKz#KnH`Jb7{Q%e-OHF2D>Jk$+yn50OcFP5ko@Y0y8pm)RT5hZjTS`56)+^x14R zUURk#)PEKy6%%)|pHJQBu)e$0zE1Fmo86_~r^wQVJu{)IvyXQDW)6xZg zeKuS8`xZv;kH_wK8(d^7g_jojlPRCGq4LQ!xM#Ff z-%7xnwVSawpp&U9+VQ?s_WTrWMhsp{gUQD6jSFmR z+#F24a12=FRm|hRGbs~cFPs{Q%e!yk8aXHEJstp!%L>@Dr-68Lh&x;qGbYD3RIsg9 z_9R?M2NxyXX9rz!AVlXNr@U_p8Cs|*(%F4UR53r3JZ#-TuGg(1E)51?WxNiJk5<9j z)6MMj7GbXVu%G>SZiGs^0k2~DHbK~^D_Z7%e{u6K8_;9ndbQn!GE@+t7f<^~CG2`A}qvLRJ&A&s3r z9;N|l$d+KNGyerFVFZn=j1>GYN!za+p0c$e-|^_I7J6)?4sR$LLvO|^Qn3S4F-X#4}J;4qTU6^Th!_L zH`07(wk-crQBlb4R+3wtk8LHq1RqyP2UMSy0&o3g+?FH0WVZe;(aGQf+zwBZoCTb%#6;vF+rxlh(> zTjPQ4q1^J82pAVrXtQ6!v8*I64W^i{=A`{+a;52KP-5X#rXIuNFV7f+H}A?HG~7Y) z>(1p?)9$miD=)F4Zf7)oR7ZYZ-U#o zw}dm}{CO)`-1JfOuct7X_yOpo)P!&Sqajj)5RJ8yaQzfYH|MDn*H0lTF$SFZus1j8aQG&8#d*U9J5k3eXbAQ zbn*h%**;Kz%N0Wg+E}6TE%M^g4z{pi(6(*N75vrr-KN`TG|sSl5Xm5jrG1XBZA9NTA&DX7;_jfralfXC%FtRR%4?&bHUw zf~+2LKxZ|xIyS#7q16DcX>ou82XOqwO$a>}2%s>HzmYOYwE&GI}R- zB>%ur4O(msFtyzu6c>-99bG}xJN<;nvECd=%{S_1@exNR z&<}xyDe?4YN1O9W(9=WI(#xA)ebkYkoO_Bd9{+{By_EoavxIDQ zix1iR_%G@=hM-Nr7^n<+iv@CW{HHO?aH)OU%d?#RcJY>o5MBjzK@IaRl-aXIIAxf5i9hF5~$LxivroK4p@<=|iM*-%KRVy32 zM2a`8$mcff-ymdb&$9dXZRqmb-JJ1o$n$Obx3w&BtxLExUamJZ0qvWk?E3?rxGwdL`6xFQ-gRmZ^N>#ErD zFd?$Z*3@qf{xXwelmBza%`T4E zBkXMx1YU(}eFmHKKo-uk>7q?P3fayMvGT{SQ{nNSTg>C-1M=#A1H9P$lN3ZnV$T^X zc>7(S&996=&ypHwQ>n&#ZB`^zrB(2+j$luG7>Z2pi()$rsK4ebVkuwu<`#(dB7QCc?7PMfGz|wvt zwMlTRc7faRa5AqvhF&=Q6*Hga^N$o2;pMy;upz;YEZcF5dic)317{ZTLwcTKY>5wi zJlVq;AFLDDCSq9JBTlVe*w7t9!Su`SezNM=VgB)@WKwV`nU~Rb$YeXH8CMR! z_e-&DQBPsUuS(`Ruv0jDE~T9l4w7f5jUmNTfrU2ys61>v1|y*zZL( zIKwdIRUq0E3o3V7$u0FEM7pyMT^#LLT2&xsfBB96GBLK{{TE^MzZ2jw=`-5YgyV0q zJ~&w71^)#-BuO)_k%fyd!n|88BImi@aAU%DJgCZX->g#bNN_9r>-L8Xs9Hn4P6(Xp zOvd(hp6Nt5z`2#nVac=Gq(XNeNIwb$tvXZ08*|`>C>?!f%3|gr2d1>XyFByp15u)} z&~NTrAo_gF2Jbbd60_si;H&&I68~cZ7IrIxm*)p^VUIulls^yaD+)>dm>~>CcapK` z{;cL%1Wr05Lw8Si0NIW&<>&n;^5c)rp)Zy8LRoqYJY4DrhhHc`NWo}+foeO1n0g1&bPr!HdOiK6o^xVWd1H9wN(-H%*Ft?B^S z`1~G>(om(&_RDDSbOuGIJRrvKIr9=`WWIe7u=L|$vSZm5QM=+e{&iR}XX5ySL~Q37 zKKjYVrFvsulPjpkyoXyT&5WHcb1`>fNzCL5c2-V=nTn%f#I;(Y=w}4D{SuUpaRK^g zIQZHx;@Ttsu>INx;B4*;xc9pgc8Zq}&6%p?e!x8v9!4;9h>$0Avl6++3obN;1I%OY zAiNglbyqV3;ewD03u#JXgWgrFWzYwWkEau@Bvq_y%j6=fKd|;G6Zz=Cl`ysS9vQda z7v-+0Uuh6Q=mkS@0}= zzr`K~+w#lKOr*;P-QiY4A?64j3yHaoa9&_!wlr3vo%g~w<%~PQM`x|msMGy8Z z(g*Eg!B^PUNNmki_>oR_R9xl)xwBSqD0Vrax6qv^qC%hL?hU+b8cS}jDkQV`33REP z7R;K8JdxSHrmPne$ZH$B0ezRcq8xh>MZX_RfeBt)_ zxUryb@uK#(KuXLU$zWtZYe`VY8K>-otnhBIOAyCJp^0pApBI^^-e3N`cP9?nR7xbx zWpUTN1K>Tk1&oSLLX}AX(eNuJF_He9hEb64UzowhCC{ZR-p>}L{C&VSdd~uW-9=oq zWE;C9FyQ+C6yrqw4q|^uo@&WG5ka1FuHa^uNG9?|%$!QfHOj-^{gJAg9@eW|6VazvaS;Oa7-ytcpkA*wRkmQ_TFvukA{j5~XE&0N3 zb$=0Q9jk`qngJO0O3CuoUKge!wiD&rmq15nHcngT0UZ&t^j`RA{CM{*IeK{-P2E3+ zYK#xVwkfZ;A8G4gi{K`eobm)-ygSEMi^nkM1Ur7;9a|VuDePhSF7{1qIBnl6ICyUQ z0RMa#RUp^sz?SRybioDeIPe(UYL?TJ_F~jlt)E<%Ta6J}pU_wTK3Ses%KuF4BfCTH zLf)iq^!#jY_h{z`y2DMDM$0kY;)ph{yX8G*8qA?T`jz;RV<*!~$N!3C=BGiIT0i{h z{|y^1n1arKir`zNi;j0wz|emoOz@n5FGXQ+FF^-;8i$~GBSn=bFR*5`G%eotRJ8SG zB=PmR26OHQ!t$6#cF6ZOtCbX?-ewqcAEs5f(~g&(<)8kV;c|xv z{?;}6KZef3pQ|s7)tI6 z&)XQ$^MjYjO26(PeQsJ}%KHGY`md8wr_)R{|01m3--q7z`N=vTI^*K4MfiGBAbUG# z8G2XT72Zvqh4D*t@tAa;KR4kxYdn#T+0}jMx6!6JY^JdgGTa<(cIeaDqvb5la1yCl z(2Ua_d0@Sp)Zf_}#+tq*kekoXkj=G8!X0%hY0nbN#JjIxewi{J9eaSSaxY;DQ-MyN z9L};`UzYD^)#KlLW~1@%msq-O6}j`c8+_Rw1FAVUWv#taVe&>PK^#*X+po8Qh_pQ-%;6O zLPr$$#h(}Ks9Uu+O-gvhLPAz^-;k?#;jIDt*ndBEDD>h+=|{+yQK7_oY9s4ae+0Z# z1JQY-D=c(a!*m~8va{J$#O6jM1k+=9VRjCV6#JrKfFk>_^pgG36}Rx?tI=@!_f1?o zXcRormRD$Bj$jo9c1-t+vS3i9%nWxFk|%R5*`=-Hh*If$lJBI2e+#E7LK$R)AY6xDcdf?#J6Xtddfh%oRY@OFR7H?q*N!BLP->pqzR@;bS zhvz}98w}9hTT-5+};EJh{lq4tqUGqDCOc*$FUu? zKgiN;=3?OqGs$g&Xg(#FXq-=Dt53$rTBo?c!o3M-@5RrZn)jrldii(Js*66ZU2}?k zsTcrOuT5Cvk8rZ%n;tXoc+J|ZB5`t6saO*<7oRPSV^NalB5uolCQjC3nV!Y$-TLKd zrA(MnP9a%1^eXAQv{^87S7yF0cSX-7JBg`IFe<70vVuii{I1)FIjG(tEom{(yWWXe z2ApNz)+?cH|5K#(t)>`|iRWBWv?pQ1rUN&`Ajl#y?|w0;GIy z-V5+6)nsoS2SA8P4eH!|0?(DlWA6SC_R{1k1bdjkiC?kk_n`+&%{StCp#s)wABN}o zGhp1I-{eI6PVDt9S5#+zN!Qml`1NEfjD$K~vqhcuee_()S0&EjyAGne zPL3+uQpts(^#CTeaNk%-?7CB##;kfRS{<8C9-qHfQMh?Cw^!{=j$Ap7e(Wx3-H^p@ zy^Lr5c73TBQ?3T%m7B?gC3$4du1FzAc0fqm6hzLYHIh*Q?RHvOo5~%5-x@Hlp^;gN&+(coJ(I0V;Ngi>sy+jr`<;lKS zuYpWg>G_mAp_y0R!MS4|>tTKwR;7mu@3(o28&~v#XZbJ1SD!V(c$O!L_UgrQDxBfO zDHF0XwU1EqL2`sR+#>5IE@wjgI7nETOLXcypXlNLdUt|Z;^oz{gdL5}yP9Z*nUJ3PgT3Jl!da~{OVRr85 z2u#({fWBAbnd{i0RPAM?uwX?fS(O`yR&k3+hkpj%wEcxWtDK->nid?N@dv2;L)H+z z9o+O3@#aezTRv$M+;j?LhMH3<%m?&<`hO^a)s;W1Mrac2$oqblbCHrFx%6J%se^{ zMs3vQa>q_qp81)$ZQ4$ap8vw)Rgt(naxOBeTWBXQ5P z8>IJ^0r+^-cXsB_edd|Afo3x!x^8$0=6+p)H8W2Lfv-yhHBT#eW}Qf9E!Y61BLdL4 zte*UExWq<%9}B~D_mR!!lPZQbDx&I&Trm7P6t+mS@oTzku+*Y~thRmyN&T}~(Xr8F zVN)2!c3&nMF3TWU1;faeQ8$UIW2F85MWdlt{x^0hA->|$MT#z0-ja+k8;qRp$9CLV zAiW!xO7{i6h%pj}?7(6e_`6yhS?We+MLiG}XE{Ld#ec+KR>^$IQ^YQQ?#%0*G0*IJ zgq+zmj`>{g!ARd)7W^a?$9iO46=b@vn>euMF}%4>VU+DW2>WcruRR<_$9?_|=28?q ztFQ}q`Zb6f8NR_SIj_mQqci!56%(nR|7S=|v8H|Bhr%y&>ARomil6ulK0dEq$oeOv zKYwS!Qk7`z_D7REliZm76PwAQ-jcHp{c)|+d+Cl2Fv&X~dmK*# zn+L0~L(7*3^}fOkb9V~2ca+($AE%8c&29?eZ_nbbHg(!7%a8l7X%zHw)yU8AG=@_X ziJIqFP*>asPaUtJ`cFHyCrX#J4^V^D7b(JB^AF6jpr;sYHI^2|<-+*{ZGN}A6Dp=R zkX}X$q51uD$al4tW?CxH*Cq*H`zOGmWv58Va%ZsgKSMmC<_Z6~rm;=ijA-wSY|^S< z#JVJeVUS$nfNA{}mfA$Z<$0gUPUrDt@|(xZNa;7x5Hv}f+89vTq|TB|Vn{dXkhGi~ zgsTdXxZ|4)Cc9sj_=4GD<==90V7danPReGx$HlRV?fF0rzRFx;{xKV`vGC(VA?f)1 zL0CAZnb~cOfW(Y&%yi$2mN~I3h5jT@{%D`SV>J~w>WqS(H^#y>XAk!K9TGODQmB4X zMyj8_m0S_0Sj?WIto`>WaQGRIOZ*IYyR{x(jT%J9S*~Ma2K{B5Cl1AlMe&dw7safO z*TJYi$MJb_586&v^JdciT`L;U@X4hriOc0U*kVc`H<)fukgYHPQus6^PNqz>F&zMLek0cR5>S% z)_?WJy-h|K6c&k%ni_OSdq1l2Lx~p7sza>~Ydq2rhqv{|kou5GJX19qmCj9J5B-B# zO4t*&O1gJZ`a2y<1T_q15O7KEEq;ofV2#XC$M}Uwi!2et@(s`Af))J2;vf zvHNGc)1U6$s1*UOW#_@VU7rG?MjyD4oDQ4Ta(MV+GuuRRLbn`8pBahpw2X=`?ca(41HG7e?p<;u>kPVtYolM%3UYs7mds&sFuNb@i#^8X zgY7;=c%au@kuzNjox0kC>C1NF+0-BZEDREME1Y3h#>7JN)HWP>J(RDEoKC!F+kx%( z_sp}e1(-IdV(p1ku(Q3yruLR{rfMs(*TCbLdh7zzZOS1v8Bfq*ex|gCD#BJ>6&ic* z0A#P-NP>PI7Nw8}G`Xd~X}fE1eyFwZ`-io>vALCuZrV-nMtSq41{BbGtw6%UL-90;*^lov+KEI#C<@up7Xs;b9Z5>8OFG|9v{WW=hw+vx3 zEQW?<4*acO7;k>w2+_wFtIN8``lkqNVBRV0@lOGb<4oxK_e-(qYA(LX(%^MR4l{ja z8$38y8_B3l7Ev|}EoTX+|5Zr}!TG|1PacB%A9EbwI}(q4pGx*Gx1e{9hLL-5eQ?R2 z?>I-)$9-LyD3=dHEB$?JRm@@{IIN;GT1@$vpYO;~vvp+nE+bGW{RMfo520fHY4GxG zhXIbsEL}U0r6--i;J_|0daEjgKQCt6_77n?t9nw2pMbZThcV4p^`w7(xUjn<9_l+2 z;NIzn#5VIIY+AaE^|f6LkCjKFw!sZ@FJz|Jvr!3^yG_O}Zey{|Zx_0jn356l#W3ai zVM05t@XSANm~zPm8zkr4RbS!NWFj(gu5czv;2W+pb~z8WLf~=xI2=ZW?^gj3?dBXEFQAGPv1m4|6H@0LPJj zByPuFC2$419N1iGoNC8>UB6Cn1M&UJMb-vNo(kiN{e-bk%Dstl~h4`?iOukU> zEIv7Kn6^*-k1uRJMSuNl<%e?LkmF+;pv6_1KhMmjm!=G&i!G#i-lzFI?Pnbf(2%&= z%oyKKcqg7~SqH1#%lVC@M$+rYK`iPr6IXxmq&{DpSoE_6Y?4J1R_33sSXZcttB!x8 zeJop0EN-FqPW^+?jic>%d= zA1CH6zDf73Dj{F@^`?d`YVwDMn~B|p?&37@F0qhYVw+0pWJwx>A?GERMXqf``-!o{ zy3cd`{n!;I-%3LL?tQ>8^&I;cW=rzB{DmMqD-0SvmRP0UXSX}!1a--2U^I5N*csj_ z9IATB#*Whgudb!2Jv^V#H}~1$l8xd*r^C$0`>{~FDXJo>v69Gazla|0A?O^gNS4-r zB6$lHNz|(B2kKP&EA@V&yMiv@|uJ1VB#GGr$LE|Z)YchIHsGCSaG!y*rzXK6l?JB#RG#+n@% zzUUcdr0xaT*bk&lYls!dcT}1G<-+z(C6fSr-J-$-hOHQXVK1pO5VBrD=aOJ=krPvm|%KE;?-Kw z5>W{gEsg2Xo7OC?>IBZayn>XjzYjG#{2)R1v#9)Y6SN++=Y39CkVtbEY;ux3xmTvq zYunX%?dd*v*Q&dd_i2bVKr*K9gj=P6lnIh?IG`6_X^)bV$w6ZW2afv3DCg7YgM zbbW6_w-{H$?Osp7b3PNC)~V7AM@3RI$5ZV4ZxQv0C}eM|XW*I~b@$9S&G zPn|hx|8Ib_pS(JeJ~`OH%5Pt<*!xJzfd-k<3m?0Jn9-HStE$uPx&yGg<3nbYyAB@J zn1Ey5NujOnFnpe}Sk(Kw03Bd1(-|Ctw`~;(TfYeL+efm(RC2`?m^xWTrr zKPx`H)o{K_<2l)qtOvexSN1`-kz*j z?|B5ho`zs_;bvA`k_q)>2srhx!_J-iaLS=U$hyRk$78yZ*g-Fa(_0QRhtVbYWY#}6 zROOp+sMkaGAP`woj2(8>oeph{n{e;?9QZY79P|58C4Q%CvHklvIIG@3UOc}8+opz- z!;{{~HqJ0+{A7i!XU7j_`mR6cCDrgS`7ke^J_~Zzv zaWA1A_U=^XrgklC{D&i$n>UsY9Wabf{W=I(LnvExsfi5u%QJ_+}lnS8{_pcT`#GfUT@*>PA}9oEmsV!uikQWP3Uhjq`zi!*;puHh@>v{4T_qoI~; z^~{44CDEYs3eaYGK6$<@5L&Lq!mO|TU{17ypsg&5OIvH1-obsaF((*JWZvRkt=(j= zUMRpUJ@{1?0X?L?%0xM1v)3LV3U0mG`ua^|^|LkLta@Htm*LAwH}=4}S>H+AxW}xs zBZipl=t{y5pCo#f#{`GZx$M$0HLx-4%XVbgkv&^~OY2Ewcd8QE_p}e}&dh`2r<*fK zW8E>*FQB{7aHxn4dS;0iOkK&mPp46*W{&9JHCXDG89`XU4MFaqiu#+Cd7_gFK0BF8 zdM+k*usJ{>Yh5 z3y zyt{e^w-6t?`KLZj>+Z+`6uZEL6U+IJS=I!q7qaPA`*B9-eyTmC5nWb|#I{WrN$Ii{ z_VczY%Q`-mhN%1#`OsW(g2@3kqg)Z+hd6@C)%iU7;0_^Y2VzymV4XYkYd$Q(-Os9X0aI3M2^=y42w#>^X?@#U#ZF6?xi>-@fEAbJr zi0cQI9>*CZ?i5we%;!UdBn-M{4`_N#EEykzL*06jzjMv_z2_+`y8ak;^>Vv;Hswm%PNDw$>U*6fe;{ps%XN6#o)WLJrfyNB_-j}zrfcHTww(&PUgHS*?F6RAm; z1E@PposQ~U%Kv`biiZCt(Pu{!s9Bi^KJ`1nWA07K9X5z+b>ENXbGp!PJG#7PT)wxZf5s-adl2Q7yDv zTRz#REMt0FhLyJsXVJ3Hiu~rK%_wYh!WkF0Q@Z~dHI6rh{z3WJp0kJVs_V}?F7Jaw z9>H|V-ksFgOQ3hyP(J_MAO7LtBx=yqmG3Btz?Jv!fbHx8m^U72$jDsDi8z%0?1{X~ z&;>B{Zy1cZwVB@9D5KHdi|Ma1DJ1hr9%uFgd7qHI!NRpD13Ihkp$MtxRmQ=hQ{pM3KahpPVQkh6!i?>h>p z+m}YzIYDmz0l2;{3Ho-9qo18`h+Dob=CIKUZ%1c9a_3^IZul9d|Ln=H=V(-pSx`Wp zCcnW|TgSjQ^E9bv5(^RQ>!f>}iS)PX8+aVilh>LU(W1m>*!a$j#<{kVsNR%Hg(y(2 zDH0;bSHPQ0J^s4Flqj4m0>6o&pfa;RZ`E+8y`4VLm;Eo`>&RPRvTq2g4toKKJtFAw z(+V)}&px`U?KkiDEsAPA?9TrY574@wiU+6K&;y&p(e&uLtw!2O3oSKpyu?tp%kU(Y!KAPqH5dg0|{FnlRgfhCRhNhB4u)&CF?`FA>*%WLgj?^8Wsp-Ic`%;H5on+ku6MP!-6JUlte_s@ZuWJwEuk|mXDSaNU>ls7W z@0YrqgEYAUnF13wsNlA+;cSJ4P*6I^b&!a8pOBzoZ+NEr?=EBWCgJuHRtp zq28h&q|rxP+ezt1Ilo`Fg;pF$KxNDAEbNI3=Mo|GrFYNUuBFd{#42zoBnrN2zwsO6k0p=h}+&KVv`cZ<_`{1G*Hy&@4)XI$dDQk1#t`53Ut ziG`;Ut7dn{UTI(LPG(P9MoX@)l9+IQ?0V&Ec=|J?TrROyM)xS^hiwAk%{hrbxo97^ zm>h>E=Z>QH*C}$@+vfz=^uzz;8c^6R1+4z;fVch(x-0GkKXVQGAxIHje2()M9m@2n z>odqFX=tg}9by!MK(miD|30w>eK!oi9^ptjSQ}rO6+sh zLhkYH70zs&Os`Ip^SvWhf_c0de{n(=%e2$*-1F_I+QkB%3@N~=xkFh=Z3r3b|B5_X zkjf6Lq=*CmbD%rKB)liVF@V;7=Zk9G8|uP#KD1@d$= zH+j0_HI~{Df@R))X+iY`GIQiRnwoZ$(g8hag5>zJXiI>p61QuWj{{%ZSO`;2E~2u$ z{(P=a37OaMl-e20;^k9!(`er)+INyEtv~#jKAW9QwQS4LiIwq~WMA6v#!7m2^e(ey^V_n|MujTVz==(9e2nL`-gv}`xm zZ;Tf9oqfxL{%(bs#G%sf3gu6?44~l-DKurh5iUh1=^kkemZ^urn~XhlS6Vb(G1d+S)a8s{aSevT^Go0(8=V3FnH?M#K znnM$RPUMcH2Y1xXrar$?!Q_w<9hxAOh%sBj+m$6VeI1Rv@(bFyy||S>LjR=ckWS`E~qLnFNZx=&aBOo8a*bI^uW?WuFy=AyL{;QD92f>&xg5@9tbnCzPgD&81U+ zTHwq}TD+~d2@74i3rwBI$O}UyH`{?mcu*BcE3^L5q;cIaCT0L`bqq$!sx11kst->o z^y2Ssx^ku6M``Y;DLDUTq`2w203G={@`sR0Pcm)V`s^1JeLq7R-|3OCRU1IVyo04l zZjDzLq&|kpL235apL<{GLM;zn!L7&jr7OQu2;W&q-xrp`^}-~`I{q21y|_v3{Z#2r zyLmV+PlsJtw}Ik|8kXBP01ST`@p!N9+{8qgC)7)MRmDe8x-N-2g-J|)^YL_3brqbA zyH3aYID!Em#9KGqCHIGy)3qHzAhS+_#^D*fX_vsA; zTqN2jac^)5edYF)8cXxJpxS)2B-44}%3(CqNROWAd4diTCV~IqIb3mLIA4(S9=)y= z@hrLo4o#1j<`{WsGx`!8vrCXu^$==g_Zk(H;`rrT>GbuvDmu3A1g#I9MBTK;aaouf zU*g{j3>|CGims$@lyhP277IQ%nbF?0S77U>19ZvbB(B%@1j%-Kz!p3oO#fb!a`sKEs`+3&5rS6)Drk>9@U+yiX5%`fJx9ZgzVy z4fePWzMJ#FZOKl4{ZJ;Izs(b8j=cr<=M9CG+F3N;_Xit#U!a0!HVyt}NRuE@hG5PP6MH8a>x@4gQM zi-Wmnv3&`hzHJ`bem()OOe(?Q@NjzSdpe*0Y%twyuRzNND)Lt^)v%YfF|B=IPKr%p zB_>HKElGVw_AYM0McIF#uF{k`5456c&x>Kw7;h@?x1XC@n9xMy-L!}IO#a0Cq;UVw z?TQsu^t1OYX>F9j$+7pbDf0-e3zqKcLrSo$#2Di%eDPHEFupOP*gl9>aQ|hJ zA9H>m>iFp&-bnYPX|I&&N7qb#HO#;AT2&Yn-^zp!ozwYfpJUXv`!O1_;2?Ku%mT~J z9`tVfIcE06TJjh@rxu!rnPZ3=eQel^QZgBL25VHFXgEdFN2>E}auqtiqY@wf*h?#i zT^D``3iRscRH~+Q4D&Y?Lv2G9{CN+w!C6ih`4>suxf8IpjZzTkzX*UGz%}p&xAflZhH>Fz(G;x^80~p2@P{PD+`e{mYq-lH8PP>C!yg>l@@Z zp6AyOq!8CJU3kP5e~gd1hBHm;sq&M4)Fju1Oe4nBC&P$6bsEE67hHse?E`7h>0sz@ z(I11y45z!g7f4>wK47=Qp3kj%&wdAwPd`4D`EYk}s&KK{2%ofkVBge4nvv{IZ6-D0`sxt=qjwO5 zrksS#`Y*6*`YBBPIG#R!{g1r48w5_LHgLgDl^1zW!d*5;;QY*Hwx%kE=I#FvGQDE? zIp^_wi^Bj>>(vDuYG6-4znn-WcmrLyDIY9OZHM3IH7k|+Y4ew=TR01O2*V#$!H?P` z8b2r>uI+5%e`4PO9@xNRy^|qCxtT&`Z+cl*pf&;a@ND)K1{Yd*qWnH2^!2Bo&JE!| z4n|;B>qolh_f1}}+*AH-daKRp>){Z4P1BBS4dKRjX(XHse+W%_q?x8 zT~-_5k+cW&;)+5(eCJcJj+nqt>t@jjaS?Rj<5rQpE}$3BXwtpaK@9m&djIkUUNrp< zJu;;iH`rf@KAA7^^s<|{qxBKi=Ujv%=V#!C$z!RiO$S^`T@C*k)X~N6)2Oh>53-$F zKy)6+owZA;O>#Zn`zr1G+s1JRok9G_>)+5Jy_fO4I~;hbz-}C$LeG862e+=)U4nM zAMcY4yTiNUH|r=gyD^J?jyi!_PLnbFW}s02YIgW2VLpo^BO#{x(6s8{y@ZoI@s9|$0vPt5+-a>W4T{k zIaH3ObA)nedznQ(JUGDjJu>2s-Ga#19+_NmW)8KnGv^g&d(cgtsW9>a!tz(Ke2MX1 z%(1T_dJpY+{?egT=4nl6ubae%C{@1H)s|m-97p$!>0X&XK@}Iz+RD3?en;O$XE493 z507kb=daTkrkIUkFMc~PW3w;Nt0ITC`*afT539j!gQ7ep>;w%qO5wdmOr>sDFONtmkzakuw<$Zw-(S{MAAYXUAau zm#;i{c_=eiv6EklH{z<@letgW_R5G*nS5Uloysz&NyK-q7boQ{bj^~dv|WqQped%1 zZ`4MXIG;xM%=L7Ot>moL`7JoTw!_bJ!_o9Z8XM()2tLm(f}a0ec;Xun=iF1K#rBjm z){YRLZ9fHi+D2SaE^${j8GwF4*a3|n79qNDeq+sm%> z-}&A6d`&e^yCLOMIzo8Y!!NPS>j5qc=*RnAiG|2FlktA)40w4Wn8bH(gu}*;q_>U& zsOOGn&r}p?isbz$aXrjGu-70SETb(??y?&Pw&C#_XC`LPhN3e^(dO$ybeXCKA3L() z&nk&W3kJ9#JqV*}d@HVYm-sJ1U2%Mx4)ykrhENiWvVozjeZ*H7d?tnEtc}C%dkEjP z(E$eq9)bh!b~Ed@%4}?OG<4bf9?zBQ(ovJTLhlJ)I6>l}?OUtNPdu}u6_!89IuAA8 z{)nOZN`I`HHUcfrFgWth8YKJ%EO!=ptgQ#Hem@@4*G7mp*Cyc4FSn^=Nao+Se&82V zo(ke@Z@9NV7XpUqam7(xxk|}UTxv5KXFN>f-;3_UBDpT^o0U)3Iu2#?pLPRr{7c%o z>M-~{QGo-+E9jEjuGF)o4DxDP@n+6J^7VEDSCcwM;Y)gOt<2Lnm!!e)w1afRlXzH= z@sM18t1E}y7pYCp>FAnsnnzzh$!E`QrYEnc@!YK{bjUI5%3tG#%DesRS-E(cv>%w_ z34bfj(3rDd;AD?VY8pS13{LpPmdt#HroE5SsY5ei#iU$&aHz*AuRgQZxz9wamho_Y zoiVje*W@bc3RJos04=?K&~@)LR8I<~0qIvU{meRyd=?{UiE}{ZKNTEsRb65bEu|-v zPmt?Je{(mh0+@5>hS+_e=s@GB z`LdIX0`TR3+lc&l9LazB4+cy8;c4hzQFCNc>_hbr&3kuG{8QZ;z2+Ulq@; zpZg1jpVe8*;vTfn^{qZ|GpDk5O!D12IQ+h`q~eu&pwLm@Tecuy2L_7tW(!K?g>xv*gm46z*nB z;M+zvQ#8Jf-Geo0%Ufl+fl?Jrh;IV%%^vFInoA?rdC@TEAb$0juBiR7gYPzERC&)x zi3RkKxoOV8T)jQC_Sr`Wy!;+N-W({u)tXBu4c<>b^c%=#*-7_pmCEwl22aTS6_@BF z$NrVCXWPjK_uIwaefWxlXL|CpOCHhWdBfqpo`QUjlr?={p1>x49*kRLK6IzTEx>)_ ziDh0jDl{wM^Bw9!&d<{@Y~B?9-|IH;Smza&Nk*dFob5uoyE$2j;#8J z66S?V9-M+ewks)#HEw!NA87Rl2YEfeNU z8E;T|eY^qvKD2~(o3NbwR+z}&d{&m{BwptIY{&A?GkoN652sNTONq-f^aj-$Gnn3c z_<^qfF9f{zzJzz%9&_KIrMM;R8+YaNH_j>kS4457iL*X`-<^y@`)O8JoofV zs&RKe)U=EIUdSN%b^n)i#BM`~z3*N*>W#jfr3K1)oLc1~V>LYEJV8#|9^p2s&cc<56#?d`uBadris3%g6>T3(Ss{f_guD^w~k_XIqW zyBgcyBJ&u$gNt8xaS!Erm2QP!BsPW;wbC4eivP*z-i9DvIMxSiubIaXZtWH-I zy#kx7@pz^~mE5+OhS|#Ybivi}e8AmmcD=e9rYmfwQ+&=~^~^B#Rzu>6H%z1D>lp8& z8_kYto1^pHUohA!72dyE3@EN zvnVUsm{c(An<#F6OYwQ`Pa(tSXlFBZZ~R%qN?Vbb((zi7@_^rf9gjwW8^*5~#|Ci0xNu z$i9h}WcJex!ER7LS>8W?@@ZI^*cHd2ndb+r88M3lm<5v4@4pCn*@bMmQXf&a;GGy~ zUng3?!iuq%Cy5uWY@q8ZOEPhmFS{@Hklc2oVA{fCc*$o4(NHl5jj$x5Jol>byzLB2 z$bBdb9HK*}7YxOeBZI^pdmW?vs5ezIN#afkMbF;Ur~$qf@w?Qzfk$G=NVc~3T3-OGyn zo;ii}Ie7rP=Y`@awMUTqZz{3$FD6BYM?+>{8w=5nu`^qu1Bw3acE!@@y|M+fqxsUtWs+ z8WP!wi)s}{@9JUe+BQLO=?$}X^d|1T4l$Woji7!mnRWm9mkIYikO$}Qv)StZNanNt zti`2Fcvzr`y6S6WJiwYI7S+fkx?5|u>6cxr7ERwNb8>g}I`ya{b{Xb;~S~DwhGxEvcTUoM$>mo^D zI%6l>cfy|K@q&DM9rLXTr`{!9VeOg&%x--GcfI^nbWMN6GMySoYErUTGe21KA5TtZcTC) zK2vgyJNASZNv}!3AVFeWMM~>KpDbzlDMrnzWwz@^(@}~CV5jPQRM!~Dy?fe9&d-(j zWJn<^%ljz$|F(zSC$d@j{AjF248L~n6>0;YL(_-#G+>MdHeYZQR^9J` zc?-{y^yD7&%6Ln7x?V}R=vW~(-wMG)>$bBgug;UobWN(zluVwURfn2_jl?ytl^9Qd zXumRN6|1_kNm#$FL5$0|0loH)1BX?j=%QRes%_Tdq~}KVZI3m@i1~L&nA8vQU3`q( z*4i`C z%LJ`-S2q2I8><{(L#(|Q3tG>{!t(r35NCXMWFzbBJRuB-4;4P;XyG~6=!%W?8bYsadUV6?A;JmA1)$h8sB*{st7MD1E2uWS zpue7fBGg6 zyBp4$t5~_qaWmZfnv2g`6y+xyj}zyDyJX(PBq7z>1sx3P*&y>M(m%P-uIgz|*m5|N zyxV>b2AMaOAO0xARddXxJ*t#n|GJC^6c*6!rCP$_$k%k$+57lz)Ih#%sWUo9O#%D- zOxTbh;{7`};kU$1^q!Ll7hN@BUZ*V^<7@$kedghpnK88SzmMcZ^<;APffHW3sLSxq_rJRJF;45>}8#8XwPAZzq`)~`C9-3$&V*QD-Y%(8Cs6J>_1cI-v6 zJ|;xGt~d=XjH-lgQg%}cK{4~kD@bDAEs~M%DTFIo!mDdi|F!)W+xyj%*pJY|B9CG6 z@B{jI!eSNq@=qWBJ>P)FT{S9pEb2vi|GOsk+uh0hY(vNp|E;nBz5Z~@qYrxLOy`rX zFCzzPYMEogD7oLL-WYyaVq!6CxG|tVzI;4E+?-<1oFC{haiKfrZtp9z`*Vx9zBPc{ z%?V)P&UyI@byA{~Zl5}Mq�~nvgKH8Y)-`Im;TEP?g61J9>oNNq@uIbayhZQ%z#< zaYGtr6iCi2FM(I%4Jyw}zbIO7IZ7_|8Y$PA)f2kc*g}8oi>qzNF=r5Z94_%hB zD9!zB*ua6rB3nk)8U+$tdy_;|yHpO08IDz{{_yYt$n*cKCYxG);p3;bY=puUEKcr; zrTzQD_R1P|FzW!Ryf==d&sqUdLwb?_r0nCKMTV7kF3-kq6+z_VB$>SFOf71=gn++_ z4%3~{fKjE3&|_>csQ!_9g2}U>aOw!4-HxHhZWDlMmT*S%E`&()#Nayy{N1hz{8VZQ zwJUuF&Bf;2%a-Hw_i@}jQ<AluK8gO}>xNbrsj=S|16ho%b%M0porfMj9`Do%J!34Hd{=qx)JK&np z6V>E#(06=KI%>etiUEuJ(Y#Yq2kKWE*<13BU68u*14=w-@$I!t({Y*9xi~4_P`klC zc7K9_HBvW9{T^G>V>WaSzlf_3YSM_6R@C;zK6@iFG7{%GBVn96=$6*BdG@>i0UqN)PI7p z`6HZnWE~o9-H!UjbA*Lv<+wuoBZ(LviARH#p-%SzzHW=cuK~eueRBqDd|@m(JnXQ0 z=tMpAFW=WFPGMLGF#ZwG9g{T+g8Zb7HG4m}Q@!C5&rbo${%^y>0ka7fDxOXfwB z9+@(Ja>a1TGq4=11}%n^sqrv5c_^8XehTL3xzTY3Wi+MbBBoCMjG05;k~5nF>Hkcf zc{G(@{O`?~WhO$VA~TV*_kKvJWJsl=IZ~2Jr8#8?MG=K0A(ae~D4f0bbEt%*RO*W& zk`j?hr13t#d)K||o-|H(V)@nqvOo#A*xD#WpmB+Z%w7~1)`Siqtx3ga~$S|Ef$I%%h8K&n|7SDfh zDyzO>HFbUci@w;K3(Bf|sP=3=3d|5i=?<=p-Wm<2vPKHO8s_)~3lnIHNHB_gkptbk z-=GgT5jt$_rU?pVG&^M~tyrx>|M@nP6;g&=G>^bVL&?mK_e#v-JqoDYM~=0rSwQi8 zQ_7et;yxWSy8oLoeLC`hz9|}}KfOMHSz_&^JlpSTE<&z)ox3?$inc>`wd zoNlVPu#6_B`?FfSMJT8xfj)Zf3HL`?v4#6B=qt?4>b5U*Xo-2l;ap#y# z3Y#%zzR+pDv8>*L%S`26G4>pu2P6M3VOqb7u;alv3D*w}Z1nHHkW_S%%PEsypS zE8{RK@5uFUFU5idEe7zdw-uYC7|O0!ZD40s2XdVtKXPVV7WqjRk~s}!xRG-?3~p_s zWf5|yXdA-LU0E=Dod*(Jw&psZ3&DxM<3QPKCsp?>q8BgzLHok@!sAyG>HMpP#B_N% zsXfO)8;Mf7d)o(OFQE?=FGBS5+GJ*Uqc-Yz97TgH(&4h3i|{;GIp&prFDecn0srtx zBxmM9cBaguhisx~@Dxnjj#4xn@yqdN_GV-qp3ig+9Y&W94$+J5HF&G~G}^yIhWU3< zn)$ov2zq#u&#{b!Y5)9gc=%EUNlOu>1r9>UxYwLF|J^a9$gzk=R_2ksqE=dAq(G0p zH7CMHry$#9%a~cdBj}XDTZ(e;632V`bYb&Cblq+yDhQFG|MuR((o#u_`?CVYF_^M92>XbRXFTIk^xR67axb#BP^l;i4et@d~Fkq`ir?8tJiXrK< zZ_u-_v&^|6H)Q*{7r6(##>>Q?-yMG^&?j8XrAG8zTou^F%aT(w$BJ z{BdFL?E8W|_Klrs`Y3x_X^_KYjfLST_VLBKqi+4qIx=hsGn{h`ZPsB>poHjn*qNSC18w$GJk}($XLNOaA3}BJ?lSXjWvl zR&kE)a1CbKlL~Unr<*vNYOwS8TWNLlK~lNT7u2NAW1Jdapf_FG^vl7^P|d=F1QZhZ zdCoNSWWgBnHWp|`AakOM_A?;F9 zfNuiRX!yxor0-S$u5q*V)(%V7eMKx9xL6J4l@wup`Yn2F+8sJ|=oayn79$@c<(c@S z0L|0RCQ`F*gLWN#wnyR~YRF4R2Y*aqhD=tm@(RM}May#d!Xy<&8Ofl+W)s%Dw4Ov} zX3{cgeMX&aK|z-!*gg5Ww9{Y`GkEwodab9(1c*&zwo6-~5qnD%{~?f7iWQTL5LSv1 zEB)EbmM!oUSZx=u&$aypS+kPxk(5$_hJT_U)2x$izg|gO2CuV6bIWN>rl5xq|Xfd(c_sIf7uTTIQg*FwJrf z5_DeNE!f1t4K6ij&@S;60-xFK?8xjaChYN6fzA3ZWW2OM@X#!Z{rX{&;BJP!pzrNu zfs1G_8&|nOa7*1w@a=aHb-m=vDvU+5mdE2+8PSu1Yz{JWW8O}-+W$Da=Ar`4;ELJ< zKIww~;VneWc@Asr7{mr@CK-q|2OvN=SDiezDn>ZFN6&bkQAgW_)BFPUC_(ts~JuAUF?d#vCM8J(do}@ zcV@&5Kba!z)d#|mN{o&v$c;>TN@b_9Yn4D-Xcvs>? zHlDH;Was&_hCz;k-&x^;To*^dP1is4&0+PLC+$i^`qH!-KT}gd^Y&k?--VfM^(%Ka zw_+|$5~ZwHfT>`eK&xh#SGu72UaR1qc_q?)`kFOeDlHWlvUmL~OV^OSlhcGXgf$|B zt)}o4HU;k36KLtOb>p5nn>O*RTx9;=t9Vw6L?nfRg`SD4NlK^+2}L+f72+O7|MO)2 zKToD@Q6kdv|N8>#tt~w_hI#G{nY@X+va^*I@BhD!i{k%%(f|89|L4-T#8SCSoQx2W zbpGG}rV%280`4$l_fly2^b{53Thj;^Q@n19Fw(rQL`g<1>^+u6=iQhF>z<0y_&p`$ zX-6dK5urriU^l6Y6Q|jx`tTK3vL1b}%f4{%qW!YB$yZwiv}dk9a+|Otxj8xT#LRHS zv-(L-39qD^o^B>tmoZEo;KRn`a{8+)ogU=Gw~MBnaa?Vqj*OO^A}bGdfb0L==Z4(5 zqz+z?FU&x9vsy_D&mP$YNYgj^ zK}6x27rFj&2kg%hLGyteI(9gc9CLn7tQw-w3(o@36*k!^J|z_<%((?yW`DURAD0 zZEO>W<~=SMP#jHMTNTKbJ*P-PYcVvwa0h2dY=zE4P4uy^IC`5Y$+k&)BFlY#Sa*jT zh3_JGJ5~+Ssde9|JkJ3tn5nSdqPu8H(*#}N^P}4Nnl!91SU}FM^QJc|-Vz-rW%{?Y z32HyM2igYvY3=?BboAIU$Eo3kjJo+NVsH~P+6(rQhU=x!V5Saz_}v8ll@&vMX#%X5 zA|O$+Do)?|YtYHoeE&Qf+Y&@*@kQ6^LAGDbeV&Bx93RdEQo+!Nb$}KzCpXd~PX9b(|jZJiR|5 zn+_v5N4f@!36dbPje%R$W3WZzdir^8Ho1*rc%9dM!NfEbxF3GuTR#5+EW-Xe<`gf0 z;=!sU?`0tgc~ysZlzWh{iVx)UhD*SA?=|457>yR!wt}c;QU1L{p+xJR2uY9WL{$w9 zyl_!7lGW9X?H`;4*M1%YmcRATMgMwohFWN#P zldqC4V@bH9IT55>OaReoK_s-UgsPkm;JapN;3EYl@Z0nf>^x!3elb4?TaKE*PM6T? zAG~l%UvD}>;uNa`&_SWQg(j0h7b`oiN)4`A2UPu(Zw5Wu?FkL!bk~IHO zf)lh5Esl?;ils`ZsOddy+;D)N*N6gnLJ{=uv5U0vVJ3clg#mMRT_7TZ8MMTF98?G^ z(DZ$!q$YF{JvjXeavjcv8^%u1#Rc`WRggsB_ z@q_ff&SCZY^yx8+?VLpEBu(F~LQH1FLxseXaHEJa(!O>Pl=_zPo|R;hV9QnTKk$@( zz9NHk&cB3O$7G$3Nwh=9>}a~iw3zyMs{`r(B5+FB5N?c3gmL2o;C+ES5*OE}55r2K z_=P4sU@D13k7nTw7Sm|fyGbNf$P=0G@1(+Ag@k`#Ix6#+foiVaL&g`!=sh@zx|wW8 z0ih?*d`TCY;5h_@UX4@v+Ku$*tV7u9TQ+eBjE5VzFmL1)J8IyR41a7Gg})1o=umYf z(Il1RM}R9cr~M>+^)iwkd{9g`Y~Dl9gr3Bg3QOq=x)>K5NuZ%+PE^;tp4lBMNey~# zF^^Uh!jUJ@D0}}PkxUU|TelJJJw`w~ZyVZv;v*B|%7Y=3{MqV;L3=4?j7a7u^pokilu7&k&e0cug4O)^b zk6d!=u<_=}?C^Gw3I5|uI3>8I~n1a0T{UK2>NXP0G}0&AtGFnq)6@$P*v?BX%+LS zd&pz-^8Hh?y=(&+7y3ucJy(;OKZkft&RdAowQTaJ^*U*cF96RrEg?w<3C&8f2DJ)v zn9Xb5(B#m?L~HtQIRC^6BoX(StaEFHZf&B~PfRROjKXPjJL@)RjLF#iZ_ zEj`P@LA)7JCJx??K1FSnKhfxtomlkgJZjI+1r3!M&^qB8-j^fIhN)N6bli#L@7#e# ziRrMi=squYu@K=K-^8uho!wo3g9u(UlaDWDn2UiT%-oNv^vaqz=ov5%`FVXJDf2R@ z_ zwY9l$_Ta%!2W8-<%}cof-&*wiWEE8Q*hj-Z?4o{aB$5AZE4q5c zWjeo~$4na!q`q&0Xn_14UduCInw0vU0=qPlbZ#Eia&#jH>%!o%-=}H%j7X%*!3Hm7 z} z-!;%*g+qcgjn9r9OT%f%3p@JGcL6Crc?cP|jgvRY@ld^0pS5CUuzwB*@_q(Zz%S8i z^rL<+Q7xPcUG6VH?dk(m_Fg6l!49;)U6t00rtvj;Zc(!_ZR+}6k^Sl^prU`INz#LK zl6gs&#CzF-S`nJNK@mE=52L9LxvYLb80ll>*wm=A zbeEhRlsRb2`YG)rW?Yc#kg1r{Ob!4L)~xKb-trk^&TpmfrpLqf4^vSg&kq(zCc~;L z7m53Y0p^H$C^N0&G%dKcgH#>4gfyDA(6H6hnektn*h7a-qrFY?TwrvFD?|2B)l1Jo zw^RmdJyDBx$*qUfI+BBV41&trw`nOSPTI1>7;RhQ!x}mXvD#y@G-3v+>tSousmy`0PqxAN4N}ahs3aM<|Sp3RX+W#>oSaquNwxAqq4xbqv1jO)_? z`xB&Syo|0M5@l{raD%A$CCFw|8I}2VjGbZMMz7vAXLc|3gB*O8$-0Z_Nd4&x z#^-<;y~Jw=tqVg~shSb-T%mA%`$q3D>`f|iX>x+RrH-|EVYdtMl)t{ zLH)_rB&6#vo!t~lRcQyUdfkAPc$uV3%bLx;JP942c?K!k3+V2xRy6qfHRMrsi`^M1 zgT&|tc7weQ8|anB`tQ)Cibj=4OtO?^es@r4vk3oQ5>5XNaKcueBYRi7j`RiTGP0T` z1Rm+5;_Kzmie;}@F-Zg!jV8r z9cb@bOXU1|;4%4CK!1N2dA55Do^E?iC3Nk{@s?pny}Xqqy(ArX{fxlhgjdtA-B!@L z>phX?&!sA{sqA{CTr|Q#w+_ZZD5lp1J;cqBSHoHQam*RkR%PI;nXx4DY7+Q7qn+%y zTgW{*il}2w%qXy?JsO-0KI}6T$`oZ>r*%W8&9yXC z!US~&FGMDbQki#Q;>a{X0)5-;L!DS18kCA7+NHA>W=D%Nh)Jky>o{hdb*qDPoHBnAn8 z8bHd9ka=)gi@uC@g$I+Ka`$jKa#UjIuCyg2)c-CcrYK8yX@ro8tPYf=u!2@9d;pzw zHB>P|3<~GJCW}*b(8ueE_|-lIn%^OdWaw1l;+sHub3H)XpGv-!?FINUqZR1)=(BFD zG`KDH51agHn!TIV=B3Z6#dpPfs-|o{Lh{vb10ji3xLA$P)3cXF-G;ryewzV(T;P2>W$f`Btly(`YJe)`>YSM{K>J%E+ z6G?7c%s{Qbl;P|HhH(0g7i1SSgO^)RLg`i^*ynr`D}PjjaF!P99iB(NEbt^BqYS_s z0MV|=Wu$#)I=PZH2R^^Kf^5$7VGcdEprr2_S^U-lxsP{|YquuD(}8JNy*_PrQ^08w z`r;2(_o(F6mi~1tIW>)3Y~mz#_d-FzELrMQFF;}jr=i?oDK_ZuJThf9C&0adinz^)sSVqOahmCVx=tC2iiry~1dVsVx3$xtiWiSx&zNoFs4UEUC-915hu> z0crZ)C;pQ9^ll(m!k={wt*|I(=jLh9tk1S=Q+G7eKfI0!-F_YQ_box&R40(;msAJ? zFzWcRkWE?BNLN}dM2c3%Y^zT)*k&hzX6=@xGWNGvaYlebOx7?SV%qRos1?<@`;}H@ zQz&&w28)ErvP4t|t*t1g8h_U@&Ri&G-;7V>YeF#dIsYBLcW@J2Ao3TEG-bhr_$XGr z=N+wHe3yfSZh+lyC5Z6@P82mZoi#mHN#{SaW-sq)pwn9qQ0M1g@K5I+x_f>;tx-~8 z%r00k4yX3hk(|v4?9^rj_&vH>upL&P)?oF^k5OSIZ|HI6EAvZpkp9t&M(=XDbteX} zA7$5|1G8U&;Q3C~_RKE4rBNEQL9fu*y+o4RG@af0NSQ~^65@XKBx@`qL3eSW=HAx{mByE0=BUClO>4UX^r=2?;zj% zioneETrhONN9@^TDA;33yPZpQmcujCc0#<(rh{gU(AmylHLy;O9mw{>68( zptLfL_b|!}PDn$n9G(j<{F@3Qza-(EnrC>2i@x(>dyB!YJU5uB&H%k#j{G8S9kr|!cC!Y5Kd)`eocJE#EsTU-b~ z?aktkxo2R99wBIWqlH(eH-I;{J?9S@-vWC$VV2BQDYE$TPd=IgV2w0_zf4Sc7mi%7 zUb7;Bzs2wl|4jQ^kZBNwf_G<=3rpsbwHH13F>C`a9BSm1S7+mm1%=hm(o=yjPaM0x zT16IytOuj-7tqp-UMiiu4&;Teh0nCptA90o;LouZq9^5dA%X3WhQwzY5rW0r81TL$W9~2+AaZUy=I=Sp9ayWe0B_@}XZ@MtWQO%quzXz<{=@BWPJODvTKF~5 z{~ZK;%s-+7UI}2O+&Pdu@rvK(bO=1kj$|5Q$3dq%20t9lK-?T}$JsxZf+>!Mg8N?- z@Z3lreCoIY?6v4{T%fT8p4oB)S}!Zdf{%@CV%G}N`|u8bB^MwTDjWfipBsUrmtK-P zRjLghW#c<$ht-`x_coy;z zeS_|_uEhU%FL8&7B-ym_G%;Mf3N`fJWS_8KX;(mIG=*_RnE*7& z8nL#EF3_9n%FxxWVX~6VBvuz%;E@@V*}P%v3B(rujJ`Nbo?2&8_;1PR_}|<5-$e>@`rOV6^_KtO{IHz4n4 zU!Zc+Mm9~#fj)lnl)l`Y&Eyx>(QDoJs2W#NF?8cml@-sa$>bbZkXOM5+>~P{hU(#k z{%E@Vvi0M33dOf7wd=)B-X%+%$@=yrt( z>~2A5y3PkA-ef{m+peKe;m zL%_u?3)=N~!@&tr%1vX?5I<62$PM_DN9rm2={E8E=SZcuY^SrOX46e`&!QZkNVeYQ zFaGbp$#iu09h5b>jCM=p)0;&u^l5`M+8(LL+If1C(ZPT4@peC4#X&IjmfEmmr!dKQ z;lcU}eWC&NtJxQ;caa^V@z|w(ia>7*OIt-uQKR!(^mOAVTr=|`tIL76!v~|$tvXEW znuFN0!I`|16_KpI{zWv+N}EpEI6&{(pGApJE>UND3#XBOcNB7PJM-y1W!CB_5$&@> zBqw44y|uInozyr@<^KJ}2i84j`n8TSSHIfPEj4K<^8qEP5m&*T^FBa5;#_rBW<3^c zeF{F+Ws{yG^RVBSCSX17e%1b&O?V^9iv3OG-K9JtQkMb0TXj4Df_`(jJb~nKOdoeDUt_N2R&Vh}s!r<1| zxx8s|(%{zg0(|H%A8M2w1$tLjgR`5g@l_=+p4DFS=hp5QNU4r#N~ z1G`7xgKOsviPZT^U{`_->XehkgSmIBy++OfP2GDq-?<1&H4pQqRixqTo|a z#euZn$`k)!8`$h~;tS^U5YPV&6Tb`k*uX@OyJrPh{`v>gmECe&3 zt5A_XmKw&Iq4)Z0+0Uc$XxIE}pFA zEW{e8J|ZnPp^VO8Aj(hjBbx8)sZv56U0w%ZWcx3IX3i!P+uD$LX$DSmABNxkzYx*R zMp{*^%!zl($>Nl&$l`=L-1_V$o%UUUD+5`uOIDRrb8ij;3Di++OE|jxwt|dH?M1?4 zhbVLQD!cCfJ9wjbGZQ*^gA-ypGVPh;X|lvK5(jP2 zd$oGX32 zX?Yhz7~|>StmQQPZ;1zmDZS)@XF3pYz$vH09boUa2)b^OFv1E4=(+)KS`!`&c{{^N zq`nK?`soc;>eECsy$z6I!ynXKe~e@Wt*0Ij))4Fa;jp5vjLx6^0T#+Wr#AfS{NXc^ zyndV8Bvxz+dZRm&nl+roTYI9(cRx?+Qj`pza4;(C-CYDez-Y;vqv*cPeVTJ7h;Dp# zkP^ip@|6{$jVoEQ?L-Fs-JitjSKMcAbS*&tLPr?Ps*_*N?a<3MjwZ$U&Mm)C=K zU##Z-CKsI>aGVjS16MU%@frZiUs@!lBW2B*)s6l=obG^SO-p? z=2vxHFOWa`-YlRoxDm)WjNsQ#lEE5LX(DsTf#e0*;q~KB!N+cX^}*SaeBCc!c+lL6 zfBDKIB4TeqMsX6}9<~P-r(JMVS|kG>+?_t#_ly;^b+#ggrNh;6>hm4njK1IxxJBdV zJ0pPfjn6!{M;7>N-7&{!cc+qd8IoA^oiwz$6;u5+Lky;BM&gO;+1TEy0srfmk3WlX zYw!|vyefkLrJzcjx?T|Vj2 zY+$W#5?Q3d3HvNMadMd{e%rnrq$#Zf-G5r}tXbY5=W|^3h2_CmcV8q$Ukn|+ox;er zb(W~6R2k^h6!Wd#2J%t9J$73?1D+k81SGmjQP1~O>~Yf${+regO4-_K9g~yji;^<4 zs!$8r|BzxVf3;I({~NgaPXtWr_(Zb17bElRK*V=FMb9Q~goB^Y5l!K{)O=k8+GCXq z6R+)|Yv&!J@nAL7cDh3jJdHwswO$~vU_H9;RVaRXrXQ*`a1GJJ1B$~AmXlLL|dfrQkD~+l!&kGIN z$EgqCpTYAqL}nwB(`cbH@1JJ(SoJW8kM}`YyLEJ3@)FV^WrXe;OHdCV6=d_xon3Xi zgs-3*%UXIbXaBpr5AFVE#QbM!Nz*UrL6z1UusKhR(Rq0Y9goUG)9;3$?$Pt;Q_*DB z({_U(b6XJ&xU-Nx+hjpC;hvefn>p;@?K}tveoV58gqK?|ne`zIhI}O}apHL#6PGy}I;+ zQ6Kwvhb_u^uHux#-v>_zi8y`PaGV37<{%aCl|cDr47Ip7i++fdKo?T4q2yc{r;RpJ zj9uIvD*f{Z{gDt!?NSq<*xGD%_0(l-*YjxBk!M5)&2}?2R*{UV{at9E#hojuDnOk- z1!SLsFjY#vM}xylL3%WgoA1iNlV$&?osu}2@G+r0mF4VEbOL-G6w65TQebxGGvW2w zp!@H&n6BeDSfes|_A_flRsTt1w7!)pY%~O_KSkJ!oUrU+x+K!oucxJ^b+l;U1xc^t zlkMLo(Hm9mbjme58nxm!d0c6ago`6^O^`a9HCcmPo$`il9Il`e3LFq_!AWD`cV=wI3pC1SflDdo{ zyOy!qK9%&;^bG#yV_k64uaoGpa4D_aV$Broe+xrIUt_S+nSC&KJ89zr#R9$qYsHmw zk9iOh9=aCoa%0%2>Ei7DU*F)?{mba~h}S49NQQMESwV|Aa7)ZV9b);joqB04MVbp9 zv0K+BqwK-GtYe=BT|eUu@E#ndPdBwN;{_gc>K^1&^0yVOu=SxP7INHvoh#3ktYo&= z7_-%%o!H}E*O>dWtI*KAC+tjFA+%8E3p&MleGJ+s$mrv3R9?l9e!F;?uAY1X%{Dp@ z^E>RB00)bI_gHy&wn4W->OsS`GB$N>BAeK;UP72QY4eES?ov0@-5h0uP1Chm*8N_-PhwA>BY<`IYXT{9;a#d7I~5d}t0 zCWg^E9Y*cT?~-rf^`J-WC9X4+Wy9ycK#8x8Lk-?lB3-x`+NH?QWjC#O{+d#(!vam> zyX80yb&2CGUxv`DMOM^F-w}EmX9%X$M=+oNq|m&DnvCwrX0oBp2TAUqf|M*j64TcQ zs6^>u%C#t1!8H@K@2w+6=Ok#_0tftVb0U>h-%r<1KSOJUJW2S|$>`kfRBEz)GX3Vx zpvgnONNFCS<6$CHWN{X?uUJLjz12cvt+HIfk-)s13$)WKnXy*-2lv~JFfaC;hex|- z(|*ff(EqjrCU^Rv%?_90yoUvx&=ez|MQfb4XicLVY9&z}w+DN)C^=F994hd}ad61m0Jwy`* zRpFC_MO6BL5F7rXoThKJW?a<6u*pYBGR1bB)~zc+`*!`H?K||?BBdYX&ynrqxHp0e z{YI(A>14J!ToJja+~kTS&ggY`Es#Hy2RA5WfT&{beQoB>E%v*>+JgT`g5(g-Yv*a` zqGrTiD9EG9J1((dF?CeOCWTtA9Vfvb{E$tW7jo!TLirtX^vhc}q^6`xAG{8u6WYN% zq4ETJV&6Zww(&PPE_!m7n(WbIqmM6^AD1^#L7r&(@9f zv_(C%xTD6d+I!gVb^k?v1DtcEc*=BZl4MJ3e}jTCxI}0l?v^uadQ$*@n+g2{Mheh4^WlS zEjlOMgY@6KiH}@eOpNPO;rB5ys^=O7Gi6`XzXokY&UzvA-5^6Bn?1)_&xWDx$TjlK z!3*!3{|Zi>&`0ZSMe)%&eq^flLC6nb$*)J#$>n8 z^6n{Mske>PC)d)*O9*)|rMy2)+DLVeB+5IhfrgFpVCD3geCr4&`cb+8nIBbw;@11% z+8;}(hq4eY^7W;&>h{or&Jl3gJdSkzy-H8aD<=U^l17QmN7^^)$-Pa>Xbn_@{$8A9 zrA4^f_<1laoXMv*Tka6yS3V@F+=1AIoxxq4h16X1EuNp&%Dbtm4qF0#a&v8CvU=_z z$B|RsAS@S<-S>aM5wmktC2AYF2LF)&;b~0BaewsYV+J;{HQ{}(vth$EpAmI`KGY99 zgfE@%MA$P0-OrqY?hfokR%07!-g{kcRy_>H<&)`;)u)JB<`!()=ah%|mUD*qCi|oC>?R2EZW+K|bqnFGL}4;XZVFHC>n(6R z(H?vmdj^)ynF~tN25=kW1v{Rd;IFo^0Y(YqJgYOVc&BV9kUO9YvThXcH%RUSg(vfX z>h0}#r3(O^KQ`fzb??AXP7z3Wx)l%nrwFvGtl@J-3Er>%^Pp$?DZHeW(qDZH-Ys(< z7xX>`lkbP{Zk=(!Ro_p6UkNHWRQNmJt|}j#eB|ypH#w1C(5B3fUdhcmcYE>&pE&_^ zc{6{;ryzWMe+Fnsvmj7?K2M?74TpBj;iH8iytpn4SYGfK*h*laU6 zrq#G>>c!b=QIB~?9Ut-{(=yrhI3=hUpHZ)%;m(H$|B(V1*XqO1>l<-iK?__?^1mvjuWa{xH zl=)qE9qo*;XP)$Dk8gTZnFLT+E78T;_mR39vUupK7jLP1RnG zg53=T0uON7@$Rq|gk&>FbywVd9 z_(0EX*j!YI+QlBg@m)#SXmt{m*rZH`8*A{jlIv*2N-4(MO@mjbAWBPguH(H4wdw$GKzC@;Kona;E6xJB*evv?w@LabRwOZvp4Kv)5U}A6^$}t@clj*?8ze@ zi*BHcBQvq~QVwFp&2ZE-=hA0SgkbDxc{)_Zk}M5PHm~a`E=~`CPJ48T{&X|+AYng~ z-YP?av=CZ7zMp-yG!ez@=Yac-A7DpH4?bF?L7x==MKP!QNYlMB(i&mK$Z&}hGU5zMTdYe=5Bp-Nn>tL^AzSKmT9%yFJWidpg4mFs*Kx=pKXhl_L-H_uh&qF9Dd@*|7f@wZ+@%?r`Emz{o0dYeuWu$%eI0pi6gjjw>-Hz(S&Dd zt%1g!PeA(69iY1I9Nxcc6&@IMCQ=TXWRlly@LT5|*7qspM}L##-IcryWKPHN-U}4T z;;aWe_+PGL=6feFHtRJ`^_2is9+}{9<0!s;wU58paRI38HR6R{d=7enI!POj=l37K z2L0b5*r?_PhIiiM$B6vLa}UeIiOO#LhPx^FNtXecWqu!MsSN_<*tPKU%3PjvvJ%;N zRs}X`+mh`~?z0Dv|KP2>wF^7l(T5jKrjSLccfgC8*Fk#D7~avbmxwq%06Smvc|u>r z9hHMDzz!d4;x9Ip9Mu%y@IUgfZ}B9YwQ&^uGJ6gB`nO`o)30!9%V%EVyjeKSaR-dh zD&cDwpXalWPJ!tI9JnB|i@)tt0``9`1yx?y^Nxm;;c>_FV0l+FPxQ({;P5sE58nF) zj&E|{&t1;Lar@ukw{A|Lxu%4LT-YTE5119EuSaONol|6E8qtXgZ$$(20!c^ z17B9>!kP90>>0B)mUn}HL3c>4iwx8&3W0~#Ujge4CzCMK zPuR}HAA~DE=FO?Hg2QL_;bh=VPL1w`*`-os+tw-YoYYJ_k166Q91X^efo(jwOEtXv z-_q~Qj(Y;SQg;%~xMb3C{F&o|k|f87@lY^5e=tyL&)f$6EZbXB~VgstTQ!i$I5L2F{ku z=aof$$Er&6Noi3of6WYiJWpl^wy!xz_T4DvpOW!{H?CX;Yh){M-T6#pd03oJ-yOql z#vAyL2Bm?6Qc=ltv&+Iry4@@}l9lm+00yEt?qcV@3@Ozy?$lG$^ONR(pKovD0B663WP z)QX6Lf8JlgBGV4Xw>pRLS)2V>QN$0PHMk1amzy(9NndfWV3036DvX9-82G#l|HU5#0fOnC9pVPwjjHQuGW!o4FYAe-()*8}#wCMR#Ej zV=p+Wx*hx%c>tGh5giyH~3`{e|Qfz^x(wdxsF@jXu?_TrqGhk zn!Wm0KmKGfix(0(4;*}80gvuE!3&pm071or{GVBFu)j|iEGmluQ?3hmy=QpfVS>FFw3_9C_i=p&PyF2<01}aOQ*sbF;2_d_5z#w)Ph+)WkBaq zA^w`y0TzT^1Njc;$=IVIaR1U1{(lFn0GMM*lrxuNj}P`h>*EmKIdK`UlD!LJ`ou`H z*<8S!l*EBUyYVku9%vB=lB)@X@iXn8w$_4_#ggy>AiaYZu_QKA8l zziR@*zXpL!Q4Vi+U>vXj$^TmE>c$-2 zq_GzKXvTRoeBc?cvt|^qQD;G&qXmDZW(U^IpEP^yycFuusUaq=F`z^tnhb|M0U{@i zpmY5?%ANSo9PV>G>gk5kDvkJ3Pc4<*!!Svs9z^>VCs0xudF$xw^GZuDD!c|r;2&q2L?%uMK26n`fcwQjNyUKwi#0}}c zjd9ermL$`KXqrmBr=wfXJciw)UM#OxBv)Z0Qb9)}rY5ju2^bS+Ey*_A8RXRO7yp?Xb za376GKc{bPT;RJ#$O}&{LEBEr&_#!}$yXn)z7^#y z^8FmN<2oFgZI*EQtND0geg+MXwn7)Vb!xHeRJy`GlLY>^lZx&-!~5!IgxwNfLg9q@ zG;3f9HG4AzUn+GIjnng(fecX&`m4#mWLQhjPT?f#N5`m&i5oi6TSWc6f|)wr2P(T^ z2c1xUOBcOfK-!niL${CQ0M$Og^aI4NKdiZ%1-OR}`eKd+-`A{91$QFYdg9bEvnHh51 z8_f2)?qK(2#$e;({p9^~V=5Hn%ue^VWt+#xI0&E!({yDa*>J&t$ScRvhGSf><2;Lh zl=R`?sAS~2(i8cbkK-kd32;SC717mJXO9@HgK}9aWXbI>bZ}KPy&7i09+{-g)UH|1 zBy3$nr~jBhUtRLxsJK#9m$l!(j` zii~O0ObVg76jGX}v)8+l5T!y&L=*{;pDB^y+uxsXu5+EU)_ULPxoBOdZIbD>Z1 zIdqsv(Ejns!kvp}(8aeOz+C%_IC1zmOuL~({XWj5(;V)?KU%_N>$9|QTo}||ok$ZW z^rP|!BV2Q<0`*zHhR4NYc}e#G9LsR!f!8MR(ykUByl}*-v-)W#TfnMwvG78JV{4Ll zDMPp=HA-59kETSBV^8PfJF3;B;^PJU?4yLO`B6!FTS@}u>g~qbbuz5!$=&dB<2OjW z(?>ge8sN^{7Z9NMn;jH9VypdIaKMgiaxyv$_UfC_3;#~h?a~HyCuhEbweT3#&OMEV zrvIRVK8J>*S=hu^r*55zIW;sL!6ox1(w~Z|RPLfXYZDO$jD;OMot=$p4}L&PZQXH# zz5+Jj3+Q!P%jqVAHY}OhLEvT}3AYd>eR zx&pq(;u%5j;AG^s>N9?xX=nSj=@Ih{FU0pl`HYf@1>86xMIDdTf&VNMJot1C+J7+> ziye9iCfcU>;XX@xO!7K*$&1E;RcTatMjzx^&A{ibTw|=HB|!4~T6XuAOfcVm7V8d7 zqDxvN*n*}KJY)J8Y`&MN%jha#W<^NW6=cQJr#vv@@1|8$&7g#+MrKe)i%WF=u@!h$ z&@0H<<$zb|9H%9R#As*!Rcv0A0;+P~;q2=#c-zA(^u=a9VsDj=4a)gG?Ll6OblR0J zG-Yg6j*e&VdCs<^u zp6wL|mHl>f*Vt6ZTDG376{?V7xeBEEbpy6`C?aIP3Ne1gk5IQB#s_tGVs){XJT%XT zXuorSMX%o5I2TJ`Ioon>bKfg+Ty}sM-P;V~Ei=J!)c(quCEFQ-A*8N)E2U(lfY?WGD*4` zh&S+sxps%1^9yFEzVamn#dPu(aY=+ zyuBd`pEy)3_|P26KDhXmIV4g9?}Yip_|s`L?ZXu|*eV`PUgV48tMZxZpd5jScqYPz zw~$B#EhE_7R)>1mB9xGk78J@G}`*Ph4s z=O}_JFAZIuWPt24r6EWz03JM=2JdH@<4mPs{MH76?U#J`r8^Dezt+P7It?#t^CB8O zv*B;^4{ny;F*IvlIvXh=gA>z4Z9TReXP-ULL<>%PAnR8=1pe3_{Kst}<*ctG&mWK3 z9ob>Tr#S+i%9o&&SFefas6PJoBMjy|oq{vRCcrOE6WptiL<}yNvgvNMI5tNKFSz#~ zveeN`pV`uRa(riYWdirPPMvmTXW>bM@!amFX{2(C zKbhKSg}i#au!G?z_&YcsRet&kqK4_@_QpCSmn?(-JK80zTi6OamRbtWnPoGdtjy83 z%pqbH^a{P&Y{L$?2cl_bDN&xEj6B6IqO`|85SF;j=G6`v+@Yod)2+6Ub3fFXIKy1@ z%5)l*4{E`kGds8~3zE?Rzjusf(G@QES1dnAZp3vGvfQ^br%0a1PQ*U2<02ZQ;i}ht z(7E*;ZBs2Er;eQCE;*b)qszi^z%~xb_|C~CCR&MDMZ)dAbF*~5LG|S z;|#|ol3lOGNuXaGENIN;r0aChEZ0uru}TN>@?IgP$r-gxRL0)76tT-C6$rb!i21$M zn5-)Qg4SPo#Fd+$fu=AiCh#MJo7pnZnl^&-txVy-B^ikN?2NN#j)UnP+ezZVyUg#4 z_t8wjMHC+JiR>#}!m5pKCXZ52K=Q#6h*Lj{T}rIrMb~w_QBXuK-%LVhTR)NAb|aa>q=G8C7xt#WNqk!8DP* zsXUfl^1y>!v?~BS;W}A*_be*RY$4Ot;)&sr0?Ih&KuMzn9yg^8{F`UcvGc~$om;Pi z|NL6$u{MRJic)Zr03=9{kPH81ke9iKvE5WvD46(zSX~>-He5HvNncOG(~tZ)?X8Z@ z)kJKCzgxNePnY8LZ%^Zth;2|>=?8Na&cLE5S7w=223$Ry!?~K(LE3o)6XqquCz}?q z>1l^?TisE6mKXVaIRfHmt1=7R2y$MS1)-rT=;o<9u<^^{&+u6!v1L5dc`=5xehQ^0 zj>m!6;uSR8*qBBU4j%9lW=Z!nRDHIYZhV$WEmCd~_Wf~i-nEXr8dp!{r@Th@@3=v- zVK9X2^F4>8Uuf;ZUN}><9Ee^86SMg^1Z`bT-VvmMJ(&F}#Id$}VcNC%$PDMfBMWc(_F6xg zS`de{JzLrPx~I{d83}mrxioYoaXyK-oq#W?|0Rj%b--TkB;B)u;5w%s?33C}e5^v@ z*@l<)4eyGLF?~3{C)Bc2ANjlQJDc) zv8937)QQ=)r<&6FMt0OX%ATxuTaM?Ad?e4x)!^i(6r{PQn7T535V`pdo}YvHJBT99 z*`I(9&UXU^Q-6pkPsV>YrP6ae{B?$E8qO$>g%dpo*@%Uu@WmyW>@J;P8*2I)>fGjo z`^5~bSE)ts{j|32@4F%}FT8@iuO)CDEABy2@ExpoMnIPsp2quZ?i0#A!TVo?k+idb z*LFx?OV2xa_SP)YC326B?dZY5XAeWs@otz^tb{jp4MP8;SL9>mIGT!#={M!s6b{>Q z#+9aYPVZSdamF)9XY#1>iQ{xa^<3S^K@?t zGqlT*OVGO`cpJQlxeA+jsVBp1N_@(wIW7_Ib~?*d*eqc*Pfq4@H=dlG?rEh6*#@b4nlYaS{u~VJzgMkQ4UA)jowextf1FCr(1A*e$|l>!-qEjVh+; z-~*d$1M*zbb1k9~`9=8KWs<B+t!=R-`S1Kt}YF{Uh_ECj*LQ?hYhg*3w>;p6akuGfs3vw!Q?Lv zeD=qYgxRH&>y6q1>4R!$*xQ#RF?ndln;B3b8^qMCmxO=c#PFej59EH~EtK5b0NYk> zfW5&4Cr!8q8`&A$y8mv}hRost|2HDYw=?e$ww((je`W$B;J@34-8_u12fBF}v83%1 zm|1BGpZFi$!#l$y)m@bQ=vQX$U;f8kvTj177aI9YaSzk1kxS$s91^^E$IB!ZY(a}f zXFzyDBf4upfu3640SiuFK_69PYR$NIu~_q z*1%GXJ1F~4#Ar?|m|01YU(dBk{r82~CvFkG8k@?khT*?`IHc^aDJE@O7<~uRYcO0>LbU58N#sNFbU5t<4)WDwx z=d(#+hj4Qq!C(12`Pp|h(65n5t{gcBqyL4_C@U2_&u2WlaH=UQzuJ+#DYFMot;(mq z9x3!150TB^?1qclDNYiZ&ua8s!XnKi_-Un&Dp&j@(-dMqzVK1^167J%;5 z7JM)E4tZymjN113La_Nsgoh@?#8Cg%JML)IBw21Mv)W4Dh z#sXaso(TD}B6aIOY10i)x4`7@wlHUFDxUxGB@Y3-O}GE>My|aXG&hcee!&wsp(z4u zZaML9A~hPSyN1@U>m}t!66k4pU9b{A0mXk$(J2|tkmaKRZ4J4sh0l5Ln%&8I1}$d= z+uotOB6idwB!lc(PH-Wmqf3Yeq&aV8Jw?f0CU3o8k0LKgKV2T#B}`Ggy!w!#S7(G=tJ%a zBIzTA)=5m@e5XCctdatamnZ^mS1;P1HXeUnwg=prQ;2f)eDXSHEdFegNhYqB#p#~e zVEW}4T6XFy+EBss5j@24&Cz%)W_gF$6bE6SNBY?7bQ89c!@Bjb^A`{27P}6a=en8A znzbZRUj?2oHNc-ovIP|fw&6)853u7%1WNiP1_i%4a^jH=>`H%vCAL&^KB>V-m@uDI zc}~W0Rv*!ew>-eS#S46{S)opgmH2amB)*im18-`bf_MDQBl~B%;JIFl>HDXlSYIli z4bQCPNX{30to}Zj9TdTzz0Hu-@DOQo2_(g&7MjzyG*zRV$^{5?=yd4G48zUk6pa+DNgh78Pi~gMN0SA*w z5Ep)wh;2TO&8j>AciB;tGzr844>zD>=0fVR+biGLp=Qpy9l9 zP;2~m;b?<6v0o6$xVL zc)=T0T)FxMj*7P99z@HMIOlDoZfh6%FSwWu`7XuoPk)WHYmW&3I}inTl@idkf@-os zUJZ?HyhtkCC{_@E2@m6*p_u8$K*-zwB zlCev654z(nf-piaNRzR^`$KbMZ639qe!t2*V==jta+Oehv8Q=_JRf{2Y`B9Kn*TXQT zlhK{gh}*jM5uIc9ID20R;neLR?3M}4=UFj{uH9&8Y&?9UyU4#94Rlo?ih37ahcyeW zu%gs7lE9utK97HZ$IUV9$(CT@uC63_vurD~_lyd=ul5r7Zu>)&nK9V+5fLtSWXa>H zF~s$W2QG4&k8l4tMNAq6>}Mrjme|Tm8P`{EMtc-UgNF=Ec;bvr|1Bb=cQMJ33L-mf zuA#eS(L~Vx2&GFzg5KTDSmwxiMnC*>?chEwH2%FLbv`l+f>Qm7K|==azgN%m0;UW5 zw%mr;>t{&W(+rTUIZb{$rNWNurKs0r0ttyd2d{4g(D!Kp%)K%#^7mCL@;Y!4sOAWB z_R?3>^MU7^oqh!~T)O~$GyswNlK4?#Dr>1715*51C&iPSSJcSM%Sw1}{v=W+tcB9A3gnWb z0aEsh!f?J;sGmxc5{qv+Fut?+bh44y`m zf!v*pwu@z!5;NeHB?TGJ1K?|OJoDjh8`*L59tqLr=fnPI$)(n7 zX!?vGMqkzr){b8U7bUESL5DW`B2o++9Pj2#)-;1g`wo1<0Z19lJCoeyRuJtLg`){9slzr9Y!59rF{O2h;lD?$32EYg41kL>?f#`QXh()aUh zvFG6_bf}_(Twfl5H(b;}8Y`zFt@)yyMZ#0^jOKyVH=dQKl1iN27eMKUi?BrDGn%_Z zoBAw@!vhjJ$aUd$boatS`dcgso?4m6m9SC^LEQl>hyV{Gnu zNx(s~7+lmJ3b%7|aLnv{)V3)APioc0JKpbMmG;}yrJrx&u#OTalgkITM1nlT5qNI2 zqV31o6q#%y?+0K4bPNs_VkGAlDv1TFqO5xbbn z)1z^P_^Q4W`-RWARw`DJN@_7!g@`d59JH34C~_}PO5jTfVTXF6b=WhVuStOMlz zyFoN64p5T?TBQ1m466Oo!o}?$kN!@NwD~5=%XIA0@Sc1REM;_?R3+$Pp?Vp&@ilA77|{^qRW4j0rRlo`x{fp)3@4$ zI1iF%0ljEh)v#cKnsVKhi3ND0(rg6VX2PL0pM+ypyho0CSJ064c|7+A4;>zsre{^| z5v>XdIP>Hnc*oyH3mxY}e8POBcI5~WaPh=7CIF?(kb{ni7vM@FFIU=<1qr%5L_c?w zYkTm7Y&KrVo$%Je#ZzP9NZU?y*2@hdW~ZT5J=)MV?tZY&Ts}(Ppzvhd9th)u#Yp2?R-AcA-!A0;lzKKL~Oke=l!{F&m zSTFmR#QvNJRjoxNbY(eCXck3%HOFz#9u?}goMo4WX)+vo&>yZ)+JYeKSz^l-BHW45VR)v3c7UP3Wa$F61-TMMD0w( zzU$ry|GB$>{ZK!5l8IuFTPxdpIgUG@g76W$*%%vt77kkok>B(_^8ML+GFlr%bC398 zhkY-}u+?MqbbUIRdrg`wCs%8C=pCV==~dj(k7IDo8w%`@BO2D%6dt}D!gm()AgDT+ zRLX`R!?6{}UELYquGFK7U$x29?`qU*=3LS~don~EtgeaJIu@7WR9LL1LM4oc;Ph=- z*fr%0;xZ$_UPlVAJz0-u8T>`5AF80mT^8zds$rK~2k|LMfZQKlFCzH@u< zCAsRc75m;=2kOqlB)Ik{_%L4x2jO_KU@?AlYbViqEDLuhy|ZZumj#EkOI&z*J^CCu z4c)YT0t&k%@SIQ95H)`qh*!D;lkN`r2l!4>+(Z&{dn?o0uo6#Ms6}LJw(y0CG~{)a zLo&|Ckt3bUPT%%`%$zMsYdp^o?JtzDIqj@{i3`d6Iu8H1^P3Cr5pr!uuaOgn4eI{f zTn7Hu^7wwjdE)P=07<3Y@N=Y}vq}9;@^|{vD@LlYt~-N^^WghmmP8eon!&kbfBxd21V-NQN0{%QU)t z)&P-Nbb>Ao>gB3!BLpEbdi2$$5p?t5MZBR+mwCCb4gMLYAaS8R++V(oluXlr(q;z; zDKfIz(_1Li@Rqf0ukwSF@juy3UEb_yjW^*BEx^T3IVqWOcI@>%&>SrV^61Sc6_CeDC7AzaB)K`wynl&X9k@X)&g^H9;GSeIncUZqdto8_Slt6Vw2RVjBENZ_)om>Ot&6>@c8)vrOA8zLJjUXy42YEN zS0rW80x7@JxOI~;!s8yG=y&g7lNryQy;=jy&A%h}@#9hSvm~1Irkty1M$xS={CjnL z7Hn~DvIl8Hb;LE#aQ-zRg@WY{!h+3z^B8_V5^G1?&lWD~sTPm3L zxsT8XFA=J>?>Ibs=s+?z8Pc^$gCug22Ke8SVb?TX!W&N?gTsc?SXmQZ>U;VopOsh& zk+HAQOLl-JT3gYNIT5(db0@j4o;mto}HTDwOaI_FuS2Hm7nM1`dEF#Y9GEr8+Ui!@B z4!WQAiDVXefiJm9O_ychRV)h|&c(CFzpSZexf;Ed*+x-O58k!inPxl>huwu&>9_b4 z`f*|o#;bRLy{8%0_)|_>qGV~$y%J8hJqL`wXtHy?#Oh{Qc9EuRFScN4KDJzP76v;% z^4wY%dUuH2s`z99N9E!p(^&Wt#u`ZUGeus&U*uXxS zcMp4y*@|Bkii7_;H?(Q74(dKBO-+smK+EVbnLWiA=KpBIAEWxo+g(%X6kd?yzAzgW zU0Mx)Tu$I4JSSrJvV4$S;)~05-9RE_5C+1f)`O`J4ClFq#U5zF>?l0JS8mn`uV&ySHJdwzJK^La67rGGen zGs!DL*9Wr)$Ea#HEn6-*&M^gV)@b{kwT>O(W%)^)t z*ca#tnQb%a$4w7FeCJ)R%z7#ePt`-cd)CyE02h=w)d=a$x&)!(i=p&wA>D9fDn1&l z%blAlO>V3lPwj5ykhL48z>bIKYVS5Zhqdc?>#8~no%PwIOJ$;M@y6ZAJmyq@U)FtZ)llgVzGw3=ieoXDi=wve^|*5N|GA<&u3 zr^^4$pnD}Afo%6Ww$}RuiuSanb81DP*?&LXx>yu1V_$&5JY8xzc#15l?}wm)5TbRc z4KDH`q|Stu5L{x1MjlH_dbx_eNq>V5&M7^ zyt9XillcF}Ut^#;MUT4O`HfZ|D@T65^J%VN6#2pqTm&~ToSwmsXo%7-gH|y6tw2+w zRUq-aHrAf+f-^1ov#h<2oxyjveFpTfF~3il^G+Mv$Mpi?IT%Y%n6RTJF=UUY1}y#F*6`an+#1r&uS6`47P*4@lhiU1Qu#?+g zV7Z}v?6|OQK}PHn)b}O;v%e+7$2@jUtQSO zx`;l0?14lMc+qaZG%}=iGn9!L%hFY_yUFy?VifxL8)ekf{!+X&=Jf8H)JCg>tmn z;6I|(Xaa`gtMKR1D1;ks0B>apiZuurfLL@R^=Yg%*u%4ls zTLY2*w^G#989_Gk3=Q|Ik8s(lE}HhQ5Uxo|(Y?7ItjB6?*7=ASYghUYuNY8c4W;Ao zwR7qCvC%h3?i!^g-R)TMa1HdV;rpU|R(wnRHrS?6M4xRh#C!FX+5Pd4i2YrTT+w_; z4!qHZ80>`f_6=M8u3|gI8_mOv)zH@1c8b0#Y5Q z({&Ny3ide}r1iA0{Q{d}HUK&^_tN@D<}7t}XIHno+V<|f18Yu5pnR)beBiG(yH;BU zX}vnj%hXP@wbS!h*?SoIcAI1I3FWw2RKOjXybq6LNMR`-I~*4o4FUOijaTva?enoR|L!g_-wQ!Ia>=JB?}?#hJ|6nez-V~8 zAo-SF=9by+Y6+RC_@LNba%)K&PWyu~s!_!Urg`E+>h55$@f<3hpo$0ELh*}zb1=XS z?z3w+xt8CC6!6QsOQV#_PW;|)K(@l3xma_{tG z!K<*H%t-J(^saY2L?#cAMO6mq#&Q|ZOX2ytac^P6a4E8mUW}}~jFGj(82mtr#T$l< zFr!n5cbGK6_gk+?j=vJq)%zM*wl`xX2TL3{EQeo-Ey22}^J*`&ufRXH^Le`M1u!o- zmW!!z!M;gF=u^ThJQS)+6xJR>$%ffzY?C3Z^2rB5fB?M~44@YIGVFHhHw4W*g+Hk@ z^7#}8cq4s@tK@r2PFm&2eo%q@F7?Cg`je=Bj5u|z3dLS)m6)OPgN#)D1)=QDmz;WG z8<)K+rZ#wWHYZ^;#GF|2+r~HGANOycH+LY8+BD2bV`64bXEv=Of^0bvqWk_Z=Nn~C zwt4Xx3BwYh%c?-mCf^0QNHlQ;D+{;}%lYnBNC{Ij+9#-T_{Nm{c+Q!nX)`~%7%uR* z0})AnEO@`ym#iD;L<=WfWt@KH*tooPMSpfm6Pvv2jCcPurs4cvp{xG{;S1Fj#8@$a z$SqmMTnlWi?fzjXSadClW4FqX@q40~^Isg8;Nz=Flf62zi$kQ*?XEyi`ibC0;CJp> z%0|KUy|Zi25Itu4jtktY=~|eH9<@oit&7~1zjCurO%kjx$*9TOdWJjK(}`YhpNM8} zok}DeFEghXM>E;h^OIidwx;fLx7!bT> z4AOXao4YM~gPFN*D^q;*1h+lMk*SEt7jlzxnB2)?q|SXNnZJHmaC%*z&Gs2x9M`ET zl-j1rr1xbokDSy<6aN@nX)wZx$33#9OpY#gM42) z#*Hx4cCkKn8|UclovKNNo5hnphiUaLBF3kk55u}G>8f`Y^w!NiwuQ>1)a=6-Als0%*~AEbQy9w%o=q}tzj0` zA7YM4sF23`6lThb)S5!U^IDbEFeGm@L1?crYSVOa9N)d~6j<)2-0YSzu6|n~H|Mhk zQt9*(pwj1D>pmUcFd@%%H3u`ci}nfj4~N*Od`}XbdT+rrWv@Zw$KDf!wqmp-REf#z z4&d&dHs{u-`7z8M8Kkh`3}a^`X|v{}G^+pSg!Wvk<&qY;FrI}68Qs^qoF1dd$WE+c zRt$$Q<<;wiiZf3!6O{6+-(N@EJo$Kmdr~Dg=XP(+y@OuNrwK=EW!;Jd2Y6S5%F&rz zgvLJc%QEpx zC6V;|ox&XljET$2D(k%CMV!*07*lqvPq@4`UhwVn58<-d7B1$`I-3>z9%b6>-?gf0 zcWXZ$6bQ51jmVZgO@g80+MLy^-AqT8BV+U76thxGhH>n1;VOq?nI?w|HW}w7IOdWA zx-+Lk=(9mlcrQhPsSI@!EaDlA{TZpu$B&jAyCs6Dj{>eU@ggjh3}s%%J|i7w^`!lW zkULyjzzA2_a}RDNGNq%>m~_`0!dXAGAWv3}eD8B068Yn;%T|?ex4&sIt1hZgt79rO z{>C8ue72bO%?V{IKg+X+?_GcmQk~@Qk@w&^M+MUi6_DJ1kX!8S0f8n@(UP2F=+*$w zUWDSl}e682*BatTQ1;LjmlAGH`y|ci5pG%QU!*gU%aMaFeMUetKac z_hLpp*?*DGw_4=lL&Ifg**+&K%JXD9`d8!Dq4~)ER2H<3y^Vi8kAtqorC{0clQA?u zMs|8%qk#*`1Xy2Ot#!?)_0V&4zwbhrT5>6;+2J;s#VqYN@$1L$*74HS(WV?#Q9 zNbUtSx|3(gejW5d4=QHZ{+QH`rySf0TbXxQKKC46zk^V(6?b9${aLtv&H+&KE8`-% zH9+K5JYKOX1|CJ+#*!^5P-3x!O3kUn>x5P0yh#yBpSGCu3+2e~VhhaW=z>W09O$pF zfX0|WP-@D-j}-Uv%#W97=CMbRnA|uF4s}OEA1rYspYpG^N407_{0+VL$hovPa;7jg)sN`pv36;s{ zM14G4(Y2G^f0JkW`Vd^dHxuh`AXsd76r4WrfSfA2$F|EKU}tBuOy!|x_^VdZSr>ZdH7x{F~$?M}mv1v6>w(IxE5<6-F1$1hMaVFH_Q z^dudBKZ1>}Jw!TtgK6@PtJu4xm(0jYV-L)>CSm5svD%_WRBo+EOSdALw*D{EXD$h? z`WUxe%4M{_4IqDUdEC8GgX)QG!6S+uAS{_q#oTW~Vplb;+DG8!x68r_dGxtT0}f0*LpQ&ap&JuDa7yAJ)!bmf zvY+Qtt8FE0c3l*^@6%?sJ}idyh;>5?c^+l^(-3ysT}Afun0C%v{0VrU%izVp^DI6fA-odkTz!#k!`Fn`6$Q0723W{-%_S(hFWk9`5iw?YPAPDv)B z{+r31o(Q}|#~UI~A7&Olk%2P3f86x5e#}?PkHYQO)Ntoc6WEk!&d%5UNa9X9z^+YU z#JesO`;=`3&oR7rF76!nL0^w}C-n-vQfrA(sua8s-voR5CPV5&MY8O|azR7MAPJuK zS9opJMA-E;x>lO+YJ3qpiXQVbJmnE<+&Vp&WM+gzM?)SdnIA#2?j@3wlT?ZBoE5M; z*_S+ViR0F8^uY7gF9W<;1Sd+2L6+aggf)ahtYRheeg6e+O-v$@35p}S$x&$epKr|i zcMO_-H;)qrlpt51YV?=8f=x&65+}z7H2Pqed~}^fG_4%?yiPpMR9J_;KNexV^TUYv zXKCzp^gD91Am~FJFDmc3PE<0}u+0J=fpK~^6De(gi+-QRM~j=tlpANccUg-#@nw?* z;*zQmESbX@8J9wS%tgmzE1Eowbv%aa2$G1cMDfe%wr67 z^O?lQcLmMo)*;2|0#4m<7I*Yk81t~om$P0JVY92{p`iO(hhXP5M@FVqjSEhm$t?I6 z$Z;i|T+n+HCUZ+R_nqd~j66OiJl;PI&3N=v==Ca?dw%_0O}Cmezt1nVnOGge#2skn z<_~&sI$e3f2>yPs*z!D6TX#b+q!hz_T3SGSn-tNW*f37caw&@bxl;J}S2`E>{2|k& zcTjM1!W6-exk;RO>`x$>yZg2v}RYX?jnn3enIp$`c^xv=BvoO|SC=85G) zp|Dz<+5cA^UH-kJHlnhCnVUD6IgszijqdCbDjbVq7DlNu_n0td{UK4o#1q#!znm{Z z+1rs!fov)hvdfM;Wo$`2{-kktz52MTuM?Qbg@h5kxKA)>cZ<2a&YpXm+|M}`dT_aq zH5h}m^~~`4W1O0~45z);hPZtSC1V@ofdLkH41FHt z-)W?Iy7_HqX59pUQ5RB2aR-44fm*lc~$r;A3yS*ym4VSdmGWP!@fNAKVyaZW{a{vwz)( z!&SWG*Zmp9D>q^d8Aqo3s|=1GQ%PFhs=%dAFYy1D30-gcP&?06Tef`y4NqGOCzq{5 z<*lMnb1@yC-P7dws488xg6;h#BsJ1=(VZ&9inKAj8tVD;sG&^sp9+?O5}m z1=)S&J(r-?jfT&g!DcIe;&HSTjQU4*AT_MtN}GQf8;AyrRHpmRVA zlF@z=Xe3D*GtFQyR*YS|BOm!3KL>XAGRgbjA&|Iy6_GnCLhqKRk)!8=P-~$*Fh`B? z@D&S?al1(BuSbJXQ88Q9GY|Uoqrl7YIm#J|#X-wovZDq&uw2k=tT+&fziPiAG%S}? z3(BeQ=k2iDyA9@rAH(9CBH<=X;v}-8N#AutEb>K;N|pQvd*xpcRX;6^etJWvuQqt5 zXLBR9=aGliVk|4sL~iu2h8G6w(45i&L^g-gnciVcpu99Ky?zwrtH#jg+iO7ICKVh% zE}(auoL;eo^L`Aw4+{>>w$REQIEdTZaFcDiI5{~PqR`FrCd_$e z;vYR?C{7JOIyjd=8<_ttjZnCZ=MEj_^31M7ku++1H~Iu($0NS7{hu z>-N5mRQU z!#^k8t@*TLI@kaC4rmuB5G^|iD@8^=IZ4~7qN>7S6 zAZgQh)LHt6i*XGhKiXx9#=BVT;$6kH^pBF>CE}2kmIkte!8ph549ZIwgP)`cnbOE8 zd;m!ZTq?FepXCy~dfFwTYM_T!1->9NCQJgqO&$Q}c}`r?DsXGqNzVMQt1AzuYJ2~O z$gHk}NJ6B+kQ+IB@3qe{g`z0UgA^IlAl(MJ%9JRnL@p&`D3bAD z!>-bxx49fl#9NVAAfX%-6+q#s6d>%>p@$}MSWk5YH8OnyG6+`#-#cuflqzpcH;5 zQ*K3Jr3#CLMUS+yq2R3-QtL8DCoWz^$=~`Yrr8lZ=5o6BZ*r+I+i7SWhfnf+TcAcb z0zGm|LGy>(@YN#`Wm=Sk(xqEquAaiu)p{%6+Aj^377vSRvtR znJj?vNB|hJNg|s{UBMJu6L5muj5`hjE)FDpK0}9IrMH^4NI#EW^-ZO3J#(aWd)iRc zhbQ3ryCACc&=YaLKBu!{p$d$)NFlG!EpYwQa%zV)pvQe#3S8BSVAPEge0;`p^f5II zoYP+Jx-Aa_2f}BJI#Q4 zXv#;2YGvqbZ3VPOO&gF3L#Sw)ggVm|M{#%yip}%~H|(2`&YD8l$?+|+XmcQrxwTpE0tbO1%wYXA)$C$KO6JhJ{WOc=KpQSSSnGN;ewYXB@AEfE;89W1BWXuhkxvkMvgCziZ**Y zA|1ma@>T5~a9U3pt=anqmF1LxxuRFNH$F&2d7h_qgt{m>@*+4l_Z^Jb&8MA-a=83O z9__d|79Q(;fVR%9g`Z+#(YoE*p#94RynUe&+MP5@(9PALc@`grs*xWkH;+lQT8y;3 zP%TorW{DcRJ>|YQl+|Xl`V!Dv>Tj$oR$w=Vq+*kzO~jyRBVK=J6Oy?zglrYk@%4;8 z{Ao)nacyQ0#v{G>NyP|U>Ziq8XX>z4yCSe;B4FRSCQ^G(^`U1{@_60gA!K+{2UrzO zLCLvGkV@nLKHaauvX&iqz^N1^^q<2^dE;4=i=}9IbpkHAG=K?nS-ePU5dU)Z9`fSq zdz!aNvtWuPd%skLy}t4zc03}-I^4^{$=2?y)j1`0%<32l7<0sRV})o=vK6qrb{S1> zo5j3?%!(1IsJx%&>-(NxpWu6uV^;El-`=DVxqBli@r*t|?o7if3Sv|^ z=Qss3#55r}3UNuJ&61_7$QCoM%ZpqhV{_0Dm%o2aoxUtbMNQa>U_mKp8Tktoq!*z@ z#<$@d?^9s?V-YCong&X99>ND(s?dw@WODvrWn$?Y0@210UlctogEe2f1Lgitd?WeK z6waH2{jZCVNG%5{D{Y{L)wtehC1J?Gsgi8vYBa~Dxr6SYvp_bM;|~Xn$G1&IHrkuF zVL{SWLQifVb9YFGwo~m!Ej_`+>9i6eH`xj;>^2kMTXdK2H;%%C8T(1oNngRtCBx*W zq?qJ+|!`X$L02 zUGLX|n?^L5)=@5Qt&t~0-2dBiI2V-vafuo+dty^n+sBC;8PIvw_R#ZgI{Ev-W8{skw?2+e z_<56~XhUPXClTS9Im*NMzls3h!cxR za%jdy2Ae)b#+eKiIWLF&HNKSD)LRQ2XN1$2o~)|{GPZH}S|?2w)H;)SJKgCHzY}Csh=_Soynr~O zZbG~4nT135tYbcz~U6FrnNWNv=?LQZaXM!p4**p=D_i(5y< z1|h4_0qtfq7V)ThZPi@h)8K?xzLzC0G|4dgWVPw)4G|#V`f)gSoi3x#M4i^z$H>7}%sWw=?C6P*ca2Gz|5#&SiFlE9Y1lC=Lhzgq< zWCVwWreF9jcIjLW>%Kgu8bn(`OJj_9d3q@^OUI5TH;Ki8Q3u4iEBw*a0X=FBSC{v| zd@+n}-%d2Q`ZBWS{)AcjIgze!7s2kBM7pVufxFK)fZwyufi^0ZQceVnx6&anpkK-l zzi%h5{xXik!TsSfVIt^kYaqK0I5OUxKvt(wCF&M>prw`l@Nj&K=!Py&yXDtWu)Ui(XMu(8Dvx*V$LW%{=Jr{spfQ4{$!ZSgW zrYtMhX-a>q_ZChMSSUI2g}@Gwj*b}#F@DuD44JsXRg!{evJP{|KSgR$9y!zOI@odE1yMjEnV> zWI3K-zw}-g7T&a#^ewTHbhVDKxr%YDX8CK@Pho)jPK_nOUhWe8gfc;Y-5k2doM*fI zyDq(9mKoGNzK^{+RUo+_suIl7N<){7PO|2mC#bLE-m)ca=Y=y~Jr%0@oM6?a%gd=v z9aHc_+dIE81@jb{zxp#d`L*YyiN;3IHYGslzF11y^q+N?TYB|*o~7S<1G%Fgn=)@I zH~!mvg14A$^WE+3&N^L?|<9>M%C3TkC2TW&-=OkSJW%qZQHi{_y+$7 g_hb5p{r~>r&ods+eX;D%32B}*FOR!6@YC=A09?4#^8f$< diff --git a/requirements_openpilot.txt b/requirements_openpilot.txt index ec525a07e..880073ee7 100644 --- a/requirements_openpilot.txt +++ b/requirements_openpilot.txt @@ -23,7 +23,7 @@ enum34==1.1.6 evdev==0.6.1 fastcluster==1.1.20 filterpy==1.2.4 -hexdump +hexdump==3.3 ipaddress==1.0.16 json-rpc==1.12.1 libusb1==1.5.0 @@ -33,6 +33,7 @@ nose==1.3.7 numpy==1.11.1 opencv-python==3.4.0.12 pause==0.1.2 +psutil==3.4.2 py==1.4.31 pyOpenSSL==16.0.0 pyasn1-modules==0.0.8 diff --git a/selfdrive/boardd/boardd.py b/selfdrive/boardd/boardd.py index fb045bb3a..686338685 100755 --- a/selfdrive/boardd/boardd.py +++ b/selfdrive/boardd/boardd.py @@ -220,7 +220,7 @@ def boardd_proxy_loop(rate=200, address="192.168.2.251"): # recv @ 100hz can_msgs = can_recv() #for m in can_msgs: - # print "R:",hex(m[0]), str(m[2]).encode("hex") + # print("R: {0} {1}".format(hex(m[0]), str(m[2]).encode("hex"))) # publish to logger # TODO: refactor for speed @@ -233,7 +233,7 @@ def boardd_proxy_loop(rate=200, address="192.168.2.251"): if tsc is not None: cl = can_capnp_to_can_list(tsc.can) #for m in cl: - # print "S:",hex(m[0]), str(m[2]).encode("hex") + # print("S: {0} {1}".format(hex(m[0]), str(m[2]).encode("hex"))) can_send_many(cl) rk.keep_time() diff --git a/selfdrive/can/Makefile b/selfdrive/can/Makefile index b140aa5f8..1909a7bb9 100644 --- a/selfdrive/can/Makefile +++ b/selfdrive/can/Makefile @@ -16,6 +16,7 @@ WARN_FLAGS = -Werror=implicit-function-declaration \ CFLAGS = -std=gnu11 -g -fPIC -O2 $(WARN_FLAGS) CXXFLAGS = -std=c++11 -g -fPIC -O2 $(WARN_FLAGS) +LDFLAGS = ifeq ($(UNAME_S),Darwin) ZMQ_LIBS = -L/usr/local/lib -lzmq @@ -28,18 +29,24 @@ else ifeq ($(UNAME_M),x86_64) else ifeq ($(UNAME_M),aarch64) ZMQ_FLAGS = -I$(PHONELIBS)/zmq/aarch64/include ZMQ_LIBS = -L$(PHONELIBS)/zmq/aarch64/lib -l:libzmq.a - CXXFLAGS += -lgnustl_shared + LDFLAGS += -lgnustl_shared endif +OBJDIR = obj + OPENDBC_PATH := $(shell python -c 'import opendbc; print opendbc.DBC_PATH') DBC_SOURCES := $(wildcard $(OPENDBC_PATH)/*.dbc) +DBC_OBJS := $(patsubst $(OPENDBC_PATH)/%.dbc,$(OBJDIR)/%.o,$(DBC_SOURCES)) DBC_CCS := $(patsubst $(OPENDBC_PATH)/%.dbc,dbc_out/%.cc,$(DBC_SOURCES)) +.SECONDARY: $(DBC_CCS) + +LIBDBC_OBJS := $(OBJDIR)/dbc.o $(OBJDIR)/parser.o $(OBJDIR)/packer.o CWD := $(shell pwd) .PHONY: all -all: libdbc.so +all: $(OBJDIR) libdbc.so include ../common/cereal.mk @@ -49,22 +56,45 @@ libdbc.so:: ../../cereal/gen/cpp/log.capnp.h ../../cereal/gen/cpp/log.capnp.h: cd ../../cereal && make -libdbc.so:: dbc.cc parser.cc packer.cc $(DBC_CCS) +libdbc.so:: $(LIBDBC_OBJS) $(DBC_OBJS) + @echo "[ LINK ] $@" $(CXX) -fPIC -shared -o '$@' $^ \ - -I. \ - -I../.. \ - $(CXXFLAGS) \ - $(ZMQ_FLAGS) \ - $(ZMQ_LIBS) \ - $(CEREAL_CXXFLAGS) \ - $(CEREAL_LIBS) + -I. -I../.. \ + $(CXXFLAGS) \ + $(LDFLAGS) \ + $(ZMQ_FLAGS) \ + $(ZMQ_LIBS) \ + $(CEREAL_CXXFLAGS) \ + $(CEREAL_LIBS) -dbc_out/%.cc: $(OPENDBC_PATH)/%.dbc process_dbc.py dbc_template.cc - PYTHONPATH=$(PYTHONPATH):$(CWD)/../../pyextra ./process_dbc.py '$<' '$@' +$(OBJDIR)/%.o: %.cc + @echo "[ CXX ] $@" + $(CXX) -fPIC -c -o '$@' $^ \ + -I. -I../.. \ + $(CXXFLAGS) \ + $(ZMQ_FLAGS) \ + $(CEREAL_CXXFLAGS) \ -.PHONY: clean +$(OBJDIR)/%.o: dbc_out/%.cc + @echo "[ CXX ] $@" + $(CXX) -fPIC -c -o '$@' $^ \ + -I. -I../.. \ + $(CXXFLAGS) \ + $(ZMQ_FLAGS) \ + $(CEREAL_CXXFLAGS) \ + +dbc_out/%.cc: process_dbc.py dbc_template.cc $(OPENDBC_PATH)/%.dbc + @echo "[ DBC GEN ] $@" + @echo "Missing prereq $?" + PYTHONPATH=$(PYTHONPATH):$(CWD)/../../pyextra ./process_dbc.py $(OPENDBC_PATH) dbc_out + +$(OBJDIR): + mkdir -p $@ + +.PHONY: clean $(OBJDIR) clean: rm -rf libdbc.so* rm -f dbc_out/*.cc rm -f dbcs.txt rm -f dbcs.csv + rm -rf $(OBJDIR)/* diff --git a/selfdrive/can/packer.py b/selfdrive/can/packer.py index cc669e60c..0c17c2e4d 100644 --- a/selfdrive/can/packer.py +++ b/selfdrive/can/packer.py @@ -63,5 +63,5 @@ if __name__ == "__main__": #s = cp.pack_bytes(0xe4, { # "STEER_TORQUE": -2, #}) - print [hex(ord(v)) for v in s[1]] + print([hex(ord(v)) for v in s[1]]) print(s[1].encode("hex")) diff --git a/selfdrive/can/parser.py b/selfdrive/can/parser.py index 8960953ed..3b02531f2 100644 --- a/selfdrive/can/parser.py +++ b/selfdrive/can/parser.py @@ -68,7 +68,7 @@ class CANParser(object): value_count = libdbc.can_query(self.can, 0, self.p_can_valid, 0, ffi.NULL) self.can_values = ffi.new("SignalValue[%d]" % value_count) self.update_vl(0) - # print "===" + # print("===") def update_vl(self, sec): @@ -77,12 +77,12 @@ class CANParser(object): self.can_valid = self.p_can_valid[0] - # print can_values_len + # print(can_values_len) ret = set() for i in xrange(can_values_len): cv = self.can_values[i] address = cv.address - # print hex(cv.address), ffi.string(cv.name) + # print("{0} {1}".format(hex(cv.address), ffi.string(cv.name))) name = ffi.string(cv.name) self.vl[address][name] = cv.value self.ts[address][name] = cv.ts @@ -240,11 +240,11 @@ if __name__ == "__main__": cp = CANParser("toyota_rav4_2017_pt_generated", signals, checks, 0) - # print cp.vl + # print(cp.vl) while True: cp.update(int(sec_since_boot()*1e9), True) - # print cp.vl + # print(cp.vl) print(cp.ts) print(cp.can_valid) time.sleep(0.01) diff --git a/selfdrive/can/plant_can_parser.py b/selfdrive/can/plant_can_parser.py index 44939747c..e58906d7a 100644 --- a/selfdrive/can/plant_can_parser.py +++ b/selfdrive/can/plant_can_parser.py @@ -78,7 +78,7 @@ class CANParser(object): msg_vl = fix(ck_portion, msg) # compare recalculated vs received checksum if msg_vl != cdat: - print "CHECKSUM FAIL: " + hex(msg) + print("CHECKSUM FAIL: {0}".format(hex(msg))) self.ck[msg] = False self.ok[msg] = False # counter check @@ -87,13 +87,13 @@ class CANParser(object): cn = out["COUNTER"] # check counter validity if it's a relevant message if cn != ((self.cn[msg] + 1) % 4) and msg in self.msgs_ck and "COUNTER" in out.keys(): - #print hex(msg), "FAILED COUNTER!" + #print("FAILED COUNTER: {0}".format(hex(msg)() self.cn_vl[msg] += 1 # counter check failed else: self.cn_vl[msg] -= 1 # counter check passed # message status is invalid if we received too many wrong counter values if self.cn_vl[msg] >= cn_vl_max: - print "COUNTER WRONG: " + hex(msg) + print("COUNTER WRONG: {0}".format(hex(msg))) self.ok[msg] = False # update msg time stamps and counter value @@ -118,7 +118,7 @@ class CANParser(object): self.can_valid = True if False in self.ok.values(): - #print "CAN INVALID!" + #print("CAN INVALID!") self.can_valid = False return msgs_upd diff --git a/selfdrive/can/process_dbc.py b/selfdrive/can/process_dbc.py index 810947c8e..61cad32bc 100755 --- a/selfdrive/can/process_dbc.py +++ b/selfdrive/can/process_dbc.py @@ -1,5 +1,6 @@ #!/usr/bin/env python import os +import glob import sys import jinja2 @@ -7,62 +8,82 @@ import jinja2 from collections import Counter from common.dbc import dbc -if len(sys.argv) != 3: - print "usage: %s dbc_path struct_path" % (sys.argv[0],) - sys.exit(0) +def main(): + if len(sys.argv) != 3: + print "usage: %s dbc_directory output_directory" % (sys.argv[0],) + sys.exit(0) -dbc_fn = sys.argv[1] -out_fn = sys.argv[2] + dbc_dir = sys.argv[1] + out_dir = sys.argv[2] -template_fn = os.path.join(os.path.dirname(__file__), "dbc_template.cc") + template_fn = os.path.join(os.path.dirname(__file__), "dbc_template.cc") + template_mtime = os.path.getmtime(template_fn) -can_dbc = dbc(dbc_fn) + this_file_mtime = os.path.getmtime(__file__) -with open(template_fn, "r") as template_f: - template = jinja2.Template(template_f.read(), trim_blocks=True, lstrip_blocks=True) + with open(template_fn, "r") as template_f: + template = jinja2.Template(template_f.read(), trim_blocks=True, lstrip_blocks=True) -msgs = [(address, msg_name, msg_size, sorted(msg_sigs, key=lambda s: s.name not in ("COUNTER", "CHECKSUM"))) # process counter and checksums first - for address, ((msg_name, msg_size), msg_sigs) in sorted(can_dbc.msgs.iteritems()) if msg_sigs] + for dbc_path in glob.iglob(os.path.join(dbc_dir, "*.dbc")): + dbc_mtime = os.path.getmtime(dbc_path) + dbc_fn = os.path.split(dbc_path)[1] + dbc_name = os.path.splitext(dbc_fn)[0] + can_dbc = dbc(dbc_path) + out_fn = os.path.join(os.path.dirname(__file__), out_dir, dbc_name + ".cc") + if os.path.exists(out_fn): + out_mtime = os.path.getmtime(out_fn) + else: + out_mtime = 0 -def_vals = {a: set(b) for a,b in can_dbc.def_vals.items()} #remove duplicates -def_vals = [(address, sig) for address, sig in sorted(def_vals.iteritems())] + if dbc_mtime < out_mtime and template_mtime < out_mtime and this_file_mtime < out_mtime: + continue #skip output is newer than template and dbc -if can_dbc.name.startswith("honda") or can_dbc.name.startswith("acura"): - checksum_type = "honda" - checksum_size = 4 -elif can_dbc.name.startswith("toyota") or can_dbc.name.startswith("lexus"): - checksum_type = "toyota" - checksum_size = 8 -else: - checksum_type = None + msgs = [(address, msg_name, msg_size, sorted(msg_sigs, key=lambda s: s.name not in ("COUNTER", "CHECKSUM"))) # process counter and checksums first + for address, ((msg_name, msg_size), msg_sigs) in sorted(can_dbc.msgs.iteritems()) if msg_sigs] -for address, msg_name, msg_size, sigs in msgs: - for sig in sigs: - if checksum_type is not None and sig.name == "CHECKSUM": - if sig.size != checksum_size: - sys.exit("CHECKSUM is not %d bits longs %s" % (checksum_size, msg_name)) - if checksum_type == "honda" and sig.start_bit % 8 != 3: - sys.exit("CHECKSUM starts at wrong bit %s" % msg_name) - if checksum_type == "toyota" and sig.start_bit % 8 != 7: - sys.exit("CHECKSUM starts at wrong bit %s" % msg_name) - if checksum_type == "honda" and sig.name == "COUNTER": - if sig.size != 2: - sys.exit("COUNTER is not 2 bits longs %s" % msg_name) - if sig.start_bit % 8 != 5: - sys.exit("COUNTER starts at wrong bit %s" % msg_name) - if address in [0x200, 0x201]: - if sig.name == "COUNTER_PEDAL" and sig.size != 4: - sys.exit("PEDAL COUNTER is not 4 bits longs %s" % msg_name) - if sig.name == "CHECKSUM_PEDAL" and sig.size != 8: - sys.exit("PEDAL CHECKSUM is not 8 bits longs %s" % msg_name) + def_vals = {a: set(b) for a,b in can_dbc.def_vals.items()} #remove duplicates + def_vals = [(address, sig) for address, sig in sorted(def_vals.iteritems())] -# Fail on duplicate message names -c = Counter([msg_name for address, msg_name, msg_size, sigs in msgs]) -for name, count in c.items(): - if count > 1: - sys.exit("Duplicate message name in DBC file %s" % name) + if can_dbc.name.startswith("honda") or can_dbc.name.startswith("acura"): + checksum_type = "honda" + checksum_size = 4 + elif can_dbc.name.startswith("toyota") or can_dbc.name.startswith("lexus"): + checksum_type = "toyota" + checksum_size = 8 + else: + checksum_type = None -parser_code = template.render(dbc=can_dbc, checksum_type=checksum_type, msgs=msgs, def_vals=def_vals, len=len) + for address, msg_name, msg_size, sigs in msgs: + for sig in sigs: + if checksum_type is not None and sig.name == "CHECKSUM": + if sig.size != checksum_size: + sys.exit("CHECKSUM is not %d bits longs %s" % (checksum_size, msg_name)) + if checksum_type == "honda" and sig.start_bit % 8 != 3: + sys.exit("CHECKSUM starts at wrong bit %s" % msg_name) + if checksum_type == "toyota" and sig.start_bit % 8 != 7: + sys.exit("CHECKSUM starts at wrong bit %s" % msg_name) + if checksum_type == "honda" and sig.name == "COUNTER": + if sig.size != 2: + sys.exit("COUNTER is not 2 bits longs %s" % msg_name) + if sig.start_bit % 8 != 5: + sys.exit("COUNTER starts at wrong bit %s" % msg_name) + if address in [0x200, 0x201]: + if sig.name == "COUNTER_PEDAL" and sig.size != 4: + sys.exit("PEDAL COUNTER is not 4 bits longs %s" % msg_name) + if sig.name == "CHECKSUM_PEDAL" and sig.size != 8: + sys.exit("PEDAL CHECKSUM is not 8 bits longs %s" % msg_name) -with open(out_fn, "w") as out_f: - out_f.write(parser_code) + # Fail on duplicate message names + c = Counter([msg_name for address, msg_name, msg_size, sigs in msgs]) + for name, count in c.items(): + if count > 1: + sys.exit("Duplicate message name in DBC file %s" % name) + + parser_code = template.render(dbc=can_dbc, checksum_type=checksum_type, msgs=msgs, def_vals=def_vals, len=len) + + + with open(out_fn, "w") as out_f: + out_f.write(parser_code) + +if __name__ == '__main__': + main() diff --git a/selfdrive/car/chrysler/chryslercan.py b/selfdrive/car/chrysler/chryslercan.py index d225420af..761b44b15 100644 --- a/selfdrive/car/chrysler/chryslercan.py +++ b/selfdrive/car/chrysler/chryslercan.py @@ -44,12 +44,6 @@ def calc_checksum(data): def make_can_msg(addr, dat): return [addr, 0, dat, 0] -def create_lkas_heartbit(packer, lkas_status_ok): - # LKAS_HEARTBIT 0x2d9 (729) Lane-keeping heartbeat. - values = { - "LKAS_STATUS_OK": lkas_status_ok - } - return packer.make_can_msg("LKAS_HEARTBIT", 0, values) def create_lkas_hud(packer, gear, lkas_active, hud_alert, hud_count, lkas_car_model): # LKAS_HUD 0x2a6 (678) Controls what lane-keeping icon is displayed. diff --git a/selfdrive/car/chrysler/chryslercan_test.py b/selfdrive/car/chrysler/chryslercan_test.py index f3c2a54f0..524a79f7a 100644 --- a/selfdrive/car/chrysler/chryslercan_test.py +++ b/selfdrive/car/chrysler/chryslercan_test.py @@ -14,12 +14,6 @@ class TestChryslerCan(unittest.TestCase): self.assertEqual(0x75, chryslercan.calc_checksum([0x01, 0x20])) self.assertEqual(0xcc, chryslercan.calc_checksum([0x14, 0, 0, 0, 0x20])) - def test_heartbit(self): - packer = CANPacker('chrysler_pacifica_2017_hybrid') - self.assertEqual( - [0x2d9, 0, '0000000820'.decode('hex'), 0], - chryslercan.create_lkas_heartbit(packer, 0x820)) - def test_hud(self): packer = CANPacker('chrysler_pacifica_2017_hybrid') self.assertEqual( diff --git a/selfdrive/car/chrysler/interface.py b/selfdrive/car/chrysler/interface.py index 7e96ebc2b..e0551ef0c 100755 --- a/selfdrive/car/chrysler/interface.py +++ b/selfdrive/car/chrysler/interface.py @@ -122,7 +122,7 @@ class CarInterface(object): ret.brakeMaxV = [1., 0.8] ret.enableCamera = not check_ecu_msgs(fingerprint, ECU.CAM) - print "ECU Camera Simulated: ", ret.enableCamera + print("ECU Camera Simulated: {0}".format(ret.enableCamera)) ret.openpilotLongitudinalControl = False ret.steerLimitAlert = True diff --git a/selfdrive/car/chrysler/radar_interface.py b/selfdrive/car/chrysler/radar_interface.py index 60eaa4566..e5fe7437f 100755 --- a/selfdrive/car/chrysler/radar_interface.py +++ b/selfdrive/car/chrysler/radar_interface.py @@ -104,4 +104,4 @@ if __name__ == "__main__": while 1: ret = RI.update() print(chr(27) + "[2J") # clear screen - print ret + print(ret) diff --git a/selfdrive/car/ford/radar_interface.py b/selfdrive/car/ford/radar_interface.py index 2acea9d70..970b411ff 100755 --- a/selfdrive/car/ford/radar_interface.py +++ b/selfdrive/car/ford/radar_interface.py @@ -90,4 +90,4 @@ if __name__ == "__main__": while 1: ret = RI.update() print(chr(27) + "[2J") - print ret + print(ret) diff --git a/selfdrive/car/gm/radar_interface.py b/selfdrive/car/gm/radar_interface.py index 6af0d3f8f..3d72ff7ab 100755 --- a/selfdrive/car/gm/radar_interface.py +++ b/selfdrive/car/gm/radar_interface.py @@ -124,4 +124,4 @@ if __name__ == "__main__": while 1: ret = RI.update() print(chr(27) + "[2J") - print ret + print(ret) diff --git a/selfdrive/car/honda/carcontroller.py b/selfdrive/car/honda/carcontroller.py index 9325e8964..ea69daba7 100644 --- a/selfdrive/car/honda/carcontroller.py +++ b/selfdrive/car/honda/carcontroller.py @@ -124,7 +124,7 @@ class CarController(object): if CS.CP.radarOffCan: snd_beep = snd_beep if snd_beep != 0 else snd_chime - #print chime, alert_id, hud_alert + #print("{0} {1} {2}".format(chime, alert_id, hud_alert)) fcw_display, steer_required, acc_alert = process_hud_alert(hud_alert) hud = HUDData(int(pcm_accel), int(round(hud_v_cruise)), 1, hud_car, diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py index 4072b0354..6c4b4a767 100755 --- a/selfdrive/car/honda/interface.py +++ b/selfdrive/car/honda/interface.py @@ -196,10 +196,10 @@ class CarInterface(object): tire_stiffness_factor = 1. # Civic at comma has modified steering FW, so different tuning for the Neo in that car is_fw_modified = os.getenv("DONGLE_ID") in ['99c94dc769b5d96e'] - ret.steerKpV, ret.steerKiV = [[0.4], [0.12]] if is_fw_modified else [[0.8], [0.24]] if is_fw_modified: - tire_stiffness_factor = 0.9 ret.steerKf = 0.00004 + + ret.steerKpV, ret.steerKiV = [[0.4], [0.12]] if is_fw_modified else [[0.8], [0.24]] ret.longitudinalKpBP = [0., 5., 35.] ret.longitudinalKpV = [3.6, 2.4, 1.5] ret.longitudinalKiBP = [0., 35.] diff --git a/selfdrive/car/honda/radar_interface.py b/selfdrive/car/honda/radar_interface.py index 7d30265c2..aa963df9a 100755 --- a/selfdrive/car/honda/radar_interface.py +++ b/selfdrive/car/honda/radar_interface.py @@ -101,4 +101,4 @@ if __name__ == "__main__": while 1: ret = RI.update() print(chr(27) + "[2J") - print ret + print(ret) diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index f106ccab3..22fb53d7c 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -121,12 +121,13 @@ FINGERPRINTS = { CAR.PILOT: [{ 57: 3, 145: 8, 228: 5, 229: 4, 308: 5, 316: 8, 334: 8, 339: 7, 342: 6, 344: 8, 379: 8, 380: 8, 392: 6, 399: 7, 419: 8, 420: 8, 422: 8, 425: 8, 426: 8, 427: 3, 432: 7, 463: 8, 464: 8, 476: 4, 490: 8, 506: 8, 507: 1, 512: 6, 513: 6, 538: 3, 542: 7, 545: 5, 546: 3, 597: 8, 660: 8, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 808: 8, 819: 7, 821: 5, 829: 5, 837: 5, 856: 7, 871: 8, 882: 2, 884: 7, 891: 8, 892: 8, 923: 2, 929: 8, 963: 8, 965: 8, 966: 8, 967: 8, 983: 8, 985: 3, 1027: 5, 1029: 8, 1036: 8, 1039: 8, 1064: 7, 1088: 8, 1089: 8, 1108: 8, 1125: 8, 1296: 8, 1424: 5, 1600: 5, 1601: 8, 1612: 5, 1613: 5, 1616: 5, 1618: 5, 1668: 5 }], + # this fingerprint also includes the Passport 2019 CAR.PILOT_2019: [{ - 57: 3, 145: 8, 228: 5, 308: 5, 316: 8, 334: 8, 342: 6, 344: 8, 379: 8, 380: 8, 399: 7, 411: 5, 419: 8, 420: 8, 422: 8, 425: 8, 426: 8, 427: 3, 432: 7, 463: 8, 464: 8, 476: 4, 490: 8, 506: 8, 538: 3, 542: 7, 545: 5, 546: 3, 597: 8, 660: 8, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 808: 8, 817: 4, 819: 7, 821: 5, 825: 4, 829: 5, 837: 5, 856: 7, 871: 8, 881: 8, 882: 2, 884: 7, 891: 8, 892: 8, 923: 2, 927: 8, 929: 8, 983: 8, 985: 3, 1029: 8, 1052: 8, 1064: 7, 1088: 8, 1089: 8, 1092: 1, 1108: 8, 1110: 8, 1125: 8, 1296: 8, 1424: 5, 1445: 8, 1600: 5, 1601: 8, 1612: 5, 1613: 5, 1614: 5, 1615: 8, 1616: 5, 1617: 8, 1618: 5, 1623: 5, 1668: 5 + 57: 3, 145: 8, 228: 5, 308: 5, 316: 8, 334: 8, 342: 6, 344: 8, 379: 8, 380: 8, 399: 7, 411: 5, 419: 8, 420: 8, 422: 8, 425: 8, 426: 8, 427: 3, 432: 7, 463: 8, 464: 8, 476: 4, 490: 8, 506: 8, 512: 6, 513: 6, 538: 3, 542: 7, 545: 5, 546: 3, 597: 8, 660: 8, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 808: 8, 817: 4, 819: 7, 821: 5, 825: 4, 829: 5, 837: 5, 856: 7, 871: 8, 881: 8, 882: 2, 884: 7, 891: 8, 892: 8, 923: 2, 927: 8, 929: 8, 983: 8, 985: 3, 1029: 8, 1052: 8, 1064: 7, 1088: 8, 1089: 8, 1092: 1, 1108: 8, 1110: 8, 1125: 8, 1296: 8, 1424: 5, 1445: 8, 1600: 5, 1601: 8, 1612: 5, 1613: 5, 1614: 5, 1615: 8, 1616: 5, 1617: 8, 1618: 5, 1623: 5, 1668: 5 }, # 2019 Pilot EX-L { - 57: 3, 145: 8, 228: 5, 229: 4, 308: 5, 316: 8, 339: 7, 342: 6, 344: 8, 380: 8, 392: 6, 399: 7, 411: 5, 419: 8, 420: 8, 422: 8, 425: 8, 426: 8, 427: 3, 432: 7, 464: 8, 476: 4, 490: 8, 506: 8, 542: 7, 545: 5, 546: 3, 597: 8, 660: 8, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 808: 8, 817: 4, 819: 7, 821: 5, 829: 5, 871: 8, 881: 8, 882: 2, 884: 7, 891: 8, 892: 8, 923: 2, 927: 8, 929: 8, 963: 8, 965: 8, 966: 8, 967: 8, 983: 8, 985: 3, 1027: 5, 1029: 8, 1039: 8, 1064: 7, 1088: 8, 1089: 8, 1092: 1, 1108: 8, 1125: 8, 1296: 8, 1424: 5, 1445: 8, 1600: 5, 1601: 8, 1612: 5, 1613: 5, 1616: 5, 1617: 8, 1618: 5, 1623: 5, 1668: 5 + 57: 3, 145: 8, 228: 5, 229: 4, 308: 5, 316: 8, 339: 7, 342: 6, 344: 8, 380: 8, 392: 6, 399: 7, 411: 5, 419: 8, 420: 8, 422: 8, 425: 8, 426: 8, 427: 3, 432: 7, 464: 8, 476: 4, 490: 8, 506: 8, 512: 6, 513: 6, 542: 7, 545: 5, 546: 3, 597: 8, 660: 8, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 808: 8, 817: 4, 819: 7, 821: 5, 829: 5, 871: 8, 881: 8, 882: 2, 884: 7, 891: 8, 892: 8, 923: 2, 927: 8, 929: 8, 963: 8, 965: 8, 966: 8, 967: 8, 983: 8, 985: 3, 1027: 5, 1029: 8, 1039: 8, 1064: 7, 1088: 8, 1089: 8, 1092: 1, 1108: 8, 1125: 8, 1296: 8, 1424: 5, 1445: 8, 1600: 5, 1601: 8, 1612: 5, 1613: 5, 1616: 5, 1617: 8, 1618: 5, 1623: 5, 1668: 5 }], # Ridgeline w/ Added Comma Pedal Support (512L & 513L) CAR.RIDGELINE: [{ diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index d7fc2bd39..618656558 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -68,13 +68,13 @@ class CarInterface(object): rotationalInertia_civic = 2500 tireStiffnessFront_civic = 192150 tireStiffnessRear_civic = 202500 + tire_stiffness_factor = 1. ret.steerActuatorDelay = 0.1 # Default delay - tire_stiffness_factor = 1. + ret.steerRateCost = 0.5 if candidate == CAR.SANTA_FE: ret.steerKf = 0.00005 - ret.steerRateCost = 0.5 ret.mass = 3982 * CV.LB_TO_KG + std_cargo ret.wheelbase = 2.766 diff --git a/selfdrive/car/hyundai/radar_interface.py b/selfdrive/car/hyundai/radar_interface.py index 96159fd87..3e458df57 100644 --- a/selfdrive/car/hyundai/radar_interface.py +++ b/selfdrive/car/hyundai/radar_interface.py @@ -21,4 +21,4 @@ if __name__ == "__main__": while 1: ret = RI.update() print(chr(27) + "[2J") - print ret + print(ret) diff --git a/selfdrive/car/mock/radar_interface.py b/selfdrive/car/mock/radar_interface.py index ec042d179..a99494b1a 100755 --- a/selfdrive/car/mock/radar_interface.py +++ b/selfdrive/car/mock/radar_interface.py @@ -13,7 +13,6 @@ class RadarInterface(object): ret = car.RadarState.new_message() time.sleep(0.05) # radard runs on RI updates - return ret if __name__ == "__main__": @@ -21,4 +20,4 @@ if __name__ == "__main__": while 1: ret = RI.update() print(chr(27) + "[2J") - print ret + print(ret) diff --git a/selfdrive/car/subaru/carcontroller.py b/selfdrive/car/subaru/carcontroller.py new file mode 100644 index 000000000..33a0fde86 --- /dev/null +++ b/selfdrive/car/subaru/carcontroller.py @@ -0,0 +1,76 @@ +#from common.numpy_fast import clip +from common.realtime import sec_since_boot +from selfdrive.boardd.boardd import can_list_to_can_capnp +from selfdrive.car import apply_std_steer_torque_limits +from selfdrive.car.subaru import subarucan +from selfdrive.car.subaru.values import CAR, DBC +from selfdrive.can.packer import CANPacker + + +class CarControllerParams(): + def __init__(self, car_fingerprint): + self.STEER_MAX = 2047 # max_steer 4095 + self.STEER_STEP = 2 # how often we update the steer cmd + self.STEER_DELTA_UP = 50 # torque increase per refresh, 0.8s to max + self.STEER_DELTA_DOWN = 70 # torque decrease per refresh + if car_fingerprint == CAR.IMPREZA: + self.STEER_DRIVER_ALLOWANCE = 60 # allowed driver torque before start limiting + self.STEER_DRIVER_MULTIPLIER = 10 # weight driver torque heavily + self.STEER_DRIVER_FACTOR = 1 # from dbc + + + +class CarController(object): + def __init__(self, car_fingerprint): + self.start_time = sec_since_boot() + self.lkas_active = False + self.steer_idx = 0 + self.apply_steer_last = 0 + self.car_fingerprint = car_fingerprint + self.es_distance_cnt = -1 + self.es_lkas_cnt = -1 + + # Setup detection helper. Routes commands to + # an appropriate CAN bus number. + self.params = CarControllerParams(car_fingerprint) + print(DBC) + self.packer = CANPacker(DBC[car_fingerprint]['pt']) + + def update(self, sendcan, enabled, CS, frame, actuators, pcm_cancel_cmd, visual_alert): + """ Controls thread """ + + P = self.params + + # Send CAN commands. + can_sends = [] + + ### STEER ### + + if (frame % P.STEER_STEP) == 0: + + final_steer = actuators.steer if enabled else 0. + apply_steer = int(round(final_steer * P.STEER_MAX)) + + # limits due to driver torque + + apply_steer = int(round(apply_steer)) + apply_steer = apply_std_steer_torque_limits(apply_steer, self.apply_steer_last, CS.steer_torque_driver, P) + + lkas_enabled = enabled and not CS.steer_not_allowed + + if not lkas_enabled: + apply_steer = 0 + + can_sends.append(subarucan.create_steering_control(self.packer, CS.CP.carFingerprint, apply_steer, frame, P.STEER_STEP)) + + self.apply_steer_last = apply_steer + + if self.es_distance_cnt != CS.es_distance_msg["Counter"]: + can_sends.append(subarucan.create_es_distance(self.packer, CS.es_distance_msg, pcm_cancel_cmd)) + self.es_distance_cnt = CS.es_distance_msg["Counter"] + + if self.es_lkas_cnt != CS.es_lkas_msg["Counter"]: + can_sends.append(subarucan.create_es_lkas(self.packer, CS.es_lkas_msg, visual_alert)) + self.es_lkas_cnt = CS.es_lkas_msg["Counter"] + + sendcan.send(can_list_to_can_capnp(can_sends, msgtype='sendcan').to_bytes()) diff --git a/selfdrive/car/subaru/carstate.py b/selfdrive/car/subaru/carstate.py index e12f5f957..38d2fe479 100644 --- a/selfdrive/car/subaru/carstate.py +++ b/selfdrive/car/subaru/carstate.py @@ -1,3 +1,4 @@ +import copy import numpy as np from common.kalman.simple_kalman import KF1D from selfdrive.config import Conversions as CV @@ -32,12 +33,49 @@ def get_powertrain_can_parser(CP): ("Dashlights", 10), ("CruiseControl", 20), ("Wheel_Speeds", 50), - ("Steering_Torque", 100), + ("Steering_Torque", 50), ("BodyInfo", 10), ] return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 0) +def get_camera_can_parser(CP): + signals = [ + ("Cruise_Set_Speed", "ES_DashStatus", 0), + + ("Counter", "ES_Distance", 0), + ("Signal1", "ES_Distance", 0), + ("Signal2", "ES_Distance", 0), + ("Main", "ES_Distance", 0), + ("Signal3", "ES_Distance", 0), + + ("Checksum", "ES_LKAS_State", 0), + ("Counter", "ES_LKAS_State", 0), + ("Keep_Hands_On_Wheel", "ES_LKAS_State", 0), + ("Empty_Box", "ES_LKAS_State", 0), + ("Signal1", "ES_LKAS_State", 0), + ("LKAS_ACTIVE", "ES_LKAS_State", 0), + ("Signal2", "ES_LKAS_State", 0), + ("Backward_Speed_Limit_Menu", "ES_LKAS_State", 0), + ("LKAS_ENABLE_3", "ES_LKAS_State", 0), + ("Signal3", "ES_LKAS_State", 0), + ("LKAS_ENABLE_2", "ES_LKAS_State", 0), + ("Signal4", "ES_LKAS_State", 0), + ("FCW_Cont_Beep", "ES_LKAS_State", 0), + ("FCW_Repeated_Beep", "ES_LKAS_State", 0), + ("Throttle_Management_Activated", "ES_LKAS_State", 0), + ("Traffic_light_Ahead", "ES_LKAS_State", 0), + ("Right_Depart", "ES_LKAS_State", 0), + ("Signal5", "ES_LKAS_State", 0), + + ] + + checks = [ + ("ES_DashStatus", 10), + ] + + return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 2) + class CarState(object): def __init__(self, CP): # initialize can parser @@ -60,9 +98,11 @@ class CarState(object): K=np.matrix([[0.12287673], [0.29666309]])) self.v_ego = 0. - def update(self, cp): + def update(self, cp, cp_cam): + + self.can_valid = cp.can_valid + self.cam_can_valid = cp_cam.can_valid - self.can_valid = True self.pedal_gas = cp.vl["Throttle"]['Throttle_Pedal'] self.brake_pressure = cp.vl["Brake_Pedal"]['Brake_Pedal'] self.user_gas_pressed = self.pedal_gas > 0 @@ -74,6 +114,8 @@ class CarState(object): self.v_wheel_rl = cp.vl["Wheel_Speeds"]['RL'] * CV.KPH_TO_MS self.v_wheel_rr = cp.vl["Wheel_Speeds"]['RR'] * CV.KPH_TO_MS + self.v_cruise_pcm = cp_cam.vl["ES_DashStatus"]["Cruise_Set_Speed"] * CV.MPH_TO_KPH + v_wheel = (self.v_wheel_fl + self.v_wheel_fr + self.v_wheel_rl + self.v_wheel_rr) / 4. # Kalman filter, even though Hyundai raw wheel speed is heaviliy filtered by default if abs(v_wheel - self.v_ego) > 2.0: # Prevent large accelerations when car starts at non zero speed @@ -101,4 +143,5 @@ class CarState(object): cp.vl["BodyInfo"]['DOOR_OPEN_FR'], cp.vl["BodyInfo"]['DOOR_OPEN_FL']]) - + self.es_distance_msg = copy.copy(cp_cam.vl["ES_Distance"]) + self.es_lkas_msg = copy.copy(cp_cam.vl["ES_LKAS_State"]) diff --git a/selfdrive/car/subaru/interface.py b/selfdrive/car/subaru/interface.py index 93a1ac62b..ef3da2f39 100644 --- a/selfdrive/car/subaru/interface.py +++ b/selfdrive/car/subaru/interface.py @@ -5,7 +5,7 @@ from selfdrive.config import Conversions as CV from selfdrive.controls.lib.drive_helpers import create_event, EventTypes as ET from selfdrive.controls.lib.vehicle_model import VehicleModel from selfdrive.car.subaru.values import CAR -from selfdrive.car.subaru.carstate import CarState, get_powertrain_can_parser +from selfdrive.car.subaru.carstate import CarState, get_powertrain_can_parser, get_camera_can_parser try: from selfdrive.car.subaru.carcontroller import CarController @@ -20,11 +20,15 @@ class CarInterface(object): self.frame = 0 self.can_invalid_count = 0 self.acc_active_prev = 0 + self.gas_pressed_prev = False # *** init the major players *** self.CS = CarState(CP) self.VM = VehicleModel(CP) self.pt_cp = get_powertrain_can_parser(CP) + self.cam_cp = get_camera_can_parser(CP) + + self.gas_pressed_prev = False # sending if read only is False if sendcan is not None: @@ -47,8 +51,9 @@ class CarInterface(object): ret.carFingerprint = candidate ret.safetyModel = car.CarParams.SafetyModels.subaru - ret.enableCruise = False + ret.enableCruise = True ret.steerLimitAlert = True + ret.enableCamera = True std_cargo = 136 @@ -116,7 +121,8 @@ class CarInterface(object): def update(self, c): self.pt_cp.update(int(sec_since_boot() * 1e9), False) - self.CS.update(self.pt_cp) + self.cam_cp.update(int(sec_since_boot() * 1e9), False) + self.CS.update(self.pt_cp, self.cam_cp) # create message ret = car.CarState.new_message() @@ -140,11 +146,19 @@ class CarInterface(object): ret.steeringPressed = self.CS.steer_override ret.steeringTorque = self.CS.steer_torque_driver + ret.gas = self.CS.pedal_gas / 255. + ret.gasPressed = self.CS.user_gas_pressed + # cruise state + ret.cruiseState.enabled = bool(self.CS.acc_active) + ret.cruiseState.speed = self.CS.v_cruise_pcm * CV.KPH_TO_MS ret.cruiseState.available = bool(self.CS.main_on) + ret.cruiseState.speedOffset = 0. + ret.leftBlinker = self.CS.left_blinker_on ret.rightBlinker = self.CS.right_blinker_on ret.seatbeltUnlatched = self.CS.seatbelt_unlatched + ret.doorOpen = self.CS.door_open buttonEvents = [] @@ -177,29 +191,31 @@ class CarInterface(object): if ret.seatbeltUnlatched: events.append(create_event('seatbeltNotLatched', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + if ret.doorOpen: + events.append(create_event('doorOpen', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + if self.CS.acc_active and not self.acc_active_prev: events.append(create_event('pcmEnable', [ET.ENABLE])) if not self.CS.acc_active: events.append(create_event('pcmDisable', [ET.USER_DISABLE])) - ## handle button presses - #for b in ret.buttonEvents: - # # do enable on both accel and decel buttons - # if b.type in ["accelCruise", "decelCruise"] and not b.pressed: - # events.append(create_event('buttonEnable', [ET.ENABLE])) - # # do disable on button down - # if b.type == "cancel" and b.pressed: - # events.append(create_event('buttonCancel', [ET.USER_DISABLE])) + # disable on gas pedal rising edge + if (ret.gasPressed and not self.gas_pressed_prev): + events.append(create_event('pedalPressed', [ET.NO_ENTRY, ET.USER_DISABLE])) + + if ret.gasPressed: + events.append(create_event('pedalPressed', [ET.PRE_ENABLE])) ret.events = events # update previous brake/gas pressed + self.gas_pressed_prev = ret.gasPressed self.acc_active_prev = self.CS.acc_active - # cast to reader so it can't be modified return ret.as_reader() def apply(self, c): - self.CC.update(self.sendcan, c.enabled, self.CS, self.frame, c.actuators) + self.CC.update(self.sendcan, c.enabled, self.CS, self.frame, c.actuators, + c.cruiseControl.cancel, c.hudControl.visualAlert) self.frame += 1 diff --git a/selfdrive/car/subaru/radar_interface.py b/selfdrive/car/subaru/radar_interface.py index 96159fd87..3e458df57 100644 --- a/selfdrive/car/subaru/radar_interface.py +++ b/selfdrive/car/subaru/radar_interface.py @@ -21,4 +21,4 @@ if __name__ == "__main__": while 1: ret = RI.update() print(chr(27) + "[2J") - print ret + print(ret) diff --git a/selfdrive/car/subaru/subarucan.py b/selfdrive/car/subaru/subarucan.py new file mode 100644 index 000000000..5c9cbde79 --- /dev/null +++ b/selfdrive/car/subaru/subarucan.py @@ -0,0 +1,54 @@ +import copy +from cereal import car +from selfdrive.car.subaru.values import CAR + +VisualAlert = car.CarControl.HUDControl.VisualAlert + +def subaru_checksum(packer, values, addr): + dat = packer.make_can_msg(addr, 0, values)[2] + dat = [ord(i) for i in dat] + return (sum(dat[1:]) + (addr >> 8) + addr) & 0xff + +def create_steering_control(packer, car_fingerprint, apply_steer, frame, steer_step): + + if car_fingerprint == CAR.IMPREZA: + #counts from 0 to 15 then back to 0 + 16 for enable bit + idx = ((frame / steer_step) % 16) + + values = { + "Counter": idx, + "LKAS_Output": apply_steer, + "LKAS_Request": 1 if apply_steer != 0 else 0, + "SET_1": 1 + } + values["Checksum"] = subaru_checksum(packer, values, 0x122) + + return packer.make_can_msg("ES_LKAS", 0, values) + +def create_steering_status(packer, car_fingerprint, apply_steer, frame, steer_step): + + if car_fingerprint == CAR.IMPREZA: + values = {} + values["Checksum"] = subaru_checksum(packer, {}, 0x322) + + return packer.make_can_msg("ES_LKAS_State", 0, values) + +def create_es_distance(packer, es_distance_msg, pcm_cancel_cmd): + + values = copy.copy(es_distance_msg) + if pcm_cancel_cmd: + values["Main"] = 1 + + values["Checksum"] = subaru_checksum(packer, values, 545) + + return packer.make_can_msg("ES_Distance", 0, values) + +def create_es_lkas(packer, es_lkas_msg, visual_alert): + + values = copy.copy(es_lkas_msg) + if visual_alert == VisualAlert.steerRequired: + values["Keep_Hands_On_Wheel"] = 1 + + values["Checksum"] = subaru_checksum(packer, values, 802) + + return packer.make_can_msg("ES_LKAS_State", 0, values) diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py index cdd1bde51..0885efcb7 100644 --- a/selfdrive/car/toyota/carcontroller.py +++ b/selfdrive/car/toyota/carcontroller.py @@ -161,7 +161,7 @@ class CarController(object): self.steer_angle_enabled, self.ipas_reset_counter = \ ipas_state_transition(self.steer_angle_enabled, enabled, CS.ipas_active, self.ipas_reset_counter) - #print self.steer_angle_enabled, self.ipas_reset_counter, CS.ipas_active + #print("{0} {1} {2}".format(self.steer_angle_enabled, self.ipas_reset_counter, CS.ipas_active)) # steer angle if self.steer_angle_enabled and CS.ipas_active: @@ -198,7 +198,7 @@ class CarController(object): can_sends = [] #*** control msgs *** - #print "steer", apply_steer, min_lim, max_lim, CS.steer_torque_motor + #print("steer {0} {1} {2} {3}".format(apply_steer, min_lim, max_lim, CS.steer_torque_motor) # toyota can trace shows this message at 42Hz, with counter adding alternatively 1 and 2; # sending it at 100Hz seem to allow a higher rate limit, as the rate limit seems imposed diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 5a8abd83c..ce291ef3a 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -99,9 +99,13 @@ FINGERPRINTS = { CAR.LEXUS_RXH: [{ 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 512: 6, 513:6, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 5, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 800: 8, 810: 2, 812: 3, 814: 8, 830: 7, 835: 8, 836: 8, 845: 5, 863: 8, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 6, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1071: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1595: 8, 1777: 8, 1779: 8, 1808: 8, 1810: 8, 1816: 8, 1818: 8, 1840: 8, 1848: 8, 1904: 8, 1912: 8, 1940: 8, 1941: 8, 1948: 8, 1949: 8, 1952: 8, 1956: 8, 1960: 8, 1964: 8, 1986: 8, 1990: 8, 1994: 8, 1998: 8, 2004: 8, 2012: 8 }, - # RX450HL + # RX450HL { - 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 512:6, 513:6, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 5, 643: 7, 658: 8, 713: 8, 742: 8, 743: 8, 800: 8, 810: 2, 812: 3, 814: 8, 830: 7, 835: 8, 836: 8, 863: 8, 865: 8, 869: 7, 870: 7, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 6, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1056: 8, 1057: 8, 1059: 1, 1063: 8, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1228: 8, 1237: 8, 1264: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 512: 6, 513: 6, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 5, 643: 7, 658: 8, 713: 8, 742: 8, 743: 8, 800: 8, 810: 2, 812: 3, 814: 8, 830: 7, 835: 8, 836: 8, 863: 8, 865: 8, 869: 7, 870: 7, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 6, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1056: 8, 1057: 8, 1059: 1, 1063: 8, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1228: 8, 1237: 8, 1264: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + }, + # RX540H 2019 with color hud + { + 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 512: 6, 513: 6, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 5, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 800: 8, 810: 2, 812: 3, 814: 8, 818: 8, 819: 8, 820: 8, 821: 8, 822: 8, 830: 7, 835: 8, 836: 8, 845: 5, 863: 8, 865: 8, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 6, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1063: 8, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1349: 8, 1350: 8, 1351: 8, 1413: 8, 1414: 8, 1415: 8, 1416: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1777: 8, 1779: 8, 1808: 8, 1810: 8, 1816: 8, 1818: 8, 1904: 8, 1912: 8, 1952: 8, 1960: 8, 1990: 8, 1998: 8 }], CAR.CHR: [{ 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 614: 8, 643: 7, 658: 8, 705: 8, 740: 5, 800: 8, 810: 2, 812: 8, 814: 8, 830: 7, 835: 8, 836: 8, 845: 5, 869: 7, 870: 7, 871: 2, 898: 8, 913: 8, 918: 8, 921: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 1014: 8, 1017: 8, 1020: 8, 1021: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1082: 8, 1083: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1175: 8, 1228: 8, 1235: 8, 1237: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8 @@ -122,7 +126,7 @@ FINGERPRINTS = { #LE and LE with Blindspot Monitor { 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 713: 8, 728: 8, 740: 5, 761: 8, 764: 8, 800: 8, 810: 2, 812: 8, 818: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 869: 7, 870: 7, 871: 2, 889: 8, 898: 8, 900: 6, 902: 6, 905: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 983: 8, 984: 8, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1011: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1808: 8, 1810: 8, 1816: 8, 1818: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 - }, + }, #SL { 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 713: 8, 728: 8, 740: 5, 761: 8, 764: 8, 800: 8, 810: 2, 812: 8, 818: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 869: 7, 870: 7, 871: 2, 888: 8, 889: 8, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 diff --git a/selfdrive/common/touch.c b/selfdrive/common/touch.c index f21fac8f0..9117154b0 100644 --- a/selfdrive/common/touch.c +++ b/selfdrive/common/touch.c @@ -90,3 +90,31 @@ int touch_poll(TouchState *s, int* out_x, int* out_y, int timeout) { return up; } +int touch_read(TouchState *s, int* out_x, int* out_y) { + assert(out_x && out_y); + struct input_event event; + int err = read(s->fd, &event, sizeof(event)); + if (err < sizeof(event)) { + return -1; + } + bool up = false; + switch (event.type) { + case EV_ABS: + if (event.code == ABS_MT_POSITION_X) { + s->last_x = event.value; + } else if (event.code == ABS_MT_POSITION_Y) { + s->last_y = event.value; + } + up = true; + break; + default: + break; + } + if (up) { + // adjust for flippening + *out_x = s->last_y; + *out_y = 1080 - s->last_x; + } + return up; +} + diff --git a/selfdrive/common/touch.h b/selfdrive/common/touch.h index c2bb6dfec..c48f66b98 100644 --- a/selfdrive/common/touch.h +++ b/selfdrive/common/touch.h @@ -12,6 +12,7 @@ typedef struct TouchState { void touch_init(TouchState *s); int touch_poll(TouchState *s, int *out_x, int *out_y, int timeout); +int touch_read(TouchState *s, int* out_x, int* out_y); #ifdef __cplusplus } diff --git a/selfdrive/common/version.h b/selfdrive/common/version.h index b1cb55d12..fd8219990 100644 --- a/selfdrive/common/version.h +++ b/selfdrive/common/version.h @@ -1 +1 @@ -#define COMMA_VERSION "0.5.10-release" +#define COMMA_VERSION "0.5.11-release" diff --git a/selfdrive/common/visionimg.cc b/selfdrive/common/visionimg.cc index 8179166e1..a533acb59 100644 --- a/selfdrive/common/visionimg.cc +++ b/selfdrive/common/visionimg.cc @@ -68,7 +68,7 @@ VisionImg visionimg_alloc_rgb24(int width, int height, VisionBuf *out_buf) { #ifdef QCOM -EGLClientBuffer visionimg_to_egl(const VisionImg *img) { +EGLClientBuffer visionimg_to_egl(const VisionImg *img, void **pph) { assert((img->size % img->stride) == 0); assert((img->stride % img->bpp) == 0); @@ -87,13 +87,14 @@ EGLClientBuffer visionimg_to_egl(const VisionImg *img) { GraphicBuffer* gb = new GraphicBuffer(img->width, img->height, (PixelFormat)format, GraphicBuffer::USAGE_HW_TEXTURE, img->stride/img->bpp, hnd, false); - + // GraphicBuffer is ref counted by EGLClientBuffer(ANativeWindowBuffer), no need and not possible to release. + *pph = hnd; return (EGLClientBuffer) gb->getNativeBuffer(); } -GLuint visionimg_to_gl(const VisionImg *img) { +GLuint visionimg_to_gl(const VisionImg *img, EGLImageKHR *pkhr, void **pph) { - EGLClientBuffer buf = visionimg_to_egl(img); + EGLClientBuffer buf = visionimg_to_egl(img, pph); EGLDisplay display = eglGetDisplay(EGL_DEFAULT_DISPLAY); assert(display != EGL_NO_DISPLAY); @@ -107,8 +108,15 @@ GLuint visionimg_to_gl(const VisionImg *img) { glGenTextures(1, &tex); glBindTexture(GL_TEXTURE_2D, tex); glEGLImageTargetTexture2DOES(GL_TEXTURE_2D, image); - + *pkhr = image; return tex; } +void visionimg_destroy_gl(EGLImageKHR khr, void *ph) { + EGLDisplay display = eglGetDisplay(EGL_DEFAULT_DISPLAY); + assert(display != EGL_NO_DISPLAY); + eglDestroyImageKHR(display, khr); + delete (private_handle_t*)ph; +} + #endif diff --git a/selfdrive/common/visionimg.h b/selfdrive/common/visionimg.h index 9fabb6054..74b0f3137 100644 --- a/selfdrive/common/visionimg.h +++ b/selfdrive/common/visionimg.h @@ -27,8 +27,9 @@ void visionimg_compute_aligned_width_and_height(int width, int height, int *alig VisionImg visionimg_alloc_rgb24(int width, int height, VisionBuf *out_buf); #ifdef QCOM -EGLClientBuffer visionimg_to_egl(const VisionImg *img); -GLuint visionimg_to_gl(const VisionImg *img); +EGLClientBuffer visionimg_to_egl(const VisionImg *img, void **pph); +GLuint visionimg_to_gl(const VisionImg *img, EGLImageKHR *pkhr, void **pph); +void visionimg_destroy_gl(EGLImageKHR khr, void *ph); #endif #ifdef __cplusplus diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index b5d699bda..60d3536ff 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -72,7 +72,7 @@ def data_sample(CI, CC, plan_sock, path_plan_sock, thermal, calibration, health, if td is not None: overtemp = td.thermal.thermalStatus >= ThermalStatus.red free_space = td.thermal.freeSpace < 0.07 # under 7% of space free no enable allowed - low_battery = td.thermal.batteryPercent < 1 # at zero percent battery, OP should not be allowed + low_battery = td.thermal.batteryPercent < 1 and td.thermal.chargingError # at zero percent battery, while discharging, OP should not be allowed # Create events for battery, temperature and disk space if low_battery: @@ -282,7 +282,7 @@ def state_control(plan, path_plan, CS, CP, state, events, v_cruise_kph, v_cruise def data_send(plan, path_plan, CS, CI, CP, VM, state, events, actuators, v_cruise_kph, rk, carstate, carcontrol, live100, AM, driver_status, - LaC, LoC, angle_model_bias, passive, start_time, params, v_acc, a_acc): + LaC, LoC, angle_model_bias, passive, start_time, v_acc, a_acc): """Send actuators and hud commands to the car, send live100 and MPC logging""" plan_ts = plan.logMonoTime plan = plan.plan @@ -327,7 +327,7 @@ def data_send(plan, path_plan, CS, CI, CP, VM, state, events, actuators, v_cruis "alertType": AM.alert_type, "alertSound": "", # no EON sounds yet "awarenessStatus": max(driver_status.awareness, 0.0) if isEnabled(state) else 0.0, - "driverMonitoringOn": bool(driver_status.monitor_on), + "driverMonitoringOn": bool(driver_status.monitor_on and driver_status.face_detected), "canMonoTimes": list(CS.canMonoTimes), "planMonoTime": plan_ts, "pathPlanMonoTime": path_plan.logMonoTime, @@ -377,9 +377,6 @@ def data_send(plan, path_plan, CS, CI, CP, VM, state, events, actuators, v_cruis cc_send.carControl = CC carcontrol.send(cc_send.to_bytes()) - if (rk.frame % 36000) == 0: # update angle offset every 6 minutes - params.put("ControlsParams", json.dumps({'angle_model_bias': angle_model_bias})) - return CC @@ -512,7 +509,7 @@ def controlsd_thread(gctx=None, rate=100): # Publish data CC = data_send(plan, path_plan, CS, CI, CP, VM, state, events, actuators, v_cruise_kph, rk, carstate, carcontrol, - live100, AM, driver_status, LaC, LoC, angle_model_bias, passive, start_time, params, v_acc, a_acc) + live100, AM, driver_status, LaC, LoC, angle_model_bias, passive, start_time, v_acc, a_acc) prof.checkpoint("Sent") rk.keep_time() # Run at 100Hz diff --git a/selfdrive/controls/lib/driver_monitor.py b/selfdrive/controls/lib/driver_monitor.py index 10e0e0be6..767b1c1a1 100644 --- a/selfdrive/controls/lib/driver_monitor.py +++ b/selfdrive/controls/lib/driver_monitor.py @@ -4,26 +4,42 @@ from selfdrive.controls.lib.drive_helpers import create_event, EventTypes as ET from common.filter_simple import FirstOrderFilter _DT = 0.01 # update runs at 100Hz -_DTM = 0.1 # DM runs at 10Hz -_AWARENESS_TIME = 180 # 3 minutes limit without user touching steering wheels make the car enter a terminal status -_AWARENESS_PRE_TIME = 20. # a first alert is issued 20s before expiration -_AWARENESS_PROMPT_TIME = 5. # a second alert is issued 5s before start decelerating the car +_DTM = 0.1 # DM runs at 10Hz +_AWARENESS_TIME = 180 # 3 minutes limit without user touching steering wheels make the car enter a terminal status +_AWARENESS_PRE_TIME = 20. # a first alert is issued 20s before expiration +_AWARENESS_PROMPT_TIME = 5. # a second alert is issued 5s before start decelerating the car _DISTRACTED_TIME = 7. _DISTRACTED_PRE_TIME = 4. _DISTRACTED_PROMPT_TIME = 2. -# measured 1 rad in x FOV. 1152x864 is original image, 160x320 is a right crop for model -_CAMERA_FOV_X = 1. # rad -_CAMERA_FOV_Y = 0.75 # 4/3 aspect ratio # model output refers to center of cropped image, so need to apply the x displacement offset -_CAMERA_OFFSET_X = 0.3125 #(1152/2 - 0.5*(160*864/320))/1152 -_CAMERA_X_CONV = 0.375 # 160*864/320/1152 _PITCH_WEIGHT = 1.5 # pitch matters a lot more _METRIC_THRESHOLD = 0.4 -_PITCH_POS_ALLOWANCE = 0.08 # rad, to not be too sensitive on positive pitch -_PITCH_NATURAL_OFFSET = 0.1 # people don't seem to look straight when they drive relaxed, rather a bit up -_STD_THRESHOLD = 0.1 # above this standard deviation consider the measurement invalid -_DISTRACTED_FILTER_TS = 0.25 # 0.6Hz -_VARIANCE_FILTER_TS = 20. # 0.008Hz +_PITCH_POS_ALLOWANCE = 0.08 # rad, to not be too sensitive on positive pitch +_PITCH_NATURAL_OFFSET = 0.1 # people don't seem to look straight when they drive relaxed, rather a bit up +_STD_THRESHOLD = 0.1 # above this standard deviation consider the measurement invalid +_DISTRACTED_FILTER_TS = 0.25 # 0.6Hz +_VARIANCE_FILTER_TS = 20. # 0.008Hz + +RESIZED_FOCAL = 320.0 +H, W, FULL_W = 320, 160, 426 + + +def head_orientation_from_descriptor(desc): + # the output of these angles are in device frame + # so from driver's perspective, pitch is up and yaw is right + # TODO this should be calibrated + pitch_prnet = desc[0] + yaw_prnet = desc[1] + roll_prnet = desc[2] + + face_pixel_position = ((desc[3] + .5)*W - W + FULL_W, (desc[4]+.5)*H) + yaw_focal_angle = np.arctan2(face_pixel_position[0] - FULL_W/2, RESIZED_FOCAL) + pitch_focal_angle = np.arctan2(face_pixel_position[1] - H/2, RESIZED_FOCAL) + + roll = roll_prnet + pitch = pitch_prnet + pitch_focal_angle + yaw = -yaw_prnet + yaw_focal_angle + return np.array([roll, pitch, yaw]) class _DriverPose(): @@ -34,10 +50,12 @@ class _DriverPose(): self.yaw_offset = 0. self.pitch_offset = 0. + def _monitor_hysteresys(variance_level, monitor_valid_prev): var_thr = 0.63 if monitor_valid_prev else 0.37 return variance_level < var_thr + class DriverStatus(): def __init__(self, monitor_on=False): self.pose = _DriverPose() @@ -50,6 +68,7 @@ class DriverStatus(): self.variance_high = False self.variance_filter = FirstOrderFilter(0., _VARIANCE_FILTER_TS, _DTM) self.ts_last_check = 0. + self.face_detected = False self._set_timers() def _reset_filters(self): @@ -69,8 +88,8 @@ class DriverStatus(): def _is_driver_distracted(self, pose): # to be tuned and to learn the driver's normal pose - yaw_error = pose.yaw - pose.yaw_offset - pitch_error = pose.pitch - pose.pitch_offset - _PITCH_NATURAL_OFFSET + pitch_error = pose.pitch - _PITCH_NATURAL_OFFSET + yaw_error = pose.yaw # add positive pitch allowance if pitch_error > 0.: pitch_error = max(pitch_error - _PITCH_POS_ALLOWANCE, 0.) @@ -82,11 +101,14 @@ class DriverStatus(): def get_pose(self, driver_monitoring, params): - self.pose.pitch = driver_monitoring.descriptor[0] - self.pose.yaw = driver_monitoring.descriptor[1] - self.pose.roll = driver_monitoring.descriptor[2] - self.pose.yaw_offset = (driver_monitoring.descriptor[3] * _CAMERA_X_CONV + _CAMERA_OFFSET_X) * _CAMERA_FOV_X - self.pose.pitch_offset = -driver_monitoring.descriptor[4] * _CAMERA_FOV_Y # positive y is down + self.pose.roll, self.pose.pitch, self.pose.yaw = head_orientation_from_descriptor(driver_monitoring.descriptor) + + # TODO: DM data should not be in a list if they are not homogeneous + if len(driver_monitoring.descriptor) > 6: + self.face_detected = driver_monitoring.descriptor[6] > 0. + else: + self.face_detected = True + self.driver_distracted = self._is_driver_distracted(self.pose) # first order filters self.driver_distraction_filter.update(self.driver_distracted) @@ -117,7 +139,8 @@ class DriverStatus(): # always reset if driver is in control (unless we are in red alert state) or op isn't active self.awareness = 1. - if (not self.monitor_on or (self.driver_distraction_filter.x > 0.63 and self.driver_distracted)) and \ + # only update if face is detected, driver is distracted and distraction filter is high + if (not self.monitor_on or (self.driver_distraction_filter.x > 0.63 and self.driver_distracted and self.face_detected)) and \ not (standstill and self.awareness - self.step_change <= self.threshold_prompt): self.awareness = max(self.awareness - self.step_change, -0.1) @@ -146,4 +169,3 @@ if __name__ == "__main__": print(ds.awareness, ds.driver_distracted, ds.driver_distraction_filter.x) ds.update([], True, True, False) print(ds.awareness, ds.driver_distracted, ds.driver_distraction_filter.x) - diff --git a/selfdrive/controls/lib/pathplanner.py b/selfdrive/controls/lib/pathplanner.py index 0161d2f94..9c0a62a0b 100644 --- a/selfdrive/controls/lib/pathplanner.py +++ b/selfdrive/controls/lib/pathplanner.py @@ -51,7 +51,8 @@ class PathPlanner(object): angle_steers = CS.carState.steeringAngle active = live100.live100.active - angle_offset_bias = live100.live100.angleModelBias + live_parameters.liveParameters.angleOffsetAverage + angle_offset_average = live_parameters.liveParameters.angleOffsetAverage + angle_offset_bias = live100.live100.angleModelBias + angle_offset_average self.MP.update(v_ego, md) @@ -65,7 +66,7 @@ class PathPlanner(object): p_poly = libmpc_py.ffi.new("double[4]", list(self.MP.p_poly)) # account for actuation delay - self.cur_state = calc_states_after_delay(self.cur_state, v_ego, angle_steers, curvature_factor, VM.sR, CP.steerActuatorDelay) + self.cur_state = calc_states_after_delay(self.cur_state, v_ego, angle_steers - angle_offset_average, curvature_factor, VM.sR, CP.steerActuatorDelay) v_ego_mpc = max(v_ego, 5.0) # avoid mpc roughness due to low speed self.libmpc.run_mpc(self.cur_state, self.mpc_solution, @@ -84,7 +85,6 @@ class PathPlanner(object): self.angle_steers_des_mpc = float(math.degrees(delta_desired * VM.sR) + angle_offset_bias) - # Check for infeasable MPC solution mpc_nans = np.any(np.isnan(list(self.mpc_solution[0].delta))) t = sec_since_boot() @@ -115,7 +115,7 @@ class PathPlanner(object): plan_send.pathPlan.rProb = float(self.MP.r_prob) plan_send.pathPlan.angleSteers = float(self.angle_steers_des_mpc) plan_send.pathPlan.rateSteers = float(rate_desired) - plan_send.pathPlan.angleOffset = float(live_parameters.liveParameters.angleOffsetAverage) + plan_send.pathPlan.angleOffset = float(angle_offset_average) plan_send.pathPlan.valid = bool(plan_valid) plan_send.pathPlan.paramsValid = bool(live_parameters.liveParameters.valid) diff --git a/selfdrive/debug/can_printer.py b/selfdrive/debug/can_printer.py index d7cbabe63..876b2ab80 100755 --- a/selfdrive/debug/can_printer.py +++ b/selfdrive/debug/can_printer.py @@ -29,7 +29,7 @@ def can_printer(bus=0, max_msg=None, addr="127.0.0.1"): for k,v in sorted(zip(msgs.keys(), map(lambda x: x[-1].encode("hex"), msgs.values()))): if max_msg is None or k < max_msg: dd += "%s(%6d) %s\n" % ("%04X(%4d)" % (k,k),len(msgs[k]), v) - print dd + print(dd) lp = sec_since_boot() if __name__ == "__main__": diff --git a/selfdrive/debug/cpu_usage_stat.py b/selfdrive/debug/cpu_usage_stat.py new file mode 100644 index 000000000..48cca99f9 --- /dev/null +++ b/selfdrive/debug/cpu_usage_stat.py @@ -0,0 +1,99 @@ +import psutil +import time +import os +import sys +import numpy as np +import argparse +import re + +''' +System tools like top/htop can only show current cpu usage values, so I write this script to do statistics jobs. + Features: + Use psutil library to sample cpu usage(avergage for all cores) of OpenPilot processes, at a rate of 5 samples/sec. + Do cpu usage statistics periodically, 5 seconds as a cycle. + Caculate the average cpu usage within this cycle. + Caculate minumium/maximium/accumulated_average cpu usage as long term inspections. + Monitor multiple processes simuteneously. + Sample usage: + root@localhost:/data/openpilot$ python selfdrive/debug/cpu_usage_stat.py boardd,ubloxd + ('Add monitored proc:', './boardd') + ('Add monitored proc:', 'python locationd/ubloxd.py') + boardd: 1.96%, min: 1.96%, max: 1.96%, acc: 1.96% + ubloxd.py: 0.39%, min: 0.39%, max: 0.39%, acc: 0.39% +''' + +# Do statistics every 5 seconds +PRINT_INTERVAL = 5 +SLEEP_INTERVAL = 0.2 + +monitored_proc_names = [ + 'ubloxd', 'thermald', 'uploader', 'controlsd', 'plannerd', 'radard', 'mapd', 'loggerd' , 'logmessaged', 'tombstoned', + 'logcatd', 'proclogd', 'boardd', 'pandad', './ui', 'calibrationd', 'locationd', 'visiond', 'sensord', 'updated', 'gpsd', 'athena'] + + +def get_arg_parser(): + parser = argparse.ArgumentParser( + description="Unlogger and UI", + formatter_class=argparse.ArgumentDefaultsHelpFormatter) + + parser.add_argument("proc_names", nargs="?", default='', + help="Process names to be monitored, comma seperated") + parser.add_argument("--list_all", nargs="?", type=bool, default=False, + help="Show all running processes' cmdline") + return parser + + +if __name__ == "__main__": + args = get_arg_parser().parse_args(sys.argv[1:]) + if args.list_all: + for p in psutil.process_iter(): + print('cmdline', p.cmdline(), 'name', p.name()) + sys.exit(0) + + if len(args.proc_names) > 0: + monitored_proc_names = args.proc_names.split(',') + monitored_procs = [] + stats = {} + for p in psutil.process_iter(): + if p == psutil.Process(): + continue + matched = any([l for l in p.cmdline() if any([pn for pn in monitored_proc_names if re.match(r'.*{}.*'.format(pn), l, re.M | re.I)])]) + if matched: + k = ' '.join(p.cmdline()) + print('Add monitored proc:', k) + stats[k] = {'cpu_samples': [], 'avg_cpu': None, 'min': None, 'max': None} + monitored_procs.append(p) + i = 0 + interval_int = int(PRINT_INTERVAL / SLEEP_INTERVAL) + while True: + for p in monitored_procs: + k = ' '.join(p.cmdline()) + stats[k]['cpu_samples'].append(p.cpu_percent()) + time.sleep(SLEEP_INTERVAL) + i += 1 + if i % interval_int == 0: + l = [] + avg_cpus = [] + for k, stat in stats.items(): + if len(stat['cpu_samples']) <= 0: + continue + avg_cpu = np.array(stat['cpu_samples']).mean() + c = len(stat['cpu_samples']) + stat['cpu_samples'] = [] + if not stat['avg_cpu']: + stat['avg_cpu'] = avg_cpu + else: + stat['avg_cpu'] = (stat['avg_cpu'] * (c + i) + avg_cpu * c) / (c + i + c) + if not stat['min'] or avg_cpu < stat['min']: + stat['min'] = avg_cpu + if not stat['max'] or avg_cpu > stat['max']: + stat['max'] = avg_cpu + msg = 'avg: {1:.2f}%, min: {2:.2f}%, max: {3:.2f}% {0}'.format(os.path.basename(k), stat['avg_cpu'], stat['min'], stat['max']) + l.append((os.path.basename(k), avg_cpu, msg)) + avg_cpus.append(avg_cpu) + l.sort(key= lambda x: -x[1]) + for x in l: + print(x[2]) + print('avg sum: {0:.2f}%\n'.format( + sum([stat['avg_cpu'] for k, stat in stats.items()]) + )) diff --git a/selfdrive/debug/dump.py b/selfdrive/debug/dump.py index 45b737953..0434023f7 100755 --- a/selfdrive/debug/dump.py +++ b/selfdrive/debug/dump.py @@ -52,7 +52,7 @@ if __name__ == "__main__": server_thread = Thread(target=run_server, args=(socketio,)) server_thread.daemon = True server_thread.start() - print 'server running' + print('server running') values = None if args.values: @@ -68,7 +68,7 @@ if __name__ == "__main__": if sock in republish_socks: republish_socks[sock].send(msg) if args.map and evt.which() == 'liveLocation': - print 'send loc' + print('send loc') socketio.emit('location', { 'lat': evt.liveLocation.lat, 'lon': evt.liveLocation.lon, @@ -83,15 +83,15 @@ if __name__ == "__main__": elif args.json: print(json.loads(msg)) elif args.dump_json: - print json.dumps(evt.to_dict()) + print(json.dumps(evt.to_dict())) elif values: - print "logMonotime = {}".format(evt.logMonoTime) + print("logMonotime = {}".format(evt.logMonoTime)) for value in values: if hasattr(evt, value[0]): item = evt for key in value: item = getattr(item, key) - print "{} = {}".format(".".join(value), item) - print "" + print("{} = {}".format(".".join(value), item)) + print("") else: - print evt + print(evt) diff --git a/selfdrive/debug/get_fingerprint.py b/selfdrive/debug/get_fingerprint.py index dd8eb4d80..c46e84970 100755 --- a/selfdrive/debug/get_fingerprint.py +++ b/selfdrive/debug/get_fingerprint.py @@ -26,5 +26,5 @@ while True: fingerprint = ', '.join("%d: %d" % v for v in sorted(msgs.items())) - print "number of messages:", len(msgs) - print "fingerprint", fingerprint + print("number of messages {0}:".format(len(msgs))) + print("fingerprint {0}".format(fingerprint)) diff --git a/selfdrive/debug/getframes/getframes.py b/selfdrive/debug/getframes/getframes.py index 292368d6a..496484175 100755 --- a/selfdrive/debug/getframes/getframes.py +++ b/selfdrive/debug/getframes/getframes.py @@ -98,4 +98,4 @@ def getframes(front=False): if __name__ == "__main__": for buf in getframes(): - print buf.shape, buf[101, 101] + print("{0} {1}".format(buf.shape, buf[101, 101])) diff --git a/selfdrive/locationd/Makefile b/selfdrive/locationd/Makefile new file mode 100644 index 000000000..110c1457e --- /dev/null +++ b/selfdrive/locationd/Makefile @@ -0,0 +1,86 @@ +CC = clang +CXX = clang++ + +ARCH := $(shell uname -m) +OS := $(shell uname -o) + +BASEDIR = ../.. +PHONELIBS = ../../phonelibs + +WARN_FLAGS = -Werror=implicit-function-declaration \ + -Werror=incompatible-pointer-types \ + -Werror=int-conversion \ + -Werror=return-type \ + -Werror=format-extra-args + +CFLAGS = -std=gnu11 -g -fPIC -I../ -I../../ -O2 $(WARN_FLAGS) +CXXFLAGS = -std=c++11 -g -fPIC -I../ -I../../ -O2 $(WARN_FLAGS) + +ZMQ_FLAGS = -I$(PHONELIBS)/zmq/aarch64/include +ZMQ_LIBS = -L$(PHONELIBS)/zmq/aarch64/lib \ + -l:libczmq.a -l:libzmq.a \ + -lgnustl_shared + +JSON_FLAGS = -I$(PHONELIBS)/json/src + +EXTRA_LIBS = -lpthread + +ifeq ($(ARCH),x86_64) +ZMQ_LIBS = -L$(BASEDIR)/external/zmq/lib \ + -l:libczmq.a -l:libzmq.a +endif + +.PHONY: all +all: ubloxd + +include ../common/cereal.mk + +OBJS = ublox_msg.o \ + ubloxd_main.o \ + ../common/swaglog.o \ + ../common/params.o \ + ../common/util.o \ + $(PHONELIBS)/json/src/json.o \ + $(CEREAL_OBJS) + +DEPS := $(OBJS:.o=.d) ubloxd.d ubloxd_test.d + +ubloxd: ubloxd.o $(OBJS) + @echo "[ LINK ] $@" + $(CXX) -fPIC -o '$@' $^ \ + $(CEREAL_LIBS) \ + $(ZMQ_LIBS) \ + $(EXTRA_LIBS) + +ubloxd_test: ubloxd_test.o $(OBJS) + @echo "[ LINK ] $@" + $(CXX) -fPIC -o '$@' $^ \ + $(CEREAL_LIBS) \ + $(ZMQ_LIBS) \ + $(EXTRA_LIBS) + +%.o: %.cc + @echo "[ CXX ] $@" + $(CXX) $(CXXFLAGS) -MMD \ + -Iinclude -I.. -I../.. \ + $(CEREAL_CXXFLAGS) \ + $(ZMQ_FLAGS) \ + $(JSON_FLAGS) \ + -I../ \ + -I../../ \ + -c -o '$@' '$<' + +%.o: %.c + @echo "[ CC ] $@" + $(CC) $(CFLAGS) -MMD \ + -Iinclude -I.. -I../.. \ + $(CEREAL_CFLAGS) \ + $(ZMQ_FLAGS) \ + $(JSON_FLAGS) \ + -c -o '$@' '$<' + +.PHONY: clean +clean: + rm -f ubloxd ubloxd.d ubloxd.o ubloxd_test ubloxd_test.o ubloxd_test.d $(OBJS) $(DEPS) + +-include $(DEPS) diff --git a/selfdrive/locationd/calibrationd.py b/selfdrive/locationd/calibrationd.py index 41911a6b7..1c0ce8ef7 100755 --- a/selfdrive/locationd/calibrationd.py +++ b/selfdrive/locationd/calibrationd.py @@ -39,6 +39,7 @@ class Calibrator(object): self.vps = [] self.cal_status = Calibration.UNCALIBRATED self.write_counter = 0 + self.just_calibrated = False self.params = Params() calibration_params = self.params.get("CalibrationParams") if calibration_params: @@ -52,10 +53,16 @@ class Calibrator(object): def update_status(self): + start_status = self.cal_status if len(self.vps) < INPUTS_NEEDED: self.cal_status = Calibration.UNCALIBRATED else: self.cal_status = Calibration.CALIBRATED if is_calibration_valid(self.vp) else Calibration.INVALID + end_status = self.cal_status + + self.just_calibrated = False + if start_status == Calibration.UNCALIBRATED and end_status == Calibration.CALIBRATED: + self.just_calibrated = True def handle_cam_odom(self, log): trans, rot = log.cameraOdometry.trans, log.cameraOdometry.rot @@ -67,7 +74,7 @@ class Calibrator(object): self.vp = np.mean(self.vps, axis=0) self.update_status() self.write_counter += 1 - if self.param_put and self.write_counter % WRITE_CYCLES == 0: + if self.param_put and (self.write_counter % WRITE_CYCLES == 0 or self.just_calibrated): cal_params = {"vanishing_point": list(self.vp), "valid_points": len(self.vps)} self.params.put("CalibrationParams", json.dumps(cal_params)) diff --git a/selfdrive/locationd/kalman/ekf_sym.py b/selfdrive/locationd/kalman/ekf_sym.py index 2dfefe92d..8b537c699 100644 --- a/selfdrive/locationd/kalman/ekf_sym.py +++ b/selfdrive/locationd/kalman/ekf_sym.py @@ -340,7 +340,7 @@ class EKF_sym(object): # rewind if t < self.filter_time: if len(self.rewind_t) == 0 or t < self.rewind_t[0] or t < self.rewind_t[-1] -1.0: - print "observation too old at %.3f with filter at %.3f, ignoring" % (t, self.filter_time) + print("observation too old at %.3f with filter at %.3f, ignoring" % (t, self.filter_time)) return None rewound = self.rewind(t) else: @@ -457,7 +457,7 @@ class EKF_sym(object): # TODO If nullspace isn't the dimension we want if A.shape[1] + He.shape[1] != A.shape[0]: - print 'Warning: null space projection failed, measurement ignored' + print('Warning: null space projection failed, measurement ignored') return x, P, np.zeros(A.shape[0] - He.shape[1]) # if using eskf diff --git a/selfdrive/locationd/locationd_local.py b/selfdrive/locationd/locationd_local.py index 0b1af2f4c..cc5498cf3 100755 --- a/selfdrive/locationd/locationd_local.py +++ b/selfdrive/locationd/locationd_local.py @@ -73,10 +73,10 @@ class Localizer(object): self.update_kalman(current_time, ObservationKind.CAMERA_ODO_TRANSLATION, np.concatenate([log.cameraOdometry.trans, log.cameraOdometry.transStd])) - def handle_car_state(self, log, current_time): + def handle_live100(self, log, current_time): self.speed_counter += 1 if self.speed_counter % 5 == 0: - self.update_kalman(current_time, ObservationKind.ODOMETRIC_SPEED, np.array([log.carState.vEgo])) + self.update_kalman(current_time, ObservationKind.ODOMETRIC_SPEED, np.array([log.live100.vEgo])) def handle_sensors(self, log, current_time): for sensor_reading in log.sensorEvents: @@ -93,8 +93,8 @@ class Localizer(object): return if typ == "sensorEvents": self.handle_sensors(log, current_time) - elif typ == "carState": - self.handle_car_state(log, current_time) + elif typ == "live100": + self.handle_live100(log, current_time) elif typ == "cameraOdometry": self.handle_cam_odo(log, current_time) @@ -113,7 +113,7 @@ class ParamsLearner(object): self.MAX_SR_TH = MAX_SR_TH * self.VM.sR self.alpha1 = 0.01 * learning_rate - self.alpha2 = 0.00025 * learning_rate + self.alpha2 = 0.0005 * learning_rate self.alpha3 = 0.1 * learning_rate self.alpha4 = 1.0 * learning_rate @@ -154,7 +154,7 @@ class ParamsLearner(object): # instant_ao = aF*m*psi*sR*u/(cR0*l*x) - aR*m*psi*sR*u/(cF0*l*x) - l*psi*sR/u + sa s4 = "Instant AO: % .2f Avg. AO % .2f" % (math.degrees(self.ao), math.degrees(self.slow_ao)) s5 = "Stiffnes: % .3f x" % self.x - print s4, s5 + print("{0} {1}".format(s4, s5)) self.ao = clip(self.ao, -MAX_ANGLE_OFFSET, MAX_ANGLE_OFFSET) @@ -173,7 +173,7 @@ def locationd_thread(gctx, addr, disabled_logs): ctx = zmq.Context() poller = zmq.Poller() - car_state_socket = messaging.sub_sock(ctx, service_list['carState'].port, poller, addr=addr, conflate=True) + live100_socket = messaging.sub_sock(ctx, service_list['live100'].port, poller, addr=addr, conflate=True) sensor_events_socket = messaging.sub_sock(ctx, service_list['sensorEvents'].port, poller, addr=addr, conflate=True) camera_odometry_socket = messaging.sub_sock(ctx, service_list['cameraOdometry'].port, poller, addr=addr, conflate=True) @@ -219,19 +219,19 @@ def locationd_thread(gctx, addr, disabled_logs): log = messaging.recv_one(socket) localizer.handle_log(log) - if socket is car_state_socket: + if socket is live100_socket: if not localizer.kf.t: continue if i % LEARNING_RATE == 0: - # carState is not updating the Kalman Filter, so update KF manually + # live100 is not updating the Kalman Filter, so update KF manually localizer.kf.predict(1e-9 * log.logMonoTime) predicted_state = localizer.kf.x yaw_rate = -float(predicted_state[5]) - steering_angle = math.radians(log.carState.steeringAngle) - params_valid = learner.update(yaw_rate, log.carState.vEgo, steering_angle) + steering_angle = math.radians(log.live100.angleSteers) + params_valid = learner.update(yaw_rate, log.live100.vEgo, steering_angle) params = messaging.new_message() params.init('liveParameters') @@ -246,6 +246,7 @@ def locationd_thread(gctx, addr, disabled_logs): params = learner.get_values() params['carFingerprint'] = CP.carFingerprint params_reader.put("LiveParameters", json.dumps(params)) + params_reader.put("ControlsParams", json.dumps({'angle_model_bias': log.live100.angleModelBias})) i += 1 elif socket is camera_odometry_socket: @@ -263,7 +264,7 @@ def main(gctx=None, addr="127.0.0.1"): disabled_logs = os.getenv("DISABLED_LOGS", "").split(",") # No speed for now - disabled_logs.append('carState') + disabled_logs.append('live100') if IN_CAR: addr = "192.168.5.11" diff --git a/selfdrive/locationd/test/__init__.py b/selfdrive/locationd/test/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/selfdrive/locationd/test/ci_test.py b/selfdrive/locationd/test/ci_test.py new file mode 100755 index 000000000..36dc4d9a7 --- /dev/null +++ b/selfdrive/locationd/test/ci_test.py @@ -0,0 +1,82 @@ +#!/usr/bin/env python2 +import subprocess +import os +import sys +import argparse +import tempfile + +from ubloxd_py_test import parser_test +from ubloxd_regression_test import compare_results + + +def mkdirs_exists_ok(path): + try: + os.makedirs(path) + except OSError: + if not os.path.isdir(path): + raise + + +def main(args): + cur_dir = os.path.dirname(os.path.realpath(__file__)) + ubloxd_dir = os.path.join(cur_dir, '../') + + cc_output_dir = os.path.join(args.output_dir, 'cc') + mkdirs_exists_ok(cc_output_dir) + + py_output_dir = os.path.join(args.output_dir, 'py') + mkdirs_exists_ok(py_output_dir) + + archive_file = os.path.join(cur_dir, args.stream_gz_file) + + try: + print('Extracting stream file') + subprocess.check_call(['tar', 'zxf', archive_file], cwd=tempfile.gettempdir()) + stream_file_path = os.path.join(tempfile.gettempdir(), 'ubloxRaw.stream') + + if not os.path.isfile(stream_file_path): + print('Extract file failed') + sys.exit(-3) + + print('Compiling test app...') + subprocess.check_call(["make", "ubloxd_test"], cwd=ubloxd_dir) + + print('Run regression test - CC parser...') + if args.valgrind: + subprocess.check_call(["valgrind", "--leak-check=full", os.path.join(ubloxd_dir, 'ubloxd_test'), stream_file_path, cc_output_dir]) + else: + subprocess.check_call([os.path.join(ubloxd_dir, 'ubloxd_test'), stream_file_path, cc_output_dir]) + + print('Running regression test - py parser...') + parser_test(stream_file_path, py_output_dir) + + print('Running regression test - compare result...') + r = compare_results(cc_output_dir, py_output_dir) + + print('All done!') + + subprocess.check_call(["rm", stream_file_path]) + subprocess.check_call(["rm", '-rf', cc_output_dir]) + subprocess.check_call(["rm", '-rf', py_output_dir]) + sys.exit(r) + + except subprocess.CalledProcessError as e: + print('CI test failed with {}'.format(e.returncode)) + sys.exit(e.returncode) + + +if __name__ == "__main__": + parser = argparse.ArgumentParser(description="Ubloxd CI test", + formatter_class=argparse.ArgumentDefaultsHelpFormatter) + + parser.add_argument("stream_gz_file", nargs='?', default='ubloxRaw.tar.gz', + help="UbloxRaw data stream zip file") + + parser.add_argument("output_dir", nargs='?', default='out', + help="Output events temp directory") + + parser.add_argument("--valgrind", default=False, action='store_true', + help="Run in valgrind") + + args = parser.parse_args() + main(args) diff --git a/selfdrive/locationd/ephemeris.py b/selfdrive/locationd/test/ephemeris.py similarity index 100% rename from selfdrive/locationd/ephemeris.py rename to selfdrive/locationd/test/ephemeris.py diff --git a/selfdrive/locationd/ublox.py b/selfdrive/locationd/test/ublox.py similarity index 100% rename from selfdrive/locationd/ublox.py rename to selfdrive/locationd/test/ublox.py diff --git a/selfdrive/locationd/ubloxd.py b/selfdrive/locationd/test/ubloxd.py similarity index 100% rename from selfdrive/locationd/ubloxd.py rename to selfdrive/locationd/test/ubloxd.py diff --git a/selfdrive/locationd/test/ubloxd_easy.py b/selfdrive/locationd/test/ubloxd_easy.py new file mode 100755 index 000000000..32f7f3d24 --- /dev/null +++ b/selfdrive/locationd/test/ubloxd_easy.py @@ -0,0 +1,55 @@ +#!/usr/bin/env python +import os +import ublox +from common import realtime +from ubloxd import gen_raw, gen_solution +import zmq +import selfdrive.messaging as messaging +from selfdrive.services import service_list + + +unlogger = os.getenv("UNLOGGER") is not None # debug prints + +def main(gctx=None): + context = zmq.Context() + poller = zmq.Poller() + + context = zmq.Context() + gpsLocationExternal = messaging.pub_sock(context, service_list['gpsLocationExternal'].port) + ubloxGnss = messaging.pub_sock(context, service_list['ubloxGnss'].port) + + # ubloxRaw = messaging.sub_sock(context, service_list['ubloxRaw'].port, poller) + + # buffer with all the messages that still need to be input into the kalman + while 1: + polld = poller.poll(timeout=1000) + for sock, mode in polld: + if mode != zmq.POLLIN: + continue + logs = messaging.drain_sock(sock) + for log in logs: + buff = log.ubloxRaw + time = log.logMonoTime + msg = ublox.UBloxMessage() + msg.add(buff) + if msg.valid(): + if msg.name() == 'NAV_PVT': + sol = gen_solution(msg) + if unlogger: + sol.logMonoTime = time + else: + sol.logMonoTime = int(realtime.sec_since_boot() * 1e9) + gpsLocationExternal.send(sol.to_bytes()) + elif msg.name() == 'RXM_RAW': + raw = gen_raw(msg) + if unlogger: + raw.logMonoTime = time + else: + raw.logMonoTime = int(realtime.sec_since_boot() * 1e9) + ubloxGnss.send(raw.to_bytes()) + else: + print "INVALID MESSAGE" + + +if __name__ == "__main__": + main() diff --git a/selfdrive/locationd/test/ubloxd_py_test.py b/selfdrive/locationd/test/ubloxd_py_test.py new file mode 100755 index 000000000..ab56ecb8c --- /dev/null +++ b/selfdrive/locationd/test/ubloxd_py_test.py @@ -0,0 +1,77 @@ +import sys +import os + +from ublox import UBloxMessage +from ubloxd import gen_solution, gen_raw, gen_nav_data +from common import realtime + + +def mkdirs_exists_ok(path): + try: + os.makedirs(path) + except OSError: + if not os.path.isdir(path): + raise + + +def parser_test(fn, prefix): + nav_frame_buffer = {} + nav_frame_buffer[0] = {} + for i in xrange(1, 33): + nav_frame_buffer[0][i] = {} + + if not os.path.exists(prefix): + print('Prefix invalid') + sys.exit(-1) + + with open(fn, 'rb') as f: + i = 0 + saved_i = 0 + msg = UBloxMessage() + while True: + n = msg.needed_bytes() + b = f.read(n) + if not b: + break + msg.add(b) + if msg.valid(): + i += 1 + if msg.name() == 'NAV_PVT': + sol = gen_solution(msg) + sol.logMonoTime = int(realtime.sec_since_boot() * 1e9) + with open(os.path.join(prefix, str(saved_i)), 'wb') as f1: + f1.write(sol.to_bytes()) + saved_i += 1 + elif msg.name() == 'RXM_RAW': + raw = gen_raw(msg) + raw.logMonoTime = int(realtime.sec_since_boot() * 1e9) + with open(os.path.join(prefix, str(saved_i)), 'wb') as f1: + f1.write(raw.to_bytes()) + saved_i += 1 + elif msg.name() == 'RXM_SFRBX': + nav = gen_nav_data(msg, nav_frame_buffer) + if nav is not None: + nav.logMonoTime = int(realtime.sec_since_boot() * 1e9) + with open(os.path.join(prefix, str(saved_i)), 'wb') as f1: + f1.write(nav.to_bytes()) + saved_i += 1 + + msg = UBloxMessage() + msg.debug_level = 0 + print('Parsed {} msgs'.format(i)) + print('Generated {} cereal events'.format(saved_i)) + + +if __name__ == "__main__": + if len(sys.argv) < 3: + print('Format: ubloxd_py_test.py file_path prefix') + sys.exit(0) + + fn = sys.argv[1] + if not os.path.isfile(fn): + print('File path invalid') + sys.exit(0) + + prefix = sys.argv[2] + mkdirs_exists_ok(prefix) + parser_test(fn, prefix) diff --git a/selfdrive/locationd/test/ubloxd_regression_test.py b/selfdrive/locationd/test/ubloxd_regression_test.py new file mode 100644 index 000000000..94d6b4fe2 --- /dev/null +++ b/selfdrive/locationd/test/ubloxd_regression_test.py @@ -0,0 +1,96 @@ +#!/usr/bin/env python +import os +import sys +import argparse + +from cereal import log +from common.basedir import BASEDIR +os.environ['BASEDIR'] = BASEDIR + + +def get_arg_parser(): + parser = argparse.ArgumentParser( + description="Compare two result files", + formatter_class=argparse.ArgumentDefaultsHelpFormatter) + + parser.add_argument("dir1", nargs='?', default='/data/ubloxdc', + help="Directory path 1 from which events are loaded") + + parser.add_argument("dir2", nargs='?', default='/data/ubloxdpy', + help="Directory path 2 from which msgs are loaded") + + return parser + + +def read_file(fn): + with open(fn, 'rb') as f: + return f.read() + + +def compare_results(dir1, dir2): + onlyfiles1 = [f for f in os.listdir(dir1) if os.path.isfile(os.path.join(dir1, f))] + onlyfiles1.sort() + + onlyfiles2 = [f for f in os.listdir(dir2) if os.path.isfile(os.path.join(dir2, f))] + onlyfiles2.sort() + + if len(onlyfiles1) != len(onlyfiles2): + print('len mismatch: {} != {}'.format(len(onlyfiles1), len(onlyfiles2))) + return -1 + events1 = [log.Event.from_bytes(read_file(os.path.join(dir1, f))) for f in onlyfiles1] + events2 = [log.Event.from_bytes(read_file(os.path.join(dir2, f))) for f in onlyfiles2] + + for i in range(len(events1)): + if events1[i].which() != events2[i].which(): + print('event {} type mismatch: {} != {}'.format(i, events1[i].which(), events2[i].which())) + return -2 + if events1[i].which() == 'gpsLocationExternal': + old_gps = events1[i].gpsLocationExternal + gps = events2[i].gpsLocationExternal + # print(gps, old_gps) + attrs = ['flags', 'latitude', 'longitude', 'altitude', 'speed', 'bearing', + 'accuracy', 'timestamp', 'source', 'vNED', 'verticalAccuracy', 'bearingAccuracy', 'speedAccuracy'] + for attr in attrs: + o = getattr(old_gps, attr) + n = getattr(gps, attr) + if attr == 'vNED': + if len(o) != len(n): + print('Gps vNED len mismatch', o, n) + return -3 + else: + for i in range(len(o)): + if abs(o[i] - n[i]) > 1e-3: + print('Gps vNED mismatch', o, n) + return + elif o != n: + print('Gps mismatch', attr, o, n) + return -4 + elif events1[i].which() == 'ubloxGnss': + old_gnss = events1[i].ubloxGnss + gnss = events2[i].ubloxGnss + if old_gnss.which() == 'measurementReport' and gnss.which() == 'measurementReport': + attrs = ['gpsWeek', 'leapSeconds', 'measurements', 'numMeas', 'rcvTow', 'receiverStatus', 'schema'] + for attr in attrs: + o = getattr(old_gnss.measurementReport, attr) + n = getattr(gnss.measurementReport, attr) + if str(o) != str(n): + print('measurementReport {} mismatched'.format(attr)) + return -5 + if not (str(old_gnss.measurementReport) == str(gnss.measurementReport)): + print('Gnss measurementReport mismatched!') + print('gnss measurementReport old', old_gnss.measurementReport.measurements) + print('gnss measurementReport new', gnss.measurementReport.measurements) + return -6 + elif old_gnss.which() == 'ephemeris' and gnss.which() == 'ephemeris': + if not (str(old_gnss.ephemeris) == str(gnss.ephemeris)): + print('Gnss ephemeris mismatched!') + print('gnss ephemeris old', old_gnss.ephemeris) + print('gnss ephemeris new', gnss.ephemeris) + return -7 + print('All {} events matched!'.format(len(events1))) + return 0 + + +if __name__ == "__main__": + args = get_arg_parser().parse_args(sys.argv[1:]) + compare_results(args.dir1, args.dir2) diff --git a/selfdrive/locationd/ublox_msg.cc b/selfdrive/locationd/ublox_msg.cc new file mode 100644 index 000000000..ef523b887 --- /dev/null +++ b/selfdrive/locationd/ublox_msg.cc @@ -0,0 +1,375 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include "cereal/gen/cpp/log.capnp.h" + +#include "common/params.h" +#include "common/swaglog.h" +#include "common/timing.h" + +#include "ublox_msg.h" + +#define UBLOX_MSG_SIZE(hdr) (*(uint16_t *)&hdr[4]) +#define GET_FIELD_U(w, nb, pos) (((w) >> (pos)) & ((1<<(nb))-1)) + +namespace ublox { + +inline int twos_complement(uint32_t v, uint32_t nb) { + int sign = v >> (nb - 1); + int value = v; + if(sign != 0) + value = value - (1 << nb); + return value; +} + +inline int GET_FIELD_S(uint32_t w, uint32_t nb, uint32_t pos) { + int v = GET_FIELD_U(w, nb, pos); + return twos_complement(v, nb); +} + +class EphemerisData { + public: + EphemerisData(uint8_t svId, subframes_map subframes) { + this->svId = svId; + int week_no = GET_FIELD_U(subframes[1][2+0], 10, 20); + int t_gd = GET_FIELD_S(subframes[1][2+4], 8, 6); + int iodc = (GET_FIELD_U(subframes[1][2+0], 2, 6) << 8) | GET_FIELD_U( + subframes[1][2+5], 8, 22); + + int t_oc = GET_FIELD_U(subframes[1][2+5], 16, 6); + int a_f2 = GET_FIELD_S(subframes[1][2+6], 8, 22); + int a_f1 = GET_FIELD_S(subframes[1][2+6], 16, 6); + int a_f0 = GET_FIELD_S(subframes[1][2+7], 22, 8); + + int c_rs = GET_FIELD_S(subframes[2][2+0], 16, 6); + int delta_n = GET_FIELD_S(subframes[2][2+1], 16, 14); + int m_0 = (GET_FIELD_S(subframes[2][2+1], 8, 6) << 24) | GET_FIELD_U( + subframes[2][2+2], 24, 6); + int c_uc = GET_FIELD_S(subframes[2][2+3], 16, 14); + int e = (GET_FIELD_U(subframes[2][2+3], 8, 6) << 24) | GET_FIELD_U(subframes[2][2+4], 24, 6); + int c_us = GET_FIELD_S(subframes[2][2+5], 16, 14); + uint32_t a_powhalf = (GET_FIELD_U(subframes[2][2+5], 8, 6) << 24) | GET_FIELD_U( + subframes[2][2+6], 24, 6); + int t_oe = GET_FIELD_U(subframes[2][2+7], 16, 14); + + int c_ic = GET_FIELD_S(subframes[3][2+0], 16, 14); + int omega_0 = (GET_FIELD_S(subframes[3][2+0], 8, 6) << 24) | GET_FIELD_U( + subframes[3][2+1], 24, 6); + int c_is = GET_FIELD_S(subframes[3][2+2], 16, 14); + int i_0 = (GET_FIELD_S(subframes[3][2+2], 8, 6) << 24) | GET_FIELD_U( + subframes[3][2+3], 24, 6); + int c_rc = GET_FIELD_S(subframes[3][2+4], 16, 14); + int w = (GET_FIELD_S(subframes[3][2+4], 8, 6) << 24) | GET_FIELD_U(subframes[3][5], 24, 6); + int omega_dot = GET_FIELD_S(subframes[3][2+6], 24, 6); + int idot = GET_FIELD_S(subframes[3][2+7], 14, 8); + + this->_rsvd1 = GET_FIELD_U(subframes[1][2+1], 23, 6); + this->_rsvd2 = GET_FIELD_U(subframes[1][2+2], 24, 6); + this->_rsvd3 = GET_FIELD_U(subframes[1][2+3], 24, 6); + this->_rsvd4 = GET_FIELD_U(subframes[1][2+4], 16, 14); + this->aodo = GET_FIELD_U(subframes[2][2+7], 5, 8); + + double gpsPi = 3.1415926535898; + + // now form variables in radians, meters and seconds etc + this->Tgd = t_gd * pow(2, -31); + this->A = pow(a_powhalf * pow(2, -19), 2.0); + this->cic = c_ic * pow(2, -29); + this->cis = c_is * pow(2, -29); + this->crc = c_rc * pow(2, -5); + this->crs = c_rs * pow(2, -5); + this->cuc = c_uc * pow(2, -29); + this->cus = c_us * pow(2, -29); + this->deltaN = delta_n * pow(2, -43) * gpsPi; + this->ecc = e * pow(2, -33); + this->i0 = i_0 * pow(2, -31) * gpsPi; + this->idot = idot * pow(2, -43) * gpsPi; + this->M0 = m_0 * pow(2, -31) * gpsPi; + this->omega = w * pow(2, -31) * gpsPi; + this->omega_dot = omega_dot * pow(2, -43) * gpsPi; + this->omega0 = omega_0 * pow(2, -31) * gpsPi; + this->toe = t_oe * pow(2, 4); + + this->toc = t_oc * pow(2, 4); + this->gpsWeek = week_no; + this->af0 = a_f0 * pow(2, -31); + this->af1 = a_f1 * pow(2, -43); + this->af2 = a_f2 * pow(2, -55); + + uint32_t iode1 = GET_FIELD_U(subframes[2][2+0], 8, 22); + uint32_t iode2 = GET_FIELD_U(subframes[3][2+7], 8, 22); + this->valid = (iode1 == iode2) && (iode1 == (iodc & 0xff)); + this->iode = iode1; + + if (GET_FIELD_U(subframes[4][2+0], 6, 22) == 56 && + GET_FIELD_U(subframes[4][2+0], 2, 28) == 1 && + GET_FIELD_U(subframes[5][2+0], 2, 28) == 1) { + double a0 = GET_FIELD_S(subframes[4][2], 8, 14) * pow(2, -30); + double a1 = GET_FIELD_S(subframes[4][2], 8, 6) * pow(2, -27); + double a2 = GET_FIELD_S(subframes[4][3], 8, 22) * pow(2, -24); + double a3 = GET_FIELD_S(subframes[4][3], 8, 14) * pow(2, -24); + double b0 = GET_FIELD_S(subframes[4][3], 8, 6) * pow(2, 11); + double b1 = GET_FIELD_S(subframes[4][4], 8, 22) * pow(2, 14); + double b2 = GET_FIELD_S(subframes[4][4], 8, 14) * pow(2, 16); + double b3 = GET_FIELD_S(subframes[4][4], 8, 6) * pow(2, 16); + this->ionoAlpha[0] = a0;this->ionoAlpha[1] = a1;this->ionoAlpha[2] = a2;this->ionoAlpha[3] = a3; + this->ionoBeta[0] = b0;this->ionoBeta[1] = b1;this->ionoBeta[2] = b2;this->ionoBeta[3] = b3; + this->ionoCoeffsValid = true; + } else { + this->ionoCoeffsValid = false; + } + } + uint16_t svId; + double Tgd, A, cic, cis, crc, crs, cuc, cus, deltaN, ecc, i0, idot, M0, omega, omega_dot, omega0, toe, toc; + uint32_t gpsWeek, iode, _rsvd1, _rsvd2, _rsvd3, _rsvd4, aodo; + double af0, af1, af2; + bool valid; + double ionoAlpha[4], ionoBeta[4]; + bool ionoCoeffsValid; +}; + +UbloxMsgParser::UbloxMsgParser() :bytes_in_parse_buf(0) { + nav_frame_buffer[0U] = std::map(); + for(int i = 1;i < 33;i++) + nav_frame_buffer[0U][i] = subframes_map(); +} + +inline int UbloxMsgParser::needed_bytes() { + // Msg header incomplete? + if(bytes_in_parse_buf < UBLOX_HEADER_SIZE) + return UBLOX_HEADER_SIZE + UBLOX_CHECKSUM_SIZE - bytes_in_parse_buf; + uint16_t needed = UBLOX_MSG_SIZE(msg_parse_buf) + UBLOX_HEADER_SIZE + UBLOX_CHECKSUM_SIZE; + // too much data + if(needed < (uint16_t)bytes_in_parse_buf) + return -1; + return needed - (uint16_t)bytes_in_parse_buf; +} + +inline bool UbloxMsgParser::valid_cheksum() { + uint8_t ck_a = 0, ck_b = 0; + for(int i = 2; i < bytes_in_parse_buf - UBLOX_CHECKSUM_SIZE;i++) { + ck_a = (ck_a + msg_parse_buf[i]) & 0xFF; + ck_b = (ck_b + ck_a) & 0xFF; + } + if(ck_a != msg_parse_buf[bytes_in_parse_buf - 2]) { + LOGD("Checksum a mismtach: %02X, %02X", ck_a, msg_parse_buf[6]); + return false; + } + if(ck_b != msg_parse_buf[bytes_in_parse_buf - 1]) { + LOGD("Checksum b mismtach: %02X, %02X", ck_b, msg_parse_buf[7]); + return false; + } + return true; +} + +inline bool UbloxMsgParser::valid() { + return bytes_in_parse_buf >= UBLOX_HEADER_SIZE + UBLOX_CHECKSUM_SIZE && + needed_bytes() == 0 && + valid_cheksum(); +} + +inline bool UbloxMsgParser::valid_so_far() { + if(bytes_in_parse_buf > 0 && msg_parse_buf[0] != PREAMBLE1) { + //LOGD("PREAMBLE1 invalid, %02X.", msg_parse_buf[0]); + return false; + } + if(bytes_in_parse_buf > 1 && msg_parse_buf[1] != PREAMBLE2) { + //LOGD("PREAMBLE2 invalid, %02X.", msg_parse_buf[1]); + return false; + } + if(needed_bytes() == 0 && !valid()) + return false; + return true; +} + +kj::Array UbloxMsgParser::gen_solution() { + nav_pvt_msg *msg = (nav_pvt_msg *)&msg_parse_buf[UBLOX_HEADER_SIZE]; + capnp::MallocMessageBuilder msg_builder; + cereal::Event::Builder event = msg_builder.initRoot(); + event.setLogMonoTime(nanos_since_boot()); + auto gpsLoc = event.initGpsLocationExternal(); + gpsLoc.setSource(cereal::GpsLocationData::SensorSource::UBLOX); + gpsLoc.setFlags(msg->flags); + gpsLoc.setLatitude(msg->lat * 1e-07); + gpsLoc.setLongitude(msg->lon * 1e-07); + gpsLoc.setAltitude(msg->height * 1e-03); + gpsLoc.setSpeed(msg->gSpeed * 1e-03); + gpsLoc.setBearing(msg->headMot * 1e-5); + gpsLoc.setAccuracy(msg->hAcc * 1e-03); + std::tm timeinfo = std::tm(); + timeinfo.tm_year = msg->year - 1900; + timeinfo.tm_mon = msg->month - 1; + timeinfo.tm_mday = msg->day; + timeinfo.tm_hour = msg->hour; + timeinfo.tm_min = msg->min; + timeinfo.tm_sec = msg->sec; + std::time_t utc_tt = timegm(&timeinfo); + gpsLoc.setTimestamp(utc_tt * 1e+03 + msg->nano * 1e-06); + float f[] = { msg->velN * 1e-03f, msg->velE * 1e-03f, msg->velD * 1e-03f }; + kj::ArrayPtr ap(&f[0], sizeof(f) / sizeof(f[0])); + gpsLoc.setVNED(ap); + gpsLoc.setVerticalAccuracy(msg->vAcc * 1e-03); + gpsLoc.setSpeedAccuracy(msg->sAcc * 1e-03); + gpsLoc.setBearingAccuracy(msg->headAcc * 1e-05); + return capnp::messageToFlatArray(msg_builder); +} + +inline bool bit_to_bool(uint8_t val, int shifts) { + return (val & (1 << shifts)) ? true : false; +} + +kj::Array UbloxMsgParser::gen_raw() { + rxm_raw_msg *msg = (rxm_raw_msg *)&msg_parse_buf[UBLOX_HEADER_SIZE]; + if(bytes_in_parse_buf != ( + UBLOX_HEADER_SIZE + sizeof(rxm_raw_msg) + msg->numMeas * sizeof(rxm_raw_msg_extra) + UBLOX_CHECKSUM_SIZE + )) { + LOGD("Invalid measurement size %u, %u, %u, %u", msg->numMeas, bytes_in_parse_buf, sizeof(rxm_raw_msg_extra), sizeof(rxm_raw_msg)); + return kj::Array(); + } + rxm_raw_msg_extra *measurements = (rxm_raw_msg_extra *)&msg_parse_buf[UBLOX_HEADER_SIZE + sizeof(rxm_raw_msg)]; + capnp::MallocMessageBuilder msg_builder; + cereal::Event::Builder event = msg_builder.initRoot(); + event.setLogMonoTime(nanos_since_boot()); + auto gnss = event.initUbloxGnss(); + auto mr = gnss.initMeasurementReport(); + mr.setRcvTow(msg->rcvTow); + mr.setGpsWeek(msg->week); + mr.setLeapSeconds(msg->leapS); + mr.setGpsWeek(msg->week); + auto mb = mr.initMeasurements(msg->numMeas); + for(int8_t i = 0; i < msg->numMeas; i++) { + mb[i].setSvId(measurements[i].svId); + mb[i].setSigId(measurements[i].sigId); + mb[i].setPseudorange(measurements[i].prMes); + mb[i].setCarrierCycles(measurements[i].cpMes); + mb[i].setDoppler(measurements[i].doMes); + mb[i].setGnssId(measurements[i].gnssId); + mb[i].setGlonassFrequencyIndex(measurements[i].freqId); + mb[i].setLocktime(measurements[i].locktime); + mb[i].setCno(measurements[i].cno); + mb[i].setPseudorangeStdev(0.01*(pow(2, (measurements[i].prStdev & 15)))); // weird scaling, might be wrong + mb[i].setCarrierPhaseStdev(0.004*(measurements[i].cpStdev & 15)); + mb[i].setDopplerStdev(0.002*(pow(2, (measurements[i].doStdev & 15)))); // weird scaling, might be wrong + auto ts = mb[i].initTrackingStatus(); + ts.setPseudorangeValid(bit_to_bool(measurements[i].trkStat, 0)); + ts.setCarrierPhaseValid(bit_to_bool(measurements[i].trkStat, 1)); + ts.setHalfCycleValid(bit_to_bool(measurements[i].trkStat, 2)); + ts.setHalfCycleSubtracted(bit_to_bool(measurements[i].trkStat, 3)); + } + + mr.setNumMeas(msg->numMeas); + auto rs = mr.initReceiverStatus(); + rs.setLeapSecValid(bit_to_bool(msg->recStat, 0)); + rs.setClkReset(bit_to_bool(msg->recStat, 2)); + return capnp::messageToFlatArray(msg_builder); +} + +kj::Array UbloxMsgParser::gen_nav_data() { + rxm_sfrbx_msg *msg = (rxm_sfrbx_msg *)&msg_parse_buf[UBLOX_HEADER_SIZE]; + if(bytes_in_parse_buf != ( + UBLOX_HEADER_SIZE + sizeof(rxm_sfrbx_msg) + msg->numWords * sizeof(rxm_sfrbx_msg_extra) + UBLOX_CHECKSUM_SIZE + )) { + LOGD("Invalid sfrbx words size %u, %u, %u, %u", msg->numWords, bytes_in_parse_buf, sizeof(rxm_raw_msg_extra), sizeof(rxm_raw_msg)); + return kj::Array(); + } + rxm_sfrbx_msg_extra *measurements = (rxm_sfrbx_msg_extra *)&msg_parse_buf[UBLOX_HEADER_SIZE + sizeof(rxm_sfrbx_msg)]; + if(msg->gnssId == 0) { + uint8_t subframeId = GET_FIELD_U(measurements[1].dwrd, 3, 8); + std::vector words; + for(int i = 0; i < msg->numWords;i++) + words.push_back(measurements[i].dwrd); + + if(subframeId == 1) { + nav_frame_buffer[msg->gnssId][msg->svid] = subframes_map(); + nav_frame_buffer[msg->gnssId][msg->svid][subframeId] = words; + } else if(nav_frame_buffer[msg->gnssId][msg->svid].find(subframeId-1) != nav_frame_buffer[msg->gnssId][msg->svid].end()) + nav_frame_buffer[msg->gnssId][msg->svid][subframeId] = words; + if(nav_frame_buffer[msg->gnssId][msg->svid].size() == 5) { + EphemerisData ephem_data(msg->svid, nav_frame_buffer[msg->gnssId][msg->svid]); + capnp::MallocMessageBuilder msg_builder; + cereal::Event::Builder event = msg_builder.initRoot(); + event.setLogMonoTime(nanos_since_boot()); + auto gnss = event.initUbloxGnss(); + auto eph = gnss.initEphemeris(); + eph.setSvId(ephem_data.svId); + eph.setToc(ephem_data.toc); + eph.setGpsWeek(ephem_data.gpsWeek); + eph.setAf0(ephem_data.af0); + eph.setAf1(ephem_data.af1); + eph.setAf2(ephem_data.af2); + eph.setIode(ephem_data.iode); + eph.setCrs(ephem_data.crs); + eph.setDeltaN(ephem_data.deltaN); + eph.setM0(ephem_data.M0); + eph.setCuc(ephem_data.cuc); + eph.setEcc(ephem_data.ecc); + eph.setCus(ephem_data.cus); + eph.setA(ephem_data.A); + eph.setToe(ephem_data.toe); + eph.setCic(ephem_data.cic); + eph.setOmega0(ephem_data.omega0); + eph.setCis(ephem_data.cis); + eph.setI0(ephem_data.i0); + eph.setCrc(ephem_data.crc); + eph.setOmega(ephem_data.omega); + eph.setOmegaDot(ephem_data.omega_dot); + eph.setIDot(ephem_data.idot); + eph.setTgd(ephem_data.Tgd); + eph.setIonoCoeffsValid(ephem_data.ionoCoeffsValid); + if(ephem_data.ionoCoeffsValid) { + kj::ArrayPtr apa(&ephem_data.ionoAlpha[0], sizeof(ephem_data.ionoAlpha) / sizeof(ephem_data.ionoAlpha[0])); + eph.setIonoAlpha(apa); + kj::ArrayPtr apb(&ephem_data.ionoBeta[0], sizeof(ephem_data.ionoBeta) / sizeof(ephem_data.ionoBeta[0])); + eph.setIonoBeta(apb); + } else { + eph.setIonoAlpha(kj::ArrayPtr()); + eph.setIonoBeta(kj::ArrayPtr()); + } + return capnp::messageToFlatArray(msg_builder); + } + } + return kj::Array(); +} + +bool UbloxMsgParser::add_data(const uint8_t *incoming_data, uint32_t incoming_data_len, size_t &bytes_consumed) { + int needed = needed_bytes(); + if(needed > 0) { + bytes_consumed = min((size_t)needed, incoming_data_len ); + // Add data to buffer + memcpy(msg_parse_buf + bytes_in_parse_buf, incoming_data, bytes_consumed); + bytes_in_parse_buf += bytes_consumed; + } else { + bytes_consumed = incoming_data_len; + } + // Validate msg format, detect invalid header and invalid checksum. + while(!valid_so_far() && bytes_in_parse_buf != 0) { + //LOGD("Drop corrupt data, remained in buf: %u", bytes_in_parse_buf); + // Corrupted msg, drop a byte. + bytes_in_parse_buf -= 1; + if(bytes_in_parse_buf > 0) + memmove(&msg_parse_buf[0], &msg_parse_buf[1], bytes_in_parse_buf); + } + // There is redundant data at the end of buffer, reset the buffer. + if(needed_bytes() == -1) + bytes_in_parse_buf = 0; + return valid(); +} + +} diff --git a/selfdrive/locationd/ublox_msg.h b/selfdrive/locationd/ublox_msg.h new file mode 100644 index 000000000..c7860f14c --- /dev/null +++ b/selfdrive/locationd/ublox_msg.h @@ -0,0 +1,149 @@ +#pragma once + +#include + +#define min(x, y) ((x) <= (y) ? (x) : (y)) + +// NAV_PVT +typedef struct __attribute__((packed)) { + uint32_t iTOW; + uint16_t year; + int8_t month; + int8_t day; + int8_t hour; + int8_t min; + int8_t sec; + int8_t valid; + uint32_t tAcc; + int32_t nano; + int8_t fixType; + int8_t flags; + int8_t flags2; + int8_t numSV; + int32_t lon; + int32_t lat; + int32_t height; + int32_t hMSL; + uint32_t hAcc; + uint32_t vAcc; + int32_t velN; + int32_t velE; + int32_t velD; + int32_t gSpeed; + int32_t headMot; + uint32_t sAcc; + uint32_t headAcc; + uint16_t pDOP; + int8_t reserverd1[6]; + int32_t headVeh; + int16_t magDec; + uint16_t magAcc; +} nav_pvt_msg; + +// RXM_RAW +typedef struct __attribute__((packed)) { + double rcvTow; + uint16_t week; + int8_t leapS; + int8_t numMeas; + int8_t recStat; + int8_t reserved1[3]; +} rxm_raw_msg; + +// Extra data count is in numMeas +typedef struct __attribute__((packed)) { + double prMes; + double cpMes; + float doMes; + int8_t gnssId; + int8_t svId; + int8_t sigId; + int8_t freqId; + uint16_t locktime; + int8_t cno; + int8_t prStdev; + int8_t cpStdev; + int8_t doStdev; + int8_t trkStat; + int8_t reserved3; +} rxm_raw_msg_extra; +// RXM_SFRBX +typedef struct __attribute__((packed)) { + int8_t gnssId; + int8_t svid; + int8_t reserved1; + int8_t freqId; + int8_t numWords; + int8_t reserved2; + int8_t version; + int8_t reserved3; +} rxm_sfrbx_msg; + +// Extra data count is in numWords +typedef struct __attribute__((packed)) { + uint32_t dwrd; +} rxm_sfrbx_msg_extra; + +namespace ublox { + // protocol constants + const uint8_t PREAMBLE1 = 0xb5; + const uint8_t PREAMBLE2 = 0x62; + + // message classes + const uint8_t CLASS_NAV = 0x01; + const uint8_t CLASS_RXM = 0x02; + + // NAV messages + const uint8_t MSG_NAV_PVT = 0x7; + + // RXM messages + const uint8_t MSG_RXM_RAW = 0x15; + const uint8_t MSG_RXM_SFRBX = 0x13; + + const int UBLOX_HEADER_SIZE = 6; + const int UBLOX_CHECKSUM_SIZE = 2; + const int UBLOX_MAX_MSG_SIZE = 65536; + + typedef std::map> subframes_map; + + class UbloxMsgParser { + public: + + UbloxMsgParser(); + kj::Array gen_solution(); + kj::Array gen_raw(); + + kj::Array gen_nav_data(); + bool add_data(const uint8_t *incoming_data, uint32_t incoming_data_len, size_t &bytes_consumed); + inline void reset() {bytes_in_parse_buf = 0;} + inline uint8_t msg_class() { + return msg_parse_buf[2]; + } + + inline uint8_t msg_id() { + return msg_parse_buf[3]; + } + inline int needed_bytes(); + + void hexdump(uint8_t *d, int l) { + for (int i = 0; i < l; i++) { + if (i%0x10 == 0 && i != 0) printf("\n"); + printf("%02X ", d[i]); + } + printf("\n"); + } + private: + inline bool valid_cheksum(); + inline bool valid(); + inline bool valid_so_far(); + + uint8_t msg_parse_buf[UBLOX_HEADER_SIZE + UBLOX_MAX_MSG_SIZE]; + int bytes_in_parse_buf; + std::map> nav_frame_buffer; + }; + +} + +typedef int (*poll_ubloxraw_msg_func)(void *gpsLocationExternal, void *ubloxGnss, void *subscriber, zmq_msg_t *msg); +typedef int (*send_gps_event_func)(uint8_t msg_cls, uint8_t msg_id, void *s, const void *buf, size_t len, int flags); +int ubloxd_main(poll_ubloxraw_msg_func poll_func, send_gps_event_func send_func); diff --git a/selfdrive/locationd/ubloxd.cc b/selfdrive/locationd/ubloxd.cc new file mode 100644 index 000000000..82853f132 --- /dev/null +++ b/selfdrive/locationd/ubloxd.cc @@ -0,0 +1,45 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include "cereal/gen/cpp/log.capnp.h" + +#include "common/params.h" +#include "common/swaglog.h" +#include "common/timing.h" + +#include "ublox_msg.h" + +const long ZMQ_POLL_TIMEOUT = 1000; // In miliseconds + +int poll_ubloxraw_msg(void *gpsLocationExternal, void *ubloxGnss, void *subscriber, zmq_msg_t *msg) { + int err; + zmq_pollitem_t item = {.socket = subscriber, .events = ZMQ_POLLIN}; + err = zmq_poll (&item, 1, ZMQ_POLL_TIMEOUT); + if(err <= 0) + return err; + return zmq_msg_recv(msg, subscriber, 0); +} + +int send_gps_event(uint8_t msg_cls, uint8_t msg_id, void *s, const void *buf, size_t len, int flags) { + return zmq_send(s, buf, len, flags); +} + +int main() { + return ubloxd_main(poll_ubloxraw_msg, send_gps_event); +} diff --git a/selfdrive/locationd/ubloxd_main.cc b/selfdrive/locationd/ubloxd_main.cc new file mode 100644 index 000000000..1cfb8c5fb --- /dev/null +++ b/selfdrive/locationd/ubloxd_main.cc @@ -0,0 +1,113 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include "cereal/gen/cpp/log.capnp.h" + +#include "common/params.h" +#include "common/swaglog.h" +#include "common/timing.h" + +#include "ublox_msg.h" + +volatile int do_exit = 0; // Flag for process exit on signal + +void set_do_exit(int sig) { + do_exit = 1; +} + +using namespace ublox; + +int ubloxd_main(poll_ubloxraw_msg_func poll_func, send_gps_event_func send_func) { + LOGW("starting ubloxd"); + signal(SIGINT, (sighandler_t) set_do_exit); + signal(SIGTERM, (sighandler_t) set_do_exit); + + UbloxMsgParser parser; + void *context = zmq_ctx_new(); + void *gpsLocationExternal = zmq_socket(context, ZMQ_PUB); + zmq_bind(gpsLocationExternal, "tcp://*:8032"); + void *ubloxGnss = zmq_socket(context, ZMQ_PUB); + zmq_bind(ubloxGnss, "tcp://*:8033"); + // ubloxRaw = 8042 + void *subscriber = zmq_socket(context, ZMQ_SUB); + zmq_setsockopt(subscriber, ZMQ_SUBSCRIBE, "", 0); + zmq_connect(subscriber, "tcp://127.0.0.1:8042"); + while (!do_exit) { + zmq_msg_t msg; + zmq_msg_init(&msg); + int err = poll_func(gpsLocationExternal, ubloxGnss, subscriber, &msg); + if(err < 0) { + LOGE_100("zmq_poll error %s in %s", strerror(errno ), __FUNCTION__); + break; + } else if(err == 0) { + continue; + } + // format for board, make copy due to alignment issues, will be freed on out of scope + auto amsg = kj::heapArray((zmq_msg_size(&msg) / sizeof(capnp::word)) + 1); + memcpy(amsg.begin(), zmq_msg_data(&msg), zmq_msg_size(&msg)); + capnp::FlatArrayMessageReader cmsg(amsg); + cereal::Event::Reader event = cmsg.getRoot(); + const uint8_t *data = event.getUbloxRaw().begin(); + size_t len = event.getUbloxRaw().size(); + size_t bytes_consumed = 0; + while(bytes_consumed < len && !do_exit) { + size_t bytes_consumed_this_time = 0U; + if(parser.add_data(data + bytes_consumed, (uint32_t)(len - bytes_consumed), bytes_consumed_this_time)) { + // New message available + if(parser.msg_class() == CLASS_NAV) { + if(parser.msg_id() == MSG_NAV_PVT) { + LOGD("MSG_NAV_PVT"); + auto words = parser.gen_solution(); + if(words.size() > 0) { + auto bytes = words.asBytes(); + send_func(parser.msg_class(), parser.msg_id(), gpsLocationExternal, bytes.begin(), bytes.size(), 0); + } + } else + LOGW("Unknown nav msg id: 0x%02X", parser.msg_id()); + } else if(parser.msg_class() == CLASS_RXM) { + if(parser.msg_id() == MSG_RXM_RAW) { + LOGD("MSG_RXM_RAW"); + auto words = parser.gen_raw(); + if(words.size() > 0) { + auto bytes = words.asBytes(); + send_func(parser.msg_class(), parser.msg_id(), ubloxGnss, bytes.begin(), bytes.size(), 0); + } + } else if(parser.msg_id() == MSG_RXM_SFRBX) { + LOGD("MSG_RXM_SFRBX"); + auto words = parser.gen_nav_data(); + if(words.size() > 0) { + auto bytes = words.asBytes(); + send_func(parser.msg_class(), parser.msg_id(), ubloxGnss, bytes.begin(), bytes.size(), 0); + } + } else + LOGW("Unknown rxm msg id: 0x%02X", parser.msg_id()); + } else + LOGW("Unknown msg class: 0x%02X", parser.msg_class()); + parser.reset(); + } + bytes_consumed += bytes_consumed_this_time; + } + zmq_msg_close(&msg); + } + zmq_close(subscriber); + zmq_close(gpsLocationExternal); + zmq_close(ubloxGnss); + zmq_ctx_destroy(context); + return 0; +} diff --git a/selfdrive/locationd/ubloxd_test.cc b/selfdrive/locationd/ubloxd_test.cc new file mode 100644 index 000000000..a1395fa59 --- /dev/null +++ b/selfdrive/locationd/ubloxd_test.cc @@ -0,0 +1,103 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include "cereal/gen/cpp/log.capnp.h" + +#include "common/params.h" +#include "common/swaglog.h" +#include "common/timing.h" +#include "common/util.h" +#include "ublox_msg.h" + +using namespace ublox; + +void write_file(std::string fpath, uint8_t *data, int len) { + FILE* f = fopen(fpath.c_str(), "wb"); + if (!f) { + std::cout << "Open " << fpath << " failed" << std::endl; + return; + } + fwrite(data, len, 1, f); + fclose(f); +} + +static size_t len = 0U; +static size_t consumed = 0U; +static uint8_t *data = NULL; +static int save_idx = 0; +static std::string prefix; +static void *gps_sock, *ublox_gnss_sock; + +int poll_ubloxraw_msg(void *gpsLocationExternal, void *ubloxGnss, void *subscriber, zmq_msg_t *msg) { + gps_sock = gpsLocationExternal; + ublox_gnss_sock = ubloxGnss; + size_t consuming = min(len - consumed, 128); + if(consumed < len) { + // create message + capnp::MallocMessageBuilder msg_builder; + cereal::Event::Builder event = msg_builder.initRoot(); + event.setLogMonoTime(nanos_since_boot()); + auto ublox_raw = event.initUbloxRaw(consuming); + memcpy(ublox_raw.begin(), (void *)(data + consumed), consuming); + auto words = capnp::messageToFlatArray(msg_builder); + auto bytes = words.asBytes(); + zmq_msg_init_size (msg, bytes.size()); + memcpy (zmq_msg_data(msg), (void *)bytes.begin(), bytes.size()); + consumed += consuming; + return 1; + } else + return -1; +} + +int send_gps_event(uint8_t msg_cls, uint8_t msg_id, void *s, const void *buf, size_t len, int flags) { + if(msg_cls == CLASS_NAV && msg_id == MSG_NAV_PVT) + assert(s == gps_sock); + else if(msg_cls == CLASS_RXM && msg_id == MSG_RXM_RAW) + assert(s == ublox_gnss_sock); + else if(msg_cls == CLASS_RXM && msg_id == MSG_RXM_SFRBX) + assert(s == ublox_gnss_sock); + else + assert(0); + write_file(prefix + "/" + std::to_string(save_idx), (uint8_t *)buf, len); + save_idx ++; + return len; +} + +int main(int argc, char** argv) { + if(argc < 3) { + printf("Format: ubloxd_test stream_file_path save_prefix\n"); + return 0; + } + // Parse 11360 msgs, generate 9452 events + data = (uint8_t *)read_file(argv[1], &len); + if(data == NULL) { + LOGE("Read file %s failed\n", argv[1]); + return -1; + } + prefix = argv[2]; + ubloxd_main(poll_ubloxraw_msg, send_gps_event); + free(data); + printf("Generated %d cereal events\n", save_idx); + if(save_idx != 9452) { + printf("Event count error: %d\n", save_idx); + return -1; + } + return 0; +} diff --git a/selfdrive/loggerd/loggerd b/selfdrive/loggerd/loggerd index 23f499602b23a68bac63b20811e9c74ae2fa7d81..788a29b705337d93e3566acbd20fc4fa34f87580 100755 GIT binary patch delta 77 zcmaEHH2KBRF7M2#)7Pc1l7LFFq7OocV7M>Q~7QPn#7J(MQEkdd%7!BLi ZP6z?9Fc6CXu_zFW0kQaYwG$GDqyR-m8?^uc delta 77 zcmaEHH2KBRF7M2#)7Pc1l7LFFq7OocV7M>Q~7QPn#7J(MQEkdd%7!BIh ZP6z?9Fc6CXu_zFW0kQaYwG$GDqyR-H8?*ob diff --git a/selfdrive/manager.py b/selfdrive/manager.py index 71469461c..8d4664090 100755 --- a/selfdrive/manager.py +++ b/selfdrive/manager.py @@ -91,7 +91,7 @@ managed_processes = { "controlsd": "selfdrive.controls.controlsd", "plannerd": "selfdrive.controls.plannerd", "radard": "selfdrive.controls.radard", - "ubloxd": "selfdrive.locationd.ubloxd", + "ubloxd": ("selfdrive/locationd", ["./ubloxd"]), "mapd": "selfdrive.mapd.mapd", "loggerd": ("selfdrive/loggerd", ["./loggerd"]), "logmessaged": "selfdrive.logmessaged", diff --git a/selfdrive/mapd/mapd.py b/selfdrive/mapd/mapd.py index 85303857a..86884d860 100755 --- a/selfdrive/mapd/mapd.py +++ b/selfdrive/mapd/mapd.py @@ -121,7 +121,7 @@ def query_thread(): query_lock.release() except Exception as e: - print e + print(e) query_lock.acquire() last_query_result = None query_lock.release() diff --git a/selfdrive/orbd/.gitignore b/selfdrive/orbd/.gitignore deleted file mode 100644 index 829780eb5..000000000 --- a/selfdrive/orbd/.gitignore +++ /dev/null @@ -1,8 +0,0 @@ -orbd -orbd_cpu -test/turbocv_profile -test/turbocv_test -dspout/* -dumb_test -bilinear_lut.h -orb_lut.h diff --git a/selfdrive/orbd/Makefile b/selfdrive/orbd/Makefile deleted file mode 100644 index 32e9c6dfa..000000000 --- a/selfdrive/orbd/Makefile +++ /dev/null @@ -1,105 +0,0 @@ -# CPU - -CC = clang -CXX = clang++ - -WARN_FLAGS = -Werror=implicit-function-declaration \ - -Werror=incompatible-pointer-types \ - -Werror=int-conversion \ - -Werror=return-type \ - -Werror=format-extra-args - -JSON_FLAGS = -I$(PHONELIBS)/json/src - -CFLAGS = -std=gnu11 -g -O2 -fPIC $(WARN_FLAGS) -Iinclude $(JSON_FLAGS) -I. -CXXFLAGS = -std=c++11 -g -O2 -fPIC $(WARN_FLAGS) -Iinclude $(JSON_FLAGS) -I. -LDFLAGS = - -# profile -# CXXFLAGS += -DTURBOCV_PROFILE=1 - -PHONELIBS = ../../phonelibs -BASEDIR = ../.. -EXTERNAL = ../../external -PYTHONLIBS = - -UNAME_M := $(shell uname -m) - -ifeq ($(UNAME_M),x86_64) -# computer - -ZMQ_FLAGS = -I$(PHONELIBS)/zmq/aarch64/include -ZMQ_LIBS = -L$(BASEDIR)/external/zmq/lib/ \ - -l:libczmq.a -l:libzmq.a -lpthread - -OPENCV_LIBS = -lopencv_core -lopencv_highgui -lopencv_features2d -lopencv_imgproc - -CXXFLAGS += -fopenmp -LDFLAGS += -lomp - -else -# phone -ZMQ_FLAGS = -I$(PHONELIBS)/zmq/aarch64/include -ZMQ_LIBS = -L$(PHONELIBS)/zmq/aarch64/lib \ - -l:libczmq.a -l:libzmq.a \ - -lgnustl_shared - -OPENCV_FLAGS = -I$(PHONELIBS)/opencv/include -OPENCV_LIBS = -Wl,--enable-new-dtags -Wl,-rpath,/usr/local/lib/python2.7/site-packages -L/usr/local/lib/python2.7/site-packages -l:cv2.so - -endif - -.PHONY: all -all: orbd - -include ../common/cereal.mk - -DEP_OBJS = ../common/visionipc.o ../common/ipc.o ../common/swaglog.o $(PHONELIBS)/json/src/json.o - -orbd: orbd_dsp.o $(DEP_OBJS) calculator_stub.o freethedsp.o - @echo "[ LINK ] $@" - $(CXX) -fPIC -o '$@' $^ \ - $(LDFLAGS) \ - $(ZMQ_LIBS) \ - $(CEREAL_LIBS) \ - -L/usr/lib \ - -L/system/vendor/lib64 \ - -ladsprpc \ - -lm -lz -llog - -%.o: %.c - @echo "[ CC ] $@" - $(CC) $(CFLAGS) \ - $(ZMQ_FLAGS) \ - -I../ \ - -I../../ \ - -c -o '$@' '$<' - -orbd_dsp.o: orbd.cc - @echo "[ CXX ] $@" - $(CXX) $(CXXFLAGS) \ - $(CEREAL_CXXFLAGS) \ - $(ZMQ_FLAGS) \ - $(OPENCV_FLAGS) \ - -DDSP \ - -I../ \ - -I../../ \ - -I../../../ \ - -I./include \ - -c -o '$@' '$<' - -freethedsp.o: dsp/freethedsp.c - @echo "[ CC ] $@" - $(CC) $(CFLAGS) \ - -c -o '$@' '$<' - -calculator_stub.o: dsp/gen/calculator_stub.c - @echo "[ CC ] $@" - $(CC) $(CFLAGS) -I./include -c -o '$@' '$<' - --include internal.mk - -.PHONY: clean -clean: - rm -f *.o turbocv.so orbd test/turbocv_profile test/turbocv_test test/*.o *_lut.h - diff --git a/selfdrive/orbd/dsp/freethedsp.c b/selfdrive/orbd/dsp/freethedsp.c deleted file mode 100644 index 298f4fd83..000000000 --- a/selfdrive/orbd/dsp/freethedsp.c +++ /dev/null @@ -1,119 +0,0 @@ -// freethedsp by geohot -// (because the DSP should be free) -// released under MIT License - -// usage instructions: -// 1. Compile an example from the Qualcomm Hexagon SDK -// 2. Try to run it on your phone -// 3. Be very sad when "adsprpc ... dlopen error: ... signature verify start failed for ..." appears in logcat -// ...here is where people would give up before freethedsp -// 4. Compile freethedsp with 'clang -shared freethedsp.c -o freethedsp.so' (or statically link it to your program) -// 5. Run your program with 'LD_PRELOAD=./freethedsp.so ./' -// 6. OMG THE DSP WORKS -// 7. Be happy. - -// *** patch may have to change for your phone *** - -// this is patching /dsp/fastrpc_shell_0 -// correct if sha hash of fastrpc_shell_0 is "fbadc96848aefad99a95aa4edb560929dcdf78f8" -// patch to return 0xFFFFFFFF from is_test_enabled instead of 0 -// your fastrpc_shell_0 may vary -#define PATCH_ADDR 0x5200c -#define PATCH_OLD "\x40\x3f\x20\x50" -#define PATCH_NEW "\x40\x3f\x00\x5a" -#define PATCH_LEN (sizeof(PATCH_OLD)-1) -#define _BITS_IOCTL_H_ - -// under 100 lines of code begins now -#include -#include -#include -#include -#include - -// ioctl stuff -#define IOC_OUT 0x40000000 /* copy out parameters */ -#define IOC_IN 0x80000000 /* copy in parameters */ -#define IOC_INOUT (IOC_IN|IOC_OUT) -#define IOCPARM_MASK 0x1fff /* parameter length, at most 13 bits */ - -#define _IOC(inout,group,num,len) \ - (inout | ((len & IOCPARM_MASK) << 16) | ((group) << 8) | (num)) -#define _IOWR(g,n,t) _IOC(IOC_INOUT, (g), (n), sizeof(t)) - -// ion ioctls -#include -#define ION_IOC_MSM_MAGIC 'M' -#define ION_IOC_CLEAN_INV_CACHES _IOWR(ION_IOC_MSM_MAGIC, 2, \ - struct ion_flush_data) - -struct ion_flush_data { - ion_user_handle_t handle; - int fd; - void *vaddr; - unsigned int offset; - unsigned int length; -}; - -// fastrpc ioctls -#define FASTRPC_IOCTL_INIT _IOWR('R', 6, struct fastrpc_ioctl_init) - -struct fastrpc_ioctl_init { - uint32_t flags; /* one of FASTRPC_INIT_* macros */ - uintptr_t __user file; /* pointer to elf file */ - int32_t filelen; /* elf file length */ - int32_t filefd; /* ION fd for the file */ - uintptr_t __user mem; /* mem for the PD */ - int32_t memlen; /* mem length */ - int32_t memfd; /* ION fd for the mem */ -}; - -int ioctl(int fd, unsigned long request, void *arg) { - static void *handle = NULL; - static int (*orig_ioctl)(int, int, void*); - - if (handle == NULL) { - handle = dlopen("/system/lib64/libc.so", RTLD_LAZY); - assert(handle != NULL); - orig_ioctl = dlsym(handle, "ioctl"); - } - - int ret = orig_ioctl(fd, request, arg); - - // carefully modify this one - if (request == FASTRPC_IOCTL_INIT) { - struct fastrpc_ioctl_init *init = (struct fastrpc_ioctl_init *)arg; - - // confirm patch is correct and do the patch - assert(memcmp((void*)(init->mem+PATCH_ADDR), PATCH_OLD, PATCH_LEN) == 0); - memcpy((void*)(init->mem+PATCH_ADDR), PATCH_NEW, PATCH_LEN); - - // flush cache - int ionfd = open("/dev/ion", O_RDONLY); - assert(ionfd > 0); - - struct ion_fd_data fd_data; - fd_data.fd = init->memfd; - int ret = ioctl(ionfd, ION_IOC_IMPORT, &fd_data); - assert(ret == 0); - - struct ion_flush_data flush_data; - flush_data.handle = fd_data.handle; - flush_data.vaddr = (void*)init->mem; - flush_data.offset = 0; - flush_data.length = init->memlen; - ret = ioctl(ionfd, ION_IOC_CLEAN_INV_CACHES, &flush_data); - assert(ret == 0); - - struct ion_handle_data handle_data; - handle_data.handle = fd_data.handle; - ret = ioctl(ionfd, ION_IOC_FREE, &handle_data); - assert(ret == 0); - - // cleanup - close(ionfd); - } - - return ret; -} - diff --git a/selfdrive/orbd/dsp/gen/calculator.h b/selfdrive/orbd/dsp/gen/calculator.h deleted file mode 100644 index 86a3de671..000000000 --- a/selfdrive/orbd/dsp/gen/calculator.h +++ /dev/null @@ -1,39 +0,0 @@ -#ifndef _CALCULATOR_H -#define _CALCULATOR_H - -#include -typedef uint8_t uint8; -typedef uint32_t uint32; - -#ifndef __QAIC_HEADER -#define __QAIC_HEADER(ff) ff -#endif //__QAIC_HEADER - -#ifndef __QAIC_HEADER_EXPORT -#define __QAIC_HEADER_EXPORT -#endif // __QAIC_HEADER_EXPORT - -#ifndef __QAIC_HEADER_ATTRIBUTE -#define __QAIC_HEADER_ATTRIBUTE -#endif // __QAIC_HEADER_ATTRIBUTE - -#ifndef __QAIC_IMPL -#define __QAIC_IMPL(ff) ff -#endif //__QAIC_IMPL - -#ifndef __QAIC_IMPL_EXPORT -#define __QAIC_IMPL_EXPORT -#endif // __QAIC_IMPL_EXPORT - -#ifndef __QAIC_IMPL_ATTRIBUTE -#define __QAIC_IMPL_ATTRIBUTE -#endif // __QAIC_IMPL_ATTRIBUTE -#ifdef __cplusplus -extern "C" { -#endif -__QAIC_HEADER_EXPORT int __QAIC_HEADER(calculator_init)(uint32* leet) __QAIC_HEADER_ATTRIBUTE; -__QAIC_HEADER_EXPORT int __QAIC_HEADER(calculator_extract_and_match)(const uint8* img, int imgLen, uint8* features, int featuresLen) __QAIC_HEADER_ATTRIBUTE; -#ifdef __cplusplus -} -#endif -#endif //_CALCULATOR_H diff --git a/selfdrive/orbd/dsp/gen/calculator_stub.c b/selfdrive/orbd/dsp/gen/calculator_stub.c deleted file mode 100644 index 66e4a0f82..000000000 --- a/selfdrive/orbd/dsp/gen/calculator_stub.c +++ /dev/null @@ -1,613 +0,0 @@ -#ifndef _CALCULATOR_STUB_H -#define _CALCULATOR_STUB_H -#include "calculator.h" - -// remote.h -#include -#include - -typedef uint32_t remote_handle; -typedef uint64_t remote_handle64; - -typedef struct { - void *pv; - size_t nLen; -} remote_buf; - -typedef struct { - int32_t fd; - uint32_t offset; -} remote_dma_handle; - -typedef union { - remote_buf buf; - remote_handle h; - remote_handle64 h64; - remote_dma_handle dma; -} remote_arg; - -int remote_handle_open(const char* name, remote_handle *ph); -int remote_handle_invoke(remote_handle h, uint32_t dwScalars, remote_arg *pra); -int remote_handle_close(remote_handle h); - -#define REMOTE_SCALARS_MAKEX(nAttr,nMethod,nIn,nOut,noIn,noOut) \ - ((((uint32_t) (nAttr) & 0x7) << 29) | \ - (((uint32_t) (nMethod) & 0x1f) << 24) | \ - (((uint32_t) (nIn) & 0xff) << 16) | \ - (((uint32_t) (nOut) & 0xff) << 8) | \ - (((uint32_t) (noIn) & 0x0f) << 4) | \ - ((uint32_t) (noOut) & 0x0f)) - -#ifndef _QAIC_ENV_H -#define _QAIC_ENV_H - -#ifdef __GNUC__ -#ifdef __clang__ -#pragma GCC diagnostic ignored "-Wunknown-pragmas" -#else -#pragma GCC diagnostic ignored "-Wpragmas" -#endif -#pragma GCC diagnostic ignored "-Wuninitialized" -#pragma GCC diagnostic ignored "-Wunused-parameter" -#pragma GCC diagnostic ignored "-Wunused-function" -#endif - -#ifndef _ATTRIBUTE_UNUSED - -#ifdef _WIN32 -#define _ATTRIBUTE_UNUSED -#else -#define _ATTRIBUTE_UNUSED __attribute__ ((unused)) -#endif - -#endif // _ATTRIBUTE_UNUSED - -#ifndef __QAIC_REMOTE -#define __QAIC_REMOTE(ff) ff -#endif //__QAIC_REMOTE - -#ifndef __QAIC_HEADER -#define __QAIC_HEADER(ff) ff -#endif //__QAIC_HEADER - -#ifndef __QAIC_HEADER_EXPORT -#define __QAIC_HEADER_EXPORT -#endif // __QAIC_HEADER_EXPORT - -#ifndef __QAIC_HEADER_ATTRIBUTE -#define __QAIC_HEADER_ATTRIBUTE -#endif // __QAIC_HEADER_ATTRIBUTE - -#ifndef __QAIC_IMPL -#define __QAIC_IMPL(ff) ff -#endif //__QAIC_IMPL - -#ifndef __QAIC_IMPL_EXPORT -#define __QAIC_IMPL_EXPORT -#endif // __QAIC_IMPL_EXPORT - -#ifndef __QAIC_IMPL_ATTRIBUTE -#define __QAIC_IMPL_ATTRIBUTE -#endif // __QAIC_IMPL_ATTRIBUTE - -#ifndef __QAIC_STUB -#define __QAIC_STUB(ff) ff -#endif //__QAIC_STUB - -#ifndef __QAIC_STUB_EXPORT -#define __QAIC_STUB_EXPORT -#endif // __QAIC_STUB_EXPORT - -#ifndef __QAIC_STUB_ATTRIBUTE -#define __QAIC_STUB_ATTRIBUTE -#endif // __QAIC_STUB_ATTRIBUTE - -#ifndef __QAIC_SKEL -#define __QAIC_SKEL(ff) ff -#endif //__QAIC_SKEL__ - -#ifndef __QAIC_SKEL_EXPORT -#define __QAIC_SKEL_EXPORT -#endif // __QAIC_SKEL_EXPORT - -#ifndef __QAIC_SKEL_ATTRIBUTE -#define __QAIC_SKEL_ATTRIBUTE -#endif // __QAIC_SKEL_ATTRIBUTE - -#ifdef __QAIC_DEBUG__ - #ifndef __QAIC_DBG_PRINTF__ - #include - #define __QAIC_DBG_PRINTF__( ee ) do { printf ee ; } while(0) - #endif -#else - #define __QAIC_DBG_PRINTF__( ee ) (void)0 -#endif - - -#define _OFFSET(src, sof) ((void*)(((char*)(src)) + (sof))) - -#define _COPY(dst, dof, src, sof, sz) \ - do {\ - struct __copy { \ - char ar[sz]; \ - };\ - *(struct __copy*)_OFFSET(dst, dof) = *(struct __copy*)_OFFSET(src, sof);\ - } while (0) - -#define _COPYIF(dst, dof, src, sof, sz) \ - do {\ - if(_OFFSET(dst, dof) != _OFFSET(src, sof)) {\ - _COPY(dst, dof, src, sof, sz); \ - } \ - } while (0) - -_ATTRIBUTE_UNUSED -static __inline void _qaic_memmove(void* dst, void* src, int size) { - int i; - for(i = 0; i < size; ++i) { - ((char*)dst)[i] = ((char*)src)[i]; - } -} - -#define _MEMMOVEIF(dst, src, sz) \ - do {\ - if(dst != src) {\ - _qaic_memmove(dst, src, sz);\ - } \ - } while (0) - - -#define _ASSIGN(dst, src, sof) \ - do {\ - dst = OFFSET(src, sof); \ - } while (0) - -#define _STD_STRLEN_IF(str) (str == 0 ? 0 : strlen(str)) - -#define AEE_SUCCESS 0 -#define AEE_EOFFSET 0x80000400 -#define AEE_EBADPARM (AEE_EOFFSET + 0x00E) - -#define _TRY(ee, func) \ - do { \ - if (AEE_SUCCESS != ((ee) = func)) {\ - __QAIC_DBG_PRINTF__((__FILE__ ":%d:error:%d:%s\n", __LINE__, (int)(ee),#func));\ - goto ee##bail;\ - } \ - } while (0) - -#define _CATCH(exception) exception##bail: if (exception != AEE_SUCCESS) - -#define _ASSERT(nErr, ff) _TRY(nErr, 0 == (ff) ? AEE_EBADPARM : AEE_SUCCESS) - -#ifdef __QAIC_DEBUG__ -#define _ALLOCATE(nErr, pal, size, alignment, pv) _TRY(nErr, _allocator_alloc(pal, __FILE_LINE__, size, alignment, (void**)&pv)) -#else -#define _ALLOCATE(nErr, pal, size, alignment, pv) _TRY(nErr, _allocator_alloc(pal, 0, size, alignment, (void**)&pv)) -#endif - - -#endif // _QAIC_ENV_H - -#ifndef _ALLOCATOR_H -#define _ALLOCATOR_H - -#include -#include - -typedef struct _heap _heap; -struct _heap { - _heap* pPrev; - const char* loc; - uint64_t buf; -}; - -typedef struct _allocator { - _heap* pheap; - uint8_t* stack; - uint8_t* stackEnd; - int nSize; -} _allocator; - -_ATTRIBUTE_UNUSED -static __inline int _heap_alloc(_heap** ppa, const char* loc, int size, void** ppbuf) { - _heap* pn = 0; - pn = malloc(size + sizeof(_heap) - sizeof(uint64_t)); - if(pn != 0) { - pn->pPrev = *ppa; - pn->loc = loc; - *ppa = pn; - *ppbuf = (void*)&(pn->buf); - return 0; - } else { - return -1; - } -} -#define _ALIGN_SIZE(x, y) (((x) + (y-1)) & ~(y-1)) - -_ATTRIBUTE_UNUSED -static __inline int _allocator_alloc(_allocator* me, - const char* loc, - int size, - unsigned int al, - void** ppbuf) { - if(size < 0) { - return -1; - } else if (size == 0) { - *ppbuf = 0; - return 0; - } - if((_ALIGN_SIZE((uintptr_t)me->stackEnd, al) + size) < (uintptr_t)me->stack + me->nSize) { - *ppbuf = (uint8_t*)_ALIGN_SIZE((uintptr_t)me->stackEnd, al); - me->stackEnd = (uint8_t*)_ALIGN_SIZE((uintptr_t)me->stackEnd, al) + size; - return 0; - } else { - return _heap_alloc(&me->pheap, loc, size, ppbuf); - } -} - -_ATTRIBUTE_UNUSED -static __inline void _allocator_deinit(_allocator* me) { - _heap* pa = me->pheap; - while(pa != 0) { - _heap* pn = pa; - const char* loc = pn->loc; - (void)loc; - pa = pn->pPrev; - free(pn); - } -} - -_ATTRIBUTE_UNUSED -static __inline void _allocator_init(_allocator* me, uint8_t* stack, int stackSize) { - me->stack = stack; - me->stackEnd = stack + stackSize; - me->nSize = stackSize; - me->pheap = 0; -} - - -#endif // _ALLOCATOR_H - -#ifndef SLIM_H -#define SLIM_H - -#include - -//a C data structure for the idl types that can be used to implement -//static and dynamic language bindings fairly efficiently. -// -//the goal is to have a minimal ROM and RAM footprint and without -//doing too many allocations. A good way to package these things seemed -//like the module boundary, so all the idls within one module can share -//all the type references. - - -#define PARAMETER_IN 0x0 -#define PARAMETER_OUT 0x1 -#define PARAMETER_INOUT 0x2 -#define PARAMETER_ROUT 0x3 -#define PARAMETER_INROUT 0x4 - -//the types that we get from idl -#define TYPE_OBJECT 0x0 -#define TYPE_INTERFACE 0x1 -#define TYPE_PRIMITIVE 0x2 -#define TYPE_ENUM 0x3 -#define TYPE_STRING 0x4 -#define TYPE_WSTRING 0x5 -#define TYPE_STRUCTURE 0x6 -#define TYPE_UNION 0x7 -#define TYPE_ARRAY 0x8 -#define TYPE_SEQUENCE 0x9 - -//these require the pack/unpack to recurse -//so it's a hint to those languages that can optimize in cases where -//recursion isn't necessary. -#define TYPE_COMPLEX_STRUCTURE (0x10 | TYPE_STRUCTURE) -#define TYPE_COMPLEX_UNION (0x10 | TYPE_UNION) -#define TYPE_COMPLEX_ARRAY (0x10 | TYPE_ARRAY) -#define TYPE_COMPLEX_SEQUENCE (0x10 | TYPE_SEQUENCE) - - -typedef struct Type Type; - -#define INHERIT_TYPE\ - int32_t nativeSize; /*in the simple case its the same as wire size and alignment*/\ - union {\ - struct {\ - const uintptr_t p1;\ - const uintptr_t p2;\ - } _cast;\ - struct {\ - uint32_t iid;\ - uint32_t bNotNil;\ - } object;\ - struct {\ - const Type *arrayType;\ - int32_t nItems;\ - } array;\ - struct {\ - const Type *seqType;\ - int32_t nMaxLen;\ - } seqSimple; \ - struct {\ - uint32_t bFloating;\ - uint32_t bSigned;\ - } prim; \ - const SequenceType* seqComplex;\ - const UnionType *unionType;\ - const StructType *structType;\ - int32_t stringMaxLen;\ - uint8_t bInterfaceNotNil;\ - } param;\ - uint8_t type;\ - uint8_t nativeAlignment\ - -typedef struct UnionType UnionType; -typedef struct StructType StructType; -typedef struct SequenceType SequenceType; -struct Type { - INHERIT_TYPE; -}; - -struct SequenceType { - const Type * seqType; - uint32_t nMaxLen; - uint32_t inSize; - uint32_t routSizePrimIn; - uint32_t routSizePrimROut; -}; - -//byte offset from the start of the case values for -//this unions case value array. it MUST be aligned -//at the alignment requrements for the descriptor -// -//if negative it means that the unions cases are -//simple enumerators, so the value read from the descriptor -//can be used directly to find the correct case -typedef union CaseValuePtr CaseValuePtr; -union CaseValuePtr { - const uint8_t* value8s; - const uint16_t* value16s; - const uint32_t* value32s; - const uint64_t* value64s; -}; - -//these are only used in complex cases -//so I pulled them out of the type definition as references to make -//the type smaller -struct UnionType { - const Type *descriptor; - uint32_t nCases; - const CaseValuePtr caseValues; - const Type * const *cases; - int32_t inSize; - int32_t routSizePrimIn; - int32_t routSizePrimROut; - uint8_t inAlignment; - uint8_t routAlignmentPrimIn; - uint8_t routAlignmentPrimROut; - uint8_t inCaseAlignment; - uint8_t routCaseAlignmentPrimIn; - uint8_t routCaseAlignmentPrimROut; - uint8_t nativeCaseAlignment; - uint8_t bDefaultCase; -}; - -struct StructType { - uint32_t nMembers; - const Type * const *members; - int32_t inSize; - int32_t routSizePrimIn; - int32_t routSizePrimROut; - uint8_t inAlignment; - uint8_t routAlignmentPrimIn; - uint8_t routAlignmentPrimROut; -}; - -typedef struct Parameter Parameter; -struct Parameter { - INHERIT_TYPE; - uint8_t mode; - uint8_t bNotNil; -}; - -#define SLIM_IFPTR32(is32,is64) (sizeof(uintptr_t) == 4 ? (is32) : (is64)) -#define SLIM_SCALARS_IS_DYNAMIC(u) (((u) & 0x00ffffff) == 0x00ffffff) - -typedef struct Method Method; -struct Method { - uint32_t uScalars; //no method index - int32_t primInSize; - int32_t primROutSize; - int maxArgs; - int numParams; - const Parameter * const *params; - uint8_t primInAlignment; - uint8_t primROutAlignment; -}; - -typedef struct Interface Interface; - -struct Interface { - int nMethods; - const Method * const *methodArray; - int nIIds; - const uint32_t *iids; - const uint16_t* methodStringArray; - const uint16_t* methodStrings; - const char* strings; -}; - - -#endif //SLIM_H - - -#ifndef _CALCULATOR_SLIM_H -#define _CALCULATOR_SLIM_H - -// remote.h - -#include - -#ifndef __QAIC_SLIM -#define __QAIC_SLIM(ff) ff -#endif -#ifndef __QAIC_SLIM_EXPORT -#define __QAIC_SLIM_EXPORT -#endif - -static const Type types[1]; -static const Type types[1] = {{0x1,{{(const uintptr_t)0,(const uintptr_t)0}}, 2,0x1}}; -static const Parameter parameters[3] = {{0x4,{{(const uintptr_t)0,(const uintptr_t)0}}, 2,0x4,3,0},{SLIM_IFPTR32(0x8,0x10),{{(const uintptr_t)&(types[0]),(const uintptr_t)0x0}}, 9,SLIM_IFPTR32(0x4,0x8),0,0},{SLIM_IFPTR32(0x8,0x10),{{(const uintptr_t)&(types[0]),(const uintptr_t)0x0}}, 9,SLIM_IFPTR32(0x4,0x8),3,0}}; -static const Parameter* const parameterArrays[3] = {(&(parameters[1])),(&(parameters[2])),(&(parameters[0]))}; -static const Method methods[2] = {{REMOTE_SCALARS_MAKEX(0,0,0x0,0x1,0x0,0x0),0x0,0x4,1,1,(&(parameterArrays[2])),0x1,0x4},{REMOTE_SCALARS_MAKEX(0,0,0x2,0x1,0x0,0x0),0x8,0x0,5,2,(&(parameterArrays[0])),0x4,0x1}}; -static const Method* const methodArrays[2] = {&(methods[0]),&(methods[1])}; -static const char strings[41] = "extract_and_match\0features\0leet\0init\0img\0"; -static const uint16_t methodStrings[5] = {0,37,18,32,27}; -static const uint16_t methodStringsArrays[2] = {3,0}; -__QAIC_SLIM_EXPORT const Interface __QAIC_SLIM(calculator_slim) = {2,&(methodArrays[0]),0,0,&(methodStringsArrays [0]),methodStrings,strings}; -#endif //_CALCULATOR_SLIM_H -#ifdef __cplusplus -extern "C" { -#endif - -#ifndef _const_calculator_handle -#define _const_calculator_handle ((remote_handle)-1) -#endif //_const_calculator_handle - -static void _calculator_pls_dtor(void* data) { - remote_handle* ph = (remote_handle*)data; - if(_const_calculator_handle != *ph) { - (void)__QAIC_REMOTE(remote_handle_close)(*ph); - *ph = _const_calculator_handle; - } -} - -static int _calculator_pls_ctor(void* ctx, void* data) { - remote_handle* ph = (remote_handle*)data; - *ph = _const_calculator_handle; - if(*ph == (remote_handle)-1) { - return __QAIC_REMOTE(remote_handle_open)((const char*)ctx, ph); - } - return 0; -} - -#if (defined __qdsp6__) || (defined __hexagon__) -#pragma weak adsp_pls_add_lookup -extern int adsp_pls_add_lookup(uint32_t type, uint32_t key, int size, int (*ctor)(void* ctx, void* data), void* ctx, void (*dtor)(void* ctx), void** ppo); -#pragma weak HAP_pls_add_lookup -extern int HAP_pls_add_lookup(uint32_t type, uint32_t key, int size, int (*ctor)(void* ctx, void* data), void* ctx, void (*dtor)(void* ctx), void** ppo); - -__QAIC_STUB_EXPORT remote_handle _calculator_handle(void) { - remote_handle* ph; - if(adsp_pls_add_lookup) { - if(0 == adsp_pls_add_lookup((uint32_t)_calculator_handle, 0, sizeof(*ph), _calculator_pls_ctor, "calculator", _calculator_pls_dtor, (void**)&ph)) { - return *ph; - } - return (remote_handle)-1; - } else if(HAP_pls_add_lookup) { - if(0 == HAP_pls_add_lookup((uint32_t)_calculator_handle, 0, sizeof(*ph), _calculator_pls_ctor, "calculator", _calculator_pls_dtor, (void**)&ph)) { - return *ph; - } - return (remote_handle)-1; - } - return(remote_handle)-1; -} - -#else //__qdsp6__ || __hexagon__ - -uint32_t _calculator_atomic_CompareAndExchange(uint32_t * volatile puDest, uint32_t uExchange, uint32_t uCompare); - -#ifdef _WIN32 -#include "Windows.h" -uint32_t _calculator_atomic_CompareAndExchange(uint32_t * volatile puDest, uint32_t uExchange, uint32_t uCompare) { - return (uint32_t)InterlockedCompareExchange((volatile LONG*)puDest, (LONG)uExchange, (LONG)uCompare); -} -#elif __GNUC__ -uint32_t _calculator_atomic_CompareAndExchange(uint32_t * volatile puDest, uint32_t uExchange, uint32_t uCompare) { - return __sync_val_compare_and_swap(puDest, uCompare, uExchange); -} -#endif //_WIN32 - - -__QAIC_STUB_EXPORT remote_handle _calculator_handle(void) { - static remote_handle handle = _const_calculator_handle; - if((remote_handle)-1 != handle) { - return handle; - } else { - remote_handle tmp; - int nErr = _calculator_pls_ctor("calculator", (void*)&tmp); - if(nErr) { - return (remote_handle)-1; - } - if(((remote_handle)-1 != handle) || ((remote_handle)-1 != (remote_handle)_calculator_atomic_CompareAndExchange((uint32_t*)&handle, (uint32_t)tmp, (uint32_t)-1))) { - _calculator_pls_dtor(&tmp); - } - return handle; - } -} - -#endif //__qdsp6__ - -__QAIC_STUB_EXPORT int __QAIC_STUB(calculator_skel_invoke)(uint32_t _sc, remote_arg* _pra) __QAIC_STUB_ATTRIBUTE { - return __QAIC_REMOTE(remote_handle_invoke)(_calculator_handle(), _sc, _pra); -} - -#ifdef __cplusplus -} -#endif - - -#ifdef __cplusplus -extern "C" { -#endif -extern int remote_register_dma_handle(int, uint32_t); -static __inline int _stub_method(remote_handle _handle, uint32_t _mid, uint32_t _rout0[1]) { - int _numIn[1]; - remote_arg _pra[1]; - uint32_t _primROut[1]; - int _nErr = 0; - _numIn[0] = 0; - _pra[(_numIn[0] + 0)].buf.pv = (void*)_primROut; - _pra[(_numIn[0] + 0)].buf.nLen = sizeof(_primROut); - _TRY(_nErr, __QAIC_REMOTE(remote_handle_invoke)(_handle, REMOTE_SCALARS_MAKEX(0, _mid, 0, 1, 0, 0), _pra)); - _COPY(_rout0, 0, _primROut, 0, 4); - _CATCH(_nErr) {} - return _nErr; -} -__QAIC_STUB_EXPORT int __QAIC_STUB(calculator_init)(uint32* leet) __QAIC_STUB_ATTRIBUTE { - uint32_t _mid = 0; - return _stub_method(_calculator_handle(), _mid, (uint32_t*)leet); -} -static __inline int _stub_method_1(remote_handle _handle, uint32_t _mid, char* _in0[1], uint32_t _in0Len[1], char* _rout1[1], uint32_t _rout1Len[1]) { - int _numIn[1]; - remote_arg _pra[3]; - uint32_t _primIn[2]; - remote_arg* _praIn; - remote_arg* _praROut; - int _nErr = 0; - _numIn[0] = 1; - _pra[0].buf.pv = (void*)_primIn; - _pra[0].buf.nLen = sizeof(_primIn); - _COPY(_primIn, 0, _in0Len, 0, 4); - _praIn = (_pra + 1); - _praIn[0].buf.pv = _in0[0]; - _praIn[0].buf.nLen = (1 * _in0Len[0]); - _COPY(_primIn, 4, _rout1Len, 0, 4); - _praROut = (_praIn + _numIn[0] + 0); - _praROut[0].buf.pv = _rout1[0]; - _praROut[0].buf.nLen = (1 * _rout1Len[0]); - _TRY(_nErr, __QAIC_REMOTE(remote_handle_invoke)(_handle, REMOTE_SCALARS_MAKEX(0, _mid, 2, 1, 0, 0), _pra)); - _CATCH(_nErr) {} - return _nErr; -} -__QAIC_STUB_EXPORT int __QAIC_STUB(calculator_extract_and_match)(const uint8* img, int imgLen, uint8* features, int featuresLen) __QAIC_STUB_ATTRIBUTE { - uint32_t _mid = 1; - return _stub_method_1(_calculator_handle(), _mid, (char**)&img, (uint32_t*)&imgLen, (char**)&features, (uint32_t*)&featuresLen); -} -#ifdef __cplusplus -} -#endif -#endif //_CALCULATOR_STUB_H diff --git a/selfdrive/orbd/dsp/gen/libcalculator_skel.so b/selfdrive/orbd/dsp/gen/libcalculator_skel.so deleted file mode 100755 index e48cab48208b0f00a59988bacb135bd659486146..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 357400 zcmeFadwf*Yz4yQNWoGv5xnvT;B@mJjZULwdiDiQ+^65tDrtBaisJ;=|t6L><2iuk47HVme@bynEvD-@Na1YN3uQmDz`B9 zQz2E}dt^_>Kbn0B!SsjnN7Dw5R3AQl!!+9lyXQt2TK%U{dI9=tT&lljjmTe~VN?0b zVYkm4%Kxp5bh=&x?4DB8(UhvMV?_Gnl#WhrH>A>^9g*HK!hR8U`y|Frp=|2Uf2Z`j z@pX&p{XLbDpX&El*d8lm+tmDeb{4i$!q^|Q{`v~`Vceg0)O3kODSa9Y?S5NuWN6=P z9BBNEgYCinIt-hxKa0|faG!A=+215PduY7f3A_C!WYN;^p>*v-{nI$Yer$yOy$oBu z|FGTlI+l-fvso594ZHp>#x`KU()B;i$WP^eM)viLy^jN>2g#nOW9x9B_HgKjao~|Y zHfCm7upVpq3d~JZ_enS_=t2dOU>5 zO$|HN?^?TQU2AjmmUY`%%Z^Q(wl%VJyrZdgdn0>b-L`Ez*0XKvTDPy?ytZX?Q{%b~ zD0FjU+qz9Vwy)i=WmogYo7k4^TUyqp${tE1_&5aqS;yQHd1C0-?cRa*u%4^p;c0AbFw6?jiWw5*rJ09HL zjJ|1HyXApRY{%M$hgurf&YR12wl=kBHD9}R$CmBGi*4R=Q#$YLIrG`ZrpBQzQ0p}8 z{Pk#m%TR_5jm_(uwm5Jnn%VlsE!#G-rX8)@H*C~eqqQyFZ9AG8Q0*<-TbkEyYi-G> z#<~p~)SjYlq?@zufh`-F*QRtTT;!Ws$Ve{v^$~|n6Aa(08z)s z&ekpK?{D7G)RJoE=3Q-Talh|J<(e8dZE0>nA0yub=+o^R(WUE}8=L7aU^H#Y?8wxO zS-Wk^{f*lmLd}udh!MGE`%QD`HZ-rry>FSX1~Z3m^R_Jy4Bo%g_+4Ax+}w!j40gkY z##BdWEyWF8yS8%WUCY-lS+rv1+O=%x9;92C9$@QtI3B{#Z)$E)M??lT&8Q|?v}?!x zjSM$w*IJc`;jFA}ZfR}6wJPXZ3zt^nQft?4Xx_1QGhhQJTZeict*3#QaRK#CssoRD zv~|1Mr&rt{wr>4;R77n!igpaa>u6&H?H0DKW!?5U>1(0w8@KJ)(X^30uw%oO@t9>r_)7TVk;WjK!#>}HRfw

Y)CMM*C4-jBEBy}>#6M1IQ~ite~II7wJ@c7v~c@M#=5oeK7>zc;pY%O zuZ3;vP$PV)ObJK&s&&WFtcB;}Nckv!9FEs(;ZrE5EFIR0 zIrKE>@oA%Ya`f?e2H|2Y{)ZGM=Qy@c9*m zwL$2nFbz_CeoJA337i@OhuY3WXT^h{6OfK0OrH{H^m8)&}lH3TqI5Nnsjn_PLh3Nr;Pd;MtUUy0QJ5Z}_{^m+J#@4W=jk}iKJ0LD?{~Pyd5l|^T>iz* zNb*wCxc6szlgXYY&sRM=nP;4r^Rzo94`<^Q*2a|xC1oCVUoshO`r%j6ofAGB=Y2jI zJ<2@KJM|tsiam#GL&@a5^F1BT2}*~vz*F!H^Ze6ty5yp}(Uwz-wp#5!?Y&F+sk6-U zQ>WE#J-|FaRnsX?=BEbvt?w_|n(sO2q&%wq)(HEx5%!4@wr9w$rt&@*VZSrNetm?E z`lhe1p5HZOS5bK%jj-PvVV@ph|9OPnJ!CJW@;)A6XS82U&uG7DXS83nGup4(8SSqe z(SFs=XuoP_v|qI|+OOIf?XMWoe$~!sziMZ+U$ryZui6>yw~uJQYG<@xwKLkU+8OOv z?Tq%Tc1HWlN3>tHGup4(8SPi?jP|Q`M*DfixV39*GK=%DHoj|;H@Q2R#X4CV^YC5< zW|)VyGSAu-%wyd8i$wC?%&|>jUa5B!<@>&PqLP1FSlICN`Eq_&Wv4jBrZB194%R$E z>-O@ZHDr4_iyqxe`A*rN*3}e0-P_6UnsQv|;}!d^Z=dIj8p?(4y{N}zWsh^!dA|6_ zqsi4J%(i5yqS#mud$brVvM#r4avgtQQZ0W#=ytn`Yxo0vr_IH6*<4DY`F7z{@zZ>b z{b{;h#r&R$8czFLKZx{w~&LydJZ6#Bs_*cLR=McXpW>X{>9a zi)ne-^;`-6U9PQX;cv~OO2m>+cb{!bpTmw#bUpqkYkO{#{i0BTXWyT*%Qn=^F5}+J zF1z^M>=ee8M=Jyd#*ZC-(T;2PbQ7v;%(IfwevUjJyc;5X; z4SU$`uP`2zPJX0oG}Ode)+Q+H9JOVlgB(gdu9JQJ=^sRU$`hk;);+cC52%ms#1pRcwUxqW%Fgqm*x#{M}1Sl%h4`l!+~Qwd_&z`)6FE6^COCt|5Qp!1Zm^UYv)r)c)p|jq)3m z4wvNl;V+reV9$jjcF=u+!cIloN*UmdP(IL~>?f4%$bqXFdmZo%H$cNFZpJ)Qr#@-w6*slKKD zM*HY|8~C{qT-)#*CjOkA&p0aL0PnwK?flV(xc7^HEY)OiWV znU^M^Zj>h%=NGIzyh6|KVbtdsSOJ_Csgn5gMy| zUF!X#dxZNq0r&AB#cTbS4Zd*S+b-T$hCoJrmtGFT^%{q8jW(3U_snVDKxJy*q9^W_@x)dVJixqQmuvchh5J zR@q$m9QWazMs8RJ@dl1*8#x*-`prdvzs(-rPy0_de zsxMuK%A)$F>rVBiHc?;YbpOzqk20vlx__CL zPW8{BG*7eRb)28Bf4c5ehVGpst|?&aW>1HU>Q46|RsT6i;K{!S~EWufnXI@pFot|v3f7=`|{b*OD$h8aS-~4umt07$ujWw`I-@PcK0p&>;3+nk94HTT10%eBOMz z!!h&=uf2GA0A?|-8te!v1QgT>}R}g=M;yt?@ zKhomr5%;nh_n_l|7T1orf2262%|Z9SU5h`A_(N*m7Dt6L-u*&lhcoY;|8P~T_~R?% z@Z73c6FEZ9Sn~%RF0r=Dty79$sd6;9#~$l&S!x@8Z>aD6o#fc_%A(WuS7zBUe^Pii zgFY^G@W1DKrZnd(4a8jAp%VV1uiK0)OBvmhr?fh_*E?L_xAVOex2Z(j%-<`X~fxt9x3`6?#K60U*SW+TUVZS zpjcVu{I-XmG6sE^TR*>f`;7K8uP8!yHtM}|;-TACqt4?iIB$JLhjSLj)Jlc*=Aeuq z%AmSu)}O7&@t@o6NY$U}Iav4AsJkOo_hXf6dtQDhHTJlQ)vht`j$d%IGTNO}nd6?V zWV@v|@A>8PXosn|rifQsobUKk_5Mj`hjX;D%d!2ox9g~W6HsS6>c3g7KWjTO@tNE1 zM%|xN_+H1v$8LKCe)8A~=6weBZKAs4nC|Oq*Y)lz>be|t>bW62-n~^9Y=q@{)ec3uk?A}pfq6kmk!6fHan;YuxBjPM36JQ?A=2>(b)uAy_Lz#a#m z(R%?yQe6kTk5KSU(0sul!u+M^GAvhZnIUMaSj|ix@fB^;rd9&x1K3d};DI4t4Eu9-(y4A*a3GhWZ?GQeR|y znETg==iuwSfTL1ByP5Ym90JmNc8+4%ir}Vv%pJZqLYDKO(Pt&1^LR{InhLVZnfu?Lf@)xOJ!8$g`eM;UP!5vTS=M%>4UQ`?*o_YUIJwq?Zq z8FAEZrp5j7L9JbdVrq_q_6)X-+6y~I?WtX~mD)$+Xb;-Ld-kYfhdH^80=TUxxm z-+0H4{wAf?&2b@*iw)?IFC~b^@HuzWA1xlH`hk(BkrrpjR&Q* z#sg;07RRstDjk%*zJ8ba)e^7%HNE#@h5l(){p3kbscNnE{5(JPBscEj?>zZ#OtBxR^!!WS5?o)bw6RHGT7OcSaapN2U{o3%e3#k#isH%>-~+#g zbshVv;-@Dm|CVP(c#86`dBw_~^04O9c6rCyHr_5ts7KqmW0Uj6g~cB~v4RztyQCSC zXJ&nV)!}#V-?**7Sk;jKoae-p9njjIWc@CtoP77fdZA$E346YLr{~>I-cWX7-GlYi zU;6Nq-JcwlUpM<_RdWY8&t}IY<(by6F-P9Hd0Ih9CpTjk)`$Af&T1(_{O^{T3g_XQ z+bPd*pzJ@a99u}`-qLBBaVx^5b)yR{IOqP&8w>u|y<-X|-S@r1nWyaew({)yoez{0 z6fb(d(0HmLe=gPpX#Cy(z~+M6P~QK>SC2BXF}}p|#|ui<=nKnm4R_7N!e1eL@d2UW zoBwIg-&DUN&w6J={*6lt3X5NTrqEGtJCKF>(4@P*r(XB-?Lxt&q)^3V~9g=dtL+m7v=mFzFWn&Dd`YM~P( zumOGm2km`8(f3p$%n)YfTs;rw3|QylPjcgk7Tc-ntR&hS?91~e6f?Jk4Z;Op7Ia4+DZNG$GWCGf^%}KEdK2Br2~0AziN@o zr+IDV-|(8snHL)R$j#-fZ!W$$i<#GUnt8L!ulN3b_nc>ck-YBNTM<7-8RHnM%yN$N z-0Xa>Zt=mb%3No&=Q`(yb#(``moe`+MRu4vi%LJJyXW8+${hzT?7sQgDV|x*4{9q9 zzF)WE;H$f5KYKno>)8)$s}H_cv*=*0GTXV#bF1_Hnq>!N+^dtjZ+-SAl>H&r96zY3 zJ-A7kH z(dJ3{4)-BU_rJaREL$#hh{dsTt38-1~7zV@gO6Z!?#?w&W(E zsfx9|wj?PupI~htL+gL+vAKUud8-zQowHa;sZzh6ZC$8_UqJk%rC(;1eQ+=Q|N8yC zca3+m)2uB4ABb1@U6gkFhxfWhujVfoBh0$)b-8g4=V^5?aP{Ua>#UbyQ=0VNk6riF zOgJza%upFWrF_bR4oWk>`(qd7Cp)V;kX7dSvFiZRsqHJ30-FtS3~@~P;okd{i8=gR zqx^fda>aLk?Beg6aCxr6_E8&f4tys2e$Lb47;De|!tPD3&TP|sDi;i8({--VE=r?z zWusj=bZxY&66cZMMD=vevdk)jO=%M9z6$N4btG!nEXs$u1f`kZ{IRQquBWzbmm}Hp z6uWuMl%^ugNdrJ3Zq&L@GPu94b?f^L~Qsr1O(sbFKVT7UkcQk)M2?Yvrf1DF4=s{NxW^D?gP*`Il$p zCtvAW`Kc_*Uz(Ah{HSZ?r?M!2G4k{1AM%L`3Z~w^3e3$1f5pn4{o@g)GW4&x@!sS5 z+xNrIVpu;ufFp->*4ifYG5VKmhWATqJl2UTwfOY&f&5SMU8W$u9`~&X$95d^aio54 z$6E9lEzG*G28}TFFU8ARnBql*sUImmu~YLq5g$UB`itTRv@qrW5@G5WivLUtQ+yA? z)P9QpKnqj+I|x&IDgJdWOz~-dv3uu`k4^0!Y+pI^)7)m1gKN{x+`6Umy8}n}EaThS zXFe_nig=Egdc8lndIRDgTei%dj^Fbp-`0iry@==5JBP*p9@kHo|012&^5(GgpJ$|Z z)A?1if0J46k22EF)A{%89G3oMM!NVY&foHzVd=Xv(x)K(v4{JIrEkngucY&rEIX2U z{Z$$18|eIRIftcJWu)(=^LM;CEPY-^`ipeFGW(Ux@~35_chmXHcMeM*laYR&&R_qV zVd?seba6M%Z|xtJ9&ilx{}iM@R<-Q6nb-d;BfXN&uX7Gde=j3_1D(I+&0*;$GSc_b z`QOR@U1s^e&q#lf&R?=~So+U1(!1&WZ~tak`j0Zw&(rxk`iG@InUT(wFZ=z_c+ENY z@Yl)J&gIVE57=|u|LAQfqWPsd7NIG0BuyT)!2!KLBj1eH>qcRXk^Hi;swU^QiqL8S zT1`Hh8S|?-o}JEGx;FG}>`Hc-IO^T)J!-vnK3!}H{NIv?w_#Y+2rrZhY5RoBfPa*V6s&y^sJ{0~Zd z4DZq?{b9^?SD`-R?0M&kkS-v7{Hn3%`0|NvXNgdotFZfME%z2>tozhJQ_;-@Ww%c+ zxZ(CTJQwf7Gcw&5RKJa=Uk~0vk>9Zi;faphcEx=kzeIhLV;B5M$Hy-v20nhNQgQC( zPZ<0^Lj75#POX0t>i>RUa`jxb-bq0$(UtJZ5B7dcdAfD}b~-A0k;k4A%KHKGGG&&? zlOJGT@x@J^`u(p{9#4Z~I((Sz%4;?e{m>0x@#0;%?tf-YwcYR;yK3zRf6fU@yK4}x zt3D`p>SlD&JLzf(@3-|c^p)M1qwQ|P94j|W=vi1R5pOq_Wde8C7!jmYg7OS1?xxG zSBnQsrzg4{Ws}Re@=xxk`9FXBX{-UWw(|p2EfxPdn*&pel8=oP65( zRgKWiD@FHbRq&-V&)bXgD|qi@MQ~?TSW0D&wWRNktZwURE5v*4gzG$6CFPxL{PmaC zPTIA>s%0u~6pcT8dDn!)mv>G${D5P^&5G_BM*ea*!e;f2k0iQYG z(<+a?^eAyXd*IK%-;_d}cy?6J5_EpWL`;Rr3wpXlJu>ZXk z3k=E@?4{c1d}}u}x4O#3PAzh=Wj6og_SVuTaNZO4yB9o;^B%W1!)`7;hig4yUxBz4 z3!cFB^qvjQCELNo!b;bZ@2y-=jJ4-~95^y*bV2^@h63y0^Njk47^U@}ruyP$TK_RC zvTZJ&9kB(^->7>5@oHbAeHSzG6?<~rydBRqWyn7m zznQHu+HdmOR@etHPtAV}`$Jy9GjB3{>2Y=StQ%vs?2)h8r`QuyTU*XOi9Ic4wf*cV zyk{S$%%~UZZ0r0H(t%Q-7-9^*V~DLZFG_>l69)8NT2 z$ysDMS84xQz8-lkNblY_CC}{1E$QAiH7_4^Fk;-kxMf-%_tE-+^2YjtOO05c*no9` z^Fo1D`InZSwSQ`P3h{l%U4^^w?!R~G^t`I`^#zvK_{%)TmPN_xEvjY*`jWAul84n( zz2qepuL(!y+2$x)W9hr@4!JJ}Hnpcn$?u!9+|>64t|5CYC9{{YK1;2|eG%8qMjdUQ zoDvcBu3Y?L{wUNf$HPjx9aLviN%z3iycfTmmUrid>k1;M-_pjCg3s^#Wufmse_r@~ z#QB%LR2X>ORT!$7o>$(uxghw)&kK87O7f~U++Pqy{X@G-@}5HcJ;$;q^xii;@7}+5 zPFV2cdkTv?ZKMiNd@du8IzFMT&tXi`coa*85?affiZQ5;J&d`9 zo}b~F{$gJK8V4gSIG5zwUMc_Qyz{%yw0(-TI~v2q%FpvAW8HA?+pIvsSojKlya8kK z^9t!{u43OwvY&+g<)VK&@%f_m6HJk?9{FOOblHzl=J^-I;Ulu2nZa{Tc2#w>1BpxbVi0 z^F5m!T&)S5N)pz>+AJ4LB?iyf63H{K-c<9OcXRRXbK9l|3VwpM$F1e^f&S#qUD?ZC zd-q~J#$9zo{&gqq`J)!T`R>3Q%hdJ9{+-?r2a*FvZ?4Wckke`L7b*WwEA8WH+A_Uh zMrY29HfUzx?C6$Bi2wa^bKx!cj_w>aqZMWU``zOTsoeRUxid-;UV!yRE6%}>FADy2 z-`K*U)%y#td)1ylu6#^=)Akt!#fyJhD8Jf}KaaGPo-w$;+qQ2hxE*C4#n*yz=zXN9 zJYF#4Tb9DxaGfKI3JU)XVOm$5{<=MXbN$vl+tP;o*>@Ed7XSHBVQcy512X3GMa%Z9 z*S_Qs3ckSF9%*yaS2NW0I~~fqutg~N{HxUZ{THeKOlI zd)F(d%k}tLas3>u4UEG4`*%xo3+JMKvzJ@?a$(PdJ?q_3g*Pp?_Wfp+xv;nvZ9Q3$ zKX*CTH+iwMP_AB|Kk4-TLJRU*@$BQ27Ih7h>RjFw)cjjF>9Hm`tz@Kb(79=SWlEulb?7$Qhx85FD-1gu_I1n8 zxTeGJ9fSGr4EVt_-#OzdfiGO_!TaP$FZ82!|AtG+)#5UmefJ!|jY z0Md#*J^N;2Ja4YC=h{5GD$>__EAlnYU%tO`EBSqFH|?*WGRQ|1->gG*ow`6#!rY?QYGYp-NK274;n zM%NZ9M!9d-;ys9;(wT~{K>Tf5JZB%}o~-469Pys@KXjMDKd1AL!RD6bdW&)10_;t! zN|#$X%3X@{DG#g2bx%r{i}+i$_;SP-rOQS9d@a5m@r7FcV~D>+i|<5yLAv~fqule- z3R}Nb-F8f?91K}IA zd==HB+(pLOYJ8`54m+7T_i?0s1J}sbu2Ei{>$c$<*K6mt!>00%Y1in4-6Qp1q%nXW zG`lV39WDj?jmQ?@%Up-D%xDkU~`1`Ujdzpnvz^<2eUi>DQvf;fGrLnG59sy%Xa# zc9A)Dxu>D5*aiM*M|HAHa7>c@*Z#LYU@;e4Xf)<^8YgDTAcuxFopTvtx9CyElSV6hMEp%^kj!K z``&v7n5VeRraa^*#{L2dcOjmRyk@_k*}d4iK=FGtyGyehH2Ve3wrlnt%`VpL2F>O* z+pgKYCsO4WYj&4r^P2sFX7_e!*VpVW&2G@_7c|?h*?Tm*ShE{6o7Zf+X7^%m6t$~Z zv%55#*X$QGySG!jzGio6c7tZWpxJiK-lN&Yn%$t;yk^@qyI1SyV$JT-Y+kcp(Cl8k z|4{p1v%56AL9<`bY`bRf(QN%Xwq`uW(q24oE3mI(qvt1BUs&%TKT4O4)($=yOX z%`4{}ufTre;%_RRX6IM4XBP2_$MIY2{h5WmKzoBnCfPg>InJXUBm3ZqtMtK1^ubeF zA8Z`a2c8jqkTa|gS~B{eWmq5l^s}KpfRD}Us1Gpz&Fq8RtM)n8SQ+0(&o5DFaISg;dtAF4u;=Jj@1_$v_uW+&&(@rfdW=U0msE*vL&dG$jVDC+-3u?Atv+GskrwJp z=c5lAtHfRl+9N6NJ6;c8p!ES(eOK#;YQMbtle7A&(cb+yKl@H`fp~Gz0_ua4kBt5h zWw__#-BI?X}DC@GYO>n$owr@LQMBEo&O_+(7@;sYm>B8UFP% z3(q*4j-PR^#Bm;u<8X|0pK(?-Chvv6`^7c*NR7jOomuL2Y5lm~!LJik|M@)pXQ$ofW}b=ey-26` zb~#wD?Zuw47dK!H7x|vK%~Vp1F*=|WZK1I`N?}_>&w7Wh(&jaEH?@q=`|zL&06{% zq`!pp%_Gt+T6z=GPa=Kah;*x#-hlKANPl@mdX|>H9O;IxM(3#!={7Chj`ZnBzc?a2 zTT7pV^lGF_<-^;Tqoo%keG}5BY3b9n_K!k(Bif&X^u2ph@8ln^7Th!kq%pF1#el8Y z!@C`8&N!EUbVgnKCjMv+#1ngV=KdOM6dUCSE}1abkulFP-iITeM;!d8;*wDxoonFF z(sPH_*(*xse6**+UYf7qH<{Rj*od*gFI}{Ca{j`yJcP&7ID)p)Gfu2{{OktkBypry zbUjllb=?yD;W?@;^lq4?D=9!&RD@n5e*dG#oP^lgQ@zKjLq5X?h(o%tq-e{A{GXLA zfi^9eIY-pndB243?@A^+L>$fdmMPnu)=xK-Vjb7L7~kjd?ZNs~?wV1TZ7Z@ackYfI zz2B4Xp1YLq8?!>bdjbVqG=_w=RteQ!QG_t{U7KFe|FY{^pAmwoSSZxifV2bDkH z`yA4pu(1>HZ1%GG-X_?8AiFmEY);)A>{n@aEJJy2q>ri_d-<*Mxz1Z)Pg$DPNA=Aw zzr}kaSUrvMrY;>#y3#gn>6pG5ubcX=Un=)~#AgS(oRz9(vC|8eh5Z zC#5E3@h<(PuA%~uJjQm1;2m>^NP41QABm08c<;+gk+&hl(;_M2n9`FCXZ z1?tbP$yt7j_d1Ws&F;$So9W4NkGb@dQk!ShuCj0M%Qe;NyubTeAC2zbwabS3|{-{QIX z`TQT*`f`?y^^QTGP&p=~kA7=`H~&3TA6q=S?+)xkmg#z5P+gYqlJ6*5GrHE`9aAfL zg|})4ZtzHBg1ehibwd5={nG-pjp{QA^|94X@Xo0ZfDV&?A1A5TkRZNKb0^4 z+3Y^bGZxpUd}{jXIo|yL%I;%#*!o)04>|syl#a!<=im4JT+=;f?=OPJXkhS~^Ux2} zmZ3hd)sDqAXFe~XAI4|)1NuMvp7ixo=j8v0uAgc@onu0}OxLIO-!1p;AJP7Kiy7L_ zd->(H1AqS7a+P}AoYD4FJ;tH!V`vTRitAJV55GRuFLixtzufn4xW2Gd@QR(HSHD#6 zm6l50vGYgIHfIp$&%w4y<4RL*VrLH_cxuEpZPMm!6Dc1+hjboaCx6@o_zFc3< zJFR$5VovV;iJf;Y?&6(toqSoWDJ!)g?;A)r9OIp1>as4gy78A+RPavm)uPhtaE&`r zMoyjOvgwXoZxH$Zh;#Gr$@S*lm+PI1vNpmNQJ=93bG;mFGp;kf&T!dKH|p|Kl(P}# z>X1ftK8W)jD37b-F57Bzz0#8FN?$|z=sN4=4{`3V5w@bfmZiDg{8eS8@}H-an(8K8 z7Vn!{syjKY^sD?}8LQqkU|v3}G>Yp^Se@$?YPJo0AJ^eJZz(mR{^OO3e|RJRzsk7k z2L~o74?BK?YnuMDptM?H4`*W?Nx$eDrOb0{={}|XVW!+a!07KC{K)9k?Xb8ztm#xWZ&T`8wU(E-{=?Z?cW*o`c0*LRr7#h$@G3*C3{$Z zs{LWHa(X}Z@4Kga*muO^Q~JddQ~JA~sy--n{p^>&%imKrRnfU4@a1_=gOmI+<@lc5 z$DwoNGoOQ9gWm$!VHe|l0@)Jm2MStlUt6&8_PX*j&eG1*{_;oZ-1y{szyHVD7-q2Kk;y!HwF zrpSP?#8*n^X#Qe^?(@~sIUeWf5vKK%;+rPV;um(kOFD0WJs$Cvg|EIl1%2>JNz+G{ zDvGxBZWqo{dvZ|L3z(Zql~{km?~C}#7v8nuH$ww68b0FhG^pjuIDh&qp=3|>(o!?# z#50wgoXS6URFm(Jr5Ji9y>93hD!SjzS9Um#l(j6Q>soN#XUkew%$~tE8|;>I)nM(E znxF3_zarnm_tJI8;5SRT_+1iRm&!B1FPThjQjWhn8a~cPSO+ga+i9+UtfIpy_jVQW zcn?{;jPLI8u(~x1*#Qynvi8nsIFn1|;0I}W z7tc(*5B?MUnj-wZim${v0M=Z3H;HE_!LQkKd{b#HelwL@|6)tcYpHgUk3{WC`Nj`B zY|2O2xBijSR?gQ;D}{4)2&a6f+};L+bCna$BF_n@RoU8aUg_vx1$#4W%iTNsv&!%9 z=k9r^pS{=CzfIY;??GkzzTBFI{?V_l@86}=?`y%n_OVOGdiC9U_uN%u)%l|Bhsy_Y z>VMd>0)F)bPjmJ7`VWp!pZsFskz5+{rQIFXRKJ1SSj~9Pc<+xYkL1$tO8$sBI`sjK ztL}+MZfje4BzJtxc<&UC=y9@EooMZfg8TJn6Yq+mg9KVnLrgylc-?On%W6E8uy8-vh{NMTfCc1C`IJx?IFv5G5IOi+8ZAIy{ zc_QXII#0)MY>K{KkE21Ubmrps)cdMyu@8ZtX7o&RN;OkU<~gl{W|_I?poa6UQq{*+OA}o+Hcfo3O&3-`vW3wk^~tU5Bq{SEZ?Q-w!D2MW0ztoIF-l>R z&lnCzd^(W{35#H6#;8H><9rdp$6NH0Xz@$Fa4Z=WqC&tB_eBg6ulMsZ=d%Q)xIxe* z#IRtN{d#lM5Yb1uFiYxU{-DJlj`?C-A{H}?VO}T627k;Kl$a&STM`m4#QC7!DEdO- zK#;|gx-bf`FjF{?^a*;O-WWiV#fnNXW+-^#&d9V^LH@MuNc*6?wtH1rw&I#bnV%IF1R?MARbsM7=R$l+B`)2nar3 z*ypntqWYj16S!~!4NU6%mZ&)_=y@q@@EI&-laTcJ^a&P^ix%F(1(V6JKEx$`@nkUK zGjegxVu{M(urHwV1%2^|KMapDVot;pp}0O4NuZ*^cpxSP4L*}z^d+T)F(QWJ2|gZ= zFuxF&LZNUxs56OrzZ}p>I-d}gnUM>jBVwkAPYz3bEF59HkC$`_ogUZ0ZIdiIbZf{G zG#QyuO7clDoD3#;k<H5|n~E zK`@ABAsS(!h{30iSa_YB48)T$F~s9WnG@(6UeA)Tcu>~s1dEX5q8KoI%n%J)bjD;j z5|YA^uxLmc{E}pdSR`{S5sd2saUUwG7eZ3doCqa&Q(U%~jRt1Y$wD;bx9~nr;(`pf z#mvioIVf0oA(4n%@H51SC<{K(z?*PKgord_fL|G2rJcNx_)VW3(od7FjZd^Z`pkAGd^!K3O(kSXv}~ zEE@7*yd*?Hz-=WeIhQ!WH~5XLO!2a(&-b4a6A%_{Go_B6u`JK z3aC97wS{NEJOeO zn*MVZHmLuJwEkPos{RMXwEjn+|M9f`o4v#IpZ&f1uN$fVf~NmLiv;}_Rs9cKssD0X z|05atFGBy5nfk9A(tkd!|Iy+4A2-L*H(ZAP^Q8Z>s{f&@=zsKT`XATy-;|;M9DEt* zzj;XiIaU9qEA>AxsQ;YL#}Dbh#cVNT>VG7q{}JfF-xnIx|AeOhm~?CUABX;jq_qAU zRQ*p_f~x*Up#RY!{b!l_AN2XnhHL0Q{u+CR{`)ok_d)+78Tubj>wg6L@3&ZF=)aHj zKcVTr;i~#?7^eT+-_(Cj)qg$|A^$%VGAAW-D1(1a_l3+O`Pcj7-jI|e{*x*H z-(Upfp+Jx$|KA8dn=^$1D*pz_KaBrKII1WAKOx6d{$m>dmV^b)s09B%9Q5-k|3Afl z%sj+@(iE`{=U-L@?|#vN&fo z$Iypf@E`EQ|BqNAfvC!Vg8YB8*A$2a;!;rZo8kWx|KYU%pM?K!2!$fCpdS8zz!boY z%O}QU&d5S4|6#u=lJ@@vNhJT@8??gLCjJc}bHFTdMkzu5e?s;Db$;0^n^gZF{0D>Z z|C4^Se~|x}F+~2q&Jr>P^{W35{*&bY8&v)ifkZMUkpB<<(Kjmpv7oGj|DWRDOa6bz zsvqY62aNE=Ek+ak|AZKbss2A7G6c=>P*N}@WUC2&x=9cJKNzqO|18Lv&3dyS2TVcH zqVjJ|@z48o@c(s~okaZ6fHkV~1u#Ct8vjDd|JV4}#U!JS{QrmrFBFm%@Nf2eLk#}E z#6pYIuQ#>5?=`rVF=p%G;GR411<=>R% zKM`T_75vMFh}kcPB4Izx|5Nw#={;d}1zYg>NU?d#V`@_7-Kju(!ihr}8 z_&58du+FIRZ_s1@5B_5Y8T?~3()=H4eHH#OIW(D2Hu(2~f2%&G4}yON{-dP-#J{NL z3?aO$F<;4lVu*i#n*UHF&A)Fr|H(A}A>v;E|8XfSX!C!S|6uT%{L93@5%d2j=Km`H zI+cH8ivQpc|H3f-fp>RZJV1|IvID-F(0sIGs_?Q1X{By)VKg7RZO!3c2;GY>HSeCIG1cNlhKlErA z|B*ERNsWKgApho&MEr|JqZRyP@hEXE{u#~xqiOyvDg94`v6Msn2c_5$|9ngkq#^z# zm47c*ct-G#<>rVr#eXuBe;NFn1<8o@qi_=ZvqAp7+WdbQ{{iqXX#8V%`1AoTkR<+@ z%6}*k`)~3uWbp5W|1bIkt4<>Q2mgsEuk!B&{~&abf05SzRQ^riUl&pNk6yvQ;qT`k zt6=~4{By(j*QNNEQ~HkuR6ZJyS_G(z6qT>Zzr?Q2e_UPvBmbX)|DdM-SMVQ;_#$SE zTTTBVt=Hy17RlgW)Y?S5yF>gNtwJQtKkrZTZ-@st zpEv3aSamT&D6RkCKWN1gv8w+%uhDEV!v7EG!G8jto+UZRe-i$`%72y#58H@0BzOaU zmH%*>e;xQY4W#^kP5-$e{U5=W|6la#H2%3*ihrZ1@*lDqj0UTq^6yXk z{~G^H=QF1HkHW18ib?YStpcQhk^cKg|G~fB95QPBb7}r#!}*WF{|{K0eu#gL_&0hv z@E^|PU!T(d81bKkD~&bpEBKdH{ZH|a|4SG7{}!`8%|Bi~CE`{CCq}_P?hyD7LH~Wx zpf#pf`42Ig{}1ZF)nwHR2JnyJ%i;LBnfwQIDgM1& z+#7}d`?3Bn%28i}=KlupABFx0tX3oR-wXdAOBV3|Wl=9d|F7g0e@~^|lOYtAYIJAO)6Zj8l`mc|9 zQ~ZlE3uLAF$EzeMAeq8x{RjVH6V4(2qiOzi{)G2$@GpUX9{zvaC+hr?!9S9J9r^!p zV+{P`UyXk&rh8_;k@yc_{ty3O zHTVx{{Kqx^{r*_ghnI(bOhd5#m(ck4$AWmxCj~490dKy@|3{bd@mMrL^MCUHLk3K+ zgDU@iU3`fDP{159YW#~=<=>E+{|g~?{?A14Z!*EbPk4v;H)ZgTie&PSCw!WJDb0T( zHUCE&22}p>8aHGTq5pr2f7z&yS+Vi}{soNrLH=W*q=@-{7Wl_YJ@6kunV8EE|0V}y~{{OZ4H);GE{C)v?BMtJemjfdB*QNNEuExLY z8{%IY;va9x%>neqApd$F^gjUqAN-^CDgH(B|KsR0@Q;^#CYAprUSZ1KF&n=W5j>(YWyci|26)jD*w?d_zwjF!}!O&8PtC!hqJEW zKc?~@8^(W}`1h;)XT>c;{9B>_#D6la|D5LkL;t~lGLAkSZ`9`h z8T?}l$Tn7J=s{h1))-e7fvUpAYljQ&N0W>p%|A-h6LUJHs zO7X7?FwFl|{ZDYAF!-0D|4hQ;bzm6(vTTI@|9$)mMt(^DhxiYOax$0&FG=IydR6`R zs`_t9`Tx2h{+T2Qacm9w8~potZ&dUDv7Q{glK%ue&48-^0n&f)FJ$V!#y@7an5~0< z$;zkwe=A0pge@JU|FIzX|ImLC{=a^R|4=6XCh(sa$-hYR|71MHKc6KN{{!&<{locB zru3iqPhf{fO8*T|VCa9Ee=I!)@uE)Ef8t+A@t;ij|KLBW=|A`v$p0Upr8m8m7j*hy zCjW6-|0n&=^AXOW+t;yJB>%ji zuK$659sGZ|gR;th%o-ZWzmN1^NBXbvk9}o+;@<@SU*%u2>Qeqc@h=YXZ&LY>lK&rv z{}2AnSMVPj?pN&m0lKMwva#J@aXj`}!t{!jW3{`DIFrnLTJpO{|Y1gy71dE%1b zP57cB^dJ1oUY$3T!1`ZA4|M4OH7vjb!_7K3+3|bld|B?JB zEOG3iGWoGGOuO5L^B;+$>(l(B>>%@bV*|lV{$ud}Ls{Qv8eHAA1*}|8XAgeA4_&DgKk*SR@w6$J z{D(r&I&8v(|8Gq5FN1%qmW<#(MEXAvf&OFfCistO{Nr^dCLhFq6#NJD1K?kfRsQkv z8_V%3{~_pq82WEY=%D{mbPe$zQTg|yFLdhsKdI_J_z$J@UuOXx1}-jQA0*ya4FpB< z|3fnI9~;ttFWQ()4Ch}~{eRl$O8gs5;#K(9d6V(Tp#I~LhL?WcAo0(q^go0DB+dU* z`X84Ac+V)w0l8o0ADc~O@NZN3H>>(@GMTU#5-?-Cu*SbWlYgDc|A1~_kpHN6IRBFB z|Ld%VAof=3u>KDZBq>I{5gF$U@-M3VCy9SNeTjcQA%vm-1HP`{Jtphk`2qcnQFRf1Wc$4O!qH8@aB+zwAx%k7Yvv z<1MBC;NLu)f5X-IH(tqq0{r7Y6Zp3h|9Gm0LOO3SCi_F!0R#VE3`DC{JMdw@$XOZ?@yQ_W-MW<`kx4^ z{Kw({hvQfB&&f&fZzTOU8!`V6rT7n;gMSzQETB*GkGDi2TL?Ru2l+S3AuQOA;Gd=R zpZLeV_x~pUS(*Hc{_vIjXVLEfz`tJQUy_FLkCkDapz?1FWf?U8KZAeEApiZ)|Ka?H zN&g{gL;Uv-)Bi#KF)m5}ZN`KtnBqT3{F_4l_#ppG?l-3Sw;HgE-+;+RTK|Xm$2Jxn zNFe`TpBUml7__MV|8V|wY5rxEe?vE(ov_}3W&!jS%}{Aa=cAJTtQ2*1aL z{znG&AFtd8`Nuf(A7c$ZMw)+Y zZ_)Tq22}o&rZ^YOmt1nPd|!h7R(NAN&mIzs|3-;%O@nh?@SV z`G-QQ{D+75*9TSp#cT1eHxvKS5&F*!#4`Q=l>X~9{f}i?#gzUBqM^8m{m9V&h^qe) z>>-5zAIidB$Ta^!yg3=-KO*}_@Q+yt-v1N-cr_#$@Ou>SA65PT{*aY6;brLmaQ?Fl zLZTn92UY(c?ge%%MKu3^IR6pei)En<{)6QIGb8xNeoWH;5&TD^DgFbP|Ev6CW9n7- zm$CjIWu!ZiN}|D3A-vQwzt@oy3Z zlLY?#D05K%Wh~xUNI_No*Z2<%<3Fw+xElY)EK$>cf!6=x)-dM(8voHm0K3tK@h^aX z>?9in%M$k>Z$+J z3jbZ*^*v;I@#e{ehXKc&&?KVS2I@!#6|zfYz9cQpT< zE{He(eYDm8_^+DUm-TVMhI{p`QX`}^KMx9NWMAME|dKlpby|NbSV zD0uZxx1RCeMwo7yrWt|0(tVW2F99|7rVVk8_&R)&C9u zsn-9}=PLfQpZ(A5|BL@AIN^VKH04MCQxTE>PR)(dQT)5_{*ye3bL0O+{*U5+VEwQD z<80@jHD>C*`45f%_SUZcum8orqxp}2Il|TTzxZ#h{|ElFiuJen=l;RsKic{4m;4w1 z`Rc#l`wy)DBIPro^}qNhEqDIuo+tm4DC%qD|0@1tS^szCkh)=K{nKH|UfO@~pYS^w z?u&mmXz<^0J(%k(i~pHB#~=Jx-XQ+DN6Qy$tNyE4{7?7~@ZYHaTJoR6bNtu$z5nN{ zf3JA+@7nw~{^zLf7XMtPrT#bm35qrUsUUrqZn)0+AG;>^qZj}DEt3DC+6zl(Y|JOF} z*;aSv^zl&tv<(I)J{(&AAN{kY=59O75o!qIzmWaEyrwU(nV0&%Gyb_2%_(_SNdCth z;WzW*zcv1&%|DlhP5$#2viNUa{BukA>gDb27Jc;JX#L+s)c+0j|6FSRv&#I*KR4bx z?s;qei+}FN8~>&HFO%484Tn%6RSJr>tiht%R zw8PkpX`RiKTw4Ec{#&j8#lN@skF@?DuJ8V5E|*FD?~-|Y|B%jZ_zw>L8~>VeD46d2 z2X64$e^q;u|2zM;&*VS;T~q(7|K#pl|Fi7>&8hJ}ihn2J z)=OIju`;@_+L`ul~dGJ5&{6E!y zrv62Oi_8Ou>QCHd-8wa;+5t<{u4fY);}jH zb)fmr01olb;iAp|u_XWTpBVow399RVi|6B6^oEG=?!n73f->KC< zb8$5P`O^;r{ftNdQJskYY4zXO`v2fRQUCP0Cxg`gi+}#NP5z62U)KNRzwsZQ)IS}j zUg>g=8UJU=f4}772J>sk|J6T--APLR=PlRj2KN8Nf6OLqzWL`4{YU?lrEmU2>%Zo2 zwEOC;|6crOX}$XI9)tRKHUH->V8c=JU;KCR=HJ=;hg<#!Zl%#y<`5)c^SBYn|JqH%=B<|A+PB z|6B84{GaeY82{eD_2qQJe{AyKdE$R~PFY<{S@*&JRoDNU|3UIUkov#n`Yiri*8dg% zHpzeWU$v|MO6z}{|AFLxK>o8!O8#@SXYzlR{NMTS*#9&BnddOeDWLIRr+L5lpUD5s ze_t*B+pPOu{huWNU;GbUz4~vd|E+)5A4&cHW`sd?A{ZAhg{<(kjoHqYVkf8n#xCqb9X#BV8Kkd|ibIkux{d1p~`rr8Xe(_ID ziU02E{@}mDe|il){u!zNt$%;$XvUrygCYKDdyU;PkYQss{}=z{ ztN8Ce`X6on@BI6j^`E@?cZ(4Jv*v$0a!SM(iR8b`b5Z|}=068EJ%6EE|F8ZXssE4u zyCwfO|Doppc%{Qy{Ih8*`Ojj~cTE2O#XqB6MtZPJ{-+VQ;aC5%lSj9n=D*v<4mWe~ zAFuwSZu1{sy)eqWiN-PVKbnpIO8npP&uVn%zhp1@8}@jw0Ozmxj^H~%yB|0n+(p~Ml>$l4|UyF>o};D0#FoEP=q z8UJiheDd#^{8#@Bop^SPYrucI%l{-}DjxN}`j0OTZ>-(Dwf+w~{Il$Q@gH3SlmFa7 zllq_hkEQ-!@?ZSZeR3aTcEt|)KUE!vC9MBLoZ(;k7&rf(t^Z|$jP=hqf%<3U2L9=V zVggVf$5qjUrv6|2KVSSaz(Dr@S^rNpr8f1yV~l0)3n?U;-C2?H{(CRKZ6%v{4*NQA87Fj7%sEV|CIb+{Rh{WUj?_}7ymcw zzfP(DcmD57{)>Od=D+nnfAT*r{<)PJyHu--e^>KAE&NyiPp$vo{IhIc{6F#U#kBCz zPu&{-T}C_Kn*UQk9~A5VZ}IO%b*%M2TWhuJ(}rO4KO_HVHgMFxoTWO0%b=~8`aj6i zFk1aj?EkTVn@Z2r|9-vspYLo`FZKU$?wIqk`e#0d_#eoB&KdXlZ~RC2&(4f(z&{s` z)IW<9=8dpMGXB|pm;8V6KUMg5jQ@1(P5m$VkN-BKx3XFNk9+?d!5sY4a?bug>wi9> zrS%`+Kg`Omt2p4wZT@@wQKNx*l*WHX{^Ng0D7cRPqpD~Z{}ic7(k9Q;-{n7A7XS3` z9{tan|4C>4Pt^azjm`q~@8bWq&ws{?)tdhf`OhdzTENJEnl9_{KFt5Kf5LVM@ZXyJ zxBeZOP1HE7|CxJwQU8<6x+BL3aX z`X9{tzYW;*So|k@|DE`c3;Kk_e|+j?{crpaNB{G||1iy2MC&vD`>$ItuKpvI#s~jx zG`S3Aee*wae$Eo*-W8+xr&B(E^UpK~^&<^k zV`g&j|4sfo$IF^LKxBriA8X z&42a(_2$11O#Q$2FQaTf`JYph|4yU%AN_gF|FCu%x;}?~IQs9^KVy=2{<}~9yOk@2LMT@&9e|fA9Y(_5Z7XXEgc0^Y4}p z_huIVUO7@mGIwFh@Xw9%F;@SKbw2q2C!`NLyF^R=)9G?q{ht!?pE^(a;3fb0KchGQ zROr^fyZHCpEU6fTywv|=g#SYQpBDe#eWJ+O`=4$8yKa5-FZYjj{^er3`j0jLWp)K) z3=`wOUHzwiIG1urmBxqsk1PC7|G|GK_5Yjyg#7;})chZ3 zI!~$pcm93q|L6}5EbUtVhY@>bd;fmP#%-I$k^k!7C;z+4Bapm@F0?{JXN4=&B|E)ju7yFa86~ z|LMkk|E|V=JzD>sYy5lUKmJF#!=U;9>Yw5Bn*X;bOCqLWkf0|2@jr65toi@ypP?69 z{*URe{wMM8KX?8^{CkW4r10+NAXWeVtN&{A&sP@tkAF_dcK+RJ?|-uSKTjd`|IUB( zJ@5V3#RvbT*v#J04wu-3# zt$#PlHUII?djw4R#Q*FM_|J|1Kqmm&{HJq%@1K)lv;XJgA1&7ZNdGQ}PIG=G|G6by zJRHgYS@IwMOdw6Ya9s1>;hxyRKOrOjnYG9rw!ST!#eX&4)qf}cOFBwP_{Kf@r)SHq~rsjXA`LF&v*}AYV+a5Ki~m;E|EwAo|IX1rXQO%x$ofyY zqV(?H-~4Ay)_n8xs{f9waL$>d>SkE|a~=IZ_-`6d{ZmYn|B>YXsi(t_`d|Dri{;W$ zL2LcL`Io*C&HqvIe<&Nb9!f6t+x7qI-!=I^nf&+CQuBZBpKDyHw3VuVr^p&kRrxS7 z+v44S8Qs%rviZ*mqV>=H5aXXIzpVd_|2cm4bik#P{OPIx@y|U7_3sZQmt@tyW9xr< z)K>qoMMPO5#6U{SS+O?z7ORFaAAU|NE8mI2->%&`*;8{fQlmo&Po& zB>$P`fd7g7U;L-5|B(D|xVVb9Tg-Kiz5kB&|BHX8P8oig@HeUc`_+HV=m_iI)%-X9 z83WF{E0X^^|6D(DAL`$y{@48HJ~#e3hY3ol|Fbv$ZBG7M|1Nv<%h%DC>U=?)}HlZ;sOz|L&uj zqs@P}^FMtLd;fh^Hw3@<_dQep<3HT|&x0%eC-F~D>L>s7U#$MwKc~s@n`vU=KYH@E zisXMI`Ok%K@!w4i-yBE(A-^nL|Nj#(xSjgH?zm!$f9}vo(`k&G{T>Xz#&^_G@ z|J+g=hOfcq|G+6qXY+sYA4>gy@LziOnfhPGe(3&RzvTbsKQ;Nk_s=bU>z@fq%$nW# zk2n8e^<=ciusU;OiWQgqF#F{P&XopZq(1Fh%Z_uPX9i{m<5aoHy~# zf5=>0$$wVOckZ?`W9;hq@*xP~hwT4t{++#lxgT`#9jTP>v#W@<}OV{pZq(Uf9}z^>Yur5ye?(@N94bsM3VnC^-qugA#l`xdI|AA z82|l?e~0|14~_%Oi~4uS|AGC#oqr~5j4%GzoTuuyWbFF9ce@9UuUo^{NKlZfL7 zSdjm&`mb448UK#)&&GoFpRD|2Qc3IBiS9gjV&|KI(yZ6@`<`2VB%A5`k! zHU3BGQ9t+}zrH+ZSpTu)zi;z@-qrv3=a@|WH@t_?%{KpsVp{xjS6%%Nw!S_-F1J{vX4IjWjyl@Lx#&v)`U3(!LwRp^X1>&HtE7 z>iB0LSMp!|N7WZvhFAYV612wuDEa>v|0DT7k^l6>vVpw%FLwF=E&0Fr=hhMHf60F@ z_~3sw>;J_+7mu=N@!v@OAG0I>^vQp|oO0r9=l^@UIXnL@JtNfryx?K-zaand-?|T8 z`}@hi&%1%v|9s+qO8v8|s`dYp|KgvHO)&Fzx-}~y{Kg-<1#XoZq z)qfW`2mjTQ|LpcWnh*Y`e}7 z)bc~(fB59TiM0M_b`8s4kYwaeAN_v)W#U}!Hl{=z^?$-cpPPS% zDmIDcf5iy;vnzA$fAwDk_XPiJK8XK@>qU%x+xt(*|JEye=TSK!7roj48#`uS;HrQz~(>x2g(0W{?iLbIKiJ;{ExHL|1JM> z9_xSdfBJ{f-o}4?bNg5Se>VTTkz)Kiyl2s*>019!50|@6Oa9}ZX^-lk{zLK4@bYAz z|Eqs_!SEbO{xAL?Kl*QYP=M|HLGpj@m`6CYrvBIb?@Q|c@hbk=>L8A_{-3|_&sVZ1 z^*`0kXa6Nv$KU)jq4jC}*GvBUf4D)Z{>NYZ=j8u*#s9qbAMW!%O=mZB>u>eXxjglM zc)v*gcWeGnjJo;01mwT*KT7>ST+YK*|Ks2FEAc<5e(-d$8hKYQ6gRnc4Q{zc%$h{vGQ7aNhZ6PeA-%U;T3!%G<;IM%u!gCI9(+ zzWMjbf9BA;;-9k~@5=X?XZ<^p|L*gX|CIb^qBiTMlo?}J&42b}P5%GnpIvgze@0i2 z+@!SrAM^=W|0DkA&3`ZXj~x7Wb=C3#dhyTON&kFt0WA2#`d|B87yrTDKj%Y3$uarF z*Q3dQhyIzocE5SiQ~f{uj1C^|(Njvl_@~;T{tut(pK(mqzo+>x{+YLWGX8n)!{mRq z)c@pvBmSq&|M36!&$Hsx|KgwKyHEbz`#Fx^{bz6f9p>e+hbaCh_1}~KLHWVIYwG_u z|4etz*sr_dzhU0M!}~K`CkCz=|McloMy&p)#s9R{|82uxrR2Z$-;@6y`9Ev^tN)n% zPt?Ch{crp;S2ch4-~r0ai94UB(= zF@EqLw^cwZUhU&QssBvW|Kgu3aYz3QlKaJfwdOxJ7+L=ZnfQ-C_~#b!wO{go<{5Ba zZ^Qri?!PN*$^Xgb|K^|3-HZR2{13kG_-8_k_^*>t*8iISj^zKVf3Kzc#rlsA{=+T* zjsJ;6GX4k6fBZ9FXY9%Uga66j{CkUkdQ?sRGbPkxfa@p!yhh03+S6%$X6ebc*eCyd zI*fl7#`Mh}{nI}`rtR2N4Yi0e%IsF)Nhxth# zy!G#|`LF(c@}JqAJhi^hf2Ti1TL1H+4I^S7j(^O5|HK#r<3F?h$1IclADO$u4~l;Z zc&0tB`R_^oi+{f6xYQ-xX@Dc5D=u8w(1BIPl^N9NA5{vTHV zq0N7$yJj@EUwKV$^*xlgKt^a%7S^un1xWu;B|7}hCcgZhO{ZA(U`3*Dos2!j9FW8)r^}pjX>?xhS(5b(j z+niI;u=gVQ??g-fckKU@|L*rSpn=SLZ2qrjqNWu8yy~{|&qgSh4K)89oBuoimH5xO z`KbOU{CBMXCztx)YZxTE^G|yT^*{L^nEW^XM~Xo8ALE~Q=@>A{~=!=w*JR|`1rH)&w~(7@L-?d;GgX<+5h9SQU!j6obiEwo~|MP_x^qS z&zk?f=D+m0Oa5aZ464mPbD?-S_9g!h{sZfu{ZVGj5B;nEAZCT|FE63*{WFGb_3scQ z;-7h=T&v9KLg77`)&Ib^?asg7K8^o0>F|Fx_5T>(#DC$*t(Lw2aF+eQp8DVTccY#m z6KN33{{NVzR7b`?7iGkMV*Jxr^yEs`=AW;JU;QWKKjpgmmsW!p|6%z>=gRQOKl`PU z{}=oZ7k|G~~bM~!d(pUg|r{z5rQBh_e;e@Brt#0XFY5ns^G`22H+MJx zzR7>}&xeot-;w&CUq5fHlmDClf4mp}yxBJJH?R56%Q?nBHH`T0nE8l*=_@n-XVy(A z&u(4c{Kw@qy!m%m|E|{m!;60g)Jgrn^B;cjAL{y_{P*SUw# zL;kCOUM=Tv#btKx%^C3T9{ux*BmUVl{>8ty_;;-TnoUmb6&U{$`R|ke)_+oO`5&Gy zq_oZd#lK7bFaGaa{;U7q`kxqGPr4*AbiBa{DG)ACn2 zOZ^{-|5)~K>mO5Kau}Ed#@B#lK&y= z|A}{a#Xl#f-&bGr-=~F$`;u)iUb!MlLz>BdF^m^^8dyEWc;(6%-iGY-xvSi#y|7+sRF70 zgJ@2z|C#l_$^Q$FOK`(?p8fB;`geG6e&;_^|E2h6qPFqRcZlYH6yBHor)&Pjzu#P3 zUdFofIpJ#T>fg2bKlDj<^gr{)(c<4H|2v!i{}2B>BwtOs{>OjJ{yzi#H~$m<*#bGs zJx^L`nLW$>Iqt_&|Bu5IJn83(1M)wqs5(FSXJ77<|AG3S5%JlDUjgyB_@}@BDP0`u z-}z_fe}3`rdVe_j{p>&4<^L!Dp7HNr={|Vz&#W2hf4RH5`5&0~>6`pt{qr*V=0C*$ zeBS(b;@``!v?0Cwuc-h1z%}_#hvm+H_gDWe`OixYPx{R8Uk$F-|GxJx{%K9w=Rf}0 z_~~dk-us`g_@9h_o;suc4~l8=?{dd_()!=M?fuWc_;(KeWAz^_{%OsS{D1S$_-ggf zgCNx({0H)q;V1t-`+tA;&j@09YWp9)#t!~_{Cnbm-tu4lr^D*MD}49MvHsgv|0DJP z?4>-`BlW-fk3RV4`FY9z>^zhIWm0*2|D*9AsDEnM`%nIZz5kK?|Eqsb>VJ+G#s3tA zRbl+|Y^%=$uFgMSJge^6`acQDf5z`pK~zt7S^smPXXn3-J((sc{yoY6seJd}e(>+A z|Ddz$f60I5o@xFs{s~;dVXgo1Uvup_yY%U}`Dah%#lOGgKmNmg{;PlbP00UT^4~j6 zELA<~|B5Aj%vO9baRB}Bib>Z0Eb!$%c2e-5UgR;gnEMCnKV9;lMix3KSO2N;Px~Sh zz$ib<2jw~!cgcUYG*b2Nustm6{}2A@RLO69|HD%MvyZC&L#hAY{JX6GCI1=iWAp#H z<-hao_KW{#>BXymSN${5GoPvd*`Z(qdGX)i-&yPbkN!FA)B4}#j`ikW1{876#=l>F z^6&H6`{2L)+5b7b$RIDCI+$pia(LAF)qgAN|26-8Nr&G@H6i%kA6{`o-6we>$TBuw((y&n8?#f$vs%uDj$>l&|icyN|A z46g(w^cx)gPt;A+{~Q|Ne_~j<@&EL`#lJ(V0Dsl;7z6!h6r0-(~i^T;M-* z#>FVJkN%UR|3LD;TkC)FfA62;5$7^+Z$sDr6@7Y=|EquI>)d#$?+<KcB*qTL+T=JeT3S|9a&A>YuiwH~(y$F#6fWf6jdpCZRK%n2Q9i z?8z281bg=*D-?D@M>6|kjY4Klnrv9G`^&jD% zZOnv&Tk8KQZ<>@JQ1V~>54;{li^+T&eSePAPyUCw`LF&x>wh->1NF~W4{r=T$C4R< zUGNb9yhe|I_r-s-`j=zw#Xl4J?|e>1t^aranXfnS-n`WRi~sqLL;W8a|NIV?{4cqi zD(C+^+bI6sUH(g-t1J1x`seXuw#CIi6X{I-AH4W?CI7|0YwLf$E4V*L{m&#g@$WzB z=ZO91>Yuxv2mg#A`sAM;hSh&Eay~1yN&m=|M8Ij4R4!z`1kMGn*aExMPfAjf1GDo|3I%<|I;3&{%Lh!|IhgM zR{z7h|62S{Oa5E`f%x~x|D*q4=bw#s&Hs=7YwLeh|H10tFKCK=_3s`0Pe=bWhAjRA z@}G^?HaPls+5dB^)9?Np@_*-_Ki}ei7XN&;8UM4c|H=Q&KVKN7@z2x0d;bh($^CVNWy{SB@ElP&*;$j_#w{%6F4&HtVMG^tYSKh2mie)K<` zxinz>`!@gG@11`dt^>(`9-5?Re)aE3{xe^17?^#%_z#j{_3u*uKZCZh_5aa-f`6V> zceVb1@y{1jz?bk({sWW$FaBkej{4_yN$dZi{vXc2vB`h&KmEhE-pS&MdF_u+wo2PGx&Ac|Nr2>3h#a>{^K?OjemK(0{<6N|F@B6 z^8ej`EcO2`|6TH*31Do>c;#cF#H4BKcmMnh)2Z!E{)>OUFY(VIB5$&M@J~<0;-8zm zlKg6aNhU(DgqPdUyf!CI9gsi+^qbO8%>V z&H^2`#{VRTd{@nXx=?B-+5CHy2H{ZQpU%8b{wMOE8cOm%{u2M8ga1tP|7!D}!_bfZ zTlW8qe~0x14}hWswfAP?KY0ZCL zO!vMWI-|*d??DT+k*fAL?~`oEL> zA9&cBEg<~!9;5M}alE|xpW-Y2gF^hXGtMoWhxq3mJDdM>=AIbHw)p3VH0%H2!K+~1 z;-4`V#a!+Evl*6pCjUp)|8W(lf4RFFoi6MQ5hri{xzdmXlK->A`ak4;QBZu5`jY?F z|A~o_*^QTEkNzFDNSFMNPOuu)zki#k|5yL%PySt2oyC2Y`rr8H8Aj{hy>n0I;GcQ> zuDt5lv>N-noDoz_+VW0wcUfAQvjq&K0y)9RXY79VoYcJn{d%wYUa-&gnGKb)^8 zss9rero8I3`Jcr9xcQH^`v0^4M*L6eKe%Qd>woJ%40(}dW>xmdKd+Th|Fiwc!!!QW zJ!br8)_-vDKbZQT)8wOnKA#hB0Q16^`sbl1^&jKkPnl}vJD8IE7yqvKZ}Y2 z2F{n_-xvS$&;DIq{|7ezz4|h1{<{}O8t?rxq>xUSAx$;^9X{Ba{|EmK?|F#-;NYKk z(ANAPS$A9iM59+dH~*9PXQ4iItAEbVX<-)s%==mVGv~$lZ>o^{@dMlUoBx^oCw1Qa zJ6HDQ*a8s$RCk`2?)}GIcE-Q6`tKJ19+%bd@7Vmu|M=?PIr?|;AMN}*PB8OS+~%M4 znDtK=+*$4)g;xe&GY$LTpKFfH%VQ5Q{@s7&8UK)OBft0>Pwm0Ki+>t@)PK0-zxrn# z><2z4ixd?2@1Gaz-!u77PwZ0vYyR^(H0yuKfA{W-f9~7`_~>mX`SM{rO+_ULE{% zuAu(gy??HSe)8{7|4aURZb!$2`uEj;yZH~u{}28t3uNYeEB<+;w?6u3$NA`gJX`;~ zxiG5#NbVND9hx%Xr2NdN}uD|=QSN{p!WG?&X#=p1t z_s%ls#rkL6u=w{L^mE5d4?X&yZ2ogM`GbF&$*KQ~y5ZT=9RK_YHUB4C#8?0QoB!#U z|GxU?N>s-bS$QK_{qxpZQZmvb4*u$&_lz%#f1Ww?Z2lko^XvxsuT5D@@k^xsXSRpt z|4;t=o*K44(W$og?_D~n|HVJ0@n`?uC;ts^{iy#bJopd9e|hvDFxAhc{%=yWzWA@a zdSp7a%a%5$BD4aL|6SLU|6bwTxZ%N@1Ni4Z^Eu+U@BF*p7Y-_n|3>ql!4OOSAN;dz zYW?%A<~h~*#XtRtJO6|6U;g1u4E4|DrSOw~N9%tk@$n+#ME-M~nf|D%l!*8gDg-(lsq^B+9%|6Kh0b;^@6JiNU4_ZI(!*8j}q(fntdx}Mno z)BG3z9{w5h^yWX7{XgcY^Jo3lzuyH6`;zrP`Oo!4^1mnlJL^9b|IE`7|L!A9cmBCQ z^Q(Whg8ni7*;`!vJNx`s{~i8k>wm_7E6p#)e?*n%iGQD_Iv)0vmJ{+H|Ic0h@6Uf& zC4KN8@BR0O{O1`i?EQ zEvf%E|8gq2_~%*5pZqg;>ZJL<_;)5+iNycNV5sk_L;W8-)xSsnJLJFkXJa}nqs2di zf2sd@3XMa^j{XGWKcoeFm_GZ@B>$a}`k$BmO#M$A6zl*0;Qx#34=D#W)87Bg6uxlh zzxO@%|2w)#m^(1>$c**R#+}LkH~*v5|D1&E{5w1U@#;TIPu4%HsyqHC>i@-mV)Fk- z|C8qb;-5pA;aU0OpZVH+Pcbu$3!6?zAJoqOyyXAj@l%oi;-7a7jeq~^i~Ofpm`7jw z+{u5Jc75NgioO44@1Nad@_*-_OWxN1Knoym&!~SXYv*Cs{EyhB_%|x*gu|L3G5#Iq zo{E3>%13|}K=IEj&(!}ZU8wXhul~8+KL6oid*h!$(#2>0!*ueWoZ>I*fA!CK6ZxN+ z{Ac3hgZz)nQ^fg)$^ZVrLw`N%f2v`b#}XG#)x|DPY}0=fUAPP@^}kF0`$Hie)XbXQ z{CnP4YW=$=|GB`&%@N+t2`I*O{lC=zgRTGBo-qD{?8Zf(nvGKNe}3^Fu(ODNWa6LQ z_RT+c;`k%-xWeL}W75@s&>H{Y>OXW^2Jrs7`1dsbkN)RjTKqfib@k7~!8}WifA>BA zgDc%Q_-6-5{fBJyZT`zw|DEyAwTV~%JmxTO{+V%c4qf(Gt^bJZ{^Rkklhps3|D^QZ zKhG)4F$ga#;ol+u<3s+tX|MU;N&Y80|J*F%x^vgZoXh%LK_dTClmGa4;za%D>YwKz zB>%l9D-wpime@VNg$ z;XfE+>)(CQ&mA#6Nc^YbpHSf1?q%as2Wt$(hunEk&%@_+Hq z8%Zt`U*n^HCr@AfGoJ0}KWF0Q-oLN@7x_Z9)pV`P!|J)2;{PQ~JJ)7A7Q~zGU zsG>&K|BHV|{j=-V)X(UTzw=KH`oZSETm1W`{->XG^8aC$|A2=-)jtz@T*-g@pN{^+@{hmz??c`-`-}gR*8h>#|8(Z|yhjz5 zJO31CjVm|C@id3R#kU^N#$R|F#=y{6`=B z^Qk-fXR4m&KmOfoW&QIV$%TO>|Be6YPyhUo{|(>E=OE(NkktRftogtBpTs{Sk;s2` z5>h7@|6$l}`S0W$Gj93M9J_Sqzajt63>8rSKKai)qNrN^$8Y|f1pk4}|5yLFzxi+1 z`X2|ptHWcJCjZs{K>n+LFQlK$_~%OENB=T&C-fiODBJm;?-l+T+VzuvpY{LhpI*w0 zmi}Jy-zERq>*r-MKiXX?M|GJe3Az6|nT{a3pF z@7Db1aWbj@>CC&4|1|D$HIyMKFZs`+W$_=M@gMM3Cg+onkaHFMvraYnZ~Sv>ck$mp zILjMld>sCr#XtY;@8C&S?wPBk-je_LA2t8|v-o$pLrMPAAoq+2_Cb=d^b3 zpKiX#_$MlM{)fv<{m)drpZ&K*-Oe%o8);|ko;;a2jXe)JwM8uJ{~?QZ{%7^?QU4qN zbN2}F9~}MH_z#$8b)x){`d|GczK{=Klx(TpqIief+nY|J?31>wlB~emxogaw@{=SN*r@-!uMs^xpU%t^fSR|G*qe z$^XrNvE)CqFF9FnpRZf09#+sh|1GnySO4MOKZg)Y{r|<-pm_D~Mlb%E z7b5|h9IE+-}z@Gsqx=0{^PitH2+`xCr*if zwm<8ZmwH(LQ~&S$^KbsT^*{UfR{yMe#J|7!kHkN(IWq6Bwf>p&FqG}lzeD|hHvU87 zpLG!RKmN~w`uDE1fN+OS@_%O9r6>7MzjV@af6Mys5B{5yU^M>2HUH=2%8lv0|L41Z zDkAk?oS2fh^Y1cuZ}ZR5G+nS~`VV=0pV_n4fAGb$a{N1q!xUeW|C~&+ z{%3A4^}qGcle>HW^lGVpK6Laz)Z#x7|MRPVMvro)viJ|Yj)y+h{O3aM%y>Lz{cHVi z{D;*4;y>~q)h_>y|B(Dw|C!YPpZzn^!un6((U#=@)4OW^@BN38|Hl9PeIEFYvHt() z-_!d4=sza^kN)YZ5dZVeKaU*Dq2zyH^Pj2mOqS64|LC7tU%Vj_hJW?nzxhwde=iHT zg!|?{#Q&`MAKpC4|5@{2{P(i|@22>tA(n}DTK|9YKZyUr`p>NYiaynL=fBnbPaR$V z)6sXA{8#_JSMxP&{WDeK&gW$D@8Cah9xh+nZ~mP>f!j9+|FWwo{vFx>qg5e3b0cE! zpQiqO{&Tg1T^FE*@2|~>Ym|f^Pd-)P5m$aIj4&D{<|lOu^0dS zkN%nRNB;Z9e@gxbw+#P|@$ce)3dSzue&o(SFQ&w<_~$-@$$#TN%+&vg|M(mKzVSam zgND)YmSh|#(&gKV|K1(H1BzYzb0?0kDCT9q`cKLKu&IoH&-iD2hwT3in*W=B&-nM) zvg1yQXXjf>_1_FOa6zKE+6wcbjK3^{j2}p*8c@f8c(jCcH+M_ z`7f_JS^vIw;xR{NGN%Xs^jMMqi~sL{cU`3ZH~uTa(Cw-J=Q_G%PCN2ecvXA&53GN# z29W=?)c+pq|3TLOCjWQ-lZri#u4hjW|GxN7H2*KA{wM#9|AG2n{j)JA{`prJ|ACi& z4c33cHO_qkkI9*#D=`%@1V#?iO6^_ZLS)m-+mqxoOQXY!vr zeeD1F{7|J#`SjF3vnwL}JK~?$5a0XIICJ3{qmrv-*8g;u4I&=xyG86! zc+D*NFaDjXfA>%I%fYkBf9L71`9JX8VEwlT|G_^0+Y<`5(nU?>lvG`JZ_v|HprNe(K=L!{QH#n}IEv zH~-DzzZU=Pvi@(~rc5;d@z3S0v-tPLf5(l&+*lN_~w7=EAoG= zcK)di&QZvo$Dg1eb@0!wo$*h}wfLtc<68SqC*oU*8cFjX{~h^%%JDxK|70gURo4Ib z;-6hq^*=57AMxMfiCN>Hj*dBJ;^`0DDP{;@t`UjE|W33-z6 zpFU=+B%eCtpPozdpKTxGzyGuM-+jt|>p!smWAgulf1W%IsQ(}8Khydj{~i7tUH=>Z zRrlh*$3ImM_qjL!Q+4)s{`qk5u-=*WkDdRZ2#W78DPR3}d;gxP|E>T0GU1omi+e^h5SSQAN(^hDNY;Xzox(P5htOn|HXfYf41tE{NMS1 zZvMYIerkp#TK_%!W&hDXXDZ@>qvqx_8fAjAYw|4cwx{(BQwJmaao*DEI#B&Hork{hzS@=gpa(*_fOEI+6PS-9P;a;-8lR zrRhWRKX~r^&l&m8DxFyj>c2@${?mmj>;IqpGYD7xColfF?kxFl{m+Yk`7z_Tna*LK zwT}9arT(}68U76^`FT0z2v`3502(Pt$?Y?|F$2kfBM{b3PqN( zvi_(3XNZdI|2ee(@=&+Qe?G8Gld%4|$HlzQ#XoaiUi`a*^Xh-p{Kx;e`sY;V;Gcmy zvi>*u&ptU1t_B`@-k|Gnfts1E+)y?@{4{}3AgjQ7tM z{|MZz|6l!2C(VELKR-ABUY@}KTn$$#cJ zS^si-Y^nP)`)_u*-}^Eqh~oBy1UhfDs?X>{}-IenW> z^kGagZmeSl!<&Czd%9i4|F^FHcm8K)^@@LA{JV8mw`?G4{r~Epc^}6Aso|dY;@>y< zkN-*Q|LM{F@iqU&zdwGp*1z*$7r^>wRFKyH#y_89o`_)tqxkQ?o1OoPZfleOtA7SX z;GdbDqxH`X@2G$ApLNE6P@H|fRE__(;2~!9->Uz>Yg4Y$MTC*j$FpsOZ2 zs9oLvS- z_Wn5~{>lG^iWC3S=HJ!)=ZuB?7yk?pQvaUu&qFOq=`xE2|8(Q;{ByN=^FQ*u7WF^= z{dfOCPL4b`|BQNLp8O~O9d`{R{}V>l#rNpxa;LS`{8#^eN{(^KMg{_ie`frD^dA&V zg%kfwwi5q5ZnXMmfjgdSUH^-J9uZalkAa>zcD2d>JPMEgn|J@5|8D;2?PdLM{c}zt z{`-&qL-jxP>YqN>CI4OZAF2P@_-~H>dFZ+c@8rMnpD^+6=s%GCKlLA>z>p!^Gd;jz>t^Rp%Rs45r{;PjyqW)L^A^E@e&k4lLqhHUs|L(#jll)IA z*8dZC%+qJ$(>l$i;k|!f7K(k_J;{G&(@XvDp1XokFDLcSesUGIAs3pB|3EebUj0wS z!zcf(|M2La?tp8P0q`aNdGMp+fKT#2uY;xj*ZfbeJj1*BZz(Bxw{oP`A^$nrlKh{U z(@Xxlfzq>!1F>JKq8LXIFdmKa>C5 z2bcVBV)DOdohtdya8KH0)qgSbzApR!zxr=7t^fHTr+Fs+n@;^t%;Wx_{3ombZhR!H zfyIAk*8iQ~@BE)${MR=Bxyhvd>FQ)8+vS7*-X;IDo&TZdOtr!P5UKy<7M#M>KWE93 z|JHx;Kl^W=7n;!u(8SDIIQp-xf1a*qd&BxquTy*@|9J@0P1L{if(^{iOU3`Vi-#X z-MnMJT>Xc#|Ic=s^e~hE_@C5&XY>E)pV=t*=PIAc|At;t{EwVKNd6abr}-~^%P;x= z{G9*)FaKBR16Kb`@lUOPdV+TTeY#AJ{@H1M@qbtUuI&Gf#U$(h%FaDcE@;|9+@lT%@`Oj!`_W#9y`~AEBUi>@aKcfC;p1>*j=%4Qe<3GVa zlaxc=mOuLUB>(G{vu*s-`nvZo^Bj1{fLlPU|E+(T?zR>!Hj?3Pj9XGPvqT4t^Z&Ab7fKU|H)Vfrs?6I+08Q7 znpT(p=-;XHga5nuAIX3IN}7@Zoi_iSG?e`Bmi*_lqU--o>VNU?`0nPPizUJ4zoY&q z|LJp&tpBMhVVJH+-yZ(my?-X&mCoWn6#t(1KfU>9O2c=p_5Uz%rn=_;-oKlifA!C^Pt^ZyS}<_m zf6Ajl{_OfbGX#pXkow=}XmOYST*syU&rYYB=`hs)CjaT6%U29auWYMX14j~dSt>0KK}X0G4!SDe5U29|6=ja%~JK>Z2spr|1{5a z$>P7|J*qeV!!uyU=H}m3|HX`~PySQ!A3s?m8vhZ0vdH+aVkhbF&rN7A+WY6xA?x3N z^G~0;_%Ce!%ZQCb{?jiza$rgQZ~Svl!{$H!>z)6I@s(2l^J0YYPj{Hhr4d*BcPUZ) zJ-+zouBWr}Uw6}g@J}=4ICJTF@gFSyxf$FI#y@kOKKV~haq#N@CiyS^UHlIj`EUIX z#y=yEW6EBW|9r{dpBtRCsSWh1HgzWT|D1EU&*MQR{}=zmmjB6`|2}6%i~p31{NkVI z8jSxkE%>Rd|0$zdmHMA~Ch9-`-T#VNR5|Mdk^a#8mG7XO!b|MV;w|5bWV zr2c0kdhze2mn^aVtLu0X|B0#pxf3V(|Kk6)_-~B=`B5j5|F8aITmSF;j}x0*TmH+b zh~$4tBJ;48+@Ck~|Ki_Q{}uVK{`>oht6g^e&y^LAj>g4*CHWsRS3CaTpP9A?|C9Kq zEEWIh&VRz27$*O@S*HGd@jo`1wBzXt zmOI8jKVW*3{NMYpwEnL(|7*?vG`)QCA4vXN|B3a_9z8vIv(w*sz@smp8rYpA6F6cKGZ*DiTJOV{AUNp=D+dZkpHYYZT{crX4w1Z z4&9~Zk-+fif6)4$C$3uYAN90n{Nlf6koa?G*7`qbzdO#GdteyWh%hmrx{zomH^{@HQ{mm;2<=m%f+W4nCb{IGR{o;QrKKZ|N=~T^SC;qcv z{9k_bFHOZJ|8JD3{2iv1@t+?3H{X)~OzGm;g{U8Lr{S|<^PiU_#D7Hn&yHCnPct0+ zk43~=ad6xFPfsuYUH1RGt``5?XcGUlqeQR%d#(R%{%`&}CUp7Di+>tTP5vMK7wrEp z{!felX7SI%O5(q_`A;AD(SOUs21oy``j;15HUCe)`=>LKsjQq#@NJXantb!`kpJ1@ zzx&{yUUsejt^Y?|oLbiZeXjnyeD(i0_zyyVbf=nscJ)6={lD|i`49Qem86dRr?-#% zxBgr5fAc@ngSYzU1#08JmHMC7f9ikZ-}zts(_cmY8~?5G-}}8^8vnyn{BxIX@gK?h zAOF4eACdoDj8y+TbU^+y41}FX$$$LMr&RpkU;Oh@=q~?xv4#A{|FrsNYE#nQ5B|rL ziLY<|8}UDB{;&S0m={Up{(<=CcKG7I<_3j~2hsXpUNBVu5xbXX>z^k)@PAtKzxOr& zIbSR;+}g4Aze|Qm{ZG%5^`GINaeX%b=a2^@Gn@Z?RaN+Bz_L;_;)1#*{+fN-}|3s{V(}1{+Xo6Q<|0Lzi0h3!Bza% z;y=WHw&g#s+H#*;*8j%;@WH=-&eL!<`EUHY#XVuOTk}7Wo8{`iHu-P-(}iyQhv$?5 zg{yy#kHvpmxm*4({==|fUKD+E*Y-SRZj65_XzKsPKa(Z8)aHLC`JX&lBQoRqNB@3A z?ZPlC$$#U2tlM(SfBXj-^Z)4IKl<;t{12kVKi?20|6lw^;-8+vgMXe=B>&kb zovMudcV+#*_n#a874N^@)jxf%@#?=a>;F#I|8Mz!<~4QJ|1r~NY4{r+DK8t7|BNxz z{O|ov{j+b0e}?Ugf8Nt2|CvF&_-F1B^?$^3)A)}h|9Acww0-bTGl0qeUh4l;{rh!h z>i-x2E&G35K{x*MiN1xnr2b$1d(X3L>i>W{geCCAf5#rjWz2n=#jO9b&GWok{qrb| z^&iUmU;Pj1Rr&y}|BwZ{_0J3DxJZqEy3Ahu7x*9WPm6};e|AqZ9)S0#|KYat&+~RQ z{s;A+n)?4o|2$5h`OlsED&@t*)&Cea-<{@vm?anEe>mj7`ezbb%=|3;xA%Z6hXLP}f|L|I+Kl_|DDDEwD=#5fA7guDBov%G5#6X$fyJA|H1h0$p4b{KmL2I|EEX$pkLnlpX)q` zJe&Xg6Ze#gV>JHjiYX_LAZM0;@}xzJo@jf|GDb$&+H2Sl<+p`W${0hj6t;i^Ms~E9yjE!jO72~zi`a{pUah_&A&ta zpFNKLW6A%V_5b4kO#VO8SDc@4 zb^p(k`hWF5#_}{H{!{$3NMJu@ER27KeJ=jlH9eK&KhLXn^!ntr_?M>*>e&lHy`rqV#L;g49 zzr*B?#eW&Nw1=qwq!$0o?OObITmFmxYn{LN=Zv0im)U9W1?>)8?IQoJ|7!1_J=sS^ z{U3FwE@u*(`hUpz-{PO1SoZ(+{*%0aJU0J<@gIKl&u69Y@!y#Ir$@x+RFnJ{|871c z;@>y^n|=QC4*i?|fp37-|HS&AOx*nU;$I$5)BOL%KdVlg|JUl&S^x2m{yB2+cppmY zfBaXg|CTpsc`4Kp|CcC_c=n0 zI9y{6q57v`D_iql{L2lhpZ!0rfA03gd;eT)Nyg$_B`^LHlmGH)`riLk$ZMKjcFtor zR{z}ndh!1pQ!b6N|IbhXssHg$wu%3&Y#&i){HN6aKC?~V{EsJINvgQ|>5pT_LxA|N zssEXf9>4l$KV?|_M~nZiEwU3wd+NV__g`86jDgB{?QiwZMSuKHd;fe0gDLF7vJDuI z^y+_-{NMSP$#SOt-~2mk{(I3$>i@ImzxtPPvrGL?fq#+w_j3Ffk=Fme`sWa#QvX@T zg%Qnv1{+NrlFIr&_N@OoY03Y_*I8-&M^n-5{8M^e&gB2zf3*7NF^(nw z#eZe?|E7#D`JI0z1N8k<{L7q2>VL)oklTEy+JSQ!m;Ws1L;S4oJfF7sAJqTM65HdW zrTHJ9o9M})bJqVn29h$LxK#htp+$J`&vVsG?KJ*#^&j%~vZwx;w#2(5Klb$@;&EyQs#$yZL8WGOq(%=nrNB7;mnYPbLMB z_^c3D|DEK&^i>Z4c1Qf@`1g2io%&z=SLAdi4UQ5$1e-Cjk{>!vk{4+rB z4yBx%f|?T;wR3GRfsR^&gV|83X2t!pQn(xY)aYm-?U6 z!V3Ss@y}J6oqu?e|KdN;{BN}WU-JLOKcC3We;YIA#`>qHQ2cX+g7vn`XJyTQ_3x4Y zd;eaZvJ-kam#csJ+~aKLpJ$?N{r~RYOXDtnq*W~bJL8|D+UBEwir8nh`R8llT9W^Z zf4VHP^mqUDF8|d(ms%zNfA?Qg|L^jj88e&z#QJAbU-O?sdd@g6gXaIM|8e}ue=q*o z_5J9-dnDFBuSgWy-6884=$ z4%a@7|LVp6toc9rJgFx6&j;{V|L2eXTk+595bEFA)&D#Hxyk>LANJLMU!SLl{P&mq z|Nr`@3%z;qKkWQdx3OPp{3q}J>+@&-><<3bKOY|BpVEuLs(<)1fuKBP21BQ*^-=FxsJ*Q_s#av33`rr5;Yvy3`Pds-1D;}ya{sY$ktAFnH zZT{=~$P%I)i#PwL)j!!R`~Ub)Qv5SDiS>WVA-MHl{^+0Sv+d@;@OU0=pa1+h`e&A} z{!dc>`#b*}%*O12@BMS^O8(QsywCsoQEL6qUd*uhX9mx2`JdH~qkpbJW+k1klK=Q; zxGF>8n<{4$J5~SX-oM;GIAvKWTl=H0`QJ$XPrCk>yQ}2?tAA(9fBre+e_|VL=f59% zm;66vz4%Xw7g`adi9>tFnji+_4z1IOpwPwIbKD%oSr)IY6xrvBgi=j!Q_|2zMj>ONNg zoKMo4x77dM&i}*upBMl1Q{aCx{sZw}R--d;F?%-kKXY=s_{ku8>z^8!d!FK-{TODA z6DkCZ@t>*x2fg{$zbE<6sq2}GP=%ai^9@trH&a!%F>+|611nG{fP)%~SH9 zN!Iv}*c7ig{WBdVX!icI&HppwYS`xgDfNF@ z$ooKh|Lk0_2sHISLs$fw`sX2PlmFc9Q2*?H;Xgk5Pmlg1UT?yGjQ?(EGZyZAvr7F> z8=R^C)&J$_KV;Fg=6_}V^WxewRsR$9KQA|K{;RyEK;=++>{!^G$bV)h?fm=d-?RQX zhUgxAPK^J!3@fH2am|(bpKmMUzoq`485-g8S>cq|_-{C1Aph}C*R}EAC*t3u{x29( zg#S4>hv`rL$8sp^|G_^^=Pv&FnY`}F&{MyAmJfRKSN|7wK4tES`ftTQ?Yj|svc1oP zo+qZ_lK<-8JyByemH3a}{h!W9|3kt0zti;7YHT)86+8cC;ly~|4#kq#=rk$&Y{hJ_0Ob6*S{2! z|LQ*x|MZ!sjAZfId&GZ9Raton`JbIbZuf})cFF(MKa<$Rf5rgz+LpF5eI`VY@s z7n#ZbY;YU$e}2xzlMXukyC(nnF5pd5_22USyypMvKjtYKNI4t_?H3yqn8!LF8=+!{}Ugf?8$p5#VD5~!p1lLX&%|-f5@RJ{u#*Z z)DQLF)RmJvn|~(J>0Ep2|Bjm0_)qaqW5cOc|4j9Nl4BG3|K`7aJahKLCI7AecJ=Q` z{y8~+vgul~6rtNu@Xc3p1Vc_*%|oX#iwSH?em?wbExR-tZL^S@?@0zUgM!eI5!m5+D-E|=jC`EUI*a!vC;$A4@5 z)6n)`{HNjSzvYaR*FF~ir#JsG>o#ssO{_$W|MSs*^~8VNd-!KQiuF(PmdStd&ww-h zkG&`UQ>p(C{<-MA`FBtJTfEpa`Twi`!un@36aPi`eDgmY{0GK={fmF@Qe>O|^5CB~ zK+eI9|7Xb2^^g8(*2RCg`hTwe^R60s7XAG0|0LJNe)iAJ(l`GN^?w__`mee|{PPg) z2mc&t{%8M8OFePRw8$t#kN#u!6V-nbvHqU}^*?|1?|IC8V=wvDf1A^k`oaIa^Y3c? zPyX-ySDOFgpIH{{l4j2|*?90px`-!tW$@3fXWqMre|7NBrsv{6C;y+;|4gwG2HL+T{+pt?SpSo* z|84#&-a^fi|C@hC8yWu|&AI5eBKbeYL$~_(xva#!Hl6=)CI3sQ|C`Vsqb8>n4EaAv{y(Lk zi=q!ThhDYypGf}GT!r^tjC&0O{z_N>!HOFJd70Pn8j;__lK-{N|FQhlzpwM(<=095KepNGpTVZmJkyu_r%KcQr?826t}6cd zHKqURU*=jo$Bvqq{0~}gzZ8SXe>QTw(dPeq|4*I&J<}>8@!!P^!;}VL*1u=+-;?~` z`Om5U$$wAkf1Us0|FY!2bIAX3@y{ig`knu=GyZ$+pUyx7he4A6^m(Xd{m*8r^&e3G z7g?hHKc)T`|E|vej9V9ZQ~7+f_~7w|mg~(s|J-3Nq-Wvc|5-HFKOfbORUVT9GkS1b z;?;l3SkS%yI^&Fp_9{~U)6^#tzysI$9aH~n|MV@d8+pQ^{g>QI%A87;>G-ecAAd>W zg8HBPQ3mWJH+!9Vk6=rL;jGr^R*m#hCN>C60i^54-oyp9L< zK*u&Ow0|u4?4M}=7d~|2pKFON{~gYzifr>wD-7+Q<`Ihfb-Mmf8EsbO1}IB2fDH=S!aa=bJTXPyR1u^5n$?{zL1ZnGGiYpLJd_!Jw*@ z)c<4X(hrLKr_ULEZH@n;rhiJC(v$}O!I-y;|AP8|riT<{+4pzpbwzjjv`Ulq$>*d9 zjemB?#Xo0uOzL9ii2T?7rx^cyR(c-R*A;#HS{9GSKd&y0f5v#>Us3-*JEwZ;^*^&K zk~kFqbe3rtq&gb^K{;`L(2S1czr#Ef?LX+_fwoY+KQB}K z-apUN@lPMJ(D;w>@9h1vl3e^d7kV-0?CD4cFzr7!{vG6s|K{L7dj@O%)76rjD){G` zrS(sp!}qxHPy2~LU3e|B`fs)W-1z5j`g!nArv~L+ScO^tyt!+$9{z;q}&;G>Df4cg2ZT?p|t(3U3DgNvC{_CTE`g)W9j2I#RSO3G=f0)xQdfNQ+sVRz_ zwXNj8_Rn4bGfl1kdZv2;vfB7;A5B_-(dC4>Um&QNuT(tl0FZ|Od6aO4Zi2r8s zPuo`Qe^UHQ|L6aI{`dL+KmY&p|G)e<`+xt-e_Q|mFaN3k|9{B;Cu;H!J|MXg~PJ`Z*~38L5Z&a$4e9yoE7fY|I=3g(;)7`2{g~;PW3-qcT6zn z>CB=2=lFQ7|Gi`VKe4^XI%lo_Jzf8^P`CAeN3TuR|D~<}X|%A`|C6l$b^V_|r2en- zVkmU|-%vW&KYp+H?KS z??Ko9*{=R)s;Q~}i>3bORzCHA{I32_*ZO~^%j8=Bvz|EC|Dn|XG~1@8W?#v!|0i4j zJ2`7fUH|h_b=2~#>1F*N>H43)NnQVU)c^gy{&%+ezkZgShrh4?okRW4XGO373+jK_ zJT7egj|a~Gc)7*y74?6XQvVmG{^y>%uK(#T{$~B(9@hW!ul4_|>;I_^xi`;(B~}7> z@vqqb;Fiv|5Z+tLDv7Pf3GQu)jwBNjeifSS2}I3{-06S z?biQIUhwLB??0?YzIJBgU&;P|l+bCOMYz)bi<)U)GtYGJALVlYaP!~E_F+dql7h=n z?EeiF_m}X05&!I7`cYezNy5>#+Z+GfpFUUP?%r?DQtQy>4AV&GvOuSq*5&x-#^@BcrG ziU}XF7bkh<^SXa(xVO9P|10+Y+K%plSr^j0h*6o1pK~xjH%@_n4*S^RH2Z&an=<|{ z@qzw)r2j#_a#~eB$)}pZ3qbXQcg4 z)g=3W@;p)eGuJ`;_XGC-jQ^+hf2Hr{-aqfin@d1T6kc>!Lm>^w801mQlj=AdQ#X5r zHTM8`_{4=J{5#y6&5N8bN@<2;{Xb;=Ps3-{|1`K}|F6%k_-AJ|V*RiE(?d@0{~P~7 z6Vu&W@BfDhPkpt24s9w%aFmUk;eX)iL?!-t*3MHlwhL#8viYW z7Q)QAX6Xa}h2H<8cV!Z>|A&9}hS~pPGgr?4Xp6}Cf%UJ<{vUTKXvCWHhv&e(F6pTx zeV%D?PP=%g!2ewGdl&zu_Rj{M_-Au4eB-}j*gQ=@%e{X_wk-KC{-5n=@}C*gea=O9 z8WvjrbPe=fHnyKp+7)sgxpn0HPyBP8)#kq!ab{S)_>b|=A)NL<6!cih=Gyqr#Q!yl z>KFm7S~o53B!N`x}b1dOg4K9~=L@_J6@Yqsg>? z2mgAMb?(yzg+zn;@=nl5BC2`@6g4Cf7beEu*Jk3syZr+ z|Aa{-*1s#~f7G_Cf8^l*a`vC#pR4o6zuNq#_@|dM*Aan$e`ocNKfV8d@}J^=wEpSy zK%aoQ<%yi5{nMT7Kl-O{5JUWQ{`*h-a}JXSkJZ21^TELX1^?sD|FHTmTgJVJ|Ng~4 z5BUDxKkefFum07+Kh0Z>f1dc$;8f24=||>0xhm2!iL#8}`j3Oak^DdV=O!Qbe{KG| z%$L&n|Hi-1v+{yTbvpn1?pObeG+F$oG+814lP&+BJ>RE`e+ENo|5P5Uf4(_h{Zqh7 z{%ilk5B{gcf9!F*N{7y{QJkY^*C3!}%{l+A|I*d@-x>eiHI6&x1|0lfcljT5@BAk` zeAwrI_LBd+#3KJ?nW6pXjDlK+U``R8}M z`7d<-JG=Zp`RD%T;y)q(SN|>-GdBODRF z^Uu(7-eC;BVz{&9|K^{|;nW! zwIQ#VdER#k9=v3TssG7;?LWCN>O<#$pVtZbUtP3+m({=2|Jwgd{crqdcMAKsxjaYe zfBd(b|9%d+Y-;L%o&RjHZ25oi&&*r#U;8W*r2c<0uE6@AxiljFnfcjpb&up@+-M*z zZnpYg=fA@>%qQ0`#D9O`4KNLqrT+IG+@CP{pEor7<04l_{jdG2&A-3*KT!Wy7a1*~ z^B@15b1D4S%m?Urmc06>hq%uFt4~V=>i?4Z|Li|~gyg^R?=1EIbMeos9M=EQ!>5rp z{^?eQ|Cs#GuNV{md`6so{G`9HXyIcJ8>!$vvX&m{_KbyrBzYFeMocu>R|7Y4~ZvOeK zX#W`C(^Wbp^*{c(gCOgF?VmZw*ED%_>Ph|Y_}u9o$^U_OhVT57JUjnW#tm!g|AT*C zB$)hn*8KNsHY{RQmoNS+>3f9#O#2TqssDK>K>j-!U9qkIfL5d8zr=rR{ddN{PyJ7e z?8Se`epK4-{I~hDq_4O54~%~$*-ROTH@{!#xg{;xmykEQ;{zjVD8 z|J=Fn@jq}MO4k3q_FtCt$fa-FCG~jSFa8@{|8qazHTmDroeuw8{Kt64g&6C<;j$0) zzxL1H#~c5VUH^0DOZ|_3F0s)W=ir}z;p%@p`)?Niadut&(|yRDkW$blT>QI@&mZ+y z|0(r9{wwW&Ea``5@}IIjW?HG6-tj+a|0z?=_4=Qu7mVJ>5+2SU{IfmAtwixZX#aK2 z<3ap;yZZkZ|E2ZcdfE7-nU?h*mQ_{KerV{$fBe>e!PUjpf3x_H%PhkGb?3ih00a52 z{l~^XgEOW6_h=c}&*VP_#6P#%@gFe3E@y7y;(x}E_%ApAf%VTj!Dwit{wM#Pa>gJ2 zUCIA`3@?fraH8Yq|eLdpNFFp_5a>~Ve+5vLCJsorzJgS=&%{`k(Pn=K$B2{Qo=u^6ZfO&)58?)8vKbRf*#@G%3{nnFnz8 zPj^7cf9;=%r}&q*t4IGl^*H$F?sd8NC#`AmyU%~^-`DXKlrEX`b+-P z*&vx@|8MjEkj@y3e|pa1Fa62C%k!$E|FL53wp)vTwlm-Pf4t3q;KKaFZDn9&&(E+|KeYf|Eqrn z>5>1|e_{O>M{|?U(D91Mc zw7dLk|EPKIKgEB-%i+cU<8A(5bpA8$F`~!RwE5?1rH6)}{TJ7)k|BUYBOU&Q=(}-vBPk)`q^y+_@ zXX<~i#J}sMCjYO`@#vrJOOyZN-%XbMC;l6T2^#-0sG?`0qvXH%_e}mzv`V1<*Zu>W z{~7;(QvYAsudH3E|GRSU-!u8Y_s$S4uxm^`)PdiUl{*=NFz<_pT3s-RDE5N|M-uqV5$GbKeuU(e;&5upKUDh zPv_yd$Y1=E!PbAU`lo|~TJoQ(+2wfjf6@8h#4~l$d`se;|9Idi0sl0NYQ%qU@}K6p zI{#1pxnX(P{7YMC^8e(2#6M3*#Xr|EX)nwEzvRF6Pcsgk|NPG+{}};o@_(lO=MFOq zKi3a@sz&@*@*tA7qIAn;|KY-I>(O8QE0h1UBR$stmuEG_v-Yo^UKp{PJLTPVBIxrz zUi~w|+2lWiS+hE0sFcqC6#p}OQQQ@XI`Plo*)9J^@_)R#S#?b=w8WwV*wMdB&x5)w zIV<;Juf?%cBf&(&`_!89!kNbR55A+r8w?t4tDZGY##C;w>^Z0djU-*L{x z`v1|$`u}G9)7XVV|3CQeraGl?-zdoQyZ%+CM|% z*?-dhS;JkqbItmHj##I5+J7whAH492s}BBS?LP?dpEMkavj4Bx{~x-`W9Q%3 z{%7N#8y_)k=shOFx>ZjTK3)GC|Dznr1VfVYj#m6X_Wt?h(yWJ5#e;u3fQWxO2_+nA zDaNDm&SUlO@&IF>|Hi+(RO85*A%#2tp3Z+&GXBf>4}SAcLuu*s}*$C2_=*VC%ox`**UY zeHj1j5qmrT{EsF7CzJm)hL`<6{PUD}@y{)%HUAZJdf)rc#6RyCd8R{o9qIgc3;d7N z|1IMe&;AvCvDJ`h{|WwS;aG;^KVdENH~txGWc&x|RDHyB4q5#tNmDV7=e# z57Q@Zn?{NO+0xO&Zh>%Vqn{Xbd%wgQV;WK%{ZA$STmN_V|F`@vpTyByFQ|CAPX2dN|EsK`N}m`1b+-3U->!;VVLSio;c@;i{+$PX3!2p9 z&Qe!1xM{dFH}6;f(Vc+3vG+>-&+9Sj|L(2-&iI#Q+~PlB;CRTeIXZk(=tM96gVN-G z+63bNB7=Wl{HG@W=OzEUtN2$Y|E+(v09XHaUbP$lY>DXgf1W6v{~Qpk`OnUK6j}eQ z6R7|3@A~x3-1~2CyaJT{|3Lh+_o@2m-r~O(|J-$y{MY`oIH;~Jb5?yutmB^pQKp)g zz0QB_-!Jjc%zF-co=g7YpPyP1RPulIpW6I4{=J6g;m7=sgXHd8|DM_ZW1y@P(DRf0 z@2?eo5>Ea{9xn11LscX7e=q){%Ex~v{$=vmz++dARLTE${;P(Z;Qi*7|Fz^lEfC{T z>VKX83H5(-@?VkvL16v6+COv9w13z7=gXRBjx>~~{(tp9nEKz7$J613KKbIGBm9y4 zr>BDWuOd1Hp8azli~7I5vrOb+@7_P3kjDC_=cmqp=7z9f$NxzEPtStYe=Yv$CNOiS zvYVv-xBj_%d-BhFWL^LFmq$Hu&2hp%E%L(6f6tB2rT*9cfyn;<$be$ffrYCd82^s= z&j(rm4=?`n;i^*OUpjz=%)H3rfk*7Um+{Wi+xut1RY%|W5AaVv!jpf+ct7Kxu|%z{ z|34T>VeL(Z{~S+9{xAN=EB@&@=fuXp zn=k(7kVR&bhQ>clBcpfzISDKG{<&HDtAGFKzx}~KJ+X{`FG(J+{=3 z;GKUO@vr%B{I}XaZ3D)ntl0ry{QGbG)31vO&qk5< zPk-_E{^{M}i~lLi>61Mrw55FS-_`l=aFNKX#Q%KuAAfV2x%e-FlAeDFdl`xGPe+v1 ze@OnT`f>74t{VR=qgVfTlmEZ@cXa-1|Fc>Di~rX8f8d{f@)RW6KQq&f|8VEOU-Mu4 zFLnNl|6ud)TmMDHS((m%@gE-i^KOa!r{|C4zwv*MIHb`2Ie-u5kI?$>@n8PC|CsuJ zNV=QxKWhIS>wkw1mTUggx9$4kpN7mdHNt<$5n#uDE&iia`{zk~M>8netcd@_WnP!~ zuLnx+)&KL=|8(}R4*of{;7+3P&mIiXZv4{>XwCo8t!Kp;$Ikkv2Ycw1Fa8^y|9u~` z)}OO@@4t$C@lSts2F=AO`5%4zC12z+L>~VEo4u=lTKI4IANo!eiI*8i{mZ}?Z*|D(3~-}|XFWO?;p;y-+n|KfiT|9oC#b`npA@UKk%cTH~mbLA;# z@u2g+m0ewF8>0P3;y;x9U;MLQDEY5s{lEB+b^dSuC;qGx-)nFEH#+~BFE90fO#QDI zNUrej{pg<-&J4IT`7i#fTKg}x|FZsO?#Y(_@t63I$$wfn8UHaIThqnAoMD>$=M)zI zcl=YHcuW3^|4`QdJO9BwiJ6GPdjy^TV}H5Vv(Ep?=D)`YWPcr-&3_VE{~QN2(}V3y z`blg5wBr^3p5(vrKgA5w;09&a==#6Gzmt}?NZtW)XC|my-o)wr*Zy5Dc#3~d*8j%8 zv*f?;a8?o3d;jgt-TU{>{zLM=-PQk+|BPhO`Cq4!|M6GG#!8QW>A5BTDWq2a-*gef zH+|cT|DNYRj1Q9Yzkoi?@BGvElu>EozcK#D&HvcneEd5Pt~qkoFL=fygP*tp(3t$6 z?(A(#{lDZt{$q#w-{e1c-K_sC6#vW)ll-Rz593Lw=cNAM{I|OP7ys_&zti=fT_5bSMXZ`=)f1Nh;(cSxxzdh=IHee+G$H2RB4u19@9Q^xI z|4)+t#y^84O7B1TZ>9d%{#)_S7CI{^>)$i}`vm`dR`6dlI9KOCXGDAd93D*kSx4jl ze#n1n&Aw>|*8i)2e(kG&R+Bpa)tdivK~I(Z}`d8d$zZn0c@$dM(?=S<=_#g1^vi~psn^*tCmG^@Mmko9PC%i@) zCI8>}e`^2UBWH-9)c-I3d+UE%{5SabssC61wedgUpT+n0=6}XNSD)ONQGJsC({<wo4mul{AKqxRot&E9{z^UpgIlm8`mx^E+2LnG~Y z#6M@Bvi|3XV*RiE^9rsXB>yL!|B5+lvi>*zee!?M`A<8v=-VrqyQ1@dH2ELLi~opM zd9449f1ZId>2ja{-Sy<3J8GMMx7_)!W{3L;*UD>ogeCsDd(KQv>i@y|mn{kQv_eMa z?EKfhL;hC}o&U5PQ;K~*lm9LGe+g(E&N@;2J3JrL{u}E*8lIl-$ohZpzq`}7Yr2-! zKb_EZ{eSY`==z@xwv3hU;$KBH(lq%m{+W!V^WXTVPcGM}XqR8|onJH=d*C|%NA^6J z1Hgx7^?&7RlH`9|vg&00FaD!18dY+DvHGVQ;hO(@|9+V2{NMZUt$#-6eA4_hHvWU) zp2p0bxBk0vxQc(p`k#r+vi@%*|HVH&3ERcLv-i)>Zt~yn(**zO<{kaZ3yQ9xGa5If zDJ95%R_PNRz;yoa{5$kKYzq7{_hHojo8XQANc=Ml1pgo8zpLwiw=({N3j>|m|L-4* z{|~+YC;kik`;z}I>wlg9ZnWgTLu-X#68|~Zv0wb(PW}gz{{v&#L!JPOf6lk4|5yK2 zbEQqU^`GkcU+2GX@}IlD{zK@d;cFh|0DS?{#_pFMniG%|Dp5$=-+RcYC4WHb5ul=f*}r#R{WmZE=R56TBc=17ZokvwpZ8qi-?9Ev@gGY4 zzw__-T#noO@80?Eb^d#7BH*9h3!VRY#Km_<^8a7`Gb@H!T@6=2@gH}WaPiO2#gKZF z|4P>X%sl=G7{p@opCR9LrIqzR{-baA9`-KvzvMsuS+%R6GX8J)@1N{bE&ly1A3Pog zS^xEY2+04ibSY+}A-D0*zF=Edn}2#Tv;Wt2+(h$>x;yxve)P|0Me6_G{Htty>%XM_ z@95KP^PhY9yZryrKZBW!|8DWG-uY(+k;#AjNBHk9^jl=c&L!IAe?zZs>VNUiF6_f$ zc;#bS>i>@X=eFg^KfQC7{2!(M*ZJRW`7i!Cn9N7pKFOb z|E{h7wg1WbXCR37KPLtLN8JH5sKkFS_5b3ZT(tRb{Lkz9f8wlC>VL`q&3`QUPyJMJ z0f+jZ{10Wk_JIH57ym(>ZvKbc(`j}7^C`?Z??D1j=fdyy+2WtRjki$y=U#!S|Be5W zwWRUS8&>j-=X&%#X8kW;<&yu_f0T09#Hq*O=CPMHv;HrKhxi{@|4aVMjBuXY+~KUdjz{u%bk*Od0pD6*q}_3D4z z{Fl`KJl|OT&yxQIqxp{h`Mi+-Z~U_=G5(+UcORaq|5KJL;y>hAX3Kwi9w#&R1@X`I z^zJV2cCTziC9MDbrm^{7k^em95&yk==PQo<=Yg%{Kl4Ra{}c5;{yBE#`YH84^NH8| z=NaWb|NWkKo|6CKpG_kgALHLA|Gk*U089QG|KV3e^WcaJ&>S~Cy+Ztti~&$`{>MhN z_Rl+*H~w8tvljpLXCU>zwmo7_x^*Ee_E(}Ofl2`GwYx0RB6v40RCym zt@9uMUD(e4>L2EuM2i3Jdi2jyZS_A({y!Ve(RKYV{{8Qr|L4*Ftn(lLv~tk?UHtpJ z7BT+$?*!jl{?i?{u=&qx)Fx;$@gII=tkChV{i^Y0_rV(7c)Mzi|B3xS z>wh}>_fGzw^SAXsU+Dot{=1A2`^mr3`LF%cOYN%tyD4{ASO2^M7XM6N)c)B(`o@3r zgMS*hOa8NkZ~W6=ozX|s|5G6Ke;;Z8!!u0BM*FYCf5Zw}*8j#o4FbgflTqK!eEIMr zx4$uhPyDCc;@J5QB>!Lhv+lmtI{!mnrAIvPWgJG9_d5T7^56Ilvy+zm_htRhushn# ztp1zLe`ox+2*5w>PfY!9{QG{U28GsQm~2ckiwKyWHFRXOMQsdG(9`In3#k zE&fL)3$Xs@fcJ9p-!m*j{1@7P(R|Sg#b^CbYc29W{9>Hi-oM)W=XNr8n4dfU-{e0Z zM;h1g{i6LdS|%CrpL4t5C;#6qWw>7dbJnx^=WtW@9*lp^dC7m{e}0_(yEi5N1MPo~ z3(5bp|A72wmI@2cj&^iQ{!@6o`2Qj;<^10nd^$q$QYBO2gW2XG>!oY|;oM`FYo@FJ z&lmqa-|5`{QG5U15B}#%RZIROA(s6A>R$4n>zzGIV-cTw>lEdKeq$baMCdB*s6E}x5k z`snTbhhOS${3}!cvky-FU(XJ?d#in^|HGu!{uzfS{-4sy({P$A-Z~g~5V<^Qn6MBGX|JQJ${x|+rUK#%t zT}Hx_e-0(OX32l+zgY5r^*`wRcf;EF9~0x>t**29=MtbJ{u6mx_})L0b0q)6Zyuf* z|Apkg_V2y-&mf_l|HS*v|784+oBsg+?&iO_PjrNo$KfU@_ z+(0n?Sz+k>PlLH4d&z(8e@qIlH)Wg~chvvdzj|ak|F!?w58J9`RYCpVW{dw}^B?sm z|5fP9{=b)0t+)CgeLBJ<+(cL5o&4t#sAKY9v5hGHWBgB_-dg{&qqX7i%*v%eMV{BLFO=Ewou>OYqC z|IWX6^55$9KlyL{J7@oyz|gBI{$z7 z-$?yW{`)%r`OYB!IhEtGm-XM0{~`aCgMVJDF8NO*=7IX3yTl~YQvWah74^T)fA>cI zy8&0<$^X6okote%O||v!G(1Tz#6Nr6Xa8k=@2Z+6QYQa9W-=N7596O(q^$pq|5@@s zh!y_%(|f-5&)K&2Plvp!|Hi*#>wn%bul}R)Ci(AslK;j(_gty}xs}hIw0^p{T&%W!t|CDo_6Zho5 z@t@3(S@QqjpW7C{`S)l*I!!wN87Az^!ASo51i?@K`4s~9&J}-p!y5k){=J)n|5ob% z&3_~Q>3W;B^|b$S=YOXD*Z#Swo+<9oS^tC7|Hi)u zKI4DV>;LiL(36_{A0+>|S33WVfA>L?fll)O;NMZSnb7%9TW!gI=IY^}^Rv9< zPC`xL{^CEnZvK@TdC^t#bN}R@!#3@I)c!{%rjq~68I$~1?0K2|pPG8-zuWug_(Af2 z=bxX8Y2D<1eD=@taP8j@d2h)jFm`Fb9O{4kJ174{y7te)Me=|3-|76<{-3LVhx{KT z|65uAKgs%E`|lV3 z+#}<2jDMFG6F>QPcmApPouvPmjDI$GF8Jr=tmMBh{=2H-HQLcX^ErF7{`da`3=a(- zom{+n;Gb@!)SqwtPvXB{{d=rtFWP_1`k!`GHvfJ1o`p957yrG(Z}s4xmIvH?FVFeE z`KLG3tN&*8&kKsZ|7h>O$3K_yssFA22T?Bh|IU9Z{vG^tD#yU->+mtZ^Y63&kN@cD zZT=nOzt{f#yybq4`1k*0^OR23zhm+r|8Cq${{P~iKFyo|_DV&*_uq~smwnIv**@O< zbA^2MPowLZi2fd_|E+&!&aM8rJ$LY*+x+LrfLZ@XS4Nh1jVJqmKl&fzZ=Sa`;|KnE z>zq{9|AoGN*XiWnEwq37Esp+|DiiI$znJ_F;=uU#m;4w1kvCQ;{%6U5r7oX3|F!>s zs}OJevsuNAzuTPqI{)!MOZ|`kh*#-*|I*i1^8eZ1XF4Lu^G`Ml*uTghXaCOTzv(^l z|FQGmr$73icK&%WM*as}HW&Z$@&o@o)fsPdy7;G$>~H>=(joc(-oK2~)c&Q<19z^( ze}I2V4eh@p|Hq>Hq8$#aPW%t-|B3&k4)9MeKjS|*`KQf8$*t=+vHl(Ee;U{G@3;Qr zxUWBHN4fW3GFFC7i?jbw=RbooJmbG&aQVn1DV1{0OYJRRq3kwG{u}?a&yVE(@y&50 z|HXgiaII8cQ0@GW(UVoW5!KX;r%{5RD9)<1^>{eu=VI{$sArGVpH z(bWHAsQpje7L@uQ|LGh5ye(kImkYfn|7Y>*#ugHJ#@5R@EpFh<8 znd-RYf9{$3pDRP+Uu7r%+~}@{&vX7C{L`$#_@{S$;Ff#;uH?V=&pCg?SBmjpb@as9 z{73B1U5$TkM4$ZA&;kEkTpn-uXHUxbS0fu%yZpyLJ^ro#W;XtVdU#Iwukg=IjWEk; zwk7`Sifv5o-&y=8tN&)rf8(E7*E1&x_;>OD$t`MK|G)b8m-=7)f9m`nzVWXX|1`Tl z`S)C@{}=yl?(&#Y=l{H`|FwU5km~%8yOH`|=l>x2zxa2pfB(fl_sH*IeG|J*WS+Wl7li+`@t8vnd9 zvH2fK{)_)k^56RJw15BTpSz}w@jw2B{}KO_%auUh#P~7yEf)XzF8@EC?&6=fft&x~ zjejNk|BHXxu0+h&UHmgIJL+3nmh1fYd0U_k{y&_ZfAxq={ja#AE9d{@zxE#~w&Q;E z&+`@If96fL@t?o(KYn(${-0U@^N!rn{+SQ*!DBn_I`8}|?Vl!z)c^E#`NcoCa+0BC zQ0w>NpZ^N}oqhfnTq{s2$G^fqv)1vSNd6oD{?~jDI;sE9{xNl{U;JmrzdHJ#CI7{L z=g-vt&7C!XuKyjE7sSkD5&whs-;IlZ4(o0Hvw0=!e?Alb%_682y_5?+3G=dk^FRNa z|4IDA<|qFn>wj9R?fl1WkWfiU{ok(jzvTbwKi>K0O5xuB#9E*H_r*VRmVGZNUHr@c zaXD|RP5!%or2eN(H60haBG&$W`Ll187eTCW}W)v*63 z`Hz3k_@@WjcNUQUJO5vM|Gvq8=hk;k#SWvb|EG%Dn{nMH|F!?z`sb|YHqUg2+UNhy zKiBL-lmCnV>reiDW(TOR;mJ2NPbx+x#HTD6GRNe98K~>{DgG1gd{h4?y8h>?RwVWR z^iaGL`N4mXz53^kgY{o;`9Csb#`yPs@n7i=Hy zzmxqxo&PlLbidi#Ui>qIN$P)}pMR_W*^{V@e_suA!@nl(jDKl%Y5hBVYHIDDmk*St zb1^UZZ~gm{|7kVt{8M?H{nx91$M{z}|GY(s_^Ds~M^if$3Hk5lpDI$*?bW|W{!3As zFz~~Z`hUv3#lK_ne~#Yyuc`mLyW?`U&G-kM|3PN*|0n4-C*41;`s)2J{JTg0!{(pWmH1bat2qCY{Kr4frx_Pu{XZBq zci~PZH|JT-NdE8qQyr84{TF|e%;&WJU7i2pf2965{u#@*@5z6c{GWCHTmN+VuN%GpH?jUV{^{HP@#;Tf z|8Ju0YRp}9>p$J{e=7I>={0Kn&(#0_?%yT<_x|Z0pyU>Cx%hXJcm7*n_WxY%znQ52 z#XkqzXaDoB{?jG@+4q+9|KR??e@p(K{nLJh2Lw9*XQ}_WhMUp`_l^Hh@_#b*zq|RL z_x@Y*f6)FJddH7;y)aDUeb8HnPrL>?=iIh z%KGoA|HXeSeUI?Zw>9SZbpCU4l(h7wHTA#b|1{GbhCBUc z{ja!0SaW!c|JwL}e7bTE*!X8JgZiH_dC6s9o2+|qG8D3hJ#>rzz~+Dd%($tZ&Ac^f z=&zvtkBfg=!qY^4`c$0AnEZG7jwJu(?^M?R+=<`$@2LMb|IWwL=Z%x(KVAOBzefj4 z@qZsW<`as48ndNsPv@qk{*MMaJg@#;$$#y?WBu=epr=;^>wky+zeM~`wc~uu-(0Mh z{O7Je{fs)3{~hapo&S8dMLaay{NE)1dC%?YsZN{!)Mq;AlK=ElzDoYD{wtnzPMpmzRSCT9#S3%9S3!9F)v z1j+h;@t^(dpI-p$f7+pNr^DvI_OCb)m;AT>o1n&jy!dZ;Q^}12dAwQS|FPyj%~Fhi z*0JwX3U+%f*)c?#EX{)_|h7?z){6G1pIhM}Q#ozUaR_#f-lzq;d}!!qMPp#MOy`FAqfO8nwKCjarzP>zY2)-u8D^`QM3u4$I_Tnf0#}Yg-!Kz516T z_vBwm{jdEiUH_B+2mjo!H~GK%58n6>^!i`&|Em2vQvYxMoge%Y(z^b4P5qDmQ6qReHVk&q!Vu z@bp0W&VBsz25s}tmpcBPU;VpF{;RuV{Bu{L%Y!E~lW)^R{(Ge8;-4;GTmJXK<5QXZ zU;L|`f7ZoY{^P&5{-=NrBzzf5{_{jUW;WAx{v40~+2}R?d1U7W4~P7p*Zgm)Afo=K z&mkvy;=iTs{-4bH=Z#~i{byVL^FbYT{_p+M&R_QbU;O*z|K2~3eX82>D%n9#HMXV@M2zxkha{%il`n*aQH z$p1<5pY{mz%t7DYzt62z?Oz@J&t=?lRa^T{Vw?X5|I;_KJ;Z;=Rq}#s#ja=ke~5p2 zGq6c(^IsYNGwc7=zv~(QqxJ8Q|EvF0`==Y9F* z-p`+G2d(~<&HsV=pZj$?|9n=a#lJ`W-`V{CKl$f|=)*Ps8Mw&$|KQ)n|8Q}Li;O#0 z0iR3BfBf@ijwzn90sI`uf4=|T`S*YF@00&-8teQg1C9S0|BNau8OSC1@32j2{m&== z>iR{a!}tDKVXXQ8&cD0(AMwvKu7iJW6;c25c9k|ei+?8Tm2@28vdHGYzYmN5fY~AQ z&OaSU#Q)^J_sAXa9=)A8$-*xD*}ZNg66)>VGd3|Gm`z2miF% zVyeT*Ker+nk74`=PoMgKps$7Yub4_d>H1%N?ETMD|Nr3MIrxvXf1h__I{%AYrJf_( zDQEwQ_0I)B?SFXh-}@{7mCpZUaQ+tn4+RWrX{^>xx`KMVb^*{axUH^A?-pl;pf7twwXk zKj$ki{-ZbkXYt<+TmDPmBgy~8zmxWtd0+qg9BR60MElE{tMiNh;Kl!F@?ZO>xLESv z`e&np{O3tOm3hJK6YBq}*8b@lP8Z{vy*IP|C;#bV*GxG@V|O9{%ixCpWb^OJ4a(a3 zXZ(rr-_ilZkGTxPUgqMTH`q1)9m)S;=-&BvOZ}xN zG5f}~?o<3vtN&;BZTvgI%=sT99a#VSwDFSsU;TU0m_1$m zkGUH=Oa71S|Izc5^}osga{4;^&*c7}_CK8bbI(ou%U6CS{=>z8ee$p96DR&T12X={ zQ~u+h=~CqXyyZVVfQ)}ibiRk(XGGrmOzPd*VM-yc4^toqwKYmEmn1t$#&3 zjKccoCIY%;{E`3obQmf8#y{I+NB_gj6I`?YpV(>6=w-L_e{nwXKb!SG{%JTs{#*Yv zc6-d<CF zrR4u`7yq$_3Ep$S+>|X9j7r_fH%0_x@?mzWQ%?I{%Y@wfLXDbFbLtzkB_fc~HOj_m=#Z zrwN2oCO|JDECq%Qe?^zX-97q$N5F;kNNKlo3qe^2|T@3HmI zJ^QnN_uzjz`}e=Ce}1w^X3ntxcl1A#|MTzuo3sC9@ju7k;(s>&=Pmy?|7VNWoX0o64&l{f$-|AXZJi+_qR@jpoZYyS`J|1om#!l_d? zi2rGrCI1V_|5yLCq368>&DeuC{%Jnhjx@%S^*^n%$baLX7aP_;_mR#1-&_Bwcazox z-1xBhZ~U{+;GQ`CA5#CfQvaL$fA!zi+$!GXKSS1;1SI}>aTv4?>;Hf8?@mmJ&bX=0 zR}=oZUlp;V@!3oMzw^)V660Sj`Co1R*;BFp=RfJuKXXVV|E+&V@?ZORrr-TLnf9L! zp){T1@nd29yZijd|9#DWc1c4ZHse~aJ z$Nbm+d2p>h8yb9&|M;JD{?7^ixoUaS`Hz2xvq`D{wSOi?`2okvJW_4AhxyLGOa500 zmzJVX{0H@ovlsp=lK*#`|G^Lbqt(CT{5kpWwf~;_fAVfk1b4OgZ}5w#Xp}XlmEQi5&ykj|1bWzTHjw87P<59t^VmR zT#X0+k;#9`-!=caOOZH>e{K>={`VQxz|KFnQGM;7CA|2LcmA1xOW%W?fA%s={lEC< zFGbh?-E)-uXCI6DU;Ix&F8)(Ka{ox10;&JGu`%7re;UV213u3G9r4elE}Q=m`Ohn$ z&3|v|f4Z_<=X~+cowbIpIm{tg{11<$a+mz4eMQyQ+$zLB*CO)Hdweov^^Je-VAccc z;wt1tXWs|R4kP~yo&VZD@5Grz!5f;hfBy7q{ZKhOKCq@Vswob{9c?tJAIxb^QJ{KHb$|M|(kGWpNo2IHR@F~)yO{xh+d{Xd?P zt^Q~4)*k)yt()+L@ZhMR6#snD%)j}crT$;@pPML>|B5>CwqQ%_mpFY{l%)&oCPWf<(e|hI^ z{nHGl;Rxs8U*Vt2^-KOQ{++AKb|-Cl@jvSIKg$iB|KdM#(@^_o(1i6*Gk)>!F8&!N zZTyd~{++#lg@1ZCE&1Q`3Xwy-gMWAR-_mP=U(&5-RethcY5&y_S2=xee)eAt_euOa z_z$CE9KYIwe}#YE&}jd`mjC$g%=&-K#XtLNEE^X86Ze1SnnUru|5301CI8t>H~u3( ze=>)FjV{k;f{hpa;daB29{kUZ@gHseSt`Hx?@<3s{!eLW{CnDeyZ6t=QuE@UpDdD| z^WvYMKcKb2&VL~JfAsI+m-THcliR-Y&r^NtKaN_~|FQM&ZvLmuf4%q500_45Cmvqx{PTa+`9G%b z{0G*5lSK4W@18^RrTtHS&tSUMf1vY!@88|$zjyt@e?ssF`)#)p6WeDTje z^Ui;4{7-+<{@{OLm+kC-$hf#SwMoqW-^o86w-W82H$vn;V=JitL!JK|^rW=#bMeov zIG<(44ekBUqtyS#Kg}qq|ATLv|0nfhlJI_E7X|MZdA`S;oXV*r3_{nOpFocdS) zjA5Yur;{G}KUEh7+Uopgl%>@F;=jayP$jGXp8Oa89reHU&)VzNe=qBQFEIXZtAC%T z(~Ez)@fiO+fN`$fMf?xq-;F;K|C0Z8r2R9@ zj(0}JfA1yg!}_0TYwJv#asV9^}o&k#Xkdc>0>{S z;@@+q|NY4NpU8iQ{1^Ycq7Jz!X8q4P|9O+C*Z+%uwgSli_x>w|_HU2+pUd1*|Kp## z$$#UY>#${1yXD^h{N=ONbX)!RcY6CM@}D+@eIX<1jDPn>|D(=-ml>Zs|IW^TyZW!j z!uqF{XVAdTf4t=X5B?{e|BHW~z2>Y7=>dX&z7!KCZ3ZsynQ3Hy@UKk%57hq=7q-Pe z&kC*oPpVS#Uvcf(lY8!5mZPTinrfo4#_FGajJ_yctkjH{!d?!GT;o8Ls{*=mHbza!1!-| z^grBlj#6q4N6h-)`cHNKGyYW7yaG=BEBW7YFs=T}SO1~-r=R1ie>F=x^~Jw? zX*qoBnZ~L8)9OI-p8-FVL^}WLgMa3?Y5%NEB>$PR%m03#|2&D;`5!W#qTBpC*ScnH z*+s$p<#E)c{qyXFVN&AXVZM|2FSY;dbKot*jXgtpv!r3TBxWaKUCuXvgNU_30*1hPup4YU;NW5pkTDtopxv}0;GM;g9f|_{<(ZW@1)_I7q#R+W2;#IlmA@O zr2fbMcqapTz5e%^p=A9tWaZ?)*ZDu|{MY_j;Tiv9l!||a|4SD&pX0Fk=ah2wKU@Da zeVJ*Nh5vx{zsY}gZjFDglI7gT76093ls+%oe@OlhtN)p1bad|$|B3P6P6OM4JO88h z@4olXUinY{8_9oe7n=NE{VU_&H~GK#cf~)wTaNynv;XkbKbIO0{^@0fe|fvgk-;a& zqtXG0{Kr2pg*X5FZB5(ye;U3Tz5ZYPJIos44GsR;=e&5I-Ri$L_5bESH2(Q#O#RQJ z_|<2LH*yzyHkV)cCKJ?EmwQJU{#Iz12Ujgy|!-&;M8d z{O|G4N0j=1ZfN2k6!d0b{)_b=>imE4&jaH6Z~P}`|1?Ocl412f+xlPp$JGC;|Ayas zZ2a?1W%EBT{*#^m;l=-K{CoJP%_6%xd;gu}KfQl#{^Os2PW(Gx_zy3C?SHiS|8M^3 zqE55+5AVf4iw`bZ;J>r^zxU4zxF?`{wwxlw){8#U20%m|L^l3{~Q^F z0|$QcV)LFWo&TGE*NbB9zp0o-Sr28D2G@3<|4!dahwmN8glm9dMKic&_{(bGAYpUgs{=;v7zDFZd7dQX2_8;r|pNd`T z|C9e{@1Hww{!Hhn694qW{^vo+G5<$)W$BQm{SW!s|3Lk}_^%}Y`zV-9 z{^P&W{<}5*X=$MIKg>SJe^2Ls^Ul9~;7$Iwmzl#_j%vOYpR~B<6>CaY3dw)te~|oN z{L>L_;IsU{CA%rE1sZdebLU5S^xV@xAU*Ge@>*=f z|KIul^6ra&`jI9P^*=jf`~3G(=6jg@=Trp$^gYKvtA~Q`4Drv7&y*Se9{Z@`ztr{r zmjB$*)A_&oXO5iYe;D4lw@Ci4{yp9=;hzYYnH|Pt%9xQZGE0HKz`Bp(SN{|K$0h%F z{uSRQw*F_zR^Dj;oLTMtQ?%3NmueUPyj$|jrmeXPOHN9})#O#Q$5?>7H|r~OA< zir`N#`G4>qOaAk2C*(#8*Mw#LKOX$opF{tf|7rCfKf}rO0*1*f{yRV6DY@i7y@ABP z^m!;{^Ks|j;o=Hia*TiW#k(=k`7i$cr}%fT>;e>dcO(C2S^v|_jr?!8>PbHlKVeT9My!q;>TNnSa z_-C`m`1hs$_ku0|xh|HF|9tFN{~P}S^}qNJbMimk>VNB>lK2Dv>2LnIBWV3MJx}9# zvd)Eqv;Sc4pNT|4(~hkF-}t8o*o*%Nu}A;);-98vtN(!f@5|n|`H%k!|Fy3FkN!EE zWb{aX{TKiJi~pGX$A5LB_<8Z)lmGN%BL92tGTdg?|4kzP8J!^e|1)R0_#b}r@26-t z{!{C}3W}ckfAvqJSn@wf?vAYgITu|0%ca$bURSLD#s9!R!8+08zms#FT>SIE^6cO7 zed_->KKN%>Q~P%um#3|g|Mh3T`RAR>G5-Uuvf2D+RBy;+H1W@U5S{;L|HB+_{(D{j zJ1PF1OOJm!WWhgo_h@***UG{FaPZH?tyllvmjBv+r569w$-m3hOu7G~g3A}HBwhdW zHd5+;@gI`^d;cBzfA-IC;~)G>m%nQCcrUO0*XsVk_8tBm@vo@=CyJ(&_mKzxLlhQs z|6OnSZ~XTY{@FlCqTK%=|Je==-^vRPm=$xH!{*sum9NqW@v%rzxZeOi#~bp{d2Li_VE80 z%Ubf^`&PW{J^K$#{U7D@0I~l0`Az;aL&Ny@B>!nKGqflFgUB`dR;U$nwL8uEtXT(-Nofx%Z~?|KPvLf{vC4BmO<(zmfev z5}o}&o&UzaZ~W5?&iH34jreC$9(y{*KL=h?|4aT)a#@S|-wionBma;7OUeJ$e<=As zJx~58{BvPi^8bzhkCT6e|55yxHve5N`{Dn?`sdz$Wb$A9Pvrlre^#X)EvoT9Nd521 z*cir-8~;w)#+!fop=tk&pN?rInO6b%&xqN};y;%B|2O}=_Rn<&o&Q5g{!gCHe>KJx z1H_mBr1Rg&{Dv<}mS}7Jzxe0>NAiDSC!h7d&VPse7yn$kTm2{O|I@X{_>a&2XY1c5 z|NTe6F+-&oZq5i@^1qG=)@Nwf|Mc*YE?+%oBjSGwOWHwe|8xL&^*>b8o#$(k|DE>V z8UK#1|M5Swh8lPN8{>cGV!828hoQwk55KK{uJVZgHVO{@DQNpYNylOn|BRuL{FnQm z6zyjJ5C87Og|}>CFhocGPdxR}{++1j;!t_^F9Svw|IUrUBDVf#@7wrq5B~XD-{*hy z9ZdId48ooN3IFtSqK&Nh=MPq?-~F?LB>6x1tA7?>%*NRHZx8H%mqp*thuaw0{~T^ZI7--x&YS5B{UF z7ylt2Y3J@d!r?K9|K}n9r@OcM=Q;V3|AWbY>puvcT((mmn}2$L_8n&id;jW7`=`%d zuK1~niT$F*KhG0C`%dbA_K}SLjG@Zxp5mXunwx(Hay>)7BFKOIJ8l@#MbVG_4{n%g z|1l$HZT`pflfXaS@Hv+`=6}jdbjg3N75w3O4}A}~YI5aKQ<=T<&%lNV|F!WSne{)L z7Bj8s$bap>v;N0eb@vOE>e)X}-q~rY@y~-iI=<-q@7MYt|B>YXd;iIWAwD5Zjkrb6 zjBxyObbRv9_5IC1L&V8{?#}Z4g@5&ne{QOaf9?yVoO9;EM^oth|H(g>i39R~^DhfS z@;@G>{$Krvi~nr#AMz;K5B}Xh9XH7TnXbmND?(ph@gISPNsRbsM_RA{$v*KP-gf@o z{<-)c&H6vOAN&up{@4D~vwyCD==^W&`k$tS)c->i&Hmy)c;o*b49o|);-6*hlK*@f zhAL-}Bim!-zwzINi+=`Mef2c6;@z_6UMl>zeT;ua{_`516}03({@Lwo>4n|*Z~Ui6 z|BdnAoBYo=|DMi&QY5AFUFv`FFMTbK{+lN~#*-wzD}SW^U;Gc`|K^`P7V3W$P$x?L z|C@i-wtispfAv3E|Ew2{|27x@-Cz4>1LWvGc=10;H6Z@eoqu)dg6<)YEZ7&<{uy>8 z{-y8H>Yr05?h{`|9%j=Q$mBm04kIV`>yrHUpZK5I|J(WJ>HO#3KkuWpf4PW7{)d+@ z-;Y-RiiTXPe^wY~{jdEqzIW%JhMtoD+`6ref7(Y`|1^u(`DcPD`EUHs)c^EZ6aT~B ze|^Y*x`EC*|Ens;fAW+6T-X1H{O@-D*>-DLx32!33)3Ma|CuuuUQPZ-+J8Z4TmQi! z|HIe(U;T4ONc(5*!K?pV{PSpv?@`JBO4t9q>|?aN&VS>-itgb)|M5>RC0;FgDTUaY z|E~MYSO1)<%Ko2|9sLi*5PZ-NPuKrj{@=sRzkBeX)yx@{=l;@nl=@%%7eg5E=KbKm zwEhRT zJ>U4BsQ<11(5(Nt7<{2)kof1#5dM|Pe@5ETs8H&E-u|2XKlta~Zj@819Q@PTZttHQ zk^Fb-U-EzFpN~{QR|4&y_c;E85mOhI8{(gt-}D-O=l{9$-+hUHjx%)r_hrVa^Dq6! zjT2|1i;ozy1(%sM;F%r%u;>tpIZqP6Hhr0ClJJUu*vX z^My?QZ~mS3o6o=Y?=T@+UaCpkCuOn!@-hQ#7v0e>8Htm zU$))%{`ua-zteqL{|RG@xcB&&!*uoUe+75X*8ly$+ld$dR5)|OR)5Pll-2*RdKgzuD(M{^=zf`>TIt{5LxP z8*YG+|5fT}|I8L&{c{Su)c-I3>&wXcf2RKTq6;k|xVtI-nesKzF>3Yy)c&9Jwiuf6 z?4Oq6Pwn5A{GS*9{qO#{Uw`sXZCI)={Bs?hgH>Js&nEwAZObqd$^TaBf9+r1xn#W~ zr>9H(Kg<3f>;I%lo{N9Kbr%1@N04p)IflF({VS>e*ZjBsNo^Y9evPYt+Q%RK(-&l) z|6X14hxCgmF!_J*|Iz07r{N#|Ti!<<^Z(mtSj$rXoBS95tSQAmQ;6n_ol{n*Oa6y@ z|GYnv{4c^|{_p))^ZlcfcR=``b^agybB`{ZXS4oy+IzM4uO`+|;-3q|G}{e#{zvWq zrv39x>Xq@V{fD~#$3J)Cb^ZtZ<;08{+4+yI)!zST@}Dv9#($TM3=uW{T^5Y&|Jn8b z*}t2R|JJ{{ZT>yuKhpjy`*&|54We+P|yof10d4 zM_vDm|FO0HS>9h4{|tZA^}q2S4LsM#sQ-=sfI&>F|0G@VfAQ~W|M~o6oC0%4r2gmD z(>LvA4*sjy_#eF0Kd-W^f9e?g`%C^)BH_R0&JO-vS^smQEH9`ky4tY+HwQ&({FnHj z7XPEv|3Omo=b!J~qhofH_~&2p-~Dqj(D@htO8hJBza{_uB)T&7*5-ed7MuT&*QPvp z$wuBZc3If)gktdzZkORPOa604K>ct1S4pc1?SC}+|Fi#z^S{MEK5hPI^Z@$V|0ClG z__X&wOa61aQu1H?kJkSr{&|?r>n%lJ7ykYHO>h3a)-khwErpiCP(mJ zF8QyT3jd+@&txFupD~+y{jc*s(Di?CBma&6=EeW8`e%Oj!}yoCd#isAIqy6F!`?sF zeEP+ICHXJ@L%sed|HZ#UL&Lfk{{i{G_upFok@yekS1C8m8s@juEi;|j(jN=)FW=zg zzxem^nDH5H@YMeKv`YOy^Zp>Efj<7(RP=*1pe?!a@4xr&dRMPr{r7wSG5#CLe>(P2 zs!RQ^^Pe{~pu!^{Nv<5^8w@)fXRQRs~i6v^HC$6|8pk)&KLg-7ZU&6uD1Ro@qbzK zfAQZ}83R*kk3m;c{B!Ze_~(U(&i}4D`S)J@KV|=q`d{t*H~7EepSRg3|Gb#q{Ab3$ zL;df^QvY*zBcm(D>YwY3Pp@A5$NjSx{{=IKk~FgZ87a=RUGdL^TIzq}pEK5+tBE1| z#8XTD2X0PHoIJdIjD{BfoN80C@R9h{KUcun|6{Zr!%W3LL&!tz-~Dg?>7pJR|6TC# z;wGmnHu+EEKHA3dVX0RC`N==6k9Gdz{~`WIss9_gw(s)a`0q0=IeS&L^Urv4@y`rl zNO;g#cwEjE2{-@6Pf9&1Yk{emlrt8oe zK(g=u8c6`5^}N1B2mqO6|EJSt+s5|TbXAd=c<}jB?&4pvnjuDgW&LxF&idzgD-6?| zN7Kc`gQV-ktEGegAZ+|k{xj`A+VelA{8`){TG_cK~wnfxDHn%;loKkB-> z@gGS37tE4N-u#p3Q%pl*{7+l{)4$L9XX4B;|FwVSU9j{7KyRQ`+qc=w;u2hjNUWc|;34$1#J-+8&pf39-V&}S;O z|By?~+_JL%N9L+<;q~C(Q~o29|7ZWxm-rua{&&xUZcF(0xe-qN9~bvXmcACQIt7uenzu`Twu} z2@6&KyT<>mtN4c@=;d`1CR_f~GlbreTmHv4v;ODauK0Ik{lEL?qAo}G)<1_-3>4&^ zOFkI?UYyhG+7bU=Hn0O&QUBxLVa%!&A63#tadeBQ|9Afm`Ol>&icHCWIzeS_z@Jb2 z`}n7KM8AgY+H3zjawPvZ|MH&bGK>G}&Hr%cz(MMNHeHg=-SYqFf9<$S_Je;%)&Fr) zu;DuMoTy)C7Q}LLqUwKN>i?tvMb-aJTLrrQ*ZJ>~{|@=@@_$w-qc4qr4&iGrIQw@@ z{?kTU{I`!<asEBB}pLT$TUE z|E1-P)6st%8vmiggO_}|nf!13Q~v*h|4{b-wSUr0{MVBIpZzD}tN*d)7KZW9TdIIk zi|OjLfZzNx()GeHAO4+75^)nx{4dzORlEPm_)k>*-!2WUpH2Q-{}cJ2M4j=^8Rnb+ zDF~R4u={tF|7u`XuK&?LmkHu4Pm}4*qWlkhdX)c$jUDcg4E=llGX%=`pWpmb!auyq z|Z*wv=~*Z#TdVEwlT|55Vfo?t9*3#|WzchFq;Q2u!#e&^oqi+`8;fAil; z{r^}0Lt3Ty53K)S_aEawko@Ng{Ad3hn!fqJPo??~|Gd%i8Pg~0f4+?*|I?@SpAl73{|DDM|Md4h`CqjETKuO6 z|HXgL^S<~`O7ZVAY@Ygm ztTz8N@MHhaeMC=Z`Q*QU1j((fb^iP0zw$qQ@}H3Znf0Hsv9#wu{%3|GdwEv;y z(zE10PspVH=VtE7f8YA`*?+J6UnD_Q{x_AZ|G)D;s{HR&{wGs+Z+J$b@}IUd3?gaR zwbTBi5B>vF|11Ab{P$c0#D6X8|2%pa|Id^EKA@#pQ{lD-I z3Zk2T9xhQYTmRIH%yCryDVnVRcx6mXdxb@xB3{Ffe-&$^TSKgN#mBAkB7yhk03{|x^%4_3ARwMdwO!9_lu|6!BO&-R%A zW5vFeuK)9h##NVY_MH#@lZw8MCjXEA#}EFa&3~`_I|h*uuO}ySx{<$LA@%&Ws zKVU+2p#5_WpKksg>p!meAL;zJ{=-W}OWdC0ivGc}k*+}^Nb3L1|9Z%OM%pD;pZXvF zJZSpH|D4s-qeuT-IymHiz-YjRr&1sMQ>35$hqnI5KV2NffBudCXkto`!#%09e^>Hf znlNYhcXj?B{nz5ZA^#cFf`7T^lJ%1R%6}&7|3R()-}9f(KI{MZ7EAt%|2D_J%bXGI ze^CB?*8gQdUs3IUmHdw=k>^?bOWz~f`*EpJ`DfzG$vB4Qk1GF1{%H80 zZ+zc|!<+w@{Xaj+#Xltk`OkY9W+ZR^7p`UN`k$2(2Rga(&mJQ?$90fz{`0(UHvilx zH~z!T|Ma}I5%&PKf7ac*|AG3SS*H>H`#E{>U*Uhkf4})p#XoCd@}HvT;GcGzG+R~v zQ(OOk&d?iqm%l7nWX;byE&mXX&)W@Q(JWRTIYY? zOa5E`9`!%@Kl7wk`CpjwJGQI~gR0a1SDx9hfy6;B`CpU&%73WpfA1MHZP)sD0}g67 z|6$5Hk@{cdf0I)GhdKSV@XwT{qyO|qGgz(;zWUGi{1^XC!!^;ff0-}P__R3-*mGbq zpr0xKnO^^Ap49(-8Fz7VGK|G)STm4BLoDE}e; zQ84rJ9&Xcc}lfEWIB6 z$2$MH_%~YrEF#mZL|?%D#cE1V`QMWN&7BJYj2`du=<0Fr>EPd|foS^VKGxa)sQh#8 zF7?0hKZ}2MMe*ON<}+FESN>J|XA!0SGoG)g$^S~{f7ELKas{3qA&m1(%Y*+&um6Wi z`;HJX==@*PqyOu>|5E3F{eypoiJSW0*8lM0pFQ1I|7@y0#ebafv;qGK`LFypXa64lGyD&O_~-h49?|1c*8kRj zulE0r{<~+$SCR40+dJ)l{OJFR{}BI)FhxN5=VVOs-}sMI{u3oC|071QzxvNM|LOenYUQ7sq;)cg|Hjt; zk@)8YW%IrNi^+e^QcnIC^51XDH~*dFKXXs>jEJ%R7xF)*2mYm@OR@4#CG>1h{!9E5 z&@`pbL#h9j|A+X`ieCIj;y)$-xd{{YZ~hBL8uP3q;=tMW*tX&=z4FgxyBGhR_@|Yf z$G=ujW1Xq|Hxt_hQ6T=~qzrT8zm)vv&5&OIr$_&ceHH)FQW3ZZ|Mj(LO7j2c zpTXoN|K-d<<-hoEHvh~+JNl<KbL*9|7jNg zEAO81Uugf7R!N}N|LnK3nq;_VuKYVy$1xcVM{WN1UcUS1af1I8|Eu*c6U@kenmNcMaQYPmbP{PP#b~u; z{nK4Q@?ZI{%c|emA`$st@=lh~LgTd^$4~y_#7&ide(?Q3R|)ceNxEG5?`Yk^n_BXp z?Jl0bi2oY@z4)hT;%okAWyUXkjCTJN&lUa5e)7MH|A{Xx?oLSl({zVu=FZBsnsoiI z{EzM$BxN?!A228Xwf``gJMqtyt%}zO%D*fANA57jl@rr%jkasgZudVGZpU_I_n0OB z=@eQ`vi`4YlmA5F=D%jzFQZA7e;S(gqw+uEzrlacC_3do<@31Z|L%XqKTnqm-?#pq zlYcHh5Le=VQu&{#`rqXL*?$Jvga5dUHvhBuXMzapZ8ykX{Ch9{y^bpw^|h`y|8mbg z>-oSL|M3t0`RvnyI+glg{6iz}q|Xb_-ah&7@Sj=#jB=anga3iw2|aXv_Me{pGecPC z|IhwY>i;eOS0?XW8rj&3|t4pT*s~|8OZ){?9u9|F8aeZV|ot5Bk*lZ}~YS z)_=FN+uq%y!-a#Dwb8bgFncU<3?=k=J&qvbuPo@4B|7o`jJV0Rm z&vnGzKbJJl`EUI*NA~EypzTGr=YOE{pAli&f1&cfnGgOm-X@>?bMb*KANM8y8N$bV z1lIo{LyO6OFh7{zvO?R^1qOVrp!8( z`hRR5mCgS*|9Q@6h@eTu|04OnNdC7i6BVe1mH)isV&hO(2mcJ5xBj_j&8ZH5Aa9WA z6kVOQPyE+={vZ8wt3~Jk$$$9V{5$xsxBCC+pZ|^WzwZ9&(~f^n>i>X!c>L!M&wm02 z%uD@GJ6_5Ei}g>5+LHhHXXZC^095^-X#YIU#{ZN2=e`x|fBY}?qgVC6pYb*s|H+pB zyMMN!W&N+}|0e^-jeqW=dh)c+&99?Cxrk$n2U#mq== zxf+varvBgkr;+tfoy{qc$$!R0ivRX!|2%mtr2}A0&wDxv8~whN7pZ!-8{ayC@-^q^tFGv5S@?YgLA0$8e@2US;i>vzIOSvgx{3qH!W49Xd z&k&q?3gcJ*?a_b4{Z-|k`@<7=NG=s;v&#Q`_WwNk=kXJNZR&rO|9NKo)0M{f_mqG7 zT5JD2RmOjh|AG83cz^2gUAX)Am4B{ZDgUkZf2muk|Kos#wf4`ZBu%81|DO6E{~h)J zWn`_@X#WX)_6p_Sr++j1e>9aP|2^`*qW)L@-H^xgTmGN?vp<}-|Al`B*Ddu*YlYMc z%1HT-o_Xo+{;MainCW{U{(J4ei-<0Yzwq-u`loR~ zD8m38SNUgDV}XB;UBrLa((y(4cNoiH{PQaF;GY|b_;+Oe&-=r%Nb%25fn)wVD*wI4 zb4y-xJTG-1{s-|NTmP={9}k`N&o#oTq9q#p|M)M*f<_i`$F3gvFaGljyMyANIV!GN z|I^-O^FJv6x%JPjSeyUiKUDc&u?&wA@t-LFC656s*Y}M7yiD-lk^jvgJ740Tp~zDI zAN<$iKNJ7U$$z`~U-kMQ|BOPe2G;*EBa*EDSmnR+&zJt7{D=6b{=Tr;#b52@eKeSF83wyUzN&#qx{c>!}{NCo)bk~A^vBT|BW*#|D4-4#(z{E4EgMn|C!GJxMa4Xa@@H5~I_ z`=3qz=OfP=t^a`h|EvF0US(VVGSr~7{);#NyeO6WAO8_QL*<_njNN~u{Zkqiu8hqf z|HVHmI;sD~f2sV>p{M<~ul_@Blw1Gqi2sWGUnKwk;=hpkAODT=UwrWI@%_8|XBbrH zwmr{u#)8^dFC#|E^;vG-U6R{O5AX zyMIsW{}29q$^Q@j*Mon^QU9y_Kl;y9{^LI!RQ@wB?Bw60cP4fBNB@mSo%D@=`U`IU zSL*-Wzt0mg@gLy7Nq+Lb)+?7@$bUxe@!zU!{=1R&UvK$eQvcT%?h}Lu|ICvssQue#(yU3 zf8L2`{~71T!>j*(7<;7shxjjJh9HW6j_8d4b#)H@Tbus{ z`Cn4Hi2s$4q-Ce}KMzY6@wlRt`k(ywRQ<2=-;IZ4byfav{%QM_5BR5LeM09+o&Ww2 zM8-euYbF1Ue@~`FfMe|8Cs;7egTaX&B5fFZTb}j=Kp1{~i2y;=eoO z|77z&=dh~8Kdlw;PtWOuM@sl-4M_dZwJ*df|Fo8o{Fg3Y9;2N-%9=8;6MM-|3v-I z_jXPG&)gxi{#oWp{yQDNRkx1^@xSyPozh$FpL*tR{-v)q`A4J z`TyB}sr-+U|2|FTvV@3WPRs6JK0j;~sQlmj7dHR7_HXiE{4?NI^4~e-KU*=@zsLIj zlYeOgBK|{_|LGLdhk*Q-J}|97-T z@|my0+aPAUihug#wreto|EPHLUu0#&@rC$L_yM#Iuoe!^n8UM79M13yt(5lBE~;iJ>Z`fm4o$P7u5e@R?>GfjuOTpX#eD} z@$ZkDf0nv#!kag)_Lgl=_h0-c+CME%8d{7kbPY*)7b^9CDfK^J5z0TK5%AAuAs2sh z^6AxoSz7#-7Acc6*%-^|O2rA%(D0VU&>U*>)@bm#$^cGxk`t;6F?`AIiIe{XfZnhk3~OXPRP| z6-@L|{#oWU;=fNB=b-&NJbD%X3?amSTo$FreQV>tEW3Ixd0UJBPWxvAI#T)1ej6td z;(rzYOF48?$$$To|AL?Q$$xnApMT@uUB2-@DF3eHzuZ4868t-7|E~2p#){1LJ>@{QsYSz8L=J|9}3;|Nr^_U;h6u|Noc&{~zanbt!$` zj+pxYS#|Yf>i_no{^z_+)&FDRNc}&TBlUmLAM5|nuK)96{ZIEImfgqoKmQDKw&eVe zw-09hPyfKulZQfb|0k98f4r~%dsY8?rv9Icm^1tJT>rE3*X#e4gPM+IHErBp>;F|I zn6v&*Px;S6bF2U7WBpG}85McSK8~*cWrM>VDFV&i?9Zw62^~{hz(p{~W04`ajy% z|1=Dw{&$b{|G3xxi&_5<;ko|j<`h4h^-%vWQvWxq{!c#C|KX?l-#7I?kIA<6Ki52^ z{;&4>pG&>e|IGGN>;FUjpKbO3S}<>8tN+>4>5uh4OKDmE(|@kai)5?+=>xCU|Bhqp zf1moFrkQ5_->drHD^pef^PsE@_xhi~GJE}>7I{Vg2HF2J>;Jv}XLiJ){?E<&zo7nS zhj*+0eY^gTsQ>el-Hxa%r2dzC?o$8De3AF{KM%qV>;Lt~`hQjRKP{YO{m&y*x2uwa z|8-i}Hf^S|sd*lrwXDgQrN`Qpw*Z{~vEN3=9Y!?x{|wrr1?`i*dx!nMtYt60q-T={rHmH3?EiCy$yL|H zooi{q(6Th;Dn5NlO7Sl(4{4_~H#E4JO6C8l{V&DH`d|8<(h5K0DQCekAlFE=e{OZj z{=e}*23p5JlQ~o1EyYQ#q{Cn*GU&KGZ<4XCb&z@fYhlTRrH%=Fk zb@}s&fBrYh|J=sbKWCoo{{^!D7p1hx&Nu%w+Y05g-y}hir@Z%PMnvj2OzqTBIsc=a z;5lW)FFfRchVwt=-{10o9=L4z>OaB%B~DWDKZ*Ye|Ec)rBuV@~OY(nY|38i5fSYx^ zpu#_UsEzht<>H^iF8Y-z|NWr-2R&nqQ$CGy{zqDW@XzLOUGwk8{{{a~UNWWl=cx)` zaOA)E=iY0d3|yUg_wVigX_>G6Cz17Eoc+7jKM#6nbAx|ctj^~APx(*NZ~Zsozr}yZ z`JeJXD*vtapYHzWlYf8UNyyp%s`8(gU>*K@=HD3qv-Tfyg7=MoI&<#+qqq_OJbxd! zcM`{a5=YGBVPZ=A;-8kY%#qyvH~)=)1_h+!vir|z3@-jxW}VFruYO7{vdr91+x(M9 zC;!~t(EeTHzux@QLQDK}E%k|i8I<&$e=ZAiR%-p1I{$g%-E+8Frzvw!HvdaNbIsj9 z&8hHziQfFT_{CgqoG4OwpVbcfy)8?ORxA7P$|KXc|rsn*s ze@?;v@BUZG|II%)#l(N3^M6?#Mj(WoJ&%1CHsAW^HQ7i1zB>Px`rpBSYV!ZhKhIma zf|T3*CtAPvA4CWLjBOzakNMB|7VAGT{%JFxNdAlec_dx8{NMZ+lK;j(cgeQ=Kl=By z|3va1|53KPUgCh2HL84NBJjx%Nr^JBR## z^*@Z%|H^-Q_P=mRd-w0>i~>ISXZW$n|8MwlI1k;(t0<;+^=zxL1lgC{54^k|g) z=N_%e|5)WerRlR}sm2%=@}E1HHvg$Bedb}3{}~56yMG><&<#-gUvlfeXYP4%2`|}m z40usu@*n>^;45|hkC&E%YwG`Oz`sYOSGt>jCP&1||AR5NWJCr2W9xs!KUcj~ z{crMLE{T}@fALSN2em6Q1+~=w(`7XNd33A%x0CXp@RXhrpvr%4>wn|l8H?8X4=F3s ziRKV_^OV*`4(orWx|09+A1W^AX#cDAADsQuIpMB(>WJF@-OTG`m-u7F_ZJOf961_{9o5n<$uoAC|Moizmxo@Z6B9M+$wXq|5MRWmTwUJ zd#e8D$_e@3>-^97SqyLfdzJrgc=Vr*+W&?856Sc45E?-A|cmH)6( z%?$HF`5*b@Y5yVXP)4NBHU62=qw;?UF4{j&zp{t*ABq32j&1(qKd$*_#D8f0kGXgG z!GDMUh5DZfKx5vi`^P8$^dnwqbQ|EG|I_$?vfQg^gO2}<^*{B$@!y{P$I`;<;GdW3 zAzyubwwn@sI}04`KT`F-^?&`we`5U8Y)1Ld^MH2`_@@k!^}q4YSQ4)J@HDTN z!Pw%TAL&9@cTd*;QvWAC3+z<+&qsgvpJY|k8visn{@}mY>wl*I%KG1#@L$tomimA9 zUmyJQ2RZuZ8{Ycwtbc~#$@-ta!&Uib8#k#Z^8Y9Q4OeNN>^$Iq<}<(fXLRYr`kxU@ zJWUb*nY>4vm4C)5(u=)L_+CBvr^!Ek7R7&{{HIAiiGRMuZ2kYe|JwMchZLhOr*894 zv+D`}qxMfjvv>auSHG?QF4+8YORmcJS#17?g8a{@|MAbCUi+V<{-+hC_;>k7lz%Q< z;y>h$3jTfTp9%C2@z4Ke_dgo{5w9F{{hv7bnj8NM{g9b|#%CY@mrVJmH zee=(KRQxk{kNmg(eeutD9{fMJBD(p1lK_-v9FE zpVl$>PZtJN)t~)eKjy#o-{9Zf{j;P|{$24ua;f*|e<6~&5zK&#vwuGF2mcRdiyr*9 zX8nKg&rYby|3>G(_;<{8#=fv$|!qj(?i{*!+L; z>FT)BrTnMH|3v*i?EaIZ{~G_^tACn4xP?ob5AnY|WKeK)rT)*){@vZb#|e+le};P{ z;+oyvdlKWqQ)=AU7Zs{Y6SEct(xtvA{i&*MPTo87-}^Z)2S!M}rlX>F$K ze-0va{?k;wr(eJ!|9z?dmH*|%e|XG)x~zr{b7zh~d~pG=0P{|CED`@*nUN^2L84`9Dhj z8~@xZ&BcFB{jdCYPsa91{V)Ex8*lyB%6};Sed>SwS8x7<%|B1qr2fZ$@9z1}!cL}cP^WdNM{3GLFRsM4+fVK3q z!+$zT{!8n0FD3t#e+U2B=0Ci~i}j!6WGDHr{5P~pLk zmH)t@RiOBvX#L744e>wWpS#QCzrS$iWBqs9zkA`dgqd@@|5dI3sW&1TX!Ly8mH&ln z=pj#)`3}cFGtVXemH&|Zm-n*#-^D-MF^;VNJMI4={%ISKvj6|z_>VIFoyLDd{%ilP z_&S{u7=5V+oIb^(Wpzab9&zC#nBw ztbzYv&wtv0QU9O)H>&=Zd+y@Dt)~zE#|tyZw*2QSjZObcD*hLp{|EoBtp9cX`}FM+ z|5gd4FV)C@?hEYxIfN(wdCw;8`L%!gUVrDGDddv>_)nGpyX3#} zUr7G5zl{HI^G~bfv;Thc@AH;^$ZY;6I{$h0yR~;9Fe`(Ex|BxS*$^Y8qKkLzvmh<#+ ztiwJ38K2xP%74zXJYAkV$(eW}NdCLLhV(Z7eeYCrGAuFk93=k}=1$|ELx2VU%gS84 z2mX1;@xgy{(f-*socX-z{Kr2{Q;+`pPyX9?{~rGN|7!d{#XsNbGAsrEdBP1C>VM_G zJNtL~q`8WJTIQJg-}vt&|H(R)|IJm_|H?lbEZToTvqzi%Ztmpc^^ZOj-}7JjZ~e?s`LF!n_Wb8P zq~t%n7$pDW@WC_!$^WS8eN){Kx+!{vG;372=<{cJrS9%Kzh(|8>${B>$r=|2cBs{PQ{aC;vCe|9AiK z*?)3>a3%NMe;*g2^6ygr^IZGgKc6*f4C|lkEyll_DgQ41)1&`ZKKWCI8neLv#1~U+4d5 z@;`VyC!PNp_5Z|uWb!{!`On)`m-;_>a2L}0PdPc+{mc9Avwv10od1b`j)uCPmf-kj z?k@HJEqTf%yhHw<{XhEIyKy|I>VL`$ZYi-x2 zA(Nye|1;MA%0CxVKlo?tc@nIgikbY69^!wc{%7cwLJzs`7n(hm;BiO zW2u7w3IFtQll<5IYno4X_@_UDx8;As=1nOHs`B6X&rbgR;rgEc-J^X>CjV#I|MQ2J2YPDZAFiv$3*=f6;7k-fAL>`k$_sM_p?-~Dc&pqUVh2;Oc|H{6A*IWKu|FNn6!&d5lN9Dg0(bH=4A2NNw*8lj=5{5~z{--qtz2P(Jf9>D7h<^r7 zvHs73SN~Im|3>^v2Qc!Vvy4gn^PHY52Hc@K_+Q)P-apq6|LdE7x482A694hh|DByh zmH&)6U~tWg|HY@>EdF6h{(D>gN2~IGVSh>IKmHk=wEO4ao?Co-{%ilVLB?0t4kHq} zc9Hy_ssESDNZ<36`yQMBg`wohRs7Q`YUUS#f5wz(|7^6W{I~wE^d6L%6Ptg&B#eKT zSHXhtAB3mY5(z{^8b#1W-4*MajgHX zf7&NEOfgXYYy77w|9Ah)fl>KSb1&mRVpqlZuf;#Zw2RgFPw}7Z`OntqmjBv+ul%R% z&2pfVb5EG#eDNQA@ZVDZUw!I-<-esxo%m;1lktDYf2-<$x#ueWoA3R*?Ei~@Z=!cl z>RprkqkoTKz_stBbd>PLKmCMW{daXIeUHRH;}1uk%2a7U{jdD@&B4DKk@x0*)c#`z zgIfQOfAR0A{Kvl>;i~n&_>YZ$nXS^$G)(#D{eksA9Q=ni|HXg3`45l&C*!|p`An$# zU;LAn2mjojC;z*Fxo6t{L;N#ai~H;}Zd%94_~(WtdujjRpU$>vaI^l|puvAcdk~(p zSpW1@Za?^E?11>Ej|N|?vGPxwHT-+{pYTsJA^fM3{~Vs{Y^sA&-AY@;_pd zlGOjK0oictjQ_Et<+1k9-+I{dKM?;N>;EP0@$W@P|1<$;i7D3q@BSH78M3YJxb5|- z{Bvz^s`zkx@Xwl>-WDuJs3ElfLiYdalzV{*LuPdSA8G%zMc|aYDJ1`Uj_?`QVEo70 z|FHXaZ2t2DvHp`6|8xm?EOmUp4X=#Xqy% zwf|iC&%3W<{{PYbX*yNJ+CRHaGy~cEbBDp?KWf^wy;1+Wv>&ngFaB9ko&1kU%iD^C z9yIL#&EX|%Z>&Eh|GiS@Klk48Pe0quf7>Yk43l=2WRTek#y?L@@bByV*Zw``kXn|*Wu99@x|mn{wc8{-oQ=%(Z8ep2U7oYd-mi%esBnH{rm6!2l78Y z)c=zIna+QXfXV+qbhg5ONdD7v>mvTyma+c3udav^{5Qrw^Kod(%lTgz1|R*qH8)9= z|IYgNt^YZ_g^!8+cP4%jt@vj8UJ-G{%QFh zGql5J5`;_1rRx9Pf2`_%@xNIAgR1|7$Gd-*$7NFguVmiQKctoa>Eu6|A1#N1?ZN-F zGG_Xd|14c3{}2A}3=f%jP9*t1^Skyw`5#aIr;gV&mE^zn&v7LGj(_(bZ~o)ylKE|M z@IOoa&pQb5A5THfhG=_}{HF!z*?+%u-h&ah+W$@V|F-<+PD)QVGS>gbzjyGTn*8Up zX7YdK-Ym0KUj5UTR^|WZpDt3m{`V$F`!BVB797&@-1?tO@*n@JuK$()?lv3$uGIgG z*-`#|@$YoJ8e;$dq5Mzy_l*DUlYgdR@cXEB{?mbHy|O<2=>MYp&tt{&45|NL{Bwq& z{BuREOtpUoLUt4NzwzH%|D4vfDfz$qckxe!{p@<3|Jb(vJ@WtTpEl2Pv=?uiv-Dk{9m;HSl9nNHbyJ0G!On`p3iLgul=v&KmMNqV~?3RX!8GG z{Fmb2VHBCJ|JS74{L>+I!2c-q|It4!=QsbfZI}G#e-Pbb?#pvCH;R>iPwM~SCi4M| z|B(C-czC7qAO9U6KI5O0lyp-0PXjLT&*7rUe?KSx@!x6xyyo-O`d|C!H`Fuj`H=sd z865q~5$f*0<|NemZ*=|#KI{MSl8OJG{P&A_DrxwH|62KxZoaYX(%DQBnTe^}AP zdhKog$K-$67Pt7xYf19oNtJ*4VyXP+Pag!_XFU5K(oXz)oBzbr|0n;Q^3Of@jz;+- zSERIm{@XhL#s4hpfAU}ZA1mdb8>UOX@{Sq*3<2YOH0R+4a{$Qy%|D0T9piz%>X>JB zG46-`;|5EvX_8+j# z!Q6S@b6ev-`g0$>Ncm^fvhqLu#s5U3R!{rCo&9rvNBm14K;xhJl3gzTdDivfpPf(q zC&?wQ$p6p&gIxKi4dpTa#eYNoAN1KUV(RNcm6B`9CWEyeFpq*Z!G^`>lU!O8iHU^&9^g{@cg6@V}Az-}q-7 zAD6LR+F*!(F7m(m&yN0k@}CJ`)c^6LUzzan?w@=W|ItVPzRCZCe`aK8|J|GawHWd5 zs{D_APKiA2U;4Qy|BlLk4s1expsN1g{5w+rpZ!NR|9AhR%76dC4Quhwrmf^Zi^-4u}tN%yFY%)Xe)&KCAbpG=OP3nL0znA*o=D+yo_Q}of*%dqG zzn4WEmazUGafW}n$GH1nO#Lq%WQ>2l36y_YZs4E0P;>yIUwKv}qptt0|I3Si8W_m_ zKkI)+S*ZG7@_+YFt6!dH(T`}$|6y>sVZm&`@BQ;*Kl%^I|5)XJR=5pKQ`43Df9=0` zL7mW7wTYB}X*Oi)f1Uq%X8kkHucdVjeX`-9>VNWo^UqxqXC(iFJ7aX8Y*z`Mt{YtfJ{jb`8F~9o1sQUlSKg(w8|AK$!5=#A_#oB*FFYi77y@`8J ztpC5n|1zY#s{h$qOV^oe2qym<^510xNBNhtR3}(zwAEApPjx#En}3h}KNfJj5YhGj zobLYJ8ynTO{%6n+eO^@li+}oKi2s26=bZ7F|Jwh6|E8pE1O9n%p!~B)q2CB=B<-Kw zcgg=3|6YcFNBeL6P}l#G|M-s^?p7t6fB)#8BbbwauAH;~&-$NFXm0#Z_#YWG7-bxA z)h7QJ{-{GhKU(d-A^-6obQD}?|3g;9*1z-@@8VA8^6vSM7VDq;yJ!Ed%Kt7h{ypmd z;Lgng<$uNh{h0r>7h_TY`R|bbw6f+382QhotJJ>*?tkr{uni{s$2$Lwe@A)~B@XL< z`krh5-paZ_{4cNm=NJE%@yqykW0^U}M&b|t>BC#`J>k=GCaH~omf{Eh9If&HZ2UWX zagAU2PrmWrv-n&c_Pn(JxxoLz!ln5$);umS{sa0P`3e5HizfaV8zk$0<6njiF}W`y z|1WNE_xfAN93Ae4XRrQwEBwL#?Z%^VmHz{IgZ~!)qsss9{CDD?>Otp!px6KL#HNS! z-yQu&;=eCAClLRA70UWw`w!0k83%UoA9!vv@bm%y;h+2DZ~h0C#wY)bpER&rNx{;J^5%n}hOSDF4Oqt4`>7$A^}-M$Vt18jk*XLtm!5|CWoH-O2wK z`OoM}#s^ye3<7O~@DEc`R^nu|A$|%`9G#k!mZCB49@;T<)1ML2mjG0|H~o&jejT6 z`R|cm`oFaP zQ{_L={<-xl{%I~o4?y}OFdsqrzbpUzt*!q>)&JVR6Lt7^f1(j+yu; zxctF+un)erd@uL-50rnJsxb!w|8lLoVv+%U?Rjh*wmSdmG4S9wMEyT&|1IwVr2aqq zXDkZ!KmNll|GDXf|H}ve9sc>O#k9bf1F z!T*{&yqmH9nKMQiN#6yp!9Op`{a*QJg2l=I?~!}Z&2zB%&rO%-=D+I1f9qVh2QT^0 z|L^eTp9rrO8tNEKU4n?zqr5>Z}tB;uxEDkKj&=R#!WxWul{H9KYDty{x|u*O8)!z zrJkQ2!`$=!%8`B7Gihn}KYcw1>i_jh{%ily^XXClYyYeE&r3Zzi%lp0t1Kp>%;vxH z&kfoa|C7pp@6LPwD8+y38~@9y{V(J{{uyHZjemwuX#YdgF{cgxmCk?sGp+Blf0|zG z`R}(s`uD{Dd^z|Z@xNIAU9sHCsa5{xSO3}WpRX+PAOD<^9sIA^(Z6T%pV5BQ{|EoW zmwWV|79ac%@BY(^XZ@#p{)_*S{l5?Xd8|UI7{Z zEl-r*{m;AqCTWr{{=Uk8#8Wtj>3YQQ=AY;2|KLAK7M1@L)8zjk`CoiqX~{x8hRmHa>Y=NT9IZ~Qw&lW?la zhmqbE@BZ`Q)@BUZQ}sV5h{iwfL$rUo{IdSn{@wl(as#gQp#XnGm{?AcmD}10ePyA|FR42G+ua`{HF({_~#m<ROKVEyx+g?swqe^KjyCaPUa?LRR2A6D#G9Q?;!Ao))}2mE{FzxCg4 z{zvjZiRr6UhxeZ69Dnier0pv8zwsY#{!>~<82_uvf9;>?ip*V<{6F~T`N?`!{%7ic zo&U-|=P*+)^?&o`Kd#AtSiGS(gc!?Kf6&n|Be4a<-hTN+5FR*i-pD9 ztMz}IkIKLQ!GC}G;yBIvU$0E#-2F!f|K3+{^dDv^F%XFVdC~Ph{>L}}p7`fZ>fim# zCC4wiiHZN=!fZ9kf0;8V^}q7(C46(7{g3>z)cXJTMB{eq|1{!>E&h2!|IE0gJn*v@ z|GbxMH~(Jij+=i!o1)9w;Gb7&LGULq`5$nK5}EwxQ>*-sQvaX)=gZBd{+G5NYX2{^ z`Oi%Y@*n?0tMh;N-`Bk2H~CKoC3?+j|GoI{cmHE{VW0Qp|H{dbk;620UL8Jn zCjZC#DEZId+UCFbXL>`@;NOipH>QP_&VT$fK)#P?=lAB{nJ30&KKQC4|6LdVZoq96 z{P%UzAN)&STgiV`%{Sh*(_`%6%<>_a`m5~!?f#w7CxcD?%lnYBzaIRD-}zsN1M7d3 z`ro15Swi72cT}~1x|Xb)e{{LQD*6A7e@gR}OGJDAbAD$0JG+10(J*I_Yb5ktW4fI7 zKal@3&ce=s@9fBPKqA87v!Dn9vl@XtLs4ltj}zeD~9?EfA7(_zDZ@!#k4 zjAAsx*+1QH$^Vx8&u8&Zrf|b>UMb_nKg|&n{IlD<`=_a?+&?D&9qm8&xKYM?q@({? z{Qr^sk68bo{X3HX+CRs)D*u&$)Qi^vZwp!GF#A-(44- z|7&^^|NM<;SVg`1(f_FYuhjqIpM8ZVPZq^Ly8w&Le=cKM|6V}L={NsroBVpu|AT+# z3)uYUhFpF2zxeWoLHzSH6aTaLZ(jV@ecx;UD_=VIlmAfp_ryQ<7%7IW|8*Wt`43&| zzcc>BbV?We)8b^{_yHE=|Em0_tg5tsNBd`E!T9gC{MY`eGim!a;@`vnFYb=h;! z$ba$g|KTo__MdP0-}6Wv|Lo&R{wx1O_6IG&tN*E+V(s6T{Qrx8pZxd8f9}MxfxP)I z4*CBj`EUL6>WKBfFz*sV2@2{=dAtbMU`% zXN3Bn2_8EC3-TZT@p_eU#^3m#nHy^SyA}T_<)2+uRsY-k7ysPYH1)qbI915{AOA8R z#3BFj@0#CR5d^Y?M{A1VLNp8u6A{^?orhXp;eOvQhy^I!X) z9`2y){}=z`*UkOlzZU;)!LZ?@e|L_>|8QN&|Bib>Z7xk~ozasuxbiVL{T?SJiOmDoR_Cb$IU$MFm3t&dr|p6Qvb_jdhRUYe-i)xGh#~pU;IbPKTp4?|MBm& zf3$yx^}q7JsQSMvT(Zadr>SDnsr=7qL0_)Y*ZxQU#dPcN&*p>pPk3HL+qa|tj{J|8 zJan#^GxE@z{XajV_ci`K{EsUCjsHpNf1Us0KPx6#|BL^H`rrF4`9G=r7yqv0KP{|T z|4aVsvN#O07ys16JX2)NTDVT`a>toVJvRT9|B=b#)c--?4aWcct5x;?$^T^XAOC^m z|0ni^g7pBX9Izr#F>q;0qQ-@C57 zb+Y-7f4V&?|J*+m|1>Y}j`_d&mkEaDAo*|oU%&OAFi?Q){6O;Gjp#=h#Jc`h`5)%g z|NcY#v(-TytNP#lgMYq~7pecLZa(|Zc{={)pAM}T?LW2oKmXzdrSk9p;J+sS{RjTt zqyO=k|8488zs-IK>4Rb zhsVJZ{u%hP`*+&3O;!E}zOVedI{!ESd=F+kOHDWbGd0SYUwfd zQ2EcEtj_=M{Ig50@}Jh#J})Va|10MN#=nn$clRGk{v!wfQJTekfL{DFJL&fy9)L~1 zSpTbguGar_^w0TFkaJA#@%5UDzxb!$YNh=%?nCE)W9xtNKN0`l?mzgy`)8~u^}qP%^4%x@D|c4=cmK_se}{fK z>>-MOPx%kY|0)0Af7SK>n|}saHtg3u@So6c;JWi;<5 zM=AMl{D|=L?myP+f5z|Ne=+_WoBvCE^v_qP_3zef zQ2f>ZLj8aAKdALTrv}=zcmGkIO8$E$|9Ahi?zaAW@_+ie;hzpI;y>+1 zS^um2cO?H`{Vy@MUyT3$-Zu0fAa6myZ^=d=Z>n*f4YP& zG;saopJ{{~u3emXrk9>tpCM- z_n7Ec=RZf~|B)I0ea(FgdBc3+9=!2CZ~3qM&*VS7I~lcl%zr1W237wv(S{bWS7$!w z|6I|=K>Kfuf4^xY|9$%I@E65D1w7pzxBOou|HVIFb3E#j^?yRIDe<3*|0n+C9IzsX|{g!&slc2`*(uN&HCrn5&1tG|F<+U{#l{$h;6I?)IloBd-_!ZeZ%acaf2jOVQvc5n&*VS;`CY60-~1=aKi#jze<$}1 z>JtB6K@Y%axNiAROC<3>O8z@N_X4H|q6qBP~^8e(2GXB{grN?v- zzWSe-<+uE&J^QB(+veXPNW?$=#(7p*a|?xeGMoQ^Z`*_aIlgHBZ5QFc)b+pL-^G8i z$g7s4|IwBGzmWQ0`(KBUM<(sm%l^OLv{XmhKM!TZf2aL(ujs;)tld9f4?p_v$bZUp zhp zqc*jF+I>;~`@4VcqVsZh_do0WSN{3%QU5zq|MTl-);jsW`~SVX_-AHYz)xP~{~8(p z)G*>dqUR(2a@_X-M7W<+TJaz3*8?+*EI{j=+2^M5VH|D1(a@4*6^ zH}rq;PqUFl*8c(X1}~iAkpId*Q_DGAS?Qg7cLMycXa7ub#6Nq+Klop)f5-Sw+2rJ1 zf%fl_|1Ix^Us;; z^*P=h@}I6oI{%v_=11vD{XdBRUh;q4{L^#q!ly7l`JdnX({Gde{}C4s&i(_||4085 z`TxPcNB)QGy;4+3{*SExJ?8L=e@;%n9<$2-nJWammy9R>!4pv~r0M+E{wwRBP9@Uv z%J}CYANBw4-&OgK|9bQ9sQh1a{&Nc@bzl6`{!;wAul`*go=w_6H++Ja{D1N9Y5(jd zGkaY5pT+-|_D{ckszB=hX>eQP-(~%;^Z&_k310ZR?)-IA{v8I+AN)7Ue=h#%sIC3; z9isAo7;iTJxi$ade@>n&ld*1mPIwx-`Cm=`2VvKo{kzOKv;JrDKQj6MfAG&B`OH)6 zfBg6C|I^Ta_wV7KEs#>)d2*GO-m|=)<9#gkzaMzhh5KCnME-XfRp%%F?8|-fA5j0( zBEEU@DoOS+h{+W!v`ycV|mb?E*{4e!`Ye?_@GwT0&T6O+&!}8!i`m6ty{AW_bg?r}s z&w^Fe|MT)6{Bt$snE&`^<0s<6@zKBgz`v*cGwO``e=0odf8~v}r|SRpe)RAD;NLm< z@0I__`sZqfN9up&fB4{^@$-`ZP3e;Vd6z9m|GxG=DgV^4x9|K< zNB=(g|5yKu)c+hWihpkyvqJl4Z0pPbSLgR1#;Px-{_jTepZ2>{5ZPt5>whlv9sI}r zBHbj#|04PCe~QfdU-F;6XDa`#e*%|q*y?}$r#yRZo?+|n{@GJ`@ju)A z$NzZDf90S1CgguD`M*>iOVx$?KVwPXvlTyi96(=}!jtts3w(Kx-4zVf8y312^Zr2j zZ*Bf_k%b$SoBvk(=lUWYz$icSE9E*5cgcUYG+O1~VS8BC{~!EwQ>DHi{Rg)GXCGDh zAEo|(^S`qGm;9%-kIDbbp8w9*8e0FCeCap;tMX4r&)TK_XNQ6fWa~e{zq8f7 z9f{^poBChO*ZrT4r%;4eAjqLtZ4|J~XDB>5k0^*{N4^w05#^9*>mq1OKy_w*$H zH~;k4xznlh7x%$|4+&Pue=hsse`Okk^6#c!>)o%pwypes;h!4?$NJy>de9-4 z78RR+@4*#u-g8R+Z~obF+Vh`hifvGiC5vVJ2ikv*e>&<<>?QN(qs0!r@$t_=2m62X zy*c^!%9{2_)_)%9`rj>-{{jDOV|E&wyJiC4S$$#J` z|LT7+{$1^VQvUhsVaCwK&*=deO;_>HGSJ3I@0O-e|qu1 zTK}u5|M{-q{T%f_o#4d(eBnMvKVLTgyzM;srw!33|J-5N{C7UbPg<>Fj@H|8LEzpZzD~|G__hKI`8V|9rJ+|E^m9 zlmEMazA$p_pV7ZZ|1@T)=aYY4;I-s`(7ySX`RRNWa%Lv=Kl#M|hN}O&J^zDYZaiE6 z)8fJ8|G|ITWv%hwHuM-j`}ay74QT(f$^Z51;GYZEljJ{xCMlX<{V$UL^w$dldS6@r zQx|OhSL*-E6ep(sKl|_S&sgHL59->~t_9p>*H}~9IN~fxjye{|7_#UeD*&1AMwA4e;R+N z^*64Kd%5K|CN8v0-ZI*zbA)$50(GiLP?!&_rFjYj6sHfZsvXR?~(u1 zP?G=sAMrmr_-|DHKTQ5}82ZtF%>JMD@35X=FxbKWsQh#1#l=65dX|*@xBfYAwEnrL zO8)zj|C@hqjouc{|HjLY{#WwfVgHX-TMXb`7VSTL^S|o+Uw`pG6aS%F|6BibEo5Nk z!N1SCTj&2%=l{WfZ1aEdw)|&e`ts#)Gn)E;xpD;FERlz(}H> z)mhwJssFWq#xNTH>y39ZC;#-@UuCLe5<5I_$a&mKciL6?_oI5!{);#NK6ew+8&_Rx z&f-Vj+3x;*E;DHV-q&M2`5)a!CG~&D!j!2_yMIso`@8>Pum3;$PsG2c{7;W&Vf}CX zk0TRVTvlbD{4=eL`k(Dj2G7i1banCH82{7Bf1vAsPLt36`FwiJ0A|9M^3R|r<-f=O z+|t!*b}%LRFaB5YA0Peq;=e6D8qVk9e-{7l_x@M4{+~?#FX_`&`M*ACX?*lglR|F7 z1Z}JG-{FI;^8e&NVV;NhpHBXngSO?r&$`?ACmNURvitYMKMQp)+Wd2V&J||y&wF3% zpFS_zf0B*7j}O?s-~GGfKdJNX-+8bv#}nJeoXKTW-0q+CnDNgoxKiF9jSm`M(+&INpJ$Hr%VQ6*|Ji@GX#bFo zhq?IUSMkaJihnNpDF36)f90Qb@I1|&EK*S5KfFAR|3&9NcVcb*ukxSi(5(L@|JU0r z{&{mZ;h))jEG_XL&hCHKTXyo#xq|W^AN}(z^pk&w`d{*YStD*tDF3taAMgGr^8bT> z$^z**AB%s6^rmP3>^PnM`=#;E%mrWhA0+?NiMQnBf56a$|JFZ0j3JBhKb-xi#y>Cc zjDPMy1thxiA6frC_5b{b2C95M@y|b{{PXS~|7;tc{d39V;D1f|6zTjQcmIL-k2n7` z4Ws_&PR3&L-}&OkRdDj}i2tQrZhTJu?!Tx0$A3ETI$!dCH2%4xYS#ZM|CN6~3>@lz z<$t0mmva5xf4ceaxJ|aQf3E#6*8fsUpBLkwb%XW4T)EHP(>?U;-!u8o+vE@axlB&| zU!)0RPiy@1Csg_GaYcOdAHMnb&iOwp|2&C`=prjKl9hjEt#vsqefsII{+Va|wEh`$ zxS0Gu`Dg3~`L8Zz(Z#Qm`rl_?N%H?Y|6xcC8&=#@JNjRqk<|azM5KQjJD@lQV;@xNZj_TZoQGe7!gE9kfO&)%Z-?;P`A`H%4L8vic-W4ZjI{SQ=m zi};_pRL5XXxpG4O z|4DWk{@|aPO!disCHc>tipzca_No7O|5?QTA49U~QZN2{$^X@Vesj2UKfd~R$p78{ zB)uA9ssCdRwWR*v{mZH7>YuTcKl!KeRH^yD`gc685{ZAG#!z2(hx&iKsQ;P#cgTP7 z&&KqS_p5&z|5E=m3XMa^i2Dh~|G*XO!29gKmi%{o>VGEtnfjk=P^|y|h5x@ie`q+c z@s9poy6_DL|KT*V{~vLiguVkFLuRahHttORzxns2{^um*;NLm;?>7H+Q(FJ5s&4rA zsQ*|0t;zo%{d=1KtA7qwkIm}Ki1zo^hwz$75~o{ z|06q#_(vxG*=^tb^CpfzBEuC{{~VKU{>Rw(A2$Dk6VrhAKdb*)^Z)GM4ZPLAv)niT z3=U>2HU5|P{2%Y!#=$>3K zTqmjjHUCNJqkqOJ%P|NOmhkV8|J^D7mnPKwk0k%wgMVHY@!UBIJI-Y%o*3c;|BU4$|HVHe zsB-S9#`7(>;@`)A_~t{ZHy&-mbRgeV)|6%SMj+=VkcnpXr>p z+GGDu{m%uhiV|J_ul^nN&#qgNUiv@N!9O`Tjl2J7^*@>VpZlbn|CECkesAL6r~aR* zI(PrvI->sH{ri&t_-BPe?~FbFqs{-^Ib26&S48vwga45Ko7Vrve!uLtdqtbb+% zlmF_UYy9J-XZ_FHCH2pcp0qjn9~u0q{^`)ONdDu$Jo_K=Khx$v9GGkN5B^K7|9h?f zxtSX>k7~#d{wdDL{}=xpXZ$Pw>AQdFXt(+2NtD+A;-7v?>A^qu4eD0>(+KG3pY}20 zKRx&#ssGRZm(~A-fA`IQ(BN{qOwq_+Rt?pZv2`$dc@fIr4A* z<0we+-+%DWr|#^Zu6mmP_+Rds_0M-C4+hr!H~zgp;pIdACwwnI$DUV1QvV08=Kt>B z6aTbCBLCS*Xq-y?4@11?zf*C{xaU88?3#oBg#3TfR6zYt=q{Es&O zU;TgolmB?D|8c-v9fnn!{8#@0`LF)xf%{~}KTi@r`j?(N!*u0E*}=bi%kWRruAlr* ztp7Lv+@-9!(jQ9xFXTU)+`9f(|0C=Fkx^G(`GbE3!+i0oolZHs|K(odKT-d@0x;|U zlmGba-=+R{=^Q8ivx%4@|2O}E*8lyze$9WMU0H|qKmH4b|GfC;27xTj)PEM${D2+z zGRS}RpXvHP+VY>_WK#cgGw+-H=i)9;Lur!olK(7PR{z}-|0A<9IiI`^oU7oUb*jmK zz~Gl z)c;5SJOn)ZZ?*nk`k^EL$G_h}=zCiKQ=CldpF64eXQD36{`dU9NdCL5|0Vy~KRft$ zj`=VCIjueV=QiKf|I-%-|G~qh{&(|V{KrKayB+=$xy~3}7@6kzA%mRaqLcN1Q1=J_ zuKJ&;|BZh)x{mlC&;C>VkMy%DDSxE?SO16)JCFLGdQAQ2w*FWDTmwJ(&nH?b&@Yoa z1Z{O+B>xBg3N`;f_+PgC{|>8!4sk96w;9ywm%LP~ziIR@`OkO+3MdAJn)N^T^cZl4 ze^=}OsJJiR|LmWkbvFM$_~-GE^*`Z1*8JynuUY?_{GU?K_?J@=R=?^$R{yi{&(M40 z-?#p&7yki$EG7SU|HYdB^u}b>bM!yC*^`P>^FNUMj|1)}(hgqppBnbfzlVR{qV;&-h<%Kl%66|5S?qnK48o_5Z;?ElG|4aP{AH zk*E3p;=grr{ImU;#!TvA{ZIXW@Xvqw?|1mK|9SJzsz>}!yZ>JNGtH5Hf3fvXpNAli z&;A|i|EKXk82_w;sQ>Z*q<0ej=Q~$Gcta=o@6zpZmi*_wbQ|-2%lZ#b{*#VKRg27PS# z&x2f-_IULA*ZSZ1AE^Jue?MKbL;f581NpE1YpMS~`=_Oa_20rH&dLAFeAoOx`X40! zjeqy+8Spp8`v0T%y1zn}6rexP-~czwBy? ze@FKJxT?@Sc@c5+&!zrj{`0hhT^F#( zv*+$Tju<>Yp(k>_Ad~MVG<1`OidFQ~!&9 z&Z+vN|LDSE?8Sfhqkp>mk^htN-;n>~ca49?_+Rkvjeb<~KJwt7i7DM8{&~+}^56I$ zYW45qzx%@fWc&xv;KJze-PRl^a?3Xs|KZ|)jTF21=S>`6QS{4x_1}>HLy{T)v++;+ z4%z<;H2-)1v++N(Wyhm-mz^6%CvlaubHqRQNg2@e*?-Fdm;4_dQRP?Zu=qLt!&m>I zt^W%yXcwNJ?Zv;WHEzx5xP`rmt;{IgfiS54r5 z_Rr_!FU2d`(LVd^B*MCV+&u_bXM&g z&HuD}9`b)A|M5Sof9YL;e@FZ?4e`zY*fO2-R{N6w%-xHbRVXVa7abfY}@uR7Hy{yAI3KX(|D)qg7f<8}QXFG=2N{^Os=TTk&niT{WfldFGc&HuE) zKj%m6|IuSARsX}5|LULdr2+N7^-pQG`cKpL`HZW+;dwlRh4IgR-0r^@|HIio3s~~M z;!Xhm-4Fg9UH{iaEicu?KWCt6LjDisul~6s=6?<3Ki#)@6D$7NkaOtMnfMp?;J+vT z@t<%0qu$m0|HXf({zuJ!cY4UKi25I6hKssf;GdWkMY%!!kN;5p_m9oLC;30x`rnuJ zKmKng|3O4=Om;o!=OE3~cK!FVKd6VT{;%-Qjlfs`iAxK{q;YSY`fy@y{Ew{v z88c$*eEiT0 zP4RaB5&2(M_z#SK>~N>b`uAV_vx} zI#T~%)qkz^KmH^9C%XPO{eWB*R5btDHle?VWzncF?|ADFhqvGtJjpf~c@W=X}X@&el{-6BQF{xYqr`)f+ zcI_bRfAJsTpRM{2{x7@#zY#w*%@VEuko~fM>7O$d@$dJGUkxeEn{56&?Z5G#v==&G z3b@CHPU}&=PK&!kb+h^(c@ul^&lWTOo#}66{HGZ&PaN)f9sDym=#Ovf z|KXb{tZ)9AYdNMax!|7s2PXeV&Hsd84Ag&+;6I_3P6sE*kN(r$zduU--?IK^=2S>; z%-w(5O8x)tpZf{opUHr7=|l2=yd310|3CSs5w7}gU;Ojj zS@PfdcUS-NV|HEQJ%_N49rfQy{crutBjhdrU;H;EZ^1_H-L{{1cgL;Bci{V(~i z{&W1x%sKT>KWCHwY0G0#>z`rH9P_l?s-l6l^*^cqNc~U6SI=B0+5g-9&*I+`|Gaf# zR=D`5)zT#O|DONcu9f_!kCXM!cko*OPhD>Oe~bT_m-`}!$M6s9pKhDG|ND!7dRXZC z-}vW2P!mc1G0M2(8@twjx%#i!_oM#*;Gcd*@b z)cXI`Km9(8|1#m7_v(K#`Hz23>woVW{h2oZlm9oi{+%nk0Melg|KsiYVEkA3pLhTM$lW<67dWdyWM{z`A?TF{NKs{iWWM%f3Di^{)Y#vB3cv}|7qsRV*<&4 zW@XRI&;B`4V1keFpB(*jO8k@m2Nfs&z1{z!`Og^(`7i!yAf*0h!7l)pfW2vhb!g*8ErhQ$vpN z$VM6hh<|$gfAl{VbcGZDbhZ-z3^&^Rv%vMAsjmOUKSM;-|25!F9J|`&f7K6X|H-?5 z&VP6R-0fxkZ~b#lBL2gV{s;B%h3cPsu511;>c3b2uJNCo{WIt~8E)ji@!!(%?(Bb* z^}qV>o*my(;-9LM7qER|{qusHv0~Q$cu$Z1xx=*iXW**%kGA|*|Bgrful@(}|LC6+ z2$!K>moEH@hNPDKZ!^~a9&gN>OFMCOnn%M&|C1~f!#KK-|MaGp`hR&w1+896_0N8C zHpBxDnvMTaHUwV%d&PAk|E>Sw?4R2K_oN2kOa3$PBjbQi^1n*Qwf@)qZ|{uZ-TlXu zl+3O4sddPIjo zm>CDg|G=!MSO3qX4r;GbRX&A&_j^B!FCKk3N-kaeo$Kg~V4F01|vm-)Kv|NrWr{a4xls7eefTIoT(=G z4|?_Aevjp_`R6QI^56O|{%im7<-ujN0yG`H7S8@t>z~opY;Rcq&E4z1$$ti6F0J~P zyI=wR^BVE*@A=Q_;GR(R<3FHrKNF%&{lEHezPc*=>_5oT{O;YwfA`V9_v)XQCrjS$ z{ylbG@h{Wj$^V}G4^93X|J*soOSkjXe?WsCTa@E??XX2n1I{^b9g|3UH}|50E1x3BKtKmWylXX<~=|HkA$mph8x ze~th4?4Q<>onB>?{14vqpHh|%m9qXHx;E)=z2?98?^ge5#C?p_KYcUU8&v=C7x`aF z{?ixF|C`VII{NLpsu==Nqe`Eb~C+OgR;+DzTKReAY{%`7kk^Miv z@MQhp-WkJ5{u}??5%F)OW~E|Jy7T|J?H;|7mT`{=fK-zkc^0ihoD^ z_tgLN6DZq{{`p=o{#*RhNqJzl{Mr93`Jcv|ZR4M-uSfsV&w)V(yaHnVZ~b%m&eQy# zWc^S6ul^lV|Ifv(W3E%gb6Tm4VtbN5fr3*Hq<{U7BsBNE8} zqkrj*VEjiqFBLTF|EKlO%krp6mYVs(E%|T#=Mh7}jQ?qBzGLy<%G^h-|6ly` zWKr|~LR$yA>EWN=&C=JJt1kc2zmrxc|2OgPlmGlmlAH#eHvgSwko=F<{O7Zx>;FjV zfAQ~3%kH0tCFAZtqW&lUx#!+n|6Z1NM69g;-E7WS|7-ovRTetb(M^VqsckI&xn;$$ z>D9jzWwITRtN%F6csJ{-fBzbP&G=uA{^@wP`ya&rEdI+k|8!~iO11tE0?t&o{6G3% z+UKwS8T&^4A2$UJ_os^t4Vv6#n&=@=G=U2p|AqQ@8JQvVKfV67{#XAO@z0z4-9K*|)PKmdC~iG(`R`}^&B^^A&HsPp zpDS+0f0$g1|NJNa$@LMQ{SObOT3i1~!zCy2&oHyyKhGmuPVn*1M~?zWL|!T-2`qW9Cu4`4285JvMj$i~28IWPS4Ai2v@w8qxUg`IGg=f7Ur| zgnwQ_&;8LqLx-&Y>CHd))Wv^c^IuwQobsRhvOWiv)c?jm?=)=w<3Bz4?`dBt^*<9M zjDK#2EIb-n#DCNf#b5r5f8KgJ2mfj0{R{tGru1DNJ+J=9)juzTqrmv5&(kOWZP|^l z{=X&v#s5P72Q~R`{RhTBEss0OUX%ZP$>5(CoU%>LUDYJ5rT%v-4)+-zWb%LYAME+x zZuviPX0-Zmc*rmQ8P{O^=S{&+W&L|K)vDD0^fOWa)$jiO*7~2>(N_P#ME$Q5Ovy#r z|6Bb(-u-iD$@tHjTPyWH8_}!(xp~yB^`G7Shxl(z{m+{?$^RGs->d(`_;;^qEBXKG zzq9rK!N2dZ$+hRdoQg>PHzYEHwdDQ0ssC61llsrdfAt^UN}hJv^*>KmW^OdD{xiw{ zfxg<^2mkc6J^A;E&glcKWnmJ z&wusr)3u(10nJ@H`{~;AXZvC_267oN({=2NF--r6AED`_dn*Z$J*!(yC z6Y`%`r_KLwZZjPH^M>w`G9+*~`wz7KXT()3{`-*Y8Nc{XX(WCLlCA!4P&o;o4V(W= zk`Vtr^*=jiy^Ll!`S**SS#fYX`fth?{|o#7QIv{*UNnh+uA}s?{zI+*ZT|26BRX_V z$%}t3nwtDS`!Cr4U;US>|77*gU?uS%+WhAp`PqNWV1u*&SpCbyR?YwNcmLdsq$?{Y z6MWmW-$}LmcgX*G^&frk&s}z{|E>RPT9h&C|FBa3QMLKMp8Su)wo-*)_+g_^Dt8VGw6W)rx^%4k&^%Tcgsfn-(LJPDfE#4Ol%?l z@$YT^>DtuBx08Rrq2ueD|3v(In*W=BuVW&Kygv~CybfRer@Ww$_8?mS%LGI9-?Mx9 zwEh|4f&X&L|8Ua$=X|kv@M_1_{|gx=^*?u(tp6JSwCl6^?+y%%tZn{>S(f3SmRD>3 zb0?mwZ6^Qm?_MVE-c9fR6MB-Y`G533eDF`@X8rSq1^tp6qd#Xp@C z8Ks$N{?FDw9bCnKD*gxj*L(gm)t2|%vi>*zgAe|vXVna@$$#U2DQ+#B-J1WcyewD$ zsmXuipIhk0|L|;RP`LT$_*neM*|O*V>VFst`bBYX?jAqAdg<^_1x@|G`lqu*)Y$y5 zCI8zCYeafn|LA|}saX@Z_IyisV20q+V8&|BI~ukNzv;KV$yeP5pDvwcGq>X8j-O`u{EepG;F{{om1j zmJ5HuwPCU``A-`|&Hr$U)Ia-{_@~*v_-CFj`A-kx)jxfYsQ-J$P2<0p{6F}o(e}wd zmjO)vhf@DH>VHaWQ~$sCkJSd_|i7L)|`%|KODW>Yq+* z9sRTLALE~n>8t;4&3^~~@w@*jX?FjM^&eUPqpAPtH@W)nn4w8CLj1c_xw8Ma<^SqG zr2ZHGe5i^WG8gf`eDE*t7srq%XRX&w)_fwJ z82bzUql5p>-O z`0K^L%ooVAmS+6vEdH6&mqnSa|2?h$@!!QAd(G-Uyf*#jpX-3Mb~*TO)PG9*)Pw(w z{1^Z8rKiJQ%q*=(a`xYge_q6E{wFsM1J3?kh8Sh_y_faB`se+9KnC;4Bo{$Kq+$^UEP>iNI=Z%+B2lK)xLB|J6BxtmMl`GbG@ zd=4qE&9a3l9Y_D6?*GkF|8M^NPDV50zrjC?1ol(>!uY4z=jxwb(=sRj8Lt{~*QZLw zzl=6W-C6w8((JMO=dm`U(I1RfB>!m!)^QE*D` z$-mF~-{gNn{wL(WL+6gwe?Bf;4^jVZD*ox)wfc|t{1^ZCw0iN+89ldMTqnL2TzBAU z7x{1fXGj0+$zC(+|2`_CicW0m|0?HytAFmqvj2DV-&W!Ey89oE|KX#5J}Y5}|HR}! zcSI&mHOYVRzf?gh{wL!PYd;@I$J=XtZ;_g2b|1vyH^ZytBtU7J}-?K8Z z{<|OjbL22HA4=+f{AZj0m>IN83U$Q)qpy0#K2iU7)NSfNh+|LlU;Wdhg8c9EMe{$Z z^Edw)!E5}dlK(S@YxE&h|6JIrxBM6X@`CDT{}=0@w>{m_KMz}4zj$Wti~rW-zYI-3 z`u7T%ra9Nos#`ks&)csT{};dE(J1@>G!>BgAOB>V_^Zk_0N7vu=?*;|504jB}aSeKYjO~S^u(3M|3$C$ z|F8ZzM99>CUGrc>^Pk2>9*3l|{_ke%-)&>^KQZ~=SF8Wr`gb?~e)%N-rLQgb)Tx@Y zyiEG2vi?JKfAU{WHvbdjpZhQYuT}e8{CBjkTm5qleB9RmNB?P^8~?pmLJKO^Cf@qPiKHIyoi74^GN+qI{HXyWJ8075-vP5yI5$@q`0e>$~W|GoIXbgO>{|AF}LQ*N7+|HDu>)c>FSC!O)%lK(6qO#XYh z`fr&P75I!ra+nYs57fa$UE#lz{7<9nYyM}nG=9dzu>0rE%#+sYzx(HVZ+tR_*0uRh z!+GaIUnMSO+4>*VF{rYZ}ZGg}wDp zbFp{-3-v#zg&F=Qo%-4vhwbM%rv!dL&Efmq1>%b{<#s9a#fZT-SS`kk2D*@|K#!acJVHu*YPM>>VMJ`~UcF8~oEXiS>WOA-MIQ|LC9Yv+?e~m>G|D z%zyqI;iaxN|E1Lb)4@LnvmJZjNBztdflK=RpxhhTJldNJByHWr7(Z9SuDC;_xt$lye{7)qRJzf9H+g0-a)xWdnKmVNZ z@3D<`@E-=@LjIR^DE?czSMC0}K=_vbtAE$zze8u>3$18(|ITHc(?$H#5M|4M{Kv2U zx%Jf74e#3gk}he~|EquB_-8_5NB>Nl|5P(P5;FP!$$!!8{(WZnEz!}(|$7j?4QvkCjU48<0CizL+XFp z`H=r^^AP_oFZY{~2EYDXab0=p#*}yU_@5fq|Fz_Qq4{5|`R{ccwcWG2_|ZSddK`pg z>YtDOtocs{(bv}a&+|&_|GMDUzxwxA|J;ckor!ZlssFiB$sTL1{<)fG>i?sEo}RAx zfAG(#?sfCe`6O5K*7|=w_`h2J?&_cW6!`ay|55zsnePNV%yv!vPoLbVyU>W<`lklw zou~L`KZai8gbD#;{MYLL%H4eHf0q2`)b+_js6x)b65i0R_5bdls}nQxVWs}Ze=6&L zF2mtJt{U>6PS*JE*j=RlpBZ1859Oi$4>R@8kP5oN46^jVpR!l;e=dXGr~Rs_ z|Be6HX9id+{=H-UpI6nve|_@5ui@iu`9Mei>|C%2H1$7CSOl8-XArf?f8KVee|Ep{-<|z8Xa7CZoABS^KMLZS zg*)G@QvY)e&eZ?v|8e#|uxQ%yKePUsxOQpOzeoMgz`wY=*s8B`0w%|qe~LcT&e&0wle->>VKD}5euIcPI-<0gaZchAOGCCHvYp_ z{Lj??1xvu)4ul9{}DB<@!#N|iw$M0{^{y}A;&!O|IL4Vy;SUnOa5E` z@#cS){Es=55dZU~GX692U;Xn$R{fWJb{AgU%_YxP%4doH%=qV?yXHTSRj6CG{7-2j zx%yvB{ts-HNdDK7|Lm_`YLowy&HrEgvk}6xfY1JmVch)luN;olEu@!v@OfAY^m@7@1W@?V*|+2sGP{tN4$%}o3k(dEs*ck(|P|LHIOc}r36 z{_~T6t^slmZv0;cj;??7&t+Zw51aqX=D&(EpRwrAcmJh47yH>iFH7J2C)EG(@ajK{ z3h~b%+7JFY()`!{>6TjZ%Cx8{M9=;^_7l~A+q3?6NA>T1_CL?`d}A;9)qh-ZDfNSY z_uzlg`k(wi`p-1~#Xr3)$bZ_bpZt50|LJG{tUZ79FY`rK{|o2;yMLxvsec-g(I+=* zfA-J6$HGzbzaamaNpJF>UJ}-SwdMbl{AZRHjZ{zmhXVgoPySy<&Htba)xRIJ#ml2M zssHg`bL#{DlhptCkGSs1wwPo5^Y7UFpC$k4__*c&tm}XE&omm=|J+wp|Cz)zudmPk za4D&((iP{$H$rmtv(K z)c+*@lOlOq|DM+WHvbpiLb;OvyMIO-8UGW_x#+hd`R}(uwD}*oti-)G&HpqGbp1cE zv|w;&%waeAPyfu3U6Iv)!S`v1|CU83qb?k-XW~DO#6MTS#D8+|PfJqC|6J<-q#yk* zDQN{m{(F-D7wPA+(1)5suhjZ)B>!oy!uu}9z4iltrJMg?&wt0{KYc*e{~-Avn*3kz zpTvC^a9mn-2?NA5|J6S)^AcVo@_ShGKh^yA^I!dsn*TGuPU?R@t~UP+HkIa?qvStT zn)>(pq~*D)_~+MD|D%7IYjN=-YGU$#h`Iez1SbF4$eDbb|DXL|H2*`URdnJ%Y8i$p z4Z^Jd$>jee`G4?VQvZ|xlhps3|Kk6-=D%~we}DDQC7AS+e?Kz*L-kK*pn$_5$$$Dh zq_X~Jv(@?^sQ-(qQU4dI|Hc2T`CoDCqD-=pj}{+1-q3Qr`QV>B%!TwUT>W2)#QNu> z8nMb_QeZ_7j%U01uNez^^q*Fo5z$^n>VKO0bOJcwI=^G;fAvq_@-&er9O^&kR#N3; zvP{Q+M*sL{(-zeK+$UH6vH0iR4EgU<|1+vOs#qFw+Xw&5o1w?3_0I%T?p|*Gy(Y}d z%ZvYr#^Grjum|eLWugADFtUH5{-1p4#6Q;(WBzwIn<}c^Kdms-Kg}Z+?$>GkUo+Y) zD+`wE(G=r9I{LpPMMhucuBl7$PnWdazr$4;@jq2zAJBip_-8+uo{mw#p;tp;d-k7| z^@S(k_)iip1LqB`$XqV9q>K9J3!k%X{Kw*7dQLMfaraMSUHnJnf7=Y|e-i(^PcZ)7 z%$NG#`Y)*e)&IowHS53NAU=$r+yvqGzy%TGpSz~kKW)N8@?ZTkM_T;zwu?QOv~qaT z>*uZHKWo9}DfPcsSJYmn{=e|dO?IhEh6v;%{`rz8|M_Me;urtVyt(jV0{^}B&&&ps z|ChAPm|&2li`4&qKhqD2{HM=Z&XK$NFH-ua#5GN6@IUxvy!tPw|6O`WL6&|0nO;|P zr>?WQi7$Lkir)BVhg|$~X2+y1c8us+S`+ZVHVH2!&YY5X(B3;zrC z|0Qy=i?08fUD33?_@}c>!XQ=O_#bkQ^Mk~9B>x@ep{V~MYzzMAy!RLXtbx@(Epm*1 zNAe&4vHFjTf-?@XtqA{U_qT5&yl`|Lj7OqvGFX>yuB-nB+hB=dk$XKRo0= z>-r!3yO*cee)iAvbo|qYtT+B!{5wbgtRz?e&XZouC3`y30Zje3#=nDH@t>UhSC?VS zf4W+7Qw9HAv$X!HbNC)N{%JokEKgpGZ2n{QUmE}XOC~`HPgY^pKX2~hD#X9H z<$rNWt$!||^1A1r{IfrC@LzBKXPf_7Nh>9;Y>NN%v;Xw$pT6GYKO;uS|IL5!>c1~( z7wzr-`P39e$=X)(U;VQez)Vx?zxm*wRunX07yr}hpWlP}FKNoT`scT3{O4t8{IjdV z`k!rn^-urZ-9L};@!#X$qs!cu|LiB6{deM@W?Pur{kzt`TaqQ}-@`wat^d~gPt-qW z;HuHzjtBXxz+#L!eL$i$6Eh$P@?s}|LnSgv%R%|LI)+du;Eq&e`h!N$YbCxm=(WlEKezQijTW~0-;?#f z*8k;I>i@JXf)PyIg}>wo{^vy~vNCD!_%x?Spj4uV+!Gk4={ z{ZA{}*ZQB|gVz7mq5fy8sj2^qwf^T;KJ|b5ss69G`roC?;H)QKRnj|&R+kgmz?wP&-K4^s{i?{ z==#5){+G?;!q)$I;QWu5TkKv@|5r8je_`r>?zwCIPk-?b>;L$){&#<^|6Q&By|m}v zJPVd~5x}eeh5bK1t8@UV=sBC!^fRKzab24n z)8^*?(pAx6{hyQtufC7|`^@KS$2I;J+5hhvI?b~PU(|n*GVROdnGXKDQtlt_{v+8w zjOa&Fa2bmIzaZoO68@j!pWVx`i?h6GINF{=(M_~MdD_ta@PM- zA^zDN?+5n6WdBe7KhFLcKAAtw`d|Fh3Xk(~=1i6;cPM!pJMlXm@&7CW9_I0yG-C3s z`1f@G|59X3_-LoLDXWp!{a(Vo-F5$eVgE0V=pI-_JHfd*KO`;Py>X*^K{7!kdq{NjLw6?EiBv zkc|aNAJp}WB(8T>*THw@5$&#)#cHw{)5ebss5z{5M#|#@z2c}<9`(Y%sS)zk6zCo{I|w`sQ#b$ zXEd4mckr*Htjm#(U>t2-qB5!9{m-j^&eyGf46pvnqkp&G{I_K_;UDlx?A!A{{HHO^ zE`IW#RaJxkkn=z5pR2q0r)A@Su7iI+J^BYp#Mp}6zw~oim_vzwn*GJ`)B2ydJj(t* z?~}Sp^8ekxEBU|s@5O%x` z{;$pdnfX$h{~!F1JS#7lRHykLM!))Jq{-^PrpXHV-|YE+3Hd%<{WBO!{Zn~t{`uy3 z_fG*U`LF(iAN+f(|90Ydl@6VKvT%-GJ%)jnHLv+^{pYjhe`NeekG74N8*uXfIOP8j zee&P%@Zp&M)m#4a5{vwoWrq4M$^S7cfApW?KO4MZ5dY4=!IhJ1{!==w`G4@AlmCc6 z_~&=L`!6*AokRY=_~-uS>c1iXH~%viGj{*Jc6>8*VX^b zt4-sdYeQ4v^1SakTzSdRQvZ|x>c4q1>O=ECEYpVk&z|akX7w-izxsEn|Be6ZMq%G3 z&x=p}kNBurc>i-Ml3ao#ZOC#c+nV$()_eeg* zjSkY{X0QJ>{~fMjUbucC{=+A4fN7vC_5XC`{)EZ@GNIWY7r7$pfAzoY{>P*Lfcigs z%4iAAfBbXKwctNxK0w5?S9^ zBaO82Pq!-kx8#5Mz?k^wGvXZcpY?>~f7%%T<6{v2G5%SwQvVzOzSRFRNUMChlK*+g zRA644azQ&EIYR5N{Eq2#k;%&=KgK`b-Qu5LH}yYFU2x~(#eb*y@6tYV z_s?fV{bPVnSMKE0|M=$)f~^15KXZ^Db#slD3-!M|1u zPyTt4VDjJD@_$O%uxOVwfAgP7-y{52>VK%D{^y|p`R`P8#kT$jT8)bT9RIEL9~u86 z^*=4LSN}cxQFVOqAD5S$zTV=0F#fs7z_r6){3rPLsQ>9h)>d-=_{D!XcYeVW#Eu3M zyj>Ij5An|=aP?nH{lEF=0^#mI&d&aO_0Q|E)&IlzAI1N;`DfxE_5bSs@q_VN!8 z*K6_5o%;~~0r#O~{U56TJf}x4ecPV(#Or?XpJ@Hh{ruVFe?oUU{B!Xi;}sWTtp9|| zKGgr}pTCa}{yV$==ggP-AOBopqchIQKmWnazyIn#S^c-wWA#t>q1i)9L7Q;#KPMx9 z)L;GA)c^R;)W4t856|R3WqZrC(z(9j-&6lJQ_Xe#&(jM=Z&VEr=TH9G9^+P`_z%>7 zTJm@h|I?xV|HXf9{l`<~UudRf{r7p6<+L9PLh;{z^j~mwar2+7{@c9j@c%gYj~Ku} z{;U7i_#aLEKhZKWbjg1Vh<|Ri<9}d+UCG?U)xV1$@t^Ph2kW1Af?beE{ZIZoxr;yi z&yxS4-#=+;$nck^_@_q{O?7A)NuQV9KMzMe>i?tv!sI{SgOdOFuXB3N&|$A4d0ut)?`O>2o>TG9cIGGl*N^#c{4-~5bQ@l+tp1}Q zSN}_WBXD>+Mg4F6&yD&I$`}7jcJzNI|I_Eef69->`hWL7O8rm%Gqc6yzxZFs|II&x z^vHkfzp(xb@;}@1pUxvQ`EUKhdYLF=ZT@rJrlW@2{kMhq&q%;(tE*kLWCl|BRP}#($VOtpCY>{JTkq|BU>1c!oeZ zw)>~u<-hiin$P}g{5QNDUj1J`=KoXkpK*^JJ*K?fKUXU!H2mzph%eq_F!jGT(vR-l z|6Hy4Uo+NF{4?No&Hv56&#Y(sx3_t#|CcNN6K+kC|EcxQ=uW=G#@#=Scvk=P*SUJ{ z{sY&g{-1LE&r@yk|8eop{@K1X`7i$GX3c-%KVg`l@h^iaLMA#&{)_*~GZ+I0|MMaLQ(OPnw9cA?lYicGSpO_@PyUBJ z|E>SNjo0o|HVJIX^np#w&R~| zEb&k0;kGE>{FA}f|FHR|gToS7|6I+^{j>k4=6}+<)Jg8WX%GI}fTINb(=aL#|Dnl$ zn&)c%zxd~d<#YEhZK28k7ymx~c{(coxsFMDS@!=W|J6UuI5hwH*ChWL0d4Z%rT*s* zGYh|Y97d`}{AcnYlD49B%Vq!J$!%+YT>UR5|7k~huK%Bx%xhiszg(uiV>j0;qlZV( zmtnj4XN0rKe+IKwX~j?}&HozzE_+ej73d=I&*0fT|9$e`f6P_(Xr8phq6663|4h$= zG|xFJAEy`p)RWV}KQF%vhxUGtlmBsW?(K6H|IBXZq_o9_;P1{6XLC;N1{crqpD_{KIKKti9uTA`dgVv>6{nyvw z+Q0c{@R(EN(IZCdj5(3M(cmKqAULDe^CEdp7O8$nOb%7->Uzi$A6P>B+CB(!v22{J+BA< zqxyG^e{OuVw4tAv2s>vXP589_H~xJ&lo^7i<{hp0zaIVb%cWTlr-~>4bN~_mbP{Sf z)LIyi#ygMA|I7o7WBwce@=}c>XND9W{7;(yOV0Q&rwt77Vf`Y%IX zlZ*dw^M7OM_~Jj_{7R5O#HK0&1sHz_D>TF zY8$?LcK;>$KX>9^rn;zqHYs2I(`xtNfAPX1{3rkHdQiQHf7j-JZtMS^^*^r)b6zkW z@}JhJ#yY+F-~YT-LN5Q-ZDkX$&v>fB5Gq@#>#jPFwyj%<2B@zY_nvW8|3*<#ng|KNtA- zssCffFTVO;=!?Asjrwo!PYcJq7yk`wnSbM-u|~%KPTOXrZyf72ux`Jfr;OT z{J)>_-}+CcO#L@s)f_hBKQ;b2?OgpkJ^oYU|3O=S&HoSnSpsmms^e4y|J(;N{?qjN z!T-Qsn)RQl|5)-rndlK36!_=6jZf*pfAfR?j^pYr|E>Sjk@df4{omL8pVs{EB>&^+ z&b5o!_-|=QarW=!_-}XrAzePdSpPFRfgmbgOlFYvL)5&n4} zPW#QXe{awKVPHNS^*{N~3sSBBSO0R?-CVZ}rT#zUKf^CS z<$q}M|2~du{?~q61oDE4m+RzzB=!GNWmM_z>OZZH{^{G5aVzZLf4NSa|BHX;O5cK{ zp189Vr3`Kgp2>as)qi&*VDId`QvdUMjQT(N=sz<4Wf`~nZx}eI^WJsV zKkEeQfBerQeKU{#lRK{fW&eK=|LlD(VRwu1ABunOI!gYl|Ee9b$IP77krC_o=RlOH z=6R_3ul~mz|IEDSpy#sYKmPftB|#zt6)({$i+Vr2Y@Zf0vE;kHo)B9t(Kv%8@Gh|H*%rkQ2P$-19$`{HFzC z>r4Hw`QK3gColdp@_!ht|5^Pr2TlFY)<0j?JaeR>JoW#(|G?D$lRTd8pY+KW{~Y1_ zVJ9`Z2nX6Pd5RV zJC%_q^}qGc-P;%cyhqmhKYU(Ok86$|{%Mid@BTw>e6IDs`UfKW|2_kXNe33L<6!(d z;=c@J{U5yfFN4QY8~@S)tY_v$)doCb52uQEp3~7k3$C>L!vBDO`VqePUl{La{4%0GcAped3F2?_N z*H5wWKkxPb>VM(@Y08*lFg_Ta;tc7Fe;P6{uZl6{<Oa@~7yrZVf3*IKjI%P$fAQa+{PS*!{HN!So}xP{~W*%?ssqfhxpI`*?&v@ zA2iY3`1jR+#QNW%gXNb0^lf{*`KKW>O^xv1a|9T%UyJ{)R{uPSk7x!(n-%fj%*^W& z|7k$!z4^bq`}bb`FDL(;T5u=P_-7A>XgB_82DIhBKd0`(7{|!^rw4mKi?SB{13-k8nV3m&+*@1$ba!4h<`pWGCPT5^W~-fZ>j$m z29huMpMLaD3ugvgn*104S*reX^`EC-%stujzx^ZrTk@Y4PR4&r$JToFFK3u0|2c)l z{|*0?C)1k$;=h;m|H1!oYg#6v@E$?)-w&U+)Ybg=Z2nK2K!y)L+5I=2_0MrY;$7L! zq@T3^5KFaDVwCizbb9>$YU&q@8i`;WE$7yt9_KhpYt?B4w^ zO`-L_`{F;c{)3bMw&5-+_5bF7Wc~lye_AK>(LMTazb5K`Hee+G{b9Ou4*u$YIQbu? z{`VyRjeiD9;EGD8NW;ZKX?Cr zP2qrl-oXun_0PC>>wn=k`_uUMjelnhM~4}R#(#kSnf-t9pS=4I9=sncxNNBT-|!mA zm;C?W|Dyhnht|Kh`cLpbQvYxMQ{&&mKa20L-M@=}u0G8zqxvNOy~n}- zobx2^Xyi1dZkaq?ecTJ^NXZn4_x!#XU~H< z0DNdR{|~MvN&d$1iHve=Z-17hEf9z|`|D*rV`e$^`Uz(q`#{V$f z>Xy0l)_>#&5AnaS{%0bytp5|qfALRG!g%%X9R2gNoBSWcy21Z)pU(c}1x1w58I2p# zloI4Wt8|YJV4D92{|-G5lLG(Deel(PGJNpgiGPNH;QyQapSAvDDr|7-rw-J1UntrZ4O{FhwEe)E5S@gJD{4;aJV^8{G@bG}9WzxmIS z2W`5o|61#R&HvHlKX-k{tL8r~044ujt{s#An}5!d1LJ?{=&C1kDAhmh*wbn-`OmxR zZucKDciZ@n8IBr%Z~mDB_U50v8Jqu(`d|GoXaCv4OX1q>|A>ET1~=wbuGatfZ_ux~N38#uT_OIHulU73&BO5D#!t=vkN(+*!@nc-|EvFu z`hW9JPe`Qv?q6mkPn7f3n4YuM&<6kQBcmLC?|LL~*Pu~2yH`>E?i{?Mwe!bN{@43XkWBu3SznA*| z;NKa!9C!2|eexe_{!eTo;Gf+K&Hu9F;+rG+|BwEe6~nBqge#!VYRmGwXVyRZ4yhcorR8j|D5_i zqEEBUf9~ZU^8ZKw3}!O^qt*ZN$v-oQO#b7)!+-Ro-y$=1p4}n;6MA)1|BHWiVXqFu zE3e*K|3~CMw=G}%(>rI)e_!f<&Hs4MfAP=3Wa*24*?X|{zms9F=Iw{9|HB6VTuVIo zpKblG{ypoTfgtMNZ3_JR+5vRP#D6ID|LUJywE1uRyW9HTo!jAJ_Zr&pk<|5yJEHC=oz&}ZtOH<)q1kpG;0EqD2*8gLY*!<7Pf1dJ)|8TzX6-WN_z*h2~`68QtkNO|~9J_M;l=`3f#9RLJ zjPjWOW5_#C$$#95-F2Lj3!T0a)bxkBw;c z&pVh8{%20JR{!bWLF#|WfAvpu73zQM-+$bW{)ZR;v{0XzVy6Bp>!0gXb;uzA{%Oap z`H%mokKJ+e4|7f;#eeiT`)8@P`FAD%FA3-9TK|jx@$2CKa`x|P{^Ork4(fl#|Hx|* zwSUg`)qf}T|K^|jV2L)~&SK-=WB+d+g@$ z&Ims7UvrD&;D3<(fAi0}`<`n4_qc2?-&;T=$=qSS9Q=Qg|9l*2 zT*LQ^`e(FE6X3t(cEL~nzhcU8UH@~|v-#(6Q}!N=f6jTyf8*c1zWSf3u zlm9e7^Gf>mKb-Dj{HN-lr-jBpEv<$>v+?gl<>sHesQ4dN|NLC!zwz%}TKqfDzpH=x z=pFs{f0mo^znJ=;eQ@gk)OE<+dpb(}-#4-PXB?jRzerzu&i8EoGrXi&wEmyUi}9ac zY1>czfA$|r{eMZqE&uWFc{OiV-uyGaca+Zx`5%6f|40AxbMwy?tG~neC!BC%^8e`n zxp1}e?BB8ZfATMH#CQK(av=XlE{%x)2LG|-e-WSk5C6eGeGj($UmgseGx<;V5B$@N zjh+RP|1S0aSM=sT-2A)7|8%RF(33Lk-qip8<14~{Df@q3Vf^#|x}W{K*8ei4ul{*| zwEOoM5oi6!n*a2!cyJ^@l`j4%+>L+!GhtsnnP42V;@bp(bx0AzngmgeP%D6pD4%~G%Wr@ssDHX0i7|Hg=;4C08#&s-lP6E{+BW{ z{xiCa^e_H7l!%fw|E>RG&Hv4Rp!q-dsqybO#{Zl>T=CB(Ku7#H^0e@?e5ygp}i-8$AZwqkmci?*3^vN&YkU zsB`Bp#p_iX;l@~dZl*TFw8#&`cIbDci;C*`&N-~6ZCvD^GNYyB_&2kQTi{wJ;f zPyTr`cl6KtXU+fJKNl~h{ulqX_0L08_0K)Hp7&tZzq{xELj6A)|4c1!H~+kk-u-*; z{ugc_82_v=H2>?t&B$KzU;X<{!S$w!bK{8mU;QuFO7ma+yJH_`F{=vd|F~NH2fP0+ zeDR<4v+Vy*O%_j^e}AMSOv6p|rN5E?Tmp4W{x57JivJe>-rs4f|Jl(x`senj@z3+0 zsf?xmU;WqCfA2o?)M3Dq=KtA0uf&Ebis;;6^1s*o$3H#vjDPmGTFw7h25~`)IWD*3;KYX{I~vTIjQ;o zyZ=P$fAW9S{O3D^{O44T%U;%hO#b)$ublkzT6N8T8Zigd|J)@ek=FWu^}kU6YyQu7 z@_!z<`cD2I{rA-W0dK0Ue<$Hdav}cN+kW+*r?)6eX(DCvKVl}6@qab`xkbwQ-}rYW z|A%(LKY#jZRR5f9tA9G=W#Je89b5nNhI#Yf`FF|xagzKu{<-H${m-p@?xcm@bLMKb z(ZlfBbWPR_5GENGaUk{CAJt|FZbJ=t}vyfAY^^oBH?Fzt6-} z@}D_llK%^PUMBy&B>ngP`MH?ZP5!s9{&^m5{qx?EOJMBM{&A@P@$bC(kJLX47s>z4 zf28@Z{x6$?6aUV?>onoFXZ*9l^TaxcQ%0%|6wC%le;oR5t&|`BwEd|0fy{i~rE!w|eqV z%L8t{=dbzCS17?P{^<>6@_+YFz|v1j>VIBP#@XgS=A(V|AL5@&`PBc`|CK10{6G44 zS^rD^*W%y7Kc{jGoPGq~?kE2v`~UdwF4O9N9vtI8RR3ccbH7IXkN>G$ulB5e$K*f$ z=Qfu7|HVIjn%#WO|M)>gZvBViKlXDj`@Z^T`*`=y6>^%482>c7c8TaOpZeeWXXc#s zKla?7JNYkd{_|wOtpB?QBg>;?lKsCQ{rl|~&)X9J8~?m@ZZhltN#DMQ_u_vp)Ia?e z{qfI|H<9Fj_%!)Hw1d?D{M2jyi~nx&vl{=diBoJUj5TYmik}v|D%7VbV&Zshx}*7Z~e^#D9|x_@|ej@jtxyr_Dpot?PF6?@<5KxSs#M z_20H(`j>W;NB=ovW!SWM_1|m$Gbm#+{xb%b`#h3bYR-A7z2z&E-R9jt?ejaie|&eG zYi0ab4*ul@)xp2tU09_{{`ai^&;A|mUaNna>qb)l&wqT@|HglS|IzyAVfVN^g1_pY z#*=)7w9P{O&(VG8EAN=#SfE`~h^qTy4#sAFGpZw>p&nN$M#=-x>m!$Zg+Q-1pZ~QaW zan1j7GW9=KhQ$9;z4+%wcN+YC&Hs~snl%{z^sXP~{OEs{{8#^+^Cx_z82{PXf5-lu z_0Nsy7ymSLz&{t4{X72IlQRAnpAD-+{^Oq>|JHxv8vjEYTs-_|_-Cd@UzIf568~w& zHm3S_R{zcBKiTr%_-EF&%Si(MXZ-)=7PZ#@@BYWN{ulp$HUEPz{4cA2n%%$npZ-7g z?mgbVeXjTT_cp#`%$kVg`R}On=seD8+w=EZYdzQd^SymOmDK;8 z|9DpMm@?$Q?$!UnKRrl;|I}OR|KQ(A{&)VX)_-xrKljM+&%MUh|A2u!;-9`p_@|Fl z$ba!at9`|#wR9kN7$@9=?fd6Ay7ga${O|l{vi_&GsrKiqzJE>r^9)b&AOD;WGAR3` ze{Lgii!slFfA;e@Eaw4a=^4i<{<+9Cj|=i&i+^qzG3~yq|KlU^&sEySKd(&M{Ldu+ z#lM&QZ~gn=zu5NAUDKrTZ?AxVi+_WEc@tBl+_&ib&wBZPVN!Mec^kO#?@sYw%l?1o zpSCL*^L0D_%*)QAn3m-s{|nw0)LZ^9sGk3Nnl<@fb4ORs|H=R0Kdae}JJUbUR~rAC zH`$H<*(v_*dEeImn)N^L$W`#qe2@z~w&SjI&wm~K(-b+v{x|-M1HG4fssDHVW9o2l!vDPSUvK-@lKVH-7f|!{s;@<`T-gf>utZ(z5%_~{|^D|LsmR~F8cQXG7|1?7F`L9^jto@HN z7xKU7U+%e|>A#pN6a3Q;ZP$Mt^1t=Z0rFPj%X3A~f6a`oBmDcB z+VVf#_;*vX-mr3q?iBO{^?^W{&~F1I4(0T zPWn#}vv{|oWYoaLfijw<}i|EV}{ z8#MV}os;^XHq~@o@Z&W2FB<%kfgeYg7(6I{%jTGt~cm|3#bs!9OeP)BG=&mi7OEn{t+93x3s>vExg_{-5MO z{>#QcJ<#^&Ir-o7f6(_|H2JR%BcBY}VQlMvGoGe!+rauA2NG<@J$0FaDR@`KJC~hWekYTA9@U zW?J)3W9|Zpcda#`Izx07EfU5WqNR5j;+lK=SU`84AK zTK`i9%^h++u$2vYw`{x4HI zHGTiZ|JFYXeCmJkKRC-jC&x=(K5qM8obb<11o^*c{8#c0=$QNAbagx7pDwbY{@?W< zHU4$*pN{hC$cTT{_)m8ISB-zOuK#0N1XBN#|Be5M{IAG=9rC~RPnZ8e688TL>;J|- zecLab^q;Z+XK1^cau>bzzu4rz8TI|sYqasNssAtEe?|WH{nJ07mRrE1&VRK$&3|0T z{$CaRCx-f8{By9q>tA2g|Dwx(_Pu5O@2Ye7kIDaC|FmD>0YS)rE%iUwa2K?}J;nb@ z^4~P|f3@+i`~G9{-v$2+z2j0P+izX|t0w<<{Ts_L$kuHoBS_A{-5EW{-Oh?j>|0J5iN_kQ~YyO-}$eT`h@?L<#|a` z@@AGPUcAQ${)esqi27grr_%Qb|NOS5{y!`_|J=Sx$2f$$yqnUaO-6+pGTzcIL;-3~Bsx|1s?Uan3{bvV9lwpOd3yOmEtz z{+IkWn(i>%>2KEmHJ1nnY#!r((DVL-MEsq`BWPZxY(26~5=R5y- zoBz>d&Q0~X=B-IWe}&-RcK&GzPZN1_zGg?Z$^VMqk>tO8Pi6hjo%o)APyN5~uP#gq z-Z)AA)8$Y6mvpcc|9j3epHTeMm~9b9bZ+YE|IE?hdF{WF{15&;>;Do25xpW<|10+Y zmg3(Gl)9kzxmYjx&s~4|8TlsvJ?sCF|NL&tcxblqe<=CSd+sVsb=vq}6if&0@}FMH zN0R?*|3jX1n)5NgT*be^zi0h#(tVy3Cgy@>+jW!wF4X^)uxjf6#yYo3Y z$r&zY;dZcMu+L#7f@J;Q`JbQdpDzIGf7+pNr=!jP;J@ZTT=Kv5pX3Alr=9oAG#k%RjH@nSUz& z7ejl%yWQZQhCS5(eg78!b;y5tM_R}|_Zjs+^F`ue-#Tv7k4tk#E&Vd6}R{9pU8__8+jf8+m%w_p`_UL^nP!-O4<;C~?b z@5MidWpb~q^sKNQe5rYU+Rd+j?m((6dnTKltbTw(mdLwc!4(KBn z{Fj&Gzv38C*8fF}|9VtLt$#-HR)D7m%KogtKX1@B{`sYje|1s+RhR$uo@)GaSHjQo z2{V%qjUoR_Qnd3=m#Slhc8OU&fOEJP}Ws&2*&C z+im}B^fvx^WLM@>MgHq`{wKpcqyDGQAt!m_Kc?;exq0iKH;${|f4<3oeo$@5|Gt0P z`OE(Q3I7H8-}ldBpZN*@hWw8>Y#{#|{}Jo|$~XSYeN~41=Wmvo#(&A*Kj$K0lmCtX zapRxm6cc(n{|vh$|2O`1$p7Gfw9bG2JmkNT{HHyF)*STp{TJL?4gTwG|9X_hT-6T# zmt1fP`M>4g>@(X#{I9r5KIU3+RW|-Fh<|!Buu0qIf8F@ktpC^ktFrNLTmOpuU;AGK z|8(P%{Ezm6e_AXB|Eu}lI{%q=&ky-l{#*R3y-1&DJ812{Zu8$!|8u{t=bxVy)A=u{ z|9zYP|11C85S>xrLl&ycgO?A3|hDdRMqs6}k#>T&I z>;JR;*W|xFWKzTN*fX9ap%SM4FIVC}lKOwkKdrWy>agRVTM>-MX#D4sg8JXl*CP0@ znM!X${a;_```1$cpW$C^`Okv?f_Gyf|Hrd>Q7YL^+4a9{{c`~@_;;uKFRzgQVaWfb zQ|Gq*Gj=npc#B5Q)=iiHeohjY;&$j(r@*n@k$oijB@>u+P@_*Mq9b>Y^ zBGKeO{^>xx@lUf<>VN#ZQ2+Zq-picf-);O`^8X6>=iM&;u}S^Uu#3ij$s2$2KfX-q z1INRZrvA^9nW~!l-%4TKtpC|v?fa)0F8&8|OM7_9f6iA<_|H!9uf@N2oBWr)N0R@Y zf3=8?b-(^EIMl2b8SO6zT%GUy=O_HzCjWzfiiCQGMFE@$e;6J7QSL^!!6#o}C{y{P|}QSeX0vKE)c?(i<<|Y0sssGJHrMya~{ulqt z9siZ0{;wwD->m&l{C?wK<(l(9Mmn(mFKFW>`M>sGW_CWQ@NZ{Ts=EBQ?Elg8l=Xj; z|08p->whly|AK$F__sUxkAJ31k^g#=|MUQA z{8OUyd$^ip^gUsR5dV67%yTlHBQ*Z$h{7EPT6S@$DgGzHKf`*Y{vT}ougHHnrm!rT zssB&+PmdS;`<{Ppz70~=KXvQB6#uK5cVc^W&p%JIMyo?>TmLofFvhKaZX%#t#vc{a z^NNwer}$@^Y}>!nJi%?&|Aw9BIlb(9{*Tpp{Oe}@kAE5tkpHcJ8oN#PzSZh{$bVjs za-!Vx&skPn){6SS@o&ig@_6F8|K0f4~{Xw^fS}=KVJK<`1^BvPU`=n^}pKA|J9Or zssH0q*#8Sn11`{Dddq*MN5^abe$M(|>i=5&)1D&I zlK)A;VXQe$M$0tvt5tQ-`Y-qt{9CF2>(l%*rQwSEH?99#{1?H0+W4nb7)k!SJ@HSA z75wWR{{$u7-^4$!Vb}g;rNuf?>i;eOye&!#ssB6wbbX`#UoBey$6fx9c$+GReI-3U zj>Ny-y&;FH`1=u|n9hz5I7Z{Fie6zwysq(}Abq3d5Hg|GfF|MeCoJ z5KaDbZD7a$pz%+iBU%5i{X4a&$p3BsMap&2)_-c}wdDU9{+F%)GWe(OaqFLZ_PhS8 zE&pcMf3e^C=WmwD%o+Cow*71JUtipRvg?1@`Pb>b_}7hpy~+QLf3}xf|3%-w!GF2s zzZU<4!+LqbKa-}%Yz473ex7N+>H_}dZ8qzFj!xSAcY7s6DcAMCJFeUOU;AJ3DwRG^ zdZ~XJmul@6G zuQ*QH`hVMhihm>ZKVxJWYp~_NIxcvh<<9o+B>zwNrw9}OPVztap9cR^%fSn$PTq-s z)q`6>QsJ{emYW6AoT)>-6#vM~3|I8tg{BQj$$^YPAnTz{Z^WcBs zR?>8e<|pIEf7Q=_{O_&vpIy=wBO_%0FOvN~%X4M%Z%Y1Vr}@w4BYA`-{#CR7r&9?- zGPd(S_~*fOeLkVV2l{8!}v zaLJ{mY$g8l!69cae2V1%UYq~<8UC}if2Gdt_>Y4Bi2C1@he-zay7M3R{qwYz{AUi# z#(%chvxUKbbTR)m`Ol9y`ETZv690z!Uq>hW^Yhf?Kks(Le-zgLoqw*@M@I~c?D;R( z{^>6~v|IkOCjTja*ZI#~ilyrObCXc=Kblhw^!#%hwFv%M!i)d3=bs6<^gZbLXD_3v z|2zMDQ$qdkCsy*GeJtvK@o(~(_+RiNcbT*)koun+8)lFEr*XVA;N$#XiGMD2wfUcs z|GWa)_>Y?UpRO!Nde-^p&RRm(9Oe*o{@rvrth)TCeZ?>yaH|miT#K0ba(bR2tEc$q z4(7nIE*`FU(HTWKv%|>$amfGRpLgO+qTmh9u7CdY>-=Xko&7)jms3NL-SaQ~-Wb29 z)wch7Q5}v~x~cyg|K-|0H#v6vmvt#qonl%4*VO+@sKkf(x77cQ|M3a`R`&nu>d@^m zSaZz!pP%)$|8niWqMvEcf1VxI{QdKk`d_9x_54@L*`(*+clH12{uAnd{4+EJ|E{9` z@BHW7HKYFLHPT7{JntVaBXiDh)=&Od`iNWLt^Z=nKP*H2KilzNH~G)thQ>cLVjBN3 z`Om~+_WyWFw)U^f!+6_2zjc@VLYQ(?FcSa#qR|)guciK9=RY@5B>!vb#2x=MSqc6J zq5fB_|H=Oy|7kRn{lAfG>i^b%a+z7@e>ta-jMV=!Utnl9{>@?_{tH8kxwU`#WHU1h z|MWQJhg1B^JMY#%kHHg;aJKx{_~&wcm;arAbyTt4Nn2k0+pzv;xe@YT{Abl-75p=3 zqV-QRe(_&*{uw6S__rthtG@pl|MYI^@;~AgB8Pfg{;ReBm|hEfkq#qPu z!x?>V&h|fadq(^#{I9aHwFmK*{~G_ip$Y!;P5$HGH|u{p6aVb5v25u48}9$;0f*v! z|2C}uCI8t>Z~SM)Y{DD@HoD4!2{vVZj@u1xvE^SUjsI-ppQZBY{uTAV|-_b!N2eOAGH3}LFa$KwHHoAgMU9*`!A{gnfAku2lYRVQG*d1RZ16{)-Wfx_CHc>_osj z10dMKH$1%P`RD%`^4~5_^Pji=lVwIfbw6>*LGW*ih{1Gg|9Qy&zW=J9|K-sE{xkBw z=52(`NEZJE{@ID({NoDv&yLpqs|D--kpDaWP00T$t;dE(ObM-VrT!=X&+;Eh{*UMr zx8=V&@0CG0I^FrF8&Bh(2Qcc$AB%q{{tLR2^{mPNaxh@jT%42t;=iK)&rb25h5f&Z zH@-(cCI8RzU&{L5%KBgOe~<WFXo^Axvufg!O_OQ z+T?%hpMD}4{nUeh2Fev5t z`{!Fm{Z9*B$^SF_R}@%n{_mYP@(zF=2Yvq;^Mx+zKVjl=&wrX92mfXvulv{j+1iu* zugU*COZ~s`&t1wD^*?=%7;7i~eOY(@M=N!xCI5H*EAoHsKVd74Lj&r6oy8oCkLsR( zPDR)LX?{FD)qh0&-{ybkpMkmbvDa4omx}to$Xfq~{8!|^_~#Y%iko7se;x9lH<@Am z-}z@Nfc!t*|FA~;eo6h$Wp1he@z34lE8?H)u%m2Hjr#ueLBUqj;o5(+M{l2+{HG0J zG?tNcjsNOQ|2E`*#f;CMf7SCJul*10xb;sh&!B;x|Fp~hGyI#7|DAuHz0Oz{(gOtl z{8C&pX)~{Q&rBoxE&p|s|Bm`U#(#ZOOZ^|w zX^TgMhVy^=f{b#`FgcVB{$t7idYU)>lQaFhy%|R-0}e-;^?&Ps5%Qn$r}cnWz>DID z{ExZu(dK_N$dA-4%h~_qGM@NXGcW!txqr+*9O{4GlQScX-jCd%9@5LU^IwVoLF->j z{%i7|yEFXx$$#Ci|6N=E^Rvf<=-}V+hDJ6L8vm1Y+rQ%`bmfBoYTG{xfNW*g{>?E% zuv`Dd;V2XT`Px4tvQ?3vtM)qo3=&(WJO1lY)%aKOp_W?_;y;)Cr~fVf^=|$bhtZzF ze;tjgef;yw*qOEe(MkU+@lQX;lm2Th?bJK})p5+>Tf{WZ;Gb3plK%|&p(G0VKiKlm z{I=kqwTa|EQ+D~!_w%18@ge_LjHmD$|LSNkU~TEMTpyGiH3k1XdtsQA_*cw#691#% ze}3Namf?^+Lwd6;R;w=mwK?a>fAQ~z;{SM)|Ef3&`Cl&SN`Zgc&XWJ)pH=~5Mr-ZS zJe5U&w9lE+fOm<1E+5c4$?fx^mi%XI73+WUpG%t5|M<6iWIzgMU_djenah#D9(dW1l7Gt=stLlydD~xBhARqG^_e|D5%IlmG18HvYLvHse07 z`1i+F`n&}HEArp1{cD=h(Y;IjFB|`{acl?n{M+EaI^92e%Zx*yR7(f8F>m zn*8tlSK^=EE!+OpuK(3Z|6FR^@=q@-{L9-_jttIoJSrW4$bbCvQh4K^@0QuD|BX9H z!ur4Sub4H$8yftx&v{&)_iO)AQ~z)LuNwdSGfn-^qxiM|rAr(CminK|^gaLVvPE^d z@o$^_XOL*{kJcvt>B7?bug3W2j-Wf+Km8k|{%`yzjeq6V{$)nEwXJ_n{TO1L@sQc% z_)qY^-11*cW_r>1AJnq{&pYzjuK%c9`{$J~eWd#Nf6_nydHnMuO8u`Bn)v5qdNVNp zrS-oG`G3Mc4~Pd>#Q$>FKMhibOSkr~+xlPpr_}#z{|R69wDHe7m5qPh`Cs<@yA%F( zHGJR|MdQC^B@2GbK+ke;D2>|h5g$$|1Zx!UDRpTexW?!pT!3kE%5K# z{O|kc7clw1_Rp`tkpIEIUi%-iAG68-#(zZ(9P0mm{^Oq`gO%gJPhM>9&FYZ<8~;_A zrNMtPWESPXjj~046!-IAMG2>gZT@q|V7lc$<(CEbl*E5Y{*RjcZ~gOjWyim2{JS>) zcl|ShSN8wU@*i*er-9=-|MBmr|6BjOq-y*Rr2ap}e;x9FYIpqC!N0z6hJQNlEjRvW zjIGY&sL6j#{@Zr_kN+b0=bGy1O#iF>Lhogksf!!`I`~gR{ZGX%_5Y6ltnZ&YZ-u6F z)Cm9d!{iQ}UH1GJq5kJV$ael)c4g_175ux|u75}U-}xU({zqAEn*7KAF!=ZD{HLWs z$p6*+0{LHt{7+8vFF){2{>R6f!&;7N_G^C9(gCkn7j&hN{BQg_$^Xtj9nmZ|f+hbI z#X;kLYRP}+n8zoPyUu@VEXjXdGvJwB-Bs|voT?f5zxMA#{onUrZTnB#{LlSyO#VB5 zt{93C>i-?WI`A>)1nEcPS{WD^=%YX5o?E0sB??Flaul>7o zn*7KAT|ATU` z^G`q0Wk&ta&R9SH%LVg2n*8Tf1po9s$3LrwF~2j!KRZ5V-uN%sM-~60Q2%f8pF4UX z|2O`bBPaR4S{-t4k^Eo#FL}R&eX#W=ZhRnN{CEMLS(Ssdn+tyQPwzIGk}d{wt~f`OEkHGvBG~`HwdK=e_#hGFE~7 z@BHiIE&nvKYy8WxwM%%hk`D1tU)zxX5IDm>`&h1++2G$~P5r<2?>GMQGWgH96v3Zf z@_);JD*4a5ofS7)xF#&?f4k*>aNb21^KaJv)5*$IWzH~}&c82~JSCU>r#F!Jmp%_8 z*?jEzS6p17OHSjTeQ|H|kpJSpn27)Ch+Tm3%pa2fTGszGb0hx~u6oi>r12kZ`A;-^ zdb0l~{yBGS@;|Mkz2kb)_kX;J}oPW>le@6ALn2aX=xepTZf7id$ z>BfH)>VLJszdDZaFNZAn=k6X2FZi{x<=<`j=i=5$|K%qCga2XO`8PZME3RhB{hvBN zK46s;>VMuwO8qbXSLA=+zbF59{WIM74FA&QZ)i*2%Lo61dhY_;clcN0zoz~-6io}> zM{fCd*=nq#{lO;x8~>5PKN|?kY*t(#|Je@BpLB7-GYJ;| zJOE(*PcUrzUy}d%;V^Ce^Zt{K?soluP=x&7_&1XORcRUN7uNr505h~e@?ZS3`$eC; z)BSU?b5P=cYDWXf|8l?PW$&*4ys7`Q89hK+|NQ-%{AY$nF!9N$KCI3(He__XejejftM{WLBT=v8Nh1Ng!_OmAc#lIo{ zPx@z7TGFB#|4!=vO2)=8e!TIo7IC`qPd~KapYhWvtt4l|ocw3R>~ZHmmHfXv|55PI zb%v1tZbbf@vd#Z=Sc-oZ>%^3r7YV;CS)#4$|IR=E8_9pePCo1ZkpGJO7yqlC|0VnX zbnR*Ur@Q`j&wnw^xs@=i8E(!9UGjgB60Ga|r-zSp`HDCj5&!hApdEDZPX~aL{@u{* z@qA74-v|GG$G>I`WqbaU#=qubdE=iBL!EyfesBAavwX`x1#NV0=~-;zpD{F&|8oD6 zqP^Mw!+&MC@HRILhVbOS;i*sXuQJcYq0z2?28^!#t3w8hwDmuG-;MwHV*a!J-0ZDv zzUuimoqxWSixGdYVSRD`>>x@0yJGF1#TTwOa2$x{DS8!Q~cALWiI|>{QKaa2Fbj>>HH@b_n(a-@xS6nTJ5Rn%1xd4 zpKRs7*(*=;@0$E?{pTw+lkL>$#y`D3BhQ&Z-+z4&{L^P|CV#83VZW&J&-29dk(c^^ z?SIZtWp+>T&tT1se+F`O`Hz1k`7i#93*0aZ{!>QIw)x-sA9~NZ%y#}Sc!@6g&$WVc zJny0J0as0qc+@nSul?6n{1@V%feqq+(D=`q^*@^yn$~pWfAH^H|2D1t-Z7PG<6o`w zpC|9^G!5|2gFHIEg#3@z^*{bI$^U}-KltZ|a^rt_%n+XyO^vuk&x~;Vb9CJKUp4-@ zzQ6I$5OMOKyR-cH@n4_fUxoGmaK=q_@y~ss1?QZz{6aDg`G1ywE)(bEKUeuA|M4#i zL-IehQva|0uR8zp&i{%>$whuK|55Ny#|`pd)74mZMd-^*BcdqdyTBwy{Ieq+*8gOm z_+K6N{8!OLzO7RK+h+Zr?QQvYvi=wU<%0G9mVd5*g#1t1^*>DussCM;>7w(WpW=Tn zcgzPl!avK}F8}#yaKjmc9N8Wt{~P~))%jovE8Z=a)$tJjag-MJpeFx$4bKW% z@*n@~_QmwVj-pfiFYr%;qRxNP_>Y?WpSAuK4?9BslOhW$->&`_|I*iT+kY~l$M|xY z?$w2*{_p%d@}G7RZT-(43-y1UQzuIOe=+~8ZHv6g|FwTJtAl^mi;e$yCjNcvp9ck! z{}=Jk28h)EjsKN&Q9a?`NHvhsPi7H0reQSx>tmn$sXVe^Up)9{*pc{`zDH~SoH}uz z_}KC=o4!D;e_~3_iouBdFDCfc?Em%r^K|}v-#_o8gMYb*h5yy@K~ZFD|1}M{*8W*x zH0%H1pYgpt|1|WJ{O8u~pz%-psMbHtB6|LrU`qZs{x$VKeb&Uk>-!&U(;e@bWONm!Y<$^+N?Z2ufv$cOtRb~HA z&A0u#vCA*e4=>dJoBZEfZTweT{^tYcjLLI=={rjOFaF1FmGkC(%m1kL?;8Jf^BbM? zKU~xi)r#bQe#qCEx0!wa(Lut1B=SFs_*1hbf6{;6^G|NJ{#~2@+-)(FQ~Vq1|JMJi zS^sk}_?V7C;-5D|_^+G%XQUmC3Z?$%?SGU1TmHGXo6RUyw*1rDuJ4~55&zW{^v{pf zn63oDKksphDI=ziS#F4bW`5Ia_%#2Mo_~KJ{yEMF`5%qutU9lt|1?qQ+)DoQbPoUA zE~5Uosq$CEf0`Y${%4lz>HfKuFl0jN#r%`&P5mzujKx3i0H`}#|AXK^XTDIA{~P}* z-sk5(_*YDbmX~TQliK`G$^U`mKX1ON|7VOkcNb#*EsBGsa-1?Dj;EhZ{ui?C-uKV% zP5di=(E498wupO=Q@vWO{TB!MUfI_Fk>l;e3I9|$ddXIQ%s7;_f7j(d9iAL7iE8@W zi~pop9VJu7R18%#D)#&S=@H6f82np^=Bt$Te|a4I+l_yArltNr;XkF16ss!oKW+1$ zZkcQUTr-jSpSGoSD*luDD3Scfe;L;QA^%VDPxb`=Nk9MbPcPZDSo^OV|4GRIgd1Sw z|8Sv#e`brX{c{T3<^Ku)gJaA3UrYXH$Fzvx?xy%>%9o>K)Y|_f_@B_*!XEyGMC|6{5DgMWGFGLMv;o_6)W zmi<50|I1`K>GHpbRp&pykk2>%Ifgvm_Fqf=zs~>GKdDVa+ylGzPy6^S|MUgv=YKgE z@rNwNS>ELTmj4U!4F5Fz!+*^CsO|jUFBsO+)&EWYi+|RX;-4u*dd|)%E7UIkSAGAy zKa%_(ueS5Q?|-QGE_itdgnu3Kf7?Iz=vG=c>wgvR4g3CULk%VVxj;;_-Br)O4gL>< ze}0peqf`g~t5E;rpF8m(|8u@MDWgVu{&1V$TpNln-}sNnf8XRkJLs+dqVdm@)5bq%n%o>3`4Nka zRq$W8{>M%JFVej#)c+^^mr>2|ifA(9YU1ib%s9g~|Fe8K?ef3ojYBX0R~I6+gwnqF zpL_P!PVqmy5Yucp=dK3%zvaJP%~}8J$TAsx;g|7pe3t)JOmDz6p3xPHne$!#TdDtp z|0>k~G+CS2Q2&d68@K*h-XC@T8U7aP|Hgmjc&;(0{%`!}3}RaQUoN`*@BEj+|4dI9 zr@-71ssFk4v`@R4E&s!`@$bsDe_my^{;6Z|Uv&9TiG=?FcXse!$@-rYWqCn0q^k}4 ze>xv88vi5wo6f(L`afR|`19*M?$I&3N&NFK`P}_;F;HEO|62Ul!GBEt7t8F3skd$Z zXN&R1|BBb9Jb0N~-Zc98D&Yx5=O5e^!(+Pq=Zt{*zx6*{#`QS(w@v<^?ccEe@BHJl z&Hp()fX?Ox`ZwaAhv~fDs_E;(zn|~)#(%lo@?X;Kha2+L z|CaiH%RggNS^sbRM?AN|KNDwn{d;CsOa7+|{M*%GeH=^uPyV<5tv?u0|F8X<+3Efr z`Hz224jcc>mZko0{1Zomu>KeSr8RDf|Ec7E)aF0EZu|a|)BJn>^sWCok@|n_pGySk zJUZ2X9{ihppB%yesLTI48RCBx{4*J-@z0peu>KGEpNINCKP3Mf|H%peZtXwL*-{Dq z#XK_vcj^1tstZvAKCe?`AaxoMU# zzhw|J)0r)OI~M=)8=U+X|K%)Yd`6s4f`5KmrT*8vKUmN}AOCDB7WpElEqUX=INg6$ z9+iW&|ETXj#eX9CPsct=b*cYD{_}>0{EwUbrzc5M|F`*{^!@XDT9N;X>!rMj<1GbO z9vQ?@Go?cOJBE53(AhTlFB<;Kk&8Z&e%YyC&;Rqpzq zxS`}fV;stOQYH!h8C50uZ-(h!=A{15)7F2MAM%fr|I7!FR{%}^GhMy$@0pL9h5XlZ z`FEc1&u}5}&+Y2gez@Av|3~=eZT60TUQBQN&l~@W`oBn}{^#z-oURmW|6FIBl!MNH8cibcKW4_za*?(E z87a=RUGdL^TI&DCKWD5nt|qS7CpIzppI0+#;^nlQ+04cG=Tw`Dg&&EF`sWHb`+tnK zW0nI0<38HP@xwA)`=9Ojr}c5jfBa9yzm@tw zp=*0D{~Q0&oJ-E-aM<(DcyjU24B^Iq!Y;|iKiw7w<=X%3bM~KcD{06Vbf!=GUpD^7 zmb;Oy|0P@e7Z~5cBtXf3{BvDX^1mSe#edo5KmKd{4}$+f<)a<{%XxNTc$WWSw4_5c z{CXPyX{zi7QmWf6cF*;D4!?JoSqihs>@hU1d7| z)tIKK>{Yh@eOUifXNZ5vYK9oa<3ZAq@XVm|lf9^vy`QP{-Nc~?fXnob@e>9-!{TcpONwVMiFC_nG%#uq__$Sd_Mnhu! zyLJB4zpwMp#F>8nH~yJ-&HkU64`+`0U;O8%_|I1x|23!lsmH$)|J+}|e;M+B$A8}X z_u{|Idj3Zj@t<||Kl#7x@}KdEJ^!49TuA!5Ohm_%FE;PW_+F_E#bQdAGEk|C6)w|9|11%20lL;h!C? zjejPX_59lt{*z-R>;EqQ@qZZn)APZuOtbz^co-=4f8&3O|HC%_{g`trlO-YlJO9Z6 zoh_H?(SSEj_+JG7T-s#+AOHKj;Jm1RsH(=l$3K%`=#$sv|F-{%p&;!4@i~*I@t^Pb zH`WZ&Y3A_1+VxLA2N@%~B>&g`4fQ|yPe)5x|Le{_Cvi>vZ?eM?!-eRY2 zO8i#~&ko?2`XB#_F{@I1jMHS5tqxbz{~P~`{O3{>MW*CGouC$V!Jkk3m-wf5M67dm z?Hm6*awPxP{^dQ~ug zQ{R7pzWs=YNrQ`QQ4l+!0d>8vi^m-xL37oBwC{-w*kJoOJ%{bU7yfPxz0U`hVk}%RSYw z@1IkVkpBbj7%pPTe=qfa=f89b{)Zd?ywNHd(tFQ=XV1yLpSe{poeKmEP8 z{F}!ANc=B*{?oPpgw>V!FVm^`FOP@8KTk%ArAb=jB5ch2i^Pze9GuZQka%i|x z*!rjCk>r2h|1jkLfS3H<(IbHTUoIJ-bDDn_@2~yyY9ZAB5s%0?pxn!42ps;iIk$Ot z{HGJ~Uovc-`ac@4{nNmY{l9u|HC5&`|M6at9u7uL{+Hx`@b6CZpOXKJ&i{gqrA_|h z-!dF&&Q8eTV8Au8jsFGtFY|?lTlvoj(#5Ftzaamq1A_nTkc)1e|5*GFHu-PY`QP~G z@63IxHvb2^{s%{VnJdb-HvfZvC+mOw$DR@G%hgIr{-5c8z+I9_&4+FLXR8(YC@0Oa z_?M2aC;a>6#(#?c(Z)Y}y}>`1ii?%_PqUr;w^RI&xBMsg=Paf1&&>DEe>FJGKeG*) zdpci=f7&K5bbh-3=~@2gt1kZs_~%Ep^}k$9xBaJ6$^V%Ak0ZG|sqjzNV_VTcbuRu_ z)c=HSeC*{^bjyE9b?mqOFOP@gb^bU0HU8yKLwl#ze?pu_mf5`uhe;(R;-goc% z&$N;J-}cXD+1meX<3DZu`vI4pCI7iXF7-b*bGQ7*gL1U(KMwwnB|$^}5680pKg)j< z@;?swpSom!$TNzN|FoT95Xq2TyTwmiCzmWQ$ zS%~p?w((zap4sXdxb>rWL{Ffe-(@`S(e~caBML7MEd5`K_ z{|o$&c(B^|*Rzxv7+mCQ@;@Ig>~zr2|7gs)7Uh-+y$9 z|JB-m9Q>=4W|wXL_x;z*8X^D1zaNeg9Sv7|_^$>@@UJ`n%V?V8f6@1!Q2+P+7hV4M z{9BsVb@|`;*Z7Z`^?#B$UT+2eT#-z8ek%E2Frm6={BsV!T>Dp@|7^@Z)Z~BXKR+JR z5;x|!BHm-!NY@|{B=!H=zwYHfBkj_olKLP2JZL(@zg>)|NBjP{bkNKHg3*9Oo=TnK zpCWzRf8N#q_@|4b_@AHQf904Gq_`)w?Z1}%mnO^${MSwX_x+E=|B(D=Pz(O$p35SZ z{15&Yvi|pB{eLq5`PpavpB-kB|Kfiz$A8V7k;cCd{!7;XlY+jYjejlqzoJC8R{Trf zBij3MsWJFx;>(tQevya#@BDLlLh?Tf`5*B|!@oV`_igS^_|Mq?E7Q67r-UH?xi8O* zMkCC0@Q88cppU+3bwSR7uxBm0Be>XiG$UVTuKkM#|e^33- ztkV_#W1H^yALHNQKVJJ^ihtI^Xtgn0dkAEh*O8(=Y+wUst`;VLaS6m~FPxH^&ap%8o@_*@D|3z2- zdtNOD{~1%=5nJ$nVanAMYTi@))5y|`e?8Vq@z0NFy*%lk;~4x88voov75`Dl|2Wak5 z1J;GbIBEQAp4qU0#6d3kKO+Bw|2)+H)ih(;Zs)%)IH+0s&zGzdssBU%50}*c`JDb* z_-9H}-~aNEX0Tix-1R@-5J1M+{k&xHU+k0p* zukSyZ=KLyZ{qy#&@gJS){|Ns%{!__+9+pe~n{h4v>&nrnZ!zN4bK^hV83zA@&VR(88~?oDlKj7@f9?)7`9IwAW6A$&&MnC^{3i=L<0!24KV18dx%0-D zFNV7e?a`1bDfrLykSPMeKPO|7|E>R3$bX_FwKW8ah{tfwG4ksu4CzAinJ)JLzn9jc;|1)~v9}nqL9Q;!WO$S^4 zC-^6zX-YrOrT!28_r(8V7K{It_+OI$+=R*F6aHt6H0D{!iUa4eV%v(h^ua%u?RNYp z;-6M_lK-oXe}0eRe<1z`tG$!{7p?zdv7`qWJ!jef6aUN>q~QQl9XtPQElK`Mmk-we z8DIBM|F`~4lmBb~gLVDC@vqkTU&S-d;mH4qtp6$KXRcZQ2miF)qS}q={wMxdGpYYC z$3N3Y#s7lM&L;moZ?mcYYpMS${@voAr-C%4O4|INZ~V_&|8%91{2#I|EGEfN`r1wy zbUQ6L_7?x6)_;Dw|8m^qf5JL5_#Zm93s!~r&(cXgZ~ads|9LaitpAsN|BQVV|0^>l zaC`noN5kQS{O|i`FnOE*a^?{7U;Gc({+Wl?_fOZxN#mbBFXEquoOANuFuYpof365} zJuD~xx$M*UcUJss-aX@g*7&EiN{g`mXTP1*B*Q)D!M_?O9Fx&-w9Egvns5B`av1-d zmSraRFWLM!)4z0l#XqkEXv?&z|4;bWGs8);_+Q|kU*D|%vlRbJ{OiuYOfVz=Y33l4 z!0A_1&`D%KDaKRl&OhA+B>#i|(PSL2^FO>)Nt0yle{sa=0QG-CA9eZ>ivJP*jVJ%b z{}BI+F8`UQDE{Ntf3fzz3jVX>wSVq)X6%Tp$o~oNWEm|K9Sx%BH2+yzFN1%+@Uf?> z1o>~$WFGt{v~J-|E&0!O7tdeB{|NuF_@`;&ZvHPO3%=>mYU7{cc}zdEi}}~$-|lRYc>Pp8nallA{-)aE}?xb{C{+ApI?gMS*D#ZmAd;eUw#m{D}W z|B|1_b^dSsYy9(cX;zkRd0ok7aY_eMWx8k1(BCNOT zVzJ}D+VNi{T)`L}jYez#a?gDc^8?rV&o1JhpM5$|FQxt$|InBx(&vR|Z>RZB@W1H% zGs?}5dj37%6ME=e-2ZahKQn}z{J*&WCH4P0|5?oS{U_o4pPiFM~9hujYp8r9U|KdMi=Rf`n@xQ`9TTqj9!i<>3w*NBZ|7y$sBJ2FaZqoYa9Yo(h z=XSJ{nOD63?dL!K`H^h>FQxt$|I5U99w4y(=Q`rXKbJJN^S|@Y9NE7A8Er2XoBS`D z{AWa1<9`z^KDoBXGlsQ9Pd zF1=-Y{&UvlNEzJLCi;9qb2)2AK(mDK+Q`|$XmE1v%p449YtpLV>G|HqwwO4I@Q zkAG%a=Sh}{c(GwdoW1Z2rLF%Xc0GcB8X}eSf6JJWKHzH1e9_kb8~@8y=bt*8 zQ=&Hi85b%32N(CxlgEj40Lo5{2z^Ny4|Hgkj_q1aZ|7NTHpU=1a54Zg5c)?*6^?z2(Q~qPD|GWI3m0|tQMEPz1 zV@H3NP5rMHegDUO|C8W`k%FUsQ;@aH$__iY2%-9aQr{!98dv;Rj^S@ORk|Hst-!GE3ecz&J#TmIP}o)10;{|v4(BTZ|CWmQa8!T)MH zpVS-w<0-G0>3bmlWAY#W$%-jBQKT&UZ6W_#|9TuJ(R4AGXHEWZ`9J3C-ShEJVyZEbZ`M2c% zlAn1F!Pt@u{v$T)xZbfS>LN;6|MU8Iemt>WGlM1M|HP61T)HxJo~FUcV4eT1|7^^0 zQ}9nG7ti`%{MX!{11bFJ5#Lx>*3T<)Xl`d4f#J*F8Jr%cG&u#jdT3xtpD+^ zvN~z=e>5Er+VwyApW8I}pA^*pOYxsb{;LUh&qDrFGm`(}pA@ClWaoc?{}lfWv9OlL zc*{vi{hyrTKbwnx-}BF`xz@kQ75=UGuZnr+pMASI{>#=sQ%$SJe~SNOekk$3ki%8# z?%-eMiwyeySv{=%Gp)r}dCt#1`M+rLKbtUHQS!fR^Z%m$Ikj`<4F5CwjdcFwlm6@6 z@@?qnf8*b_`9F_%*4X(k$p6drzm!+moqri>FzNiyPWb0Vsnq}YU-2~z{yD+e_#Za@ zDGg_}jLjhb#Xl=LssF|QB>1;^)%YLm`p>yh-ubU1{Ex|hBl&+h{%2DE<9`_Z&rb1Q z@%wkb_9@?X(Ale+s< z|HFzp=?wq$7hL<-)c+g*B~Qr2e}VsDdNKccq`CA${xfoq&l-36U#~jw^1ty<8{;C|5d2}L;ly9Pjwygf9;>P zUvrOtTGpp@o^0~J^u?<6Py1TQ|JFYzG~|C7@;}KKw$6M#7xF)e*8XR{5dSm`W|$ZI z|2pArg6DJapNRjYm;bKI|2c#u>0TTatlmEHof1TxAMq?g&T*vb`iL*&O4*8FN{-8X*3i(gJ zHOc>h)c-^L&oAoVQUCLMdqn{RptAy`r9cNzrn>e9U@}TigJ#%^frLQ&l zPe*IX|CrWC_%9^?S)r}-|8)P8;6IZ5FKIHjNQnsMv~2v#&ktJ#A^+F@XI=ht?Z3@` z@y~!;$$zz#|7^u{{wvo1r}>vQAmTp{`M-1-eF(^Z>GMLnl?4O2XFmAnMnC>(^@jgR zQ~!&9_J_vPMEs9A9%7w1;0?`e%fF(n7!kDgKUpL*ZgAq?0v;aXpR1qvPdfi&?gEhi zYyb1*WWgBRBKT*2fMzaqe3~s8xJdoq`sXV*OS8pNiT~l8TZzmFYy49N&z79oGmMG) zU;NXLSp4&#h5Rr18ccYTMg7ktK=DtnYkG_Z|2h2?xj3-#&#}Tp^1tWb(|>KiY$N7w z&Su$s7W_;7*7=|0bOgkI#BjNb8@h z_V}korSJTYX4L=rVnW}|Y?U$&q47@+xBkm$?VqJ?o$}_5tG$y!O!r^>r;UGFo(yR* zX6PESdBn#^!XT z;snVLdCOAqMdMt#^*@*m`Gv-fK>X)?(>niS>VM6qW~l$mY8>*v7!H?1{LjWo0#_B^wSMGOA(CFeu)WXArV>K|)b7$xK^8DK^|Lj$?`EQ#1$NvETQSiS!%|G8=$^VUi9t@NJRmlI=zdPyQuO$CB z{@MQGYh!x;8Cjka7~+3 z`saIre||pcDa6f)b^ed}L2mOu_|F>uxvD4NSo^PA|8?E@XR0_y=$-$h^`D0P=R(P( z*!X7yMC$*>e>&UspHgu&{^=dD@jvVQ&l~^63I7@XXOqbY|8wy#_uRz4zXJaG*~kC9 z^Pe{Ui`Ku9{8x&-E~BhsJSR;>6E#pnR?ibPW%9wkI;XCruB@)2E>TxgS6A0i*HqV1 z*HPD1*HhP5H&8cHH&!=MH&r)Nw@|lKm#SN-TdUiuFHpBrw^w&icT``b?xen0-C5m5 zeW|*ux|_PYx`+C5bx-vb>R#&J>Z{a!)K{zfs{5(0Rrgn4ryiglsJ=lxNPVMvuzHC4 zX7y0@E$U(F;p*GeBhdESd z)Kk{>Q(C1>bKNu)NiZTs@JLCRj*gSr{196sQy5` zN&TUEvwDmAWA#?`C+cnL?ds3eJJg@6cdB=(zf|v5f2H1|-mCsby-)qEdcXRB`g`?3 z^$+Sp>ci@v)JN1mtB6sw2g) zL&h>JnOBl2p4h6AVNlG|(mYetPSZ*W6ExMKej95#(dm7CpwH#OKX^i}oM^fmM~ z^|kc1^>y_1^!4=(^bPfm^iA|l_09Cn^)2+J`d0eZ`ZoHu`gZ#E`VRUF^&Rz{^cU+p z>o3uF(RbB%(|6ZjrthKeslP(sOMj)lx4w`5YJFe*HTr(~{`%|m1N7JH2kHmuZ`2Rg z-=rU+AF97aKTLnCez<;w{&xLH{T=#I`qBEk^kejQ>&NQH>F?E#*Wag~pr5FJKtDX+$X)i2k-reC37seePiO8=&QwSJBMZT(vPJNk9{_4@bp8}#q% zH|jU(Kh$s5f27}{->UyazfJ$Ce!G5${&W3K{TKRO`rZ1k^n3JQ>-XyS>A%(Q*MFx! zpg*YpL4Qd9qyDh|i2i5&QT;FaWBTLz-}EQ+zw1xxPwD^EpVt4SKchdZ|3_b@&ogiJ zNFVE&p6dmjWiw6d3)-Jmn&)Fi8yY5B(y&n@n~aWre@z9m~-Yz=E~+0b5(OS zb9HkKb1idia~*SCb3Jndb3=0@b7ON8b2D>ua|?4zbE&ztxsAE4`2ur0a|iQ<=8ooz z%$>}g&6k+Fm@hSVHFq~(X6|9W+}zXL%Y3D|xA`h_A9G*xHRgWiYt8-51I*W(2bym% z4>Aun-(((QzS%s~Jj{HndARvD^9b`u^Bv|<<~z-!&11}Wo5z~(F^@BkH{WNTV7}ix z(LBlgpn0D^A7V)^B3k_<}b~=&3nvWoA;W(G4C_) zH-Be7VE*2G(0s`JqxrD;C-V{WQS&e6W9DDY$IU0qznf2*|1h62pEmzxK4bpdeAZlM z&YKJ7&>Zn#fWuz1G^ttff``71rs7v0jj*icwu5IUIk5vK0*H2$LG~N%gY84?H`|BWZ?O-v54YcDA7Q`UKGHtQey4r3{Vw|$`&j!u_Hp)m?c?ne z?DyLz+8?k_vQM@@WS?Sx*gn-h&Hku;y8SWx4Es#`6ZTp5C+)NCbL>ys=h~mK&$G|B zKWATHf8M^(zR3QfeX;!|`x5(7`z!Wk_E+u8?JMlB+gIA(u&=VOw!dXxV}IMe*1pdE zu6@1zJ^KdxM*9c$P4*A%o9$cdAKSOuKe2DKZ?}JD-(mmUzSF+T{-u4l{VV$(`(FDu z_I>tm?fdNq?BClD+JCSgvLCkpWItm6*?!c1%>JwWxcxW#3HwR=ANEuBKkcXOXY7C5 z&)Wa7m)Q&U&>q=i>UstpTbd114|BubR<8|Cj?XKgl=dSN=;BM${Tc$4?rz~Ob+>Z2cDHf2b+>c3 zcXx1K=UhXU1z1@A>SG)VVuW|Qt_jh0C z9^k&-Jj7{@s1jeaii(`?UKn z_ZjzD_do73cb?hTNA8#!neLE|u@J1sc>3omS34DHYEDM#MxLkBNi^i<_?R||(`Y|B zh|WbBD!UCX>{x8 zHqmXPFNkgz-68tI=#J4BMR$ts9DPZ2m*`8QyGD19zAU;&^ySe#qkBbP8QnYjs^~t^ zeWS05?iYP+bpPl9(bq>0jJ_dyQ1syFo1%wA-yA(OdRX+W(Zi!}iyjd@GWw3_QPFos zkB%M_eRuTO=zF5aMURiZFM2}s{m~PnCq+LPJvsWJ=qb@tqaTT$7X4`S^ynGUk4Mjp zej<8S^z7)TqUS_E9X&UCUi7ok^P``OUJ$)7`i1C4(Jw|Xj$RV|a`e*ZSE83iFOPmL zdPVf>(JP}@MZX!nI{K~XHPLIM--%uq{ciO7=nc{DM{kV&AbL~u=ID>2w?uy&y)}AU z^rz9=qd$w@5xq0|i|Ad^Uq=7#ZvKVjaHspQm6F=}nKlT$p^?QEbpYvDpSN2!&m-wsstNUyCYx-;X>-g*X z>-p>Z8~7Xf8~dC1oBEsiTlic0OZ~0%x+xt8CJNhs3ck*BC@9gj5ztrE= z-_76M-@|{ozo-8Se=mP;|5g4z{;U0c{r&vc`uqE@^AGS3^xxngJo9sbY#JN>)-U;20Zzw+<#@AZG<-{=3nZMu<{gFRrWxJr8 zL(0zRio5fr=XHTsv59T$*o@=?bv%fN@rc`+(|9l5j}PK=@s;DN#FxZZjjtA8Bfe&Q zt@zsUb>i#A*N<-y-!Q&We3SU5@y+6!$G3;Qzbdgi2|)D%t;HvCayR z7m|a)a5x%q4{kD@?(OaG9~_)Jccm*``N~(h$|aXv^{Q99+SRXqjcZ)s&!Oe%a7>zHT+-kaaoBi7!oV(qX zZhz&geBmW`yz15NboDR3#x=j>T6ekjb?$oIyVd`f|E2iQ8(2Q{#`5tukdMEyeEiMi z<8LV+e{1>pFOZMFgM9oK$;aPWKK@JpUwr)a?WBJrQ`P6grsaKIt zy_$ULHRV&U^Z(#4eLXFo>iE=~#C+(@hkWQwU&xJ0akyI)gNN@k*yBnSKRy#<5%4L4&ztc z{0`$+-24vXR~SFz=0_Mm{7(Z{EfAuB9_!Y*_`dV*1H;iBPH3`0zIPWK6{D@_Kh^6{7(e6YM;Jfj=0_MmB!?>s>_eh zF;n!fScyM?Ue$`f|GQ<)7)-tO$@MgUkme85{4tvUB+VbE`6p@q6wN!)G^c#=P}fK3=DOTiJ{(K#!&aoW2hf{ z0YiP{i#Negb5vV6s;fDwYdNaxIjS2us_h)r%^cOvJ2o7r`6p=pB+WlV^Uu@#XK22p z`7<U+uRZDjQWWc7n&^)9k{H(A|HR`-(C2gvG!Wc4Ak`ti?k{?@GulRA?BBGYO9 zb2ML}`DvP;rTG_Veu3tfXud`B=V<-{&3}>R|KDeIRR7iJ{yVDwYIOe{)qgd*|BmXv z8r^?K^S@Ri0VHZ-G4;&pN;N6HsU;>I^G8C#|=m`u1Dm5YFdZ57I6*YYQz>qyKK%F z>ReKNbl<^5X~DFf)}Kx4g=}Km;l%jqR0<+aK#@|=)0R~7c|)zfZ+~~?zN}KVEL|ze z>lG~3)6?CXFpY9C-8FG)@TfdBadvW-XwTnJ@6beQa+hl4UA=Sl6kpQQcCJ=0`e82&!hMM&hZEh29Xp)# zp@h>`>h$Cl7@93gOEnc+%}LvktjjC(F4G*CW@z?6vj>_z(CmR`4>WtA*#pfUX!by} z2bw+5?15$vG<%@odte1DShvdEV|f=FFWhhW0GkBJ5)Wguh5Ib8B69zw4Y3um13%o0 z*$g4>!7M7R_%GU`#Pq+eT{Ebo1MwEbt%&bo17{_!S0Tha8_Kwca{`$AIo#jbg2=Gh zyZ5F z*onwMaX;X{t~&Q!@#TT%5OwF7puxUfv*7j_iqEf3QS*5`5|DRzkG6>1WtH- zrMG_$*yk^wI2Qx>E5P*e^sy_@>X(7(|NA`r9bo!x&IFdf4ots|E_Luvf%!~gSg~@G zxB|@inFnsi6YaOa{(NjlEq?~?^5$n7@JGP?z#ZrZmam3;pT1q-y9X}b0-We@p8+iI z1?~sNkT~)Kz?Xr4@8NOaMLgL0J$xScUEs?ez6d;x2jFG+6zcmbut?xJ>DB)V@85<# z_vBxv{QUyom2lB;XP-h)D~J%@l7d(lJ>j{slZhv>klw!*ieYzX0q9cKc6& z6C>yoPv0*BMpI!y_{b?KKXA7xt8u6`F z@P6w=yGspZP+o}b0lY7OhXeRb0B4EuQD731`Yqy3_`#!q_{+pwm+-fV?`g%CJ>2r| z0_Upmk63;$emdRqH;E6l;>#i~eh0X(3cm-u2<*%M4#^I0zO`Zg{gFi#yk7hj_^s(y ze9MITHi~}(^Lc=718&D>3Bj!@ycTx!SK&6`F<{P5%5MQa3CzI$b`tUbNU6>%5~~3v zuRpJef_t)8&ZqL2fYrI|J}D)mxBx#;M? zQl!`;GI_%=GooOmGZ~S#N_(@jNeSg>ik&mkleVcBv(|uVDhq6HRi41Ihh@TED8ZJ~ z#|O@dWGabVT%^pDi>j2#zyYc&klgD@CVQ%7YY#a+(OzG4U$y9`oI^@EG&ONbrjAWc zNr|pMN;Euv)B(d|a^%#&@nJbQJbG-rHp`W9?W-}?5+#KzLyVu7U%{4;qp69(fs~vW z8JQfOl2ZeNsbN&>EIn&!CM~->g9fE7L*|rXIuFj&jvVfqGiGbD9X(ZI-aty+FAF?> z6?p}{jAK}bqQWc}y`+{Fyjf;>wCxjM>Ap|P7v5<33Z2ttSu!=)tofN~4X3|)iH!5= zb*bdE$f1sVTN-_)+BhFpOiL3rd6;~fUzdNhULi_ab7!Q_2GuAnV7i)?&GU7i!7^=J zDq83q&B?u3*40_dz!dUt^AF`K88yb#=3-!S?%RlT{eaBtm`n>e^~dbg(A#>kw`XR- z)+|{l=j}cxSV4t{9Nx^e@ zd0y$>o<6^rNw1tqZ!Y??&zXwe#H`}9mDdZT0_K^i%}FO^8`&%-h)Z56wPN~zekx#T zfG3&z&i*Q{jEi_+VaeeHKD)Rc=4%<3GtB2c1ta$<{6IYnd<)_ei*kIIV;lqU%XteU z*R;G+j{6pj+_$Kf!(-oBYx{EC?_lJ92j%z%$TG@3gvdNRGMzQ4zb*xILc+W9S?|mF z`vLE>5niCJ3IcG701Z2UrB^WOw?FYZD^T_b!_|DAO=L_NLw}J1xz8v2z7~igv^Ywil zc}%ljuBjM1>&Sf*dDO>u76!^4ag)w3%NWUX$5tm7@8Xbq(@XP08HVp8`h7tBfQt7a c5D%{vPM{s+%#RVP^-W#CI*=Xe1z+EP0iNLN)Bpeg diff --git a/selfdrive/orbd/extractor.h b/selfdrive/orbd/extractor.h deleted file mode 100644 index f506cd386..000000000 --- a/selfdrive/orbd/extractor.h +++ /dev/null @@ -1,38 +0,0 @@ -#ifndef EXTRACTOR_H -#define EXTRACTOR_H - -#ifdef __cplusplus -extern "C" { -#endif - -#include - -#define ORBD_KEYPOINTS 3000 -#define ORBD_DESCRIPTOR_LENGTH 32 -#define ORBD_HEIGHT 874 -#define ORBD_WIDTH 1164 -#define ORBD_FOCAL 910 - -// matches OrbFeatures from log.capnp -struct orb_features { - // align this - uint16_t n_corners; - uint16_t xy[ORBD_KEYPOINTS][2]; - uint8_t octave[ORBD_KEYPOINTS]; - uint8_t des[ORBD_KEYPOINTS][ORBD_DESCRIPTOR_LENGTH]; - int16_t matches[ORBD_KEYPOINTS]; -}; - -// forward declare this -struct pyramid; - -// manage the pyramids in extractor.c -void init_gpyrs(); -int extract_and_match_gpyrs(const uint8_t *img, struct orb_features *); -int extract_and_match(const uint8_t *img, struct pyramid *pyrs, struct pyramid *prev_pyrs, struct orb_features *); - -#ifdef __cplusplus -} -#endif - -#endif // EXTRACTOR_H diff --git a/selfdrive/orbd/orbd.cc b/selfdrive/orbd/orbd.cc deleted file mode 100644 index ce0d47aec..000000000 --- a/selfdrive/orbd/orbd.cc +++ /dev/null @@ -1,191 +0,0 @@ -#include -#include -#include -#include -#include -#include -#include - -#include "common/visionipc.h" -#include "common/swaglog.h" - -#include "extractor.h" - -#ifdef DSP -#include "dsp/gen/calculator.h" -#else -#include "turbocv.h" -#endif - -#include -#include -#include "cereal/gen/cpp/log.capnp.h" - -#ifndef PATH_MAX -#include -#endif - -volatile int do_exit = 0; - -static void set_do_exit(int sig) { - do_exit = 1; -} - -int main(int argc, char *argv[]) { - int err; - setpriority(PRIO_PROCESS, 0, -13); - printf("starting orbd\n"); - -#ifdef DSP - uint32_t test_leet = 0; - char my_path[PATH_MAX+1]; - memset(my_path, 0, sizeof(my_path)); - - ssize_t len = readlink("/proc/self/exe", my_path, sizeof(my_path)); - assert(len > 5); - my_path[len-5] = '\0'; - LOGW("running from %s with PATH_MAX %d", my_path, PATH_MAX); - - char adsp_path[PATH_MAX+1]; - snprintf(adsp_path, PATH_MAX, "ADSP_LIBRARY_PATH=%s/dsp/gen", my_path); - assert(putenv(adsp_path) == 0); - - assert(calculator_init(&test_leet) == 0); - assert(test_leet == 0x1337); - LOGW("orbd init complete"); -#else - init_gpyrs(); -#endif - - signal(SIGINT, (sighandler_t) set_do_exit); - signal(SIGTERM, (sighandler_t) set_do_exit); - - void *ctx = zmq_ctx_new(); - - void *orb_features_sock = zmq_socket(ctx, ZMQ_PUB); - assert(orb_features_sock); - zmq_bind(orb_features_sock, "tcp://*:8058"); - - void *orb_features_summary_sock = zmq_socket(ctx, ZMQ_PUB); - assert(orb_features_summary_sock); - zmq_bind(orb_features_summary_sock, "tcp://*:8062"); - - struct orb_features *features = (struct orb_features *)malloc(sizeof(struct orb_features)); - int last_frame_id = 0; - uint64_t frame_count = 0; - - // every other frame - const int RATE = 2; - - VisionStream stream; - while (!do_exit) { - VisionStreamBufs buf_info; - err = visionstream_init(&stream, VISION_STREAM_YUV, true, &buf_info); - if (err) { - printf("visionstream connect fail\n"); - usleep(100000); - continue; - } - uint64_t timestamp_last_eof = 0; - while (!do_exit) { - VIPCBuf *buf; - VIPCBufExtra extra; - buf = visionstream_get(&stream, &extra); - if (buf == NULL) { - printf("visionstream get failed\n"); - break; - } - - // every other frame - frame_count++; - if ((frame_count%RATE) != 0) { - continue; - } - - uint64_t start = nanos_since_boot(); -#ifdef DSP - int ret = calculator_extract_and_match((uint8_t *)buf->addr, ORBD_HEIGHT*ORBD_WIDTH, (uint8_t *)features, sizeof(struct orb_features)); -#else - int ret = extract_and_match_gpyrs((uint8_t *) buf->addr, features); -#endif - uint64_t end = nanos_since_boot(); - LOGD("total(%d): %6.2f ms to get %4d features on %d", ret, (end-start)/1000000.0, features->n_corners, extra.frame_id); - assert(ret == 0); - - if (last_frame_id+RATE != extra.frame_id) { - LOGW("dropped frame!"); - } - - last_frame_id = extra.frame_id; - - if (timestamp_last_eof == 0) { - timestamp_last_eof = extra.timestamp_eof; - continue; - } - - int match_count = 0; - - // *** send OrbFeatures *** - { - // create capnp message - capnp::MallocMessageBuilder msg; - cereal::Event::Builder event = msg.initRoot(); - event.setLogMonoTime(nanos_since_boot()); - - auto orb_features = event.initOrbFeatures(); - - // set timestamps - orb_features.setTimestampEof(extra.timestamp_eof); - orb_features.setTimestampLastEof(timestamp_last_eof); - - // init descriptors for send - kj::ArrayPtr descriptorsPtr = kj::arrayPtr((uint8_t *)features->des, ORBD_DESCRIPTOR_LENGTH * features->n_corners); - orb_features.setDescriptors(descriptorsPtr); - - auto xs = orb_features.initXs(features->n_corners); - auto ys = orb_features.initYs(features->n_corners); - auto octaves = orb_features.initOctaves(features->n_corners); - auto matches = orb_features.initMatches(features->n_corners); - - // copy out normalized keypoints - for (int i = 0; i < features->n_corners; i++) { - xs.set(i, (features->xy[i][0] * 1.0f - ORBD_WIDTH / 2) / ORBD_FOCAL); - ys.set(i, (features->xy[i][1] * 1.0f - ORBD_HEIGHT / 2) / ORBD_FOCAL); - octaves.set(i, features->octave[i]); - matches.set(i, features->matches[i]); - match_count += features->matches[i] != -1; - } - - auto words = capnp::messageToFlatArray(msg); - auto bytes = words.asBytes(); - zmq_send(orb_features_sock, bytes.begin(), bytes.size(), 0); - } - - // *** send OrbFeaturesSummary *** - - { - // create capnp message - capnp::MallocMessageBuilder msg; - cereal::Event::Builder event = msg.initRoot(); - event.setLogMonoTime(nanos_since_boot()); - - auto orb_features_summary = event.initOrbFeaturesSummary(); - - orb_features_summary.setTimestampEof(extra.timestamp_eof); - orb_features_summary.setTimestampLastEof(timestamp_last_eof); - orb_features_summary.setFeatureCount(features->n_corners); - orb_features_summary.setMatchCount(match_count); - orb_features_summary.setComputeNs(end-start); - - auto words = capnp::messageToFlatArray(msg); - auto bytes = words.asBytes(); - zmq_send(orb_features_summary_sock, bytes.begin(), bytes.size(), 0); - } - - timestamp_last_eof = extra.timestamp_eof; - } - } - visionstream_destroy(&stream); - return 0; -} - diff --git a/selfdrive/orbd/orbd_wrapper.sh b/selfdrive/orbd/orbd_wrapper.sh deleted file mode 100755 index 8ec7443a3..000000000 --- a/selfdrive/orbd/orbd_wrapper.sh +++ /dev/null @@ -1,13 +0,0 @@ -#!/bin/sh -finish() { - echo "exiting orbd" - pkill -SIGINT -P $$ -} - -trap finish EXIT - -while true; do - ./orbd & - wait $! -done - diff --git a/selfdrive/sensord/gpsd b/selfdrive/sensord/gpsd index 540f9b161a28a3cfb4d05ff726262ff00015b382..72b5570da3b0bc867e28910b06707fa4fefe4776 100755 GIT binary patch delta 59 zcmca{!2QMn_l6e67N!>F7M2#)7Pc1l7LFFq7OocV7M?AF7M2#)7Pc1l7LFFq7OocV7M?AF7M2#)7Pc1l7LFFq7OocVEj;UPGa9z9zs&>0ygF7M2#)7Pc1l7LFFq7OocVEj;UPGa9t7zs&>0yg= buttons_sorted[0][1]: current_button = buttons_sorted[0][0] buttons_sorted = buttons_sorted[1:] - print "current button changed to", current_button - + print("current button changed to {0}".format(current_button)) + grade = np.interp(plant.current_time(), self.grade_breakpoints, self.grade_values) speed_lead = np.interp(plant.current_time(), self.speed_lead_breakpoints, self.speed_lead_values) @@ -46,11 +46,11 @@ class Maneuver(object): if live100: last_live100 = live100[-1] - d_rel = distance_lead - distance if self.lead_relevancy else 200. - v_rel = speed_lead - speed if self.lead_relevancy else 0. + d_rel = distance_lead - distance if self.lead_relevancy else 200. + v_rel = speed_lead - speed if self.lead_relevancy else 0. if last_live100: - # print last_live100 + # print(last_live100) #develop plots plot.add_data( time=plant.current_time(), @@ -64,8 +64,8 @@ class Maneuver(object): jerk_factor=last_live100.jerkFactor, a_target=last_live100.aTarget, fcw=fcw) - - print "maneuver end" + + print("maneuver end") return (None, plot) diff --git a/selfdrive/test/plant/plant.py b/selfdrive/test/plant/plant.py index 903a7e4f7..4d32b9af2 100755 --- a/selfdrive/test/plant/plant.py +++ b/selfdrive/test/plant/plant.py @@ -208,7 +208,7 @@ class Plant(object): # print at 5hz if (self.rk.frame%(self.rate/5)) == 0: - print "%6.2f m %6.2f m/s %6.2f m/s2 %.2f ang gas: %.2f brake: %.2f steer: %5.2f lead_rel: %6.2f m %6.2f m/s" % (distance, speed, acceleration, self.angle_steer, gas, brake, steer_torque, d_rel, v_rel) + print("%6.2f m %6.2f m/s %6.2f m/s2 %.2f ang gas: %.2f brake: %.2f steer: %5.2f lead_rel: %6.2f m %6.2f m/s" % (distance, speed, acceleration, self.angle_steer, gas, brake, steer_torque, d_rel, v_rel)) # ******** publish the car ******** vls_tuple = namedtuple('vls', [ diff --git a/selfdrive/test/plant/plant_ui.py b/selfdrive/test/plant/plant_ui.py index 650442d75..501263604 100755 --- a/selfdrive/test/plant/plant_ui.py +++ b/selfdrive/test/plant/plant_ui.py @@ -75,7 +75,7 @@ if __name__ == "__main__": car_pts = map(pt_to_car, control_pts) - print car_pts + print(car_pts) car_poly = np.polyfit([x[0] for x in car_pts], [x[1] for x in car_pts], 3) md.model.path.points = np.polyval(car_poly, np.arange(0, 50)).tolist() @@ -90,9 +90,9 @@ if __name__ == "__main__": cary += plant.speed * plant.ts * math.sin(heading) # positive steering angle = steering right - print plant.angle_steer + print(plant.angle_steer) heading += plant.angle_steer * plant.ts - print heading + print(heading) # draw my car display.blit(pygame.transform.rotate(car, 90-math.degrees(heading)), (carx*METER, cary*METER)) diff --git a/selfdrive/test/test_fingerprints.py b/selfdrive/test/test_fingerprints.py index b1f1a97a2..b247b4ca1 100755 --- a/selfdrive/test/test_fingerprints.py +++ b/selfdrive/test/test_fingerprints.py @@ -53,16 +53,16 @@ for idx1, f1 in enumerate(fingerprints_flat): for idx2, f2 in enumerate(fingerprints_flat): if idx1 < idx2 and not check_fingerprint_consistency(f1, f2): valid = False - print "Those two fingerprints are inconsistent", car_names[idx1], car_names[idx2] - print "" - print ', '.join("%d: %d" % v for v in sorted(f1.items())) - print "" - print ', '.join("%d: %d" % v for v in sorted(f2.items())) - print "" + print("Those two fingerprints are inconsistent {0} {1}".format(car_names[idx1], car_names[idx2])) + print("") + print(', '.join("%d: %d" % v for v in sorted(f1.items()))) + print("") + print(', '.join("%d: %d" % v for v in sorted(f2.items()))) + print("") -print "Found ", len(fingerprints_flat), " individual fingerprints" +print("Found {0} individual fingerprints".format(len(fingerprints_flat))) if not valid or len(fingerprints_flat) == 0: - print "TEST FAILED" + print("TEST FAILED") sys.exit(1) else: - print "TEST SUCESSFUL" + print("TEST SUCESSFUL") diff --git a/selfdrive/test/test_openpilot.py b/selfdrive/test/test_openpilot.py index 0a825e3a3..13770f50a 100644 --- a/selfdrive/test/test_openpilot.py +++ b/selfdrive/test/test_openpilot.py @@ -63,25 +63,25 @@ def with_processes(processes): @phone_only @with_processes(['loggerd', 'logmessaged', 'tombstoned', 'proclogd', 'logcatd']) def test_logging(): - print "LOGGING IS SET UP" + print("LOGGING IS SET UP") time.sleep(1.0) @phone_only @with_processes(['visiond']) def test_visiond(): - print "VISIOND IS SET UP" + print("VISIOND IS SET UP") time.sleep(5.0) @phone_only @with_processes(['sensord']) def test_sensord(): - print "SENSORS ARE SET UP" + print("SENSORS ARE SET UP") time.sleep(1.0) @phone_only @with_processes(['ui']) def test_ui(): - print "RUNNING UI" + print("RUNNING UI") time.sleep(1.0) # will have one thing to upload if loggerd ran @@ -89,5 +89,5 @@ def test_ui(): @phone_only @with_processes(['uploader']) def test_uploader(): - print "UPLOADER" + print("UPLOADER") time.sleep(10.0) diff --git a/selfdrive/thermald.py b/selfdrive/thermald.py index fea5a8968..bacabec29 100755 --- a/selfdrive/thermald.py +++ b/selfdrive/thermald.py @@ -14,7 +14,7 @@ from common.numpy_fast import clip from common.filter_simple import FirstOrderFilter ThermalStatus = log.ThermalData.ThermalStatus -CURRENT_TAU = 2. # 2s time constant +CURRENT_TAU = 15. # 15s time constant def read_tz(x): with open("/sys/devices/virtual/thermal/thermal_zone%d/temp" % x) as f: @@ -46,7 +46,7 @@ def setup_eon_fan(): bus.write_byte_data(0x21, 0x02, 0x2) # needed? bus.write_byte_data(0x21, 0x04, 0x4) # manual override source except IOError: - print "LEON detected" + print("LEON detected") #os.system("echo 1 > /sys/devices/soc/6a00000.ssusb/power_supply/usb/usb_otg") LEON = True bus.close() @@ -290,16 +290,16 @@ def thermald_thread(): started_seen and (sec_since_boot() - off_ts) > 60: os.system('LD_LIBRARY_PATH="" svc power shutdown') - charging_disabled = check_car_battery_voltage(should_start, health, charging_disabled) + #charging_disabled = check_car_battery_voltage(should_start, health, charging_disabled) msg.thermal.chargingDisabled = charging_disabled - msg.thermal.chargingError = current_filter.x > 1.0 # if current is > 1A out, then charger might be off + msg.thermal.chargingError = current_filter.x > 0. # if current is positive, then battery is being discharged msg.thermal.started = started_ts is not None msg.thermal.startedTs = int(1e9*(started_ts or 0)) msg.thermal.thermalStatus = thermal_status thermal_sock.send(msg.to_bytes()) - print msg + print(msg) # report to server once per minute if (count%60) == 0: diff --git a/selfdrive/tombstoned.py b/selfdrive/tombstoned.py index c76294e6c..9b90013d1 100644 --- a/selfdrive/tombstoned.py +++ b/selfdrive/tombstoned.py @@ -1,7 +1,6 @@ import os import re import time -import uuid import datetime from raven import Client @@ -38,32 +37,68 @@ def report_tombstone(fn, client): if parsed: parsedict = parsed.groupdict() - message = parsedict.get('thread') or '' - message += parsedict.get('signal') or '' - message += parsedict.get('abort') or '' else: parsedict = {} - message = fn+"\n"+dat[:1024] - client.send( - event_id=uuid.uuid4().hex, - timestamp=datetime.datetime.utcfromtimestamp(mtime), - logger='tombstoned', - platform='other', + thread_line = parsedict.get('thread', '') + thread_parsed = re.match(r'pid: (?P\d+), tid: (?P\d+), name: (?P.*) >>> (?P.*) <<<', thread_line) + if thread_parsed: + thread_parseddict = thread_parsed.groupdict() + else: + thread_parseddict = {} + pid = thread_parseddict.get('pid', '') + tid = thread_parseddict.get('tid', '') + name = thread_parseddict.get('name', 'unknown') + cmd = thread_parseddict.get('cmd', 'unknown') + + signal_line = parsedict.get('signal', '') + signal_parsed = re.match(r'signal (?P.*?), code (?P.*?), fault addr (?P.*)\n', signal_line) + if signal_parsed: + signal_parseddict = signal_parsed.groupdict() + else: + signal_parseddict = {} + signal = signal_parseddict.get('signal', 'unknown') + code = signal_parseddict.get('code', 'unknown') + fault_addr = signal_parseddict.get('fault_addr', '') + + abort_line = parsedict.get('abort', '') + + if parsed: + message = 'Process {} ({}) got signal {} code {}'.format(name, cmd, signal, code) + if abort_line: + message += '\n'+abort_line + else: + message = fn+'\n'+dat[:1024] + + + client.captureMessage( + message=message, + date=datetime.datetime.utcfromtimestamp(mtime), + data={ + 'logger':'tombstoned', + 'platform':'other', + }, sdk={'name': 'tombstoned', 'version': '0'}, extra={ + 'fault_addr': fault_addr, + 'abort_msg': abort_line, + 'pid': pid, + 'tid': tid, + 'name':'{} ({})'.format(name, cmd), 'tombstone_fn': fn, 'header': parsedict.get('header'), 'registers': parsedict.get('registers'), 'backtrace': parsedict.get('backtrace'), 'logtail': logtail, - 'version': version, - 'dirty': not bool(os.environ.get('CLEAN')), }, - user={'id': os.environ.get('DONGLE_ID')}, - message=message, + tags={ + 'name':'{} ({})'.format(name, cmd), + 'signal':signal, + 'code':code, + 'fault_addr':fault_addr, + }, ) - cloudlog.error({"tombstone": message}) + cloudlog.error({'tombstone': message}) def main(gctx): @@ -72,6 +107,7 @@ def main(gctx): client = Client('https://d3b175702f62402c91ade04d1c547e68:b20d68c813c74f63a7cdf9c4039d8f56@sentry.io/157615', install_sys_hook=False, transport=HTTPTransport, release=version, tags={'dirty': dirty}) + client.user_context({'id': os.environ.get('DONGLE_ID')}) while True: now_tombstones = set(get_tombstones()) diff --git a/selfdrive/ui/Makefile b/selfdrive/ui/Makefile index a78a48cf2..a2d857a28 100644 --- a/selfdrive/ui/Makefile +++ b/selfdrive/ui/Makefile @@ -10,8 +10,8 @@ WARN_FLAGS = -Werror=implicit-function-declaration \ -Werror=return-type \ -Werror=format-extra-args -CFLAGS = -std=gnu11 -g -fPIC -O2 $(WARN_FLAGS) -CXXFLAGS = -std=c++11 -g -fPIC -O2 $(WARN_FLAGS) +CFLAGS = -std=gnu11 -fPIC -O2 $(WARN_FLAGS) +CXXFLAGS = -std=c++11 -fPIC -O2 $(WARN_FLAGS) ZMQ_FLAGS = -I$(PHONELIBS)/zmq/aarch64/include ZMQ_LIBS = -L$(PHONELIBS)/zmq/aarch64/lib \ diff --git a/selfdrive/ui/ui.c b/selfdrive/ui/ui.c index 33e35d381..dea27ab18 100644 --- a/selfdrive/ui/ui.c +++ b/selfdrive/ui/ui.c @@ -50,6 +50,8 @@ #define UI_BUF_COUNT 4 //#define DEBUG_TURN +//#define DEBUG_FPS + const int vwp_w = 1920; const int vwp_h = 1080; const int nav_w = 640; @@ -65,7 +67,11 @@ const int header_h = 420; const int footer_h = 280; const int footer_y = vwp_h-bdr_s-footer_h; -const int UI_FREQ = 60; // Hz +const int UI_FREQ = 30; // Hz + +const int MODEL_PATH_MAX_VERTICES_CNT = 98; +const int MODEL_LANE_PATH_CNT = 3; +const int TRACK_POINTS_MAX_CNT = 50 * 2; const uint8_t bg_colors[][4] = { [STATUS_STOPPED] = {0x07, 0x23, 0x39, 0xff}, @@ -158,6 +164,21 @@ typedef struct UIScene { bool is_playing_alert; } UIScene; +typedef struct { + float x, y; +}vertex_data; + +typedef struct { + vertex_data v[MODEL_PATH_MAX_VERTICES_CNT]; + int cnt; +} model_path_vertices_data; + +typedef struct { + vertex_data v[TRACK_POINTS_MAX_CNT]; + int cnt; +} track_vertices_data; + + typedef struct UIState { pthread_mutex_t lock; pthread_cond_t bg_cond; @@ -212,7 +233,11 @@ typedef struct UIState { GLuint frame_program; GLuint frame_texs[UI_BUF_COUNT]; + EGLImageKHR khr[UI_BUF_COUNT]; + void *priv_hnds[UI_BUF_COUNT]; GLuint frame_front_texs[UI_BUF_COUNT]; + EGLImageKHR khr_front[UI_BUF_COUNT]; + void *priv_hnds_front[UI_BUF_COUNT]; GLint frame_pos_loc, frame_texcoord_loc; GLint frame_texture_loc, frame_transform_loc; @@ -251,6 +276,20 @@ typedef struct UIState { bool alert_blinked; float light_sensor; + + int touch_fd; + + // Hints for re-calculations and redrawing + bool model_changed; + bool livempc_or_live20_changed; + + GLuint frame_vao[2], frame_vbo[2], frame_ibo[2]; + mat4 rear_frame_mat, front_frame_mat; + + model_path_vertices_data model_path_vertices[MODEL_LANE_PATH_CNT * 2]; + + track_vertices_data track_vertices[2]; + } UIState; static int last_brightness = -1; @@ -534,6 +573,58 @@ static void ui_init(UIState *s) { free(value); } } + for(int i = 0; i < 2; i++) { + float x1, x2, y1, y2; + if (i == 1) { + // flip horizontally so it looks like a mirror + x1 = 0.0; + x2 = 1.0; + y1 = 1.0; + y2 = 0.0; + } else { + x1 = 1.0; + x2 = 0.0; + y1 = 1.0; + y2 = 0.0; + } + const uint8_t frame_indicies[] = {0, 1, 2, 0, 2, 3}; + const float frame_coords[4][4] = { + {-1.0, -1.0, x2, y1}, //bl + {-1.0, 1.0, x2, y2}, //tl + { 1.0, 1.0, x1, y2}, //tr + { 1.0, -1.0, x1, y1}, //br + }; + + glGenVertexArrays(1,&s->frame_vao[i]); + glBindVertexArray(s->frame_vao[i]); + glGenBuffers(1, &s->frame_vbo[i]); + glBindBuffer(GL_ARRAY_BUFFER, s->frame_vbo[i]); + glBufferData(GL_ARRAY_BUFFER, sizeof(frame_coords), frame_coords, GL_STATIC_DRAW); + glEnableVertexAttribArray(s->frame_pos_loc); + glVertexAttribPointer(s->frame_pos_loc, 2, GL_FLOAT, GL_FALSE, + sizeof(frame_coords[0]), (const void *)0); + glEnableVertexAttribArray(s->frame_texcoord_loc); + glVertexAttribPointer(s->frame_texcoord_loc, 2, GL_FLOAT, GL_FALSE, + sizeof(frame_coords[0]), (const void *)(sizeof(float) * 2)); + glGenBuffers(1, &s->frame_ibo[i]); + glBindBuffer(GL_ELEMENT_ARRAY_BUFFER, s->frame_ibo[i]); + glBufferData(GL_ELEMENT_ARRAY_BUFFER, sizeof(frame_indicies), frame_indicies, GL_STATIC_DRAW); + glBindBuffer(GL_ARRAY_BUFFER,0); + glBindVertexArray(0); + } + + s->model_changed = false; + s->livempc_or_live20_changed = false; + + s->front_frame_mat = matmul(device_transform, full_to_wide_frame_transform); + s->rear_frame_mat = matmul(device_transform, frame_transform); + + for(int i = 0;i < UI_BUF_COUNT; i++) { + s->khr[i] = NULL; + s->priv_hnds[i] = NULL; + s->khr_front[i] = NULL; + s->priv_hnds_front[i] = NULL; + } } static void ui_init_vision(UIState *s, const VisionStreamBufs back_bufs, @@ -699,8 +790,7 @@ static void draw_chevron(UIState *s, float x_in, float y_in, float sz, nvgRestore(s->vg); } -static void ui_draw_lane_line(UIState *s, const float *points, float off, - NVGcolor color, bool is_ghost) { +static void ui_draw_lane_line(UIState *s, const model_path_vertices_data *pvd, NVGcolor color) { const UIScene *scene = &s->scene; nvgSave(s->vg); @@ -711,70 +801,36 @@ static void ui_draw_lane_line(UIState *s, const float *points, float off, nvgBeginPath(s->vg); bool started = false; - for (int i=0; i<49; i++) { - float px = (float)i; - float py = points[i] - off; - vec4 p_car_space = (vec4){{px, py, 0., 1.}}; - vec3 p_full_frame = car_space_to_full_frame(s, p_car_space); - float x = p_full_frame.v[0]; - float y = p_full_frame.v[1]; - if (x < 0 || y < 0.) { + for (int i=0; icnt; i++) { + if (pvd->v[i].x < 0 || pvd->v[i].y < 0.) { continue; } if (!started) { - nvgMoveTo(s->vg, x, y); + nvgMoveTo(s->vg, pvd->v[i].x, pvd->v[i].y); started = true; } else { - nvgLineTo(s->vg, x, y); + nvgLineTo(s->vg, pvd->v[i].x, pvd->v[i].y); } } - for (int i=49; i>0; i--) { - float px = (float)i; - float py = is_ghost?(points[i]-off):(points[i]+off); - vec4 p_car_space = (vec4){{px, py, 0., 1.}}; - vec3 p_full_frame = car_space_to_full_frame(s, p_car_space); - float x = p_full_frame.v[0]; - float y = p_full_frame.v[1]; - if (x < 0 || y < 0.) { - continue; - } - nvgLineTo(s->vg, x, y); - } - nvgClosePath(s->vg); nvgFillColor(s->vg, color); nvgFill(s->vg); nvgRestore(s->vg); } -static void ui_draw_lane(UIState *s, const PathData path, NVGcolor color) { - ui_draw_lane_line(s, path.points, 0.025*path.prob, color, false); - float var = min(path.std, 0.7); - color.a /= 4; - ui_draw_lane_line(s, path.points, -var, color, true); - ui_draw_lane_line(s, path.points, var, color, true); -} - -static void ui_draw_track(UIState *s, bool is_mpc) { +static void update_track_data(UIState *s, bool is_mpc, track_vertices_data *pvd) { const UIScene *scene = &s->scene; const PathData path = scene->model.path; const float *mpc_x_coords = &scene->mpc_x[0]; const float *mpc_y_coords = &scene->mpc_y[0]; - nvgSave(s->vg); - nvgTranslate(s->vg, 240.0f, 0.0); // rgb-box space - nvgTranslate(s->vg, -1440.0f / 2, -1080.0f / 2); // zoom 2x - nvgScale(s->vg, 2.0, 2.0); - nvgScale(s->vg, 1440.0f / s->rgb_width, 1080.0f / s->rgb_height); - nvgBeginPath(s->vg); - bool started = false; float off = is_mpc?0.3:0.5; float lead_d = scene->lead_d_rel*2.; float path_height = is_mpc?(lead_d>5.)?min(lead_d, 25.)-min(lead_d*0.35, 10.):20. :(lead_d>0.)?min(lead_d, 50.)-min(lead_d*0.35, 10.):49.; - + pvd->cnt = 0; // left side up for (int i=0; i<=path_height; i++) { float px, py, mpx; @@ -789,18 +845,12 @@ static void ui_draw_track(UIState *s, bool is_mpc) { vec4 p_car_space = (vec4){{px, py, 0., 1.}}; vec3 p_full_frame = car_space_to_full_frame(s, p_car_space); - float x = p_full_frame.v[0]; - float y = p_full_frame.v[1]; - if (x < 0 || y < 0) { + if (p_full_frame.v[0] < 0. || p_full_frame.v[1] < 0.) { continue; } - - if (!started) { - nvgMoveTo(s->vg, x, y); - started = true; - } else { - nvgLineTo(s->vg, x, y); - } + pvd->v[pvd->cnt].x = p_full_frame.v[0]; + pvd->v[pvd->cnt].y = p_full_frame.v[1]; + pvd->cnt += 1; } // right side down @@ -817,13 +867,54 @@ static void ui_draw_track(UIState *s, bool is_mpc) { vec4 p_car_space = (vec4){{px, py, 0., 1.}}; vec3 p_full_frame = car_space_to_full_frame(s, p_car_space); - float x = p_full_frame.v[0]; - float y = p_full_frame.v[1]; - if (x < 0 || y < 0.) { + pvd->v[pvd->cnt].x = p_full_frame.v[0]; + pvd->v[pvd->cnt].y = p_full_frame.v[1]; + pvd->cnt += 1; + } +} + +static void update_all_track_data(UIState *s) { + const UIScene *scene = &s->scene; + // Draw vision path + update_track_data(s, false, &s->track_vertices[0]); + + if (scene->engaged) { + // Draw MPC path when engaged + update_track_data(s, true, &s->track_vertices[1]); + } +} + + +static void ui_draw_track(UIState *s, bool is_mpc, track_vertices_data *pvd) { +const UIScene *scene = &s->scene; + const PathData path = scene->model.path; + const float *mpc_x_coords = &scene->mpc_x[0]; + const float *mpc_y_coords = &scene->mpc_y[0]; + + nvgSave(s->vg); + nvgTranslate(s->vg, 240.0f, 0.0); // rgb-box space + nvgTranslate(s->vg, -1440.0f / 2, -1080.0f / 2); // zoom 2x + nvgScale(s->vg, 2.0, 2.0); + nvgScale(s->vg, 1440.0f / s->rgb_width, 1080.0f / s->rgb_height); + nvgBeginPath(s->vg); + + bool started = false; + float off = is_mpc?0.3:0.5; + float lead_d = scene->lead_d_rel*2.; + float path_height = is_mpc?(lead_d>5.)?min(lead_d, 25.)-min(lead_d*0.35, 10.):20. + :(lead_d>0.)?min(lead_d, 50.)-min(lead_d*0.35, 10.):49.; + int vi = 0; + for(int i = 0;i < pvd->cnt;i++) { + if (pvd->v[i].x < 0 || pvd->v[i].y < 0) { continue; } - nvgLineTo(s->vg, x, y); + if (!started) { + nvgMoveTo(s->vg, pvd->v[i].x, pvd->v[i].y); + started = true; + } else { + nvgLineTo(s->vg, pvd->v[i].x, pvd->v[i].y); + } } nvgClosePath(s->vg); @@ -860,33 +951,17 @@ static void draw_frame(UIState *s) { float x1, x2, y1, y2; if (s->scene.frontview) { - // flip horizontally so it looks like a mirror - x1 = 0.0; - x2 = 1.0; - y1 = 1.0; - y2 = 0.0; + glBindVertexArray(s->frame_vao[1]); } else { - x1 = 1.0; - x2 = 0.0; - y1 = 1.0; - y2 = 0.0; + glBindVertexArray(s->frame_vao[0]); } - mat4 out_mat; + mat4 *out_mat; if (s->scene.frontview || s->scene.fullview) { - out_mat = matmul(device_transform, full_to_wide_frame_transform); + out_mat = &s->front_frame_mat; } else { - out_mat = matmul(device_transform, frame_transform); + out_mat = &s->rear_frame_mat; } - - const uint8_t frame_indicies[] = {0, 1, 2, 0, 2, 3}; - const float frame_coords[4][4] = { - {-1.0, -1.0, x2, y1}, //bl - {-1.0, 1.0, x2, y2}, //tl - { 1.0, 1.0, x1, y2}, //tr - { 1.0, -1.0, x1, y1}, //br - }; - glActiveTexture(GL_TEXTURE0); if (s->scene.frontview && s->cur_vision_front_idx >= 0) { glBindTexture(GL_TEXTURE_2D, s->frame_front_texs[s->cur_vision_front_idx]); @@ -895,40 +970,90 @@ static void draw_frame(UIState *s) { } glUseProgram(s->frame_program); - glUniform1i(s->frame_texture_loc, 0); - glUniformMatrix4fv(s->frame_transform_loc, 1, GL_TRUE, out_mat.v); - - glEnableVertexAttribArray(s->frame_pos_loc); - glVertexAttribPointer(s->frame_pos_loc, 2, GL_FLOAT, GL_FALSE, - sizeof(frame_coords[0]), frame_coords); - - glEnableVertexAttribArray(s->frame_texcoord_loc); - glVertexAttribPointer(s->frame_texcoord_loc, 2, GL_FLOAT, GL_FALSE, - sizeof(frame_coords[0]), &frame_coords[0][2]); + glUniformMatrix4fv(s->frame_transform_loc, 1, GL_TRUE, out_mat->v); assert(glGetError() == GL_NO_ERROR); - glDrawElements(GL_TRIANGLES, 6, GL_UNSIGNED_BYTE, &frame_indicies[0]); + glEnableVertexAttribArray(0); + glDrawElements(GL_TRIANGLES, 6, GL_UNSIGNED_BYTE, (const void*)0); + glDisableVertexAttribArray(0); + glBindVertexArray(0); +} + +static inline bool valid_frame_pt(UIState *s, float x, float y) { + return x >= 0 && x <= s->rgb_width && y >= 0 && y <= s->rgb_height; + +} +static void update_lane_line_data(UIState *s, const float *points, float off, bool is_ghost, model_path_vertices_data *pvd) { + pvd->cnt = 0; + for (int i = 0; i < MODEL_PATH_MAX_VERTICES_CNT / 2; i++) { + float px = (float)i; + float py = points[i] - off; + const vec4 p_car_space = (vec4){{px, py, 0., 1.}}; + const vec3 p_full_frame = car_space_to_full_frame(s, p_car_space); + if(!valid_frame_pt(s, p_full_frame.v[0], p_full_frame.v[1])) + continue; + pvd->v[pvd->cnt].x = p_full_frame.v[0]; + pvd->v[pvd->cnt].y = p_full_frame.v[1]; + pvd->cnt += 1; + } + for (int i = MODEL_PATH_MAX_VERTICES_CNT / 2; i > 0; i--) { + float px = (float)i; + float py = is_ghost?(points[i]-off):(points[i]+off); + const vec4 p_car_space = (vec4){{px, py, 0., 1.}}; + const vec3 p_full_frame = car_space_to_full_frame(s, p_car_space); + if(!valid_frame_pt(s, p_full_frame.v[0], p_full_frame.v[1])) + continue; + pvd->v[pvd->cnt].x = p_full_frame.v[0]; + pvd->v[pvd->cnt].y = p_full_frame.v[1]; + pvd->cnt += 1; + } +} + +static void update_all_lane_lines_data(UIState *s, const PathData path, model_path_vertices_data *pstart) { + update_lane_line_data(s, path.points, 0.025*path.prob, false, pstart); + float var = min(path.std, 0.7); + update_lane_line_data(s, path.points, -var, true, pstart + 1); + update_lane_line_data(s, path.points, var, true, pstart + 2); +} + +static void ui_draw_lane(UIState *s, const PathData *path, model_path_vertices_data *pstart, NVGcolor color) { + ui_draw_lane_line(s, pstart, color); + float var = min(path->std, 0.7); + color.a /= 4; + ui_draw_lane_line(s, pstart + 1, color); + ui_draw_lane_line(s, pstart + 2, color); } static void ui_draw_vision_lanes(UIState *s) { const UIScene *scene = &s->scene; + model_path_vertices_data *pvd = &s->model_path_vertices[0]; + if(s->model_changed) { + update_all_lane_lines_data(s, scene->model.left_lane, pvd); + update_all_lane_lines_data(s, scene->model.right_lane, pvd + MODEL_LANE_PATH_CNT); + s->model_changed = false; + } // Draw left lane edge ui_draw_lane( - s, scene->model.left_lane, + s, &scene->model.left_lane, + pvd, nvgRGBAf(1.0, 1.0, 1.0, scene->model.left_lane.prob)); // Draw right lane edge ui_draw_lane( - s, scene->model.right_lane, + s, &scene->model.right_lane, + pvd + MODEL_LANE_PATH_CNT, nvgRGBAf(1.0, 1.0, 1.0, scene->model.right_lane.prob)); + if(s->livempc_or_live20_changed) { + update_all_track_data(s); + s->livempc_or_live20_changed = false; + } // Draw vision path - ui_draw_track(s, false); - + ui_draw_track(s, false, &s->track_vertices[0]); if (scene->engaged) { // Draw MPC path when engaged - ui_draw_track(s, true); + ui_draw_track(s, true, &s->track_vertices[1]); } } @@ -1379,14 +1504,14 @@ static void ui_draw_vision(UIState *s) { glEnable(GL_SCISSOR_TEST); glViewport(ui_viz_rx+ui_viz_ro, s->fb_h-(box_y+box_h), viz_w, box_h); glScissor(ui_viz_rx, s->fb_h-(box_y+box_h), ui_viz_rw, box_h); + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); draw_frame(s); glViewport(0, 0, s->fb_w, s->fb_h); glDisable(GL_SCISSOR_TEST); - glEnable(GL_BLEND); - glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); glClear(GL_STENCIL_BUFFER_BIT); - + nvgBeginFrame(s->vg, s->fb_w, s->fb_h, 1.0f); nvgSave(s->vg); @@ -1439,8 +1564,6 @@ static void ui_draw(UIState *s) { nvgEndFrame(s->vg); glDisable(GL_BLEND); } - - assert(glGetError() == GL_NO_ERROR); } static PathData read_path(cereal_ModelData_PathData_ptr pathp) { @@ -1496,7 +1619,10 @@ static void ui_update(UIState *s) { // do this here for now in lieu of a run_on_main_thread event for (int i=0; iframe_texs[i]); + if(s->khr[i] != NULL) { + visionimg_destroy_gl(s->khr[i], s->priv_hnds[i]); + glDeleteTextures(1, &s->frame_texs[i]); + } VisionImg img = { .fd = s->bufs[i].fd, @@ -1507,7 +1633,7 @@ static void ui_update(UIState *s) { .bpp = 3, .size = s->rgb_buf_len, }; - s->frame_texs[i] = visionimg_to_gl(&img); + s->frame_texs[i] = visionimg_to_gl(&img, &s->khr[i], &s->priv_hnds[i]); glBindTexture(GL_TEXTURE_2D, s->frame_texs[i]); glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST); @@ -1520,7 +1646,10 @@ static void ui_update(UIState *s) { } for (int i=0; iframe_front_texs[i]); + if(s->khr_front[i] != NULL) { + visionimg_destroy_gl(s->khr_front[i], s->priv_hnds_front[i]); + glDeleteTextures(1, &s->frame_front_texs[i]); + } VisionImg img = { .fd = s->front_bufs[i].fd, @@ -1531,7 +1660,7 @@ static void ui_update(UIState *s) { .bpp = 3, .size = s->rgb_front_buf_len, }; - s->frame_front_texs[i] = visionimg_to_gl(&img); + s->frame_front_texs[i] = visionimg_to_gl(&img, &s->khr_front[i], &s->priv_hnds_front[i]); glBindTexture(GL_TEXTURE_2D, s->frame_front_texs[i]); glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST); @@ -1556,9 +1685,67 @@ static void ui_update(UIState *s) { s->alert_blinked = false; } - // poll for events - while (true) { - zmq_pollitem_t polls[10] = {{0}}; + zmq_pollitem_t polls[9] = {{0}}; + // Wait for next rgb image from visiond + while(true) { + assert(s->ipc_fd >= 0); + polls[0].fd = s->ipc_fd; + polls[0].events = ZMQ_POLLIN; + int ret = zmq_poll(polls, 1, 1000); + if (ret < 0) { + LOGW("poll failed (%d)", ret); + close(s->ipc_fd); + s->ipc_fd = -1; + s->vision_connected = false; + return; + } else if (ret == 0) + continue; + // vision ipc event + VisionPacket rp; + err = vipc_recv(s->ipc_fd, &rp); + if (err <= 0) { + LOGW("vision disconnected"); + close(s->ipc_fd); + s->ipc_fd = -1; + s->vision_connected = false; + return; + } + if (rp.type == VIPC_STREAM_ACQUIRE) { + bool front = rp.d.stream_acq.type == VISION_STREAM_RGB_FRONT; + int idx = rp.d.stream_acq.idx; + + int release_idx; + if (front) { + release_idx = s->cur_vision_front_idx; + } else { + release_idx = s->cur_vision_idx; + } + if (release_idx >= 0) { + VisionPacket rep = { + .type = VIPC_STREAM_RELEASE, + .d = { .stream_rel = { + .type = rp.d.stream_acq.type, + .idx = release_idx, + }}, + }; + vipc_send(s->ipc_fd, &rep); + } + + if (front) { + assert(idx < UI_BUF_COUNT); + s->cur_vision_front_idx = idx; + } else { + assert(idx < UI_BUF_COUNT); + s->cur_vision_idx = idx; + // printf("v %d\n", ((uint8_t*)s->bufs[idx].addr)[0]); + } + } else { + assert(false); + } + break; + } + // peek and consume all events in the zmq queue, then return. + while(true) { polls[0].socket = s->live100_sock_raw; polls[0].events = ZMQ_POLLIN; polls[1].socket = s->livecalibration_sock_raw; @@ -1577,22 +1764,14 @@ static void ui_update(UIState *s) { polls[7].events = ZMQ_POLLIN; polls[8].socket = s->plus_sock_raw; // plus_sock should be last polls[8].events = ZMQ_POLLIN; - int num_polls = 9; - if (s->vision_connected) { - assert(s->ipc_fd >= 0); - polls[9].fd = s->ipc_fd; - polls[9].events = ZMQ_POLLIN; - num_polls++; - } - int ret = zmq_poll(polls, num_polls, 0); if (ret < 0) { LOGW("poll failed (%d)", ret); - break; + return; } if (ret == 0) { - break; + return; } if (polls[0].revents || polls[1].revents || polls[2].revents || @@ -1602,52 +1781,8 @@ static void ui_update(UIState *s) { set_awake(s, true); } - if (s->vision_connected && polls[9].revents) { - // vision ipc event - VisionPacket rp; - err = vipc_recv(s->ipc_fd, &rp); - if (err <= 0) { - LOGW("vision disconnected"); - close(s->ipc_fd); - s->ipc_fd = -1; - s->vision_connected = false; - continue; - } - if (rp.type == VIPC_STREAM_ACQUIRE) { - bool front = rp.d.stream_acq.type == VISION_STREAM_RGB_FRONT; - int idx = rp.d.stream_acq.idx; - - int release_idx; - if (front) { - release_idx = s->cur_vision_front_idx; - } else { - release_idx = s->cur_vision_idx; - } - if (release_idx >= 0) { - VisionPacket rep = { - .type = VIPC_STREAM_RELEASE, - .d = { .stream_rel = { - .type = rp.d.stream_acq.type, - .idx = release_idx, - }}, - }; - vipc_send(s->ipc_fd, &rep); - } - - if (front) { - assert(idx < UI_BUF_COUNT); - s->cur_vision_front_idx = idx; - } else { - assert(idx < UI_BUF_COUNT); - s->cur_vision_idx = idx; - // printf("v %d\n", ((uint8_t*)s->bufs[idx].addr)[0]); - } - } else { - assert(false); - } - } else if (polls[8].revents) { + if (polls[8].revents) { // plus socket - zmq_msg_t msg; err = zmq_msg_init(&msg); assert(err == 0); @@ -1670,7 +1805,7 @@ static void ui_update(UIState *s) { } } if (which == NULL) { - continue; + return; } zmq_msg_t msg; @@ -1686,7 +1821,7 @@ static void ui_update(UIState *s) { eventp.p = capn_getp(capn_root(&ctx), 0, 1); struct cereal_Event eventd; cereal_read_Event(&eventd, eventp); - + double t = millis_since_boot(); if (eventd.which == cereal_Event_live100) { struct cereal_Live100Data datad; cereal_read_Live100Data(&datad, eventd.live100); @@ -1799,6 +1934,7 @@ static void ui_update(UIState *s) { s->scene.lead_d_rel = leaddatad.dRel; s->scene.lead_y_rel = leaddatad.yRel; s->scene.lead_v_rel = leaddatad.vRel; + s->livempc_or_live20_changed = true; } else if (eventd.which == cereal_Event_liveCalibration) { s->scene.world_objects_visible = true; struct cereal_LiveCalibrationData datad; @@ -1820,6 +1956,7 @@ static void ui_update(UIState *s) { } else if (eventd.which == cereal_Event_model) { s->scene.model_ts = eventd.logMonoTime; s->scene.model = read_model(eventd.model); + s->model_changed = true; } else if (eventd.which == cereal_Event_liveMpc) { struct cereal_LiveMpcData datad; cereal_read_LiveMpcData(&datad, eventd.liveMpc); @@ -1837,6 +1974,7 @@ static void ui_update(UIState *s) { for (int i = 0; i < 50; i++){ s->scene.mpc_y[i] = capn_to_f32(capn_get32(y_list, i)); } + s->livempc_or_live20_changed = true; } else if (eventd.which == cereal_Event_thermal) { struct cereal_ThermalData datad; cereal_read_ThermalData(&datad, eventd.thermal); @@ -1877,7 +2015,6 @@ static void ui_update(UIState *s) { zmq_msg_close(&msg); } } - } static int vision_subscribe(int fd, VisionPacket *rp, int type) { @@ -2070,6 +2207,7 @@ int main() { TouchState touch = {0}; touch_init(&touch); + s->touch_fd = touch.fd; char* error = NULL; ui_sound_init(&error); @@ -2089,9 +2227,18 @@ int main() { float smooth_brightness = BRIGHTNESS_B; set_volume(s, 0); - +#ifdef DEBUG_FPS + vipc_t1 = millis_since_boot(); + double t1 = millis_since_boot(); + int draws = 0, old_draws = 0; +#endif //DEBUG_FPS while (!do_exit) { bool should_swap = false; + if (!s->vision_connected) { + // Delay a while to avoid 9% cpu usage while car is not started and user is keeping touching on the screen. + // Don't hold the lock while sleeping, so that vision_connect_thread have chances to get the lock. + usleep(30 * 1000); + } pthread_mutex_lock(&s->lock); if (EON) { @@ -2106,27 +2253,53 @@ int main() { set_brightness(s, NEO_BRIGHTNESS); } - ui_update(s); - - // awake on any touch - int touch_x = -1, touch_y = -1; - int touched = touch_poll(&touch, &touch_x, &touch_y, s->awake ? 0 : 100); - if (touched == 1) { - // touch event will still happen :( - set_awake(s, true); + if (!s->vision_connected) { + // Car is not started, keep in idle state and awake on touch events + zmq_pollitem_t polls[1] = {{0}}; + polls[0].fd = s->touch_fd; + polls[0].events = ZMQ_POLLIN; + int ret = zmq_poll(polls, 1, 0); + if (ret < 0) + LOGW("poll failed (%d)", ret); + else if (ret > 0) { + // awake on any touch + int touch_x = -1, touch_y = -1; + int touched = touch_read(&touch, &touch_x, &touch_y); + if (touched == 1) { + set_awake(s, true); + } + } + } else { + // Car started, fetch a new rgb image from ipc and peek for zmq events. + ui_update(s); + if(!s->vision_connected) { + // Visiond process is just stopped, force a redraw to make screen blank again. + ui_draw(s); + glFinish(); + should_swap = true; + } } - // manage wakefulness if (s->awake_timeout > 0) { s->awake_timeout--; } else { set_awake(s, false); } - - if (s->awake) { + // Don't waste resources on drawing in case screen is off or car is not started. + if (s->awake && s->vision_connected) { ui_draw(s); glFinish(); should_swap = true; +#ifdef DEBUG_FPS + draws++; + double t2 = millis_since_boot(); + const double interval = 30.; + if(t2 - t1 >= interval * 1000.) { + printf("ui draw fps: %.2f\n",((double)(draws - old_draws)) / interval) ; + t1 = t2; + old_draws = draws; + } +#endif } if (s->volume_timeout > 0) { diff --git a/selfdrive/visiond/build_from_src.mk b/selfdrive/visiond/build_from_src.mk index e23887f27..c9394f34a 100644 --- a/selfdrive/visiond/build_from_src.mk +++ b/selfdrive/visiond/build_from_src.mk @@ -58,7 +58,8 @@ endif OPENCV_FLAGS = OPENCV_LIBS = -lopencv_video \ -lopencv_imgproc \ - -lopencv_core + -lopencv_core \ + -lopencv_highgui OTHER_LIBS = -lz -lm -lpthread PLATFORM_OBJS = camera_fake.o \ @@ -127,6 +128,7 @@ OBJS += $(PLATFORM_OBJS) \ ../common/buffering.o \ transform.o \ loadyuv.o \ + rgb_to_yuv.o \ commonmodel.o \ snpemodel.o \ monitoring.o \ @@ -170,6 +172,16 @@ endif DEPS := $(OBJS:.o=.d) +rgb_to_yuv_test: rgb_to_yuv_test.o clutil.o rgb_to_yuv.o ../common/util.o + @echo "[ LINK ] $@" + $(CXX) -fPIC -o '$@' $^ \ + $(LIBYUV_LIBS) \ + $(LDFLAGS) \ + -L/usr/lib \ + -L/system/vendor/lib64 \ + $(OPENCL_LIBS) \ + + $(OUTPUT): $(OBJS) @echo "[ LINK ] $@" $(CXX) -fPIC -o '$@' $^ \ @@ -222,6 +234,6 @@ $(MODEL_OBJS): %.o: %.dlc .PHONY: clean clean: - rm -f visiond $(OBJS) $(DEPS) + rm -f visiond rgb_to_yuv_test rgb_to_yuv_test.o $(OBJS) $(DEPS) -include $(DEPS) diff --git a/selfdrive/visiond/monitoring.cc b/selfdrive/visiond/monitoring.cc index 84ed9e8c5..921473108 100644 --- a/selfdrive/visiond/monitoring.cc +++ b/selfdrive/visiond/monitoring.cc @@ -41,7 +41,7 @@ MonitoringResult monitoring_eval_frame(MonitoringState* s, cl_command_queue q, MonitoringResult ret = {0}; memcpy(ret.vs, s->output, sizeof(ret.vs)); - ret.std = sqrtf(2.f) / s->output[6]; + ret.std = sqrtf(2.f) / s->output[OUTPUT_SIZE - 1]; return ret; } diff --git a/selfdrive/visiond/monitoring.h b/selfdrive/visiond/monitoring.h index 5689e7941..1e9e25018 100644 --- a/selfdrive/visiond/monitoring.h +++ b/selfdrive/visiond/monitoring.h @@ -8,10 +8,10 @@ extern "C" { #endif -#define OUTPUT_SIZE 7 +#define OUTPUT_SIZE 8 typedef struct MonitoringResult { - float vs[6]; + float vs[OUTPUT_SIZE - 1]; float std; } MonitoringResult; diff --git a/selfdrive/visiond/rgb_to_yuv.c b/selfdrive/visiond/rgb_to_yuv.c new file mode 100644 index 000000000..0ce3d5a02 --- /dev/null +++ b/selfdrive/visiond/rgb_to_yuv.c @@ -0,0 +1,53 @@ +#include +#include + +#include "clutil.h" + +#include "rgb_to_yuv.h" + +void rgb_to_yuv_init(RGBToYUVState* s, cl_context ctx, cl_device_id device_id, int width, int height, int rgb_stride) { + int err = 0; + memset(s, 0, sizeof(*s)); + assert(width % 2 == 0); + assert(height % 2 == 0); + s->width = width; + s->height = height; + char args[1024]; + snprintf(args, sizeof(args), + "-cl-fast-relaxed-math -cl-denorms-are-zero " +#ifdef CL_DEBUG + "-DCL_DEBUG " +#endif + "-DWIDTH=%d -DHEIGHT=%d -DUV_WIDTH=%d -DUV_HEIGHT=%d -DRGB_STRIDE=%d -DRGB_SIZE=%d", + width, height, width/ 2, height / 2, rgb_stride, width * height); + cl_program prg = CLU_LOAD_FROM_FILE(ctx, device_id, "rgb_to_yuv.cl", args); + + s->rgb_to_yuv_krnl = clCreateKernel(prg, "rgb_to_yuv", &err); + assert(err == 0); + // done with this + err = clReleaseProgram(prg); + assert(err == 0); +} + +void rgb_to_yuv_destroy(RGBToYUVState* s) { + int err = 0; + err = clReleaseKernel(s->rgb_to_yuv_krnl); + assert(err == 0); +} + +void rgb_to_yuv_queue(RGBToYUVState* s, cl_command_queue q, cl_mem rgb_cl, cl_mem yuv_cl) { + int err = 0; + err = clSetKernelArg(s->rgb_to_yuv_krnl, 0, sizeof(cl_mem), &rgb_cl); + assert(err == 0); + err = clSetKernelArg(s->rgb_to_yuv_krnl, 1, sizeof(cl_mem), &yuv_cl); + assert(err == 0); + const size_t work_size[2] = { + (size_t)(s->width + (s->width % 4 == 0 ? 0 : (4 - s->width % 4))) / 4, + (size_t)(s->height + (s->height % 4 == 0 ? 0 : (4 - s->height % 4))) / 4 + }; + cl_event event; + err = clEnqueueNDRangeKernel(q, s->rgb_to_yuv_krnl, 2, NULL, &work_size[0], NULL, 0, 0, &event); + assert(err == 0); + clWaitForEvents(1, &event); + clReleaseEvent(event); +} diff --git a/selfdrive/visiond/rgb_to_yuv.cl b/selfdrive/visiond/rgb_to_yuv.cl new file mode 100644 index 000000000..60dbdb4d5 --- /dev/null +++ b/selfdrive/visiond/rgb_to_yuv.cl @@ -0,0 +1,127 @@ +#define RGB_TO_Y(r, g, b) ((((mul24(b, 13) + mul24(g, 65) + mul24(r, 33)) + 64) >> 7) + 16) +#define RGB_TO_U(r, g, b) ((mul24(b, 56) - mul24(g, 37) - mul24(r, 19) + 0x8080) >> 8) +#define RGB_TO_V(r, g, b) ((mul24(r, 56) - mul24(g, 47) - mul24(b, 9) + 0x8080) >> 8) +#define AVERAGE(x, y, z, w) ((convert_ushort(x) + convert_ushort(y) + convert_ushort(z) + convert_ushort(w) + 1) >> 1) + +inline void convert_2_ys(__global uchar * out_yuv, int yi, const uchar8 rgbs1) { + uchar2 yy = (uchar2)( + RGB_TO_Y(rgbs1.s2, rgbs1.s1, rgbs1.s0), + RGB_TO_Y(rgbs1.s5, rgbs1.s4, rgbs1.s3) + ); +#ifdef CL_DEBUG + if(yi >= RGB_SIZE) + printf("Y vector2 overflow, %d > %d\n", yi, RGB_SIZE); +#endif + vstore2(yy, 0, out_yuv + yi); +} + +inline void convert_4_ys(__global uchar * out_yuv, int yi, const uchar8 rgbs1, const uchar8 rgbs3) { + const uchar4 yy = (uchar4)( + RGB_TO_Y(rgbs1.s2, rgbs1.s1, rgbs1.s0), + RGB_TO_Y(rgbs1.s5, rgbs1.s4, rgbs1.s3), + RGB_TO_Y(rgbs3.s0, rgbs1.s7, rgbs1.s6), + RGB_TO_Y(rgbs3.s3, rgbs3.s2, rgbs3.s1) + ); +#ifdef CL_DEBUG + if(yi > RGB_SIZE - 4) + printf("Y vector4 overflow, %d > %d\n", yi, RGB_SIZE - 4); +#endif + vstore4(yy, 0, out_yuv + yi); +} + +inline void convert_uv(__global uchar * out_yuv, int ui, int vi, + const uchar8 rgbs1, const uchar8 rgbs2) { + // U & V: average of 2x2 pixels square + const short ab = AVERAGE(rgbs1.s0, rgbs1.s3, rgbs2.s0, rgbs2.s3); + const short ag = AVERAGE(rgbs1.s1, rgbs1.s4, rgbs2.s1, rgbs2.s4); + const short ar = AVERAGE(rgbs1.s2, rgbs1.s5, rgbs2.s2, rgbs2.s5); +#ifdef CL_DEBUG + if(ui >= RGB_SIZE + RGB_SIZE / 4) + printf("U overflow, %d >= %d\n", ui, RGB_SIZE + RGB_SIZE / 4); + if(vi >= RGB_SIZE + RGB_SIZE / 2) + printf("V overflow, %d >= %d\n", vi, RGB_SIZE + RGB_SIZE / 2); +#endif + out_yuv[ui] = RGB_TO_U(ar, ag, ab); + out_yuv[vi] = RGB_TO_V(ar, ag, ab); +} + +inline void convert_2_uvs(__global uchar * out_yuv, int ui, int vi, + const uchar8 rgbs1, const uchar8 rgbs2, const uchar8 rgbs3, const uchar8 rgbs4) { + // U & V: average of 2x2 pixels square + const short ab1 = AVERAGE(rgbs1.s0, rgbs1.s3, rgbs2.s0, rgbs2.s3); + const short ag1 = AVERAGE(rgbs1.s1, rgbs1.s4, rgbs2.s1, rgbs2.s4); + const short ar1 = AVERAGE(rgbs1.s2, rgbs1.s5, rgbs2.s2, rgbs2.s5); + const short ab2 = AVERAGE(rgbs1.s6, rgbs3.s1, rgbs2.s6, rgbs4.s1); + const short ag2 = AVERAGE(rgbs1.s7, rgbs3.s2, rgbs2.s7, rgbs4.s2); + const short ar2 = AVERAGE(rgbs3.s0, rgbs3.s3, rgbs4.s0, rgbs4.s3); + uchar2 u2 = (uchar2)( + RGB_TO_U(ar1, ag1, ab1), + RGB_TO_U(ar2, ag2, ab2) + ); + uchar2 v2 = (uchar2)( + RGB_TO_V(ar1, ag1, ab1), + RGB_TO_V(ar2, ag2, ab2) + ); +#ifdef CL_DEBUG1 + if(ui > RGB_SIZE + RGB_SIZE / 4 - 2) + printf("U 2 overflow, %d >= %d\n", ui, RGB_SIZE + RGB_SIZE / 4 - 2); + if(vi > RGB_SIZE + RGB_SIZE / 2 - 2) + printf("V 2 overflow, %d >= %d\n", vi, RGB_SIZE + RGB_SIZE / 2 - 2); +#endif + vstore2(u2, 0, out_yuv + ui); + vstore2(v2, 0, out_yuv + vi); +} + +__kernel void rgb_to_yuv(__global uchar const * const rgb, + __global uchar * out_yuv) +{ + const int dx = get_global_id(0); + const int dy = get_global_id(1); + const int col = mul24(dx, 4); // Current column in rgb image + const int row = mul24(dy, 4); // Current row in rgb image + const int bgri_start = mad24(row, RGB_STRIDE, mul24(col, 3)); // Start offset of rgb data being converted + const int yi_start = mad24(row, WIDTH, col); // Start offset in the target yuv buffer + int ui = mad24(row / 2, UV_WIDTH, RGB_SIZE + col / 2); + int vi = mad24(row / 2 , UV_WIDTH, RGB_SIZE + UV_WIDTH * UV_HEIGHT + col / 2); + int num_col = min(WIDTH - col, 4); + int num_row = min(HEIGHT - row, 4); + if(num_row == 4) { + const uchar8 rgbs0_0 = vload8(0, rgb + bgri_start); + const uchar8 rgbs0_1 = vload8(0, rgb + bgri_start + 8); + const uchar8 rgbs1_0 = vload8(0, rgb + bgri_start + RGB_STRIDE); + const uchar8 rgbs1_1 = vload8(0, rgb + bgri_start + RGB_STRIDE + 8); + const uchar8 rgbs2_0 = vload8(0, rgb + bgri_start + RGB_STRIDE * 2); + const uchar8 rgbs2_1 = vload8(0, rgb + bgri_start + RGB_STRIDE * 2 + 8); + const uchar8 rgbs3_0 = vload8(0, rgb + bgri_start + RGB_STRIDE * 3); + const uchar8 rgbs3_1 = vload8(0, rgb + bgri_start + RGB_STRIDE * 3 + 8); + if(num_col == 4) { + convert_4_ys(out_yuv, yi_start, rgbs0_0, rgbs0_1); + convert_4_ys(out_yuv, yi_start + WIDTH, rgbs1_0, rgbs1_1); + convert_4_ys(out_yuv, yi_start + WIDTH * 2, rgbs2_0, rgbs2_1); + convert_4_ys(out_yuv, yi_start + WIDTH * 3, rgbs3_0, rgbs3_1); + convert_2_uvs(out_yuv, ui, vi, rgbs0_0, rgbs1_0, rgbs0_1, rgbs1_1); + convert_2_uvs(out_yuv, ui + UV_WIDTH, vi + UV_WIDTH, rgbs2_0, rgbs3_0, rgbs2_1, rgbs3_1); + } else if(num_col == 2) { + convert_2_ys(out_yuv, yi_start, rgbs0_0); + convert_2_ys(out_yuv, yi_start + WIDTH, rgbs1_0); + convert_2_ys(out_yuv, yi_start + WIDTH * 2, rgbs2_0); + convert_2_ys(out_yuv, yi_start + WIDTH * 3, rgbs3_0); + convert_uv(out_yuv, ui, vi, rgbs0_0, rgbs1_0); + convert_uv(out_yuv, ui + UV_WIDTH, vi + UV_WIDTH, rgbs2_0, rgbs3_0); + } + } else { + const uchar8 rgbs0_0 = vload8(0, rgb + bgri_start); + const uchar8 rgbs0_1 = vload8(0, rgb + bgri_start + 8); + const uchar8 rgbs1_0 = vload8(0, rgb + bgri_start + RGB_STRIDE); + const uchar8 rgbs1_1 = vload8(0, rgb + bgri_start + RGB_STRIDE + 8); + if(num_col == 4) { + convert_4_ys(out_yuv, yi_start, rgbs0_0, rgbs0_1); + convert_4_ys(out_yuv, yi_start + WIDTH, rgbs1_0, rgbs1_1); + convert_2_uvs(out_yuv, ui, vi, rgbs0_0, rgbs1_0, rgbs0_1, rgbs1_1); + } else if(num_col == 2) { + convert_2_ys(out_yuv, yi_start, rgbs0_0); + convert_2_ys(out_yuv, yi_start + WIDTH, rgbs1_0); + convert_uv(out_yuv, ui, vi, rgbs0_0, rgbs1_0); + } + } +} diff --git a/selfdrive/visiond/rgb_to_yuv.h b/selfdrive/visiond/rgb_to_yuv.h new file mode 100644 index 000000000..798958034 --- /dev/null +++ b/selfdrive/visiond/rgb_to_yuv.h @@ -0,0 +1,32 @@ +#ifndef RGB_TO_YUV_H +#define RGB_TO_YUV_H + +#include +#include + +#ifdef __APPLE__ +#include +#else +#include +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +typedef struct { + int width, height; + cl_kernel rgb_to_yuv_krnl; +} RGBToYUVState; + +void rgb_to_yuv_init(RGBToYUVState* s, cl_context ctx, cl_device_id device_id, int width, int height, int rgb_stride); + +void rgb_to_yuv_destroy(RGBToYUVState* s); + +void rgb_to_yuv_queue(RGBToYUVState* s, cl_command_queue q, cl_mem rgb_cl, cl_mem yuv_cl); + +#ifdef __cplusplus +} +#endif + +#endif // RGB_TO_YUV_H diff --git a/selfdrive/visiond/rgb_to_yuv_test.cc b/selfdrive/visiond/rgb_to_yuv_test.cc new file mode 100644 index 000000000..c8b875105 --- /dev/null +++ b/selfdrive/visiond/rgb_to_yuv_test.cc @@ -0,0 +1,201 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#ifdef ANDROID + +#define MAXE 0 +#include + +#else +// The libyuv implementation on ARM is slightly different than on x86 +// Our implementation matches the ARM version, so accept errors of 1 +#define MAXE 1 + +#endif + +#include + +#include + +#include "clutil.h" +#include "rgb_to_yuv.h" + + +static inline double millis_since_boot() { + struct timespec t; + clock_gettime(CLOCK_BOOTTIME, &t); + return t.tv_sec * 1000.0 + t.tv_nsec * 1e-6; +} + +void cl_init(cl_device_id &device_id, cl_context &context) { + int err; + cl_platform_id platform_id = NULL; + cl_uint num_devices; + cl_uint num_platforms; + + err = clGetPlatformIDs(1, &platform_id, &num_platforms); + err = clGetDeviceIDs(platform_id, CL_DEVICE_TYPE_DEFAULT, 1, + &device_id, &num_devices); + cl_print_info(platform_id, device_id); + context = clCreateContext(NULL, 1, &device_id, NULL, NULL, &err); +} + + +bool compare_results(uint8_t *a, uint8_t *b, int len, int stride, int width, int height, uint8_t *rgb) { + int min_diff = 0., max_diff = 0., max_e = 0.; + int e1 = 0, e0 = 0; + int e0y = 0, e0u = 0, e0v = 0, e1y = 0, e1u = 0, e1v = 0; + int max_e_i = 0; + for (int i = 0;i < len;i++) { + int e = ((int)a[i]) - ((int)b[i]); + if(e < min_diff) { + min_diff = e; + } + if(e > max_diff) { + max_diff = e; + } + int e_abs = std::abs(e); + if(e_abs > max_e) { + max_e = e_abs; + max_e_i = i; + } + if(e_abs < 1) { + e0++; + if(i < stride * height) + e0y++; + else if(i < stride * height + stride * height / 4) + e0u++; + else + e0v++; + } else { + e1++; + if(i < stride * height) + e1y++; + else if(i < stride * height + stride * height / 4) + e1u++; + else + e1v++; + } + } + //printf("max diff : %d, min diff : %d, e < 1: %d, e >= 1: %d\n", max_diff, min_diff, e0, e1); + //printf("Y: e < 1: %d, e >= 1: %d, U: e < 1: %d, e >= 1: %d, V: e < 1: %d, e >= 1: %d\n", e0y, e1y, e0u, e1u, e0v, e1v); + if(max_e <= MAXE) { + return true; + } + int row = max_e_i / stride; + if(row < height) { + printf("max error is Y: %d = (libyuv: %u - cl: %u), row: %d, col: %d\n", max_e, a[max_e_i], b[max_e_i], row, max_e_i % stride); + } else if(row >= height && row < (height + height / 4)) { + printf("max error is U: %d = %u - %u, row: %d, col: %d\n", max_e, a[max_e_i], b[max_e_i], (row - height) / 2, max_e_i % stride / 2); + } else { + printf("max error is V: %d = %u - %u, row: %d, col: %d\n", max_e, a[max_e_i], b[max_e_i], (row - height - height / 4) / 2, max_e_i % stride / 2); + } + return false; +} + +int main(int argc, char** argv) { + srand(1337); + + clu_init(); + cl_device_id device_id; + cl_context context; + cl_init(device_id, context) ; + + int err; + const cl_queue_properties props[] = {0}; //CL_QUEUE_PRIORITY_KHR, CL_QUEUE_PRIORITY_HIGH_KHR, 0}; + cl_command_queue q = clCreateCommandQueueWithProperties(context, device_id, props, &err); + if(err != 0) { + std::cout << "clCreateCommandQueueWithProperties error: " << err << std::endl; + } + + int width = 1164; + int height = 874; + + int opt = 0; + while ((opt = getopt(argc, argv, "f")) != -1) + { + switch (opt) + { + case 'f': + std::cout << "Using front camera dimensions" << std::endl; + int width = 1152; + int height = 846; + } + } + + std::cout << "Width: " << width << " Height: " << height << std::endl; + uint8_t *rgb_frame = new uint8_t[width * height * 3]; + + + RGBToYUVState rgb_to_yuv_state; + rgb_to_yuv_init(&rgb_to_yuv_state, context, device_id, width, height, width * 3); + + int frame_yuv_buf_size = width * height * 3 / 2; + cl_mem yuv_cl = clCreateBuffer(context, CL_MEM_READ_WRITE, frame_yuv_buf_size, (void*)NULL, &err); + uint8_t *frame_yuv_buf = new uint8_t[frame_yuv_buf_size]; + uint8_t *frame_yuv_ptr_y = frame_yuv_buf; + uint8_t *frame_yuv_ptr_u = frame_yuv_buf + (width * height); + uint8_t *frame_yuv_ptr_v = frame_yuv_ptr_u + ((width/2) * (height/2)); + + cl_mem rgb_cl = clCreateBuffer(context, CL_MEM_READ_WRITE, width * height * 3, (void*)NULL, &err); + int mismatched = 0; + int counter = 0; + srand (time(NULL)); + + for (int i = 0; i < 100; i++){ + for (int i = 0; i < width * height * 3; i++){ + rgb_frame[i] = (uint8_t)rand(); + } + + double t1 = millis_since_boot(); + libyuv::RGB24ToI420((uint8_t*)rgb_frame, width * 3, + frame_yuv_ptr_y, width, + frame_yuv_ptr_u, width/2, + frame_yuv_ptr_v, width/2, + width, height); + double t2 = millis_since_boot(); + //printf("Libyuv: rgb to yuv: %.2fms\n", t2-t1); + + clEnqueueWriteBuffer(q, rgb_cl, CL_TRUE, 0, width * height * 3, (void *)rgb_frame, 0, NULL, NULL); + t1 = millis_since_boot(); + rgb_to_yuv_queue(&rgb_to_yuv_state, q, rgb_cl, yuv_cl); + t2 = millis_since_boot(); + + //printf("OpenCL: rgb to yuv: %.2fms\n", t2-t1); + uint8_t *yyy = (uint8_t *)clEnqueueMapBuffer(q, yuv_cl, CL_TRUE, + CL_MAP_READ, 0, frame_yuv_buf_size, + 0, NULL, NULL, &err); + if(!compare_results(frame_yuv_ptr_y, yyy, frame_yuv_buf_size, width, width, height, (uint8_t*)rgb_frame)) + mismatched++; + clEnqueueUnmapMemObject(q, yuv_cl, yyy, 0, NULL, NULL); + + // std::this_thread::sleep_for(std::chrono::milliseconds(20)); + if(counter++ % 100 == 0) + printf("Matched: %d, Mismatched: %d\n", counter - mismatched, mismatched); + + } + printf("Matched: %d, Mismatched: %d\n", counter - mismatched, mismatched); + + delete[] frame_yuv_buf; + rgb_to_yuv_destroy(&rgb_to_yuv_state); + clReleaseContext(context); + delete[] rgb_frame; + + if (mismatched == 0) + return 0; + else + return -1; +} diff --git a/selfdrive/visiond/visiond.cc b/selfdrive/visiond/visiond.cc index af10d760c..f7a52dc0e 100644 --- a/selfdrive/visiond/visiond.cc +++ b/selfdrive/visiond/visiond.cc @@ -46,6 +46,7 @@ #include "model.h" #include "monitoring.h" +#include "rgb_to_yuv.h" #include "cereal/gen/cpp/log.capnp.h" @@ -122,6 +123,7 @@ struct VisionState { FrameMetadata yuv_metas[YUV_COUNT]; size_t yuv_buf_size; int yuv_width, yuv_height; + RGBToYUVState rgb_to_yuv_state; // for front camera recording Pool yuv_front_pool; @@ -131,6 +133,7 @@ struct VisionState { FrameMetadata yuv_front_metas[YUV_COUNT]; size_t yuv_front_buf_size; int yuv_front_width, yuv_front_height; + RGBToYUVState front_rgb_to_yuv_state; size_t rgb_buf_size; int rgb_width, rgb_height, rgb_stride; @@ -398,6 +401,10 @@ void init_buffers(VisionState *s) { assert(err == 0); s->krnl_debayer_front = clCreateKernel(s->prg_debayer_front, "debayer10", &err); assert(err == 0); + + rgb_to_yuv_init(&s->rgb_to_yuv_state, s->context, s->device_id, s->yuv_width, s->yuv_height, s->rgb_stride); + rgb_to_yuv_init(&s->front_rgb_to_yuv_state, s->context, s->device_id, s->yuv_front_width, s->yuv_front_height, s->rgb_front_stride); + } void free_buffers(VisionState *s) { @@ -831,7 +838,6 @@ void* frontview_thread(void *arg) { if (cnt % 3 == 0) #endif { - // for driver autoexposure, use bottom right corner const int y_start = s->rgb_front_height / 3; const int y_end = s->rgb_front_height; @@ -869,15 +875,9 @@ void* frontview_thread(void *arg) { int yuv_idx = pool_select(&s->yuv_front_pool); s->yuv_front_metas[yuv_idx] = frame_data; - uint8_t *bgr_ptr = (uint8_t*)s->rgb_front_bufs[ui_idx].addr; - libyuv::RGB24ToI420(bgr_ptr, s->rgb_front_stride, - s->yuv_front_bufs[yuv_idx].y, s->yuv_front_width, - s->yuv_front_bufs[yuv_idx].u, s->yuv_front_width/2, - s->yuv_front_bufs[yuv_idx].v, s->yuv_front_width/2, - s->rgb_front_width, s->rgb_front_height); - + rgb_to_yuv_queue(&s->front_rgb_to_yuv_state, q, s->rgb_front_bufs_cl[ui_idx], s->yuv_front_cl[yuv_idx]); + visionbuf_sync(&s->yuv_front_ion[yuv_idx], VISIONBUF_SYNC_FROM_DEVICE); s->yuv_front_metas[yuv_idx] = frame_data; - visionbuf_sync(&s->yuv_front_ion[yuv_idx], VISIONBUF_SYNC_TO_DEVICE); // no reference required cause we don't use this in visiond //pool_acquire(&s->yuv_front_pool, yuv_idx); @@ -1020,17 +1020,10 @@ void* processing_thread(void *arg) { uint8_t* yuv_ptr_u = s->yuv_bufs[yuv_idx].u; uint8_t* yuv_ptr_v = s->yuv_bufs[yuv_idx].v; cl_mem yuv_cl = s->yuv_cl[yuv_idx]; - - libyuv::RGB24ToI420(bgr_ptr, s->rgb_stride, - yuv_ptr_y, s->yuv_width, - yuv_ptr_u, s->yuv_width/2, - yuv_ptr_v, s->yuv_width/2, - s->rgb_width, s->rgb_height); + rgb_to_yuv_queue(&s->rgb_to_yuv_state, q, s->rgb_bufs_cl[rgb_idx], yuv_cl); + visionbuf_sync(&s->yuv_ion[yuv_idx], VISIONBUF_SYNC_FROM_DEVICE); double yt2 = millis_since_boot(); - - visionbuf_sync(&s->yuv_ion[yuv_idx], VISIONBUF_SYNC_TO_DEVICE); - // keep another reference around till were done processing pool_acquire(&s->yuv_pool, yuv_idx); @@ -1129,7 +1122,7 @@ void* processing_thread(void *arg) { //printf("avg %f\n", pose_output[0]); posenet->execute(posenet_input); - + // fix stddevs for (int i = 6; i < 12; i++) { pose_output[i] = log1p(exp(pose_output[i])) + 1e-6;