From 8cc32df779b311f4541d9c4509e0591e30c70077 Mon Sep 17 00:00:00 2001 From: Jamezz Date: Mon, 1 Oct 2018 10:13:34 -0700 Subject: [PATCH 01/12] Revert the changes to GM in 0.5.4 (#380) * Revert 0.5.4 changes for GM for 18ers * Redo the refactor of stock control msgs * Fixed missing CONTROL_MSGS -> STOCK_CONTROL_MSGS * Remove spacing * Need candidate array idx --- selfdrive/car/gm/carcontroller.py | 21 ++++++++------------- selfdrive/car/gm/gmcan.py | 16 +++++++++------- selfdrive/car/gm/interface.py | 4 +++- selfdrive/car/gm/values.py | 7 ------- 4 files changed, 20 insertions(+), 28 deletions(-) diff --git a/selfdrive/car/gm/carcontroller.py b/selfdrive/car/gm/carcontroller.py index 199b6a5c3268e6..be0ca64ccb1996 100644 --- a/selfdrive/car/gm/carcontroller.py +++ b/selfdrive/car/gm/carcontroller.py @@ -4,7 +4,7 @@ from selfdrive.boardd.boardd import can_list_to_can_capnp from selfdrive.car import apply_std_steer_torque_limits from selfdrive.car.gm import gmcan -from selfdrive.car.gm.values import CAR, DBC, AccState +from selfdrive.car.gm.values import CAR, DBC from selfdrive.can.packer import CANPacker @@ -29,11 +29,11 @@ def __init__(self, car_fingerprint): self.ADAS_KEEPALIVE_STEP = 10 # pedal lookups, only for Volt MAX_GAS = 3072 # Only a safety limit - self.ZERO_GAS = 2048 + ZERO_GAS = 2048 MAX_BRAKE = 350 # Should be around 3.5m/s^2, including regen self.MAX_ACC_REGEN = 1404 # ACC Regen braking is slightly less powerful than max regen paddle self.GAS_LOOKUP_BP = [-0.25, 0., 0.5] - self.GAS_LOOKUP_V = [self.MAX_ACC_REGEN, self.ZERO_GAS, MAX_GAS] + self.GAS_LOOKUP_V = [self.MAX_ACC_REGEN, ZERO_GAS, MAX_GAS] self.BRAKE_LOOKUP_BP = [-1., -0.25] self.BRAKE_LOOKUP_V = [MAX_BRAKE, 0] @@ -83,6 +83,7 @@ def update(self, sendcan, enabled, CS, frame, actuators, \ return P = self.params + # Send CAN commands. can_sends = [] canbus = self.canbus @@ -130,18 +131,12 @@ def update(self, sendcan, enabled, CS, frame, actuators, \ if (frame % 4) == 0: idx = (frame / 4) % 4 - car_stopping = apply_gas < P.ZERO_GAS - standstill = CS.pcm_acc_status == AccState.STANDSTILL - at_full_stop = enabled and standstill and car_stopping - near_stop = enabled and (CS.v_ego < P.NEAR_STOP_BRAKE_PHASE) and car_stopping + at_full_stop = enabled and CS.standstill + near_stop = enabled and (CS.v_ego < P.NEAR_STOP_BRAKE_PHASE) can_sends.append(gmcan.create_friction_brake_command(self.packer_ch, canbus.chassis, apply_brake, idx, near_stop, at_full_stop)) - # Auto-resume from full stop by resetting ACC control - acc_enabled = enabled - if standstill and not car_stopping: - acc_enabled = False - - can_sends.append(gmcan.create_gas_regen_command(self.packer_pt, canbus.powertrain, apply_gas, idx, acc_enabled, at_full_stop)) + at_full_stop = enabled and CS.standstill + can_sends.append(gmcan.create_gas_regen_command(self.packer_pt, canbus.powertrain, apply_gas, idx, enabled, at_full_stop)) # Send dashboard UI commands (ACC status), 25hz if (frame % 4) == 0: diff --git a/selfdrive/car/gm/gmcan.py b/selfdrive/car/gm/gmcan.py index 6db69bad592768..47b0d8b38dfad4 100644 --- a/selfdrive/car/gm/gmcan.py +++ b/selfdrive/car/gm/gmcan.py @@ -60,15 +60,17 @@ def create_gas_regen_command(packer, bus, throttle, idx, acc_engaged, at_full_st def create_friction_brake_command(packer, bus, apply_brake, idx, near_stop, at_full_stop): - mode = 0x1 - if apply_brake > 0: + if apply_brake == 0: + mode = 0x1 + else: mode = 0xa - if near_stop: - mode = 0xb - - if at_full_stop: - mode = 0xd + if at_full_stop: + mode = 0xd + # TODO: this is to have GM bringing the car to complete stop, + # but currently it conflicts with OP controls, so turned off. + #elif near_stop: + # mode = 0xb brake = (0x1000 - apply_brake) & 0xfff checksum = (0x10000 - (mode << 12) - brake - idx) & 0xffff diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index f7fb42a391f089..27d94b885b4af7 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -193,7 +193,7 @@ def update(self, c): ret.cruiseState.available = bool(self.CS.main_on) cruiseEnabled = self.CS.pcm_acc_status != 0 ret.cruiseState.enabled = cruiseEnabled - ret.cruiseState.standstill = False + ret.cruiseState.standstill = self.CS.pcm_acc_status == 4 ret.leftBlinker = self.CS.left_blinker_on ret.rightBlinker = self.CS.right_blinker_on @@ -276,6 +276,8 @@ def update(self, c): events.append(create_event('pedalPressed', [ET.NO_ENTRY, ET.USER_DISABLE])) if ret.gasPressed: events.append(create_event('pedalPressed', [ET.PRE_ENABLE])) + if ret.cruiseState.standstill: + events.append(create_event('resumeRequired', [ET.WARNING])) # handle button presses for b in ret.buttonEvents: diff --git a/selfdrive/car/gm/values.py b/selfdrive/car/gm/values.py index 62529ed6d73578..8e93b677c8ae66 100644 --- a/selfdrive/car/gm/values.py +++ b/selfdrive/car/gm/values.py @@ -12,12 +12,6 @@ class CruiseButtons: MAIN = 5 CANCEL = 6 -class AccState: - OFF = 0 - ACTIVE = 1 - FAULTED = 3 - STANDSTILL = 4 - def is_eps_status_ok(eps_status, car_fingerprint): valid_eps_status = [] if car_fingerprint == CAR.VOLT: @@ -55,7 +49,6 @@ def parse_gear_shifter(can_gear): STEER_THRESHOLD = 1.0 - STOCK_CONTROL_MSGS = { CAR.VOLT: [384, 715], # 384 = "ASCMLKASteeringCmd", 715 = "ASCMGasRegenCmd" CAR.CADILLAC_CT6: [], # Cadillac does not require ASCMs to be disconnected From 0a99fe3baa06ca67af7aade312171cc0e8a4c502 Mon Sep 17 00:00:00 2001 From: dekerr Date: Mon, 8 Oct 2018 15:02:20 -0400 Subject: [PATCH 02/12] Save one inverse call in building transformation matrix (#384) --- common/transformations/model.py | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/common/transformations/model.py b/common/transformations/model.py index 26a20d509fd970..107c3d542c2036 100644 --- a/common/transformations/model.py +++ b/common/transformations/model.py @@ -75,10 +75,8 @@ def get_model_height_transform(camera_frame_from_road_frame, height): [0, 0, 1], ])) - ground_from_camera_frame = np.linalg.inv(camera_frame_from_road_ground) - - low_camera_from_high_camera = np.dot(camera_frame_from_road_high, ground_from_camera_frame) - high_camera_from_low_camera = np.linalg.inv(low_camera_from_high_camera) + road_high_from_camera_frame = np.linalg.inv(camera_frame_from_road_high) + high_camera_from_low_camera = np.dot(camera_frame_from_road_ground, road_high_from_camera_frame) return high_camera_from_low_camera From c499aa549cdf794260718bba1f88b9e14b66b8c0 Mon Sep 17 00:00:00 2001 From: Vasily Tarasov Date: Fri, 12 Oct 2018 17:37:13 -0700 Subject: [PATCH 03/12] GM: LKA dashboard icon support (#389) * GM: LKA dashboard icon support * Decrease camera keepalive interval * Use tuple for LKA icon status --- selfdrive/car/gm/carcontroller.py | 22 ++++++++++++++++++---- selfdrive/car/gm/gmcan.py | 10 ++++++++++ 2 files changed, 28 insertions(+), 4 deletions(-) diff --git a/selfdrive/car/gm/carcontroller.py b/selfdrive/car/gm/carcontroller.py index be0ca64ccb1996..71277cf2a7f08b 100644 --- a/selfdrive/car/gm/carcontroller.py +++ b/selfdrive/car/gm/carcontroller.py @@ -26,7 +26,11 @@ def __init__(self, car_fingerprint): self.STEER_DRIVER_FACTOR = 100 # from dbc self.NEAR_STOP_BRAKE_PHASE = 0.5 # m/s, more aggressive braking near full stop - self.ADAS_KEEPALIVE_STEP = 10 + # Takes case of "Service Adaptive Cruise" and "Service Front Camera" + # dashboard messages. + self.ADAS_KEEPALIVE_STEP = 100 + self.CAMERA_KEEPALIVE_STEP = 100 + # pedal lookups, only for Volt MAX_GAS = 3072 # Only a safety limit ZERO_GAS = 2048 @@ -59,12 +63,11 @@ def __init__(self, canbus, car_fingerprint, allow_controls): self.pedal_steady = 0. self.start_time = sec_since_boot() self.chime = 0 - self.lkas_active = False - self.inhibit_steer_for = 0 self.steer_idx = 0 self.apply_steer_last = 0 self.car_fingerprint = car_fingerprint self.allow_controls = allow_controls + self.lka_icon_status_last = (False, False) # Setup detection helper. Routes commands to # an appropriate CAN bus number. @@ -158,10 +161,21 @@ def update(self, sendcan, enabled, CS, frame, actuators, \ can_sends.append(gmcan.create_adas_steering_status(canbus.obstacle, idx)) can_sends.append(gmcan.create_adas_accelerometer_speed_status(canbus.obstacle, CS.v_ego, idx)) - # Send ADAS keepalive, 10hz if frame % P.ADAS_KEEPALIVE_STEP == 0: can_sends += gmcan.create_adas_keepalive(canbus.powertrain) + # Show green icon when LKA torque is applied, and + # alarming orange icon when approaching torque limit. + # If not sent again, LKA icon disappears in about 5 seconds. + # Conveniently, sending camera message periodically also works as a keepalive. + lka_active = CS.lkas_status == 1 + lka_critical = lka_active and abs(actuators.steer) > 0.9 + lka_icon_status = (lka_active, lka_critical) + if frame % P.CAMERA_KEEPALIVE_STEP == 0 \ + or lka_icon_status != self.lka_icon_status_last: + can_sends.append(gmcan.create_lka_icon_command(canbus.sw_gmlan, lka_active, lka_critical)) + self.lka_icon_status_last = lka_icon_status + # Send chimes if self.chime != chime: duration = 0x3c diff --git a/selfdrive/car/gm/gmcan.py b/selfdrive/car/gm/gmcan.py index 47b0d8b38dfad4..910cb1d95604ce 100644 --- a/selfdrive/car/gm/gmcan.py +++ b/selfdrive/car/gm/gmcan.py @@ -134,6 +134,16 @@ def create_chime_command(bus, chime_type, duration, repeat_cnt): dat = [chime_type, duration, repeat_cnt, 0xff, 0] return [0x10400060, 0, "".join(map(chr, dat)), bus] +def create_lka_icon_command(bus, active, critical): + if active: + if critical: + dat = "\x40\xc0\x14" + else: + dat = "\x40\x40\x18" + else: + dat = "\x00\x00\x00" + return [0x104c006c, 0, dat, bus] + # TODO: WIP ''' def create_friction_brake_command_ct6(packer, bus, apply_brake, idx, near_stop, at_full_stop): From 5641fc986d53c7d0e745c7bdaa4a454770778b0d Mon Sep 17 00:00:00 2001 From: Andrew Frahn Date: Mon, 15 Oct 2018 01:30:18 +1100 Subject: [PATCH 04/12] Revert to using CLU15 message for Gear Selection for Compatability Reasons (#362) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * hyundai WIP * steer_driver_factor is 1 * removed unnecessary file * removed unnecessary code * Update carcontroller.py bug fix * safety tuning and fixed interface stiffness * better lateral tuning, some fixes * Fix set speed * added camera state reading, autoresume from stop, cancel on accel, hud alerts * WIP * Updated for Kia Sorento *WIP* * Cleanup * clean2 * Bug Fixes * pre-merge * Add all the cars! * Panda to auto-detect Camera Bus * Move Checksum Check * Final Sorento Tuning * Make CAN3 for Cam default * Update README.md * update panda, minor aesthetic updates * few other minor changes * added steer not allowed alert * bup panda version to force panda update * fixed camera alerts * Revert to using CLU15 for Gear Selection * Missing Defines Didn’t realise this was removed as well! * Change Gear Selection Definitions Add logic to use transmission message rather than cluster message for all gear selections UNLESS the car in question does not have the known good transmission messages * Revert Camera CAN Bus * self.candidate * fixed fingerpint, tested on Sorento * Update for Elantra on Hyundai-Dev Branch Latest Elantra values that correlate to progress Community branch. --- selfdrive/car/hyundai/carstate.py | 19 ++++++++++++++++++- selfdrive/car/hyundai/interface.py | 14 +++++++++----- 2 files changed, 27 insertions(+), 6 deletions(-) diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index 4714644957bb3d..451183802085e0 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -44,6 +44,11 @@ def get_can_parser(CP): ("CF_Clu_AmpInfo", "CLU11", 0), ("CF_Clu_AliveCnt1", "CLU11", 0), + ("CF_Clu_InhibitD", "CLU15", 0), + ("CF_Clu_InhibitP", "CLU15", 0), + ("CF_Clu_InhibitN", "CLU15", 0), + ("CF_Clu_InhibitR", "CLU15", 0), + ("CF_Lvr_Gear","LVR12",0), ("ACCEnable", "TCS13", 0), @@ -204,7 +209,7 @@ def update(self, cp, cp_cam): self.pedal_gas = cp.vl["EMS12"]['TPS'] self.car_gas = cp.vl["EMS12"]['TPS'] - # Gear Selecton - This should be compatible with all Kia/Hyundai with Auto's + # Gear Selecton - This is not compatible with all Kia/Hyundai's, But is the best way for those it is compatible with gear = cp.vl["LVR12"]["CF_Lvr_Gear"] if gear == 5: self.gear_shifter = "drive" @@ -217,6 +222,18 @@ def update(self, cp, cp_cam): else: self.gear_shifter = "unknown" + # Gear Selection via Cluster - For those Kia/Hyundai which are not fully discovered, we can use the Cluster Indicator for Gear Selection, as this seems to be standard over all cars, but is not the preferred method. + if cp.vl["CLU15"]["CF_Clu_InhibitD"] == 1: + self.gear_shifter_cluster = "drive" + elif cp.vl["CLU15"]["CF_Clu_InhibitN"] == 1: + self.gear_shifter_cluster = "neutral" + elif cp.vl["CLU15"]["CF_Clu_InhibitP"] == 1: + self.gear_shifter_cluster = "park" + elif cp.vl["CLU15"]["CF_Clu_InhibitR"] == 1: + self.gear_shifter_cluster = "reverse" + else: + self.gear_shifter_cluster = "unknown" + # save the entire LKAS11 and CLU11 self.lkas11 = cp_cam.vl["LKAS11"] self.clu11 = cp.vl["CLU11"] diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 5f9d75c94b1287..96174ef09643e8 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -95,14 +95,15 @@ def get_params(candidate, fingerprint): ret.steerKpV, ret.steerKiV = [[0.25], [0.05]] ret.minSteerSpeed = 0. elif candidate == CAR.ELANTRA: - ret.steerKf = 0.00004 + ret.steerKf = 0.00006 ret.steerRateCost = 0.5 ret.mass = 1275 + std_cargo ret.wheelbase = 2.7 - ret.steerRatio = 16.9 + ret.steerRatio = 13.73 #Spec + tire_stiffness_factor = 0.385 ret.steerKiBP, ret.steerKpBP = [[0.], [0.]] - ret.steerKpV, ret.steerKiV = [[0.20], [0.01]] - ret.minSteerSpeed = 35 * CV.MPH_TO_MS + ret.steerKpV, ret.steerKiV = [[0.25], [0.05]] + ret.minSteerSpeed = 32 * CV.MPH_TO_MS elif candidate == CAR.GENESIS: ret.steerKf = 0.00005 ret.steerRateCost = 0.5 @@ -190,7 +191,10 @@ def update(self, c): ret.wheelSpeeds.rr = self.CS.v_wheel_rr # gear shifter - ret.gearShifter = self.CS.gear_shifter + if self.CP.carFingerprint == CAR.ELANTRA: + ret.gearShifter = self.CS.gear_shifter_cluster + else: + ret.gearShifter = self.CS.gear_shifter # gas pedal ret.gas = self.CS.car_gas From 7ed5c6554d3875cb3c3eb0ce9112fad3767b5b91 Mon Sep 17 00:00:00 2001 From: Ted Slesinski Date: Sat, 20 Oct 2018 14:02:00 -0400 Subject: [PATCH 05/12] Added new fingerprint for EX-L (#401) --- selfdrive/car/honda/values.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index eec1a7e0c69b33..c9dbcdc7a829e4 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -90,7 +90,7 @@ class CAR: 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 }], 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, 229: 4, 308: 5, 316: 8, 334: 8, 342: 6, 344: 8, 379: 8, 380: 8, 392: 6, 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, 963: 8, 965: 8, 966: 8, 967: 8, 983: 8, 985: 3, 1027: 5, 1029: 8, 1039: 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 }], # Ridgeline w/ Added Comma Pedal Support (512L & 513L) CAR.RIDGELINE: [{ From a51a60b5984ddf46623cd396afe3e9ee366847dd Mon Sep 17 00:00:00 2001 From: Vehicle Researcher Date: Sun, 21 Oct 2018 14:52:57 -0700 Subject: [PATCH 06/12] Squashed 'panda/' changes from 5253ab0..4dd3f5a 4dd3f5a bump version 6385551 Added Tesla safety changes. (#132) git-subtree-dir: panda git-subtree-split: 4dd3f5ac0101a6a14b003ecac1105e122a8f10bd --- VERSION | 2 +- board/safety.h | 3 + board/safety/safety_tesla.h | 287 ++++++++++++++++++++++++++++++++++++ tests/safety/test.c | 10 ++ 4 files changed, 301 insertions(+), 1 deletion(-) create mode 100644 board/safety/safety_tesla.h diff --git a/VERSION b/VERSION index 261f3475721dd3..46882bcf3de0b4 100644 --- a/VERSION +++ b/VERSION @@ -1 +1 @@ -v1.1.5 \ No newline at end of file +v1.1.6 \ No newline at end of file diff --git a/board/safety.h b/board/safety.h index 4c24bd9b261bf8..51a2bb8963b3b0 100644 --- a/board/safety.h +++ b/board/safety.h @@ -56,6 +56,7 @@ int controls_allowed = 0; #include "safety/safety_toyota.h" #ifdef PANDA #include "safety/safety_toyota_ipas.h" +#include "safety/safety_tesla.h" #endif #include "safety/safety_gm.h" #include "safety/safety_ford.h" @@ -100,6 +101,7 @@ typedef struct { #define SAFETY_FORD 5 #define SAFETY_CADILLAC 6 #define SAFETY_HYUNDAI 7 +#define SAFETY_TESLA 8 #define SAFETY_TOYOTA_IPAS 0x1335 #define SAFETY_TOYOTA_NOLIMITS 0x1336 #define SAFETY_ALLOUTPUT 0x1337 @@ -117,6 +119,7 @@ const safety_hook_config safety_hook_registry[] = { {SAFETY_TOYOTA_NOLIMITS, &toyota_nolimits_hooks}, #ifdef PANDA {SAFETY_TOYOTA_IPAS, &toyota_ipas_hooks}, + {SAFETY_TESLA, &tesla_hooks}, #endif {SAFETY_ALLOUTPUT, &alloutput_hooks}, {SAFETY_ELM327, &elm327_hooks}, diff --git a/board/safety/safety_tesla.h b/board/safety/safety_tesla.h new file mode 100644 index 00000000000000..a13e78f5a561c2 --- /dev/null +++ b/board/safety/safety_tesla.h @@ -0,0 +1,287 @@ +// board enforces +// in-state +// accel set/resume +// out-state +// cancel button +// regen paddle +// accel rising edge +// brake rising edge +// brake > 0mph +// +int fmax_limit_check(float val, const float MAX, const float MIN) { + return (val > MAX) || (val < MIN); +} + +// 2m/s are added to be less restrictive +const struct lookup_t TESLA_LOOKUP_ANGLE_RATE_UP = { + {2., 7., 17.}, + {5., .8, .25}}; + +const struct lookup_t TESLA_LOOKUP_ANGLE_RATE_DOWN = { + {2., 7., 17.}, + {5., 3.5, .8}}; + +const struct lookup_t TESLA_LOOKUP_MAX_ANGLE = { + {2., 29., 38.}, + {410., 92., 36.}}; + +const int TESLA_RT_INTERVAL = 250000; // 250ms between real time checks + +// state of angle limits +float tesla_desired_angle_last = 0; // last desired steer angle +float tesla_rt_angle_last = 0.; // last real time angle +float tesla_ts_angle_last = 0; + +int tesla_controls_allowed_last = 0; + +int tesla_brake_prev = 0; +int tesla_gas_prev = 0; +int tesla_speed = 0; +int eac_status = 0; + +int tesla_ignition_started = 0; + + +void set_gmlan_digital_output(int to_set); +void reset_gmlan_switch_timeout(void); +void gmlan_switch_init(int timeout_enable); + + +static void tesla_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) +{ + set_gmlan_digital_output(0); // #define GMLAN_HIGH 0 + reset_gmlan_switch_timeout(); //we're still in tesla safety mode, reset the timeout counter and make sure our output is enabled + + //int bus_number = (to_push->RDTR >> 4) & 0xFF; + uint32_t addr; + if (to_push->RIR & 4) + { + // Extended + // Not looked at, but have to be separated + // to avoid address collision + addr = to_push->RIR >> 3; + } + else + { + // Normal + addr = to_push->RIR >> 21; + } + + if (addr == 0x45) + { + // 6 bits starting at position 0 + int lever_position = (to_push->RDLR & 0x3F); + if (lever_position == 2) + { // pull forward + // activate openpilot + controls_allowed = 1; + //} + } + else if (lever_position == 1) + { // push towards the back + // deactivate openpilot + controls_allowed = 0; + } + } + + // Detect drive rail on (ignition) (start recording) + if (addr == 0x348) + { + // GTW_status + int drive_rail_on = (to_push->RDLR & 0x0001); + tesla_ignition_started = drive_rail_on == 1; + } + + // exit controls on brake press + // DI_torque2::DI_brakePedal 0x118 + if (addr == 0x118) + { + // 1 bit at position 16 + if (((to_push->RDLR & 0x8000)) >> 15 == 1) + { + //disable break cancel by commenting line below + controls_allowed = 0; + } + //get vehicle speed in m/s. Tesla gives MPH + tesla_speed = ((((((to_push->RDLR >> 24) & 0x0F) << 8) + ((to_push->RDLR >> 16) & 0xFF)) * 0.05 - 25) * 1.609 / 3.6); + if (tesla_speed < 0) + { + tesla_speed = 0; + } + } + + // exit controls on EPAS error + // EPAS_sysStatus::EPAS_eacStatus 0x370 + if (addr == 0x370) + { + // if EPAS_eacStatus is not 1 or 2, disable control + eac_status = ((to_push->RDHR >> 21)) & 0x7; + // For human steering override we must not disable controls when eac_status == 0 + // Additional safety: we could only allow eac_status == 0 when we have human steering allowed + if ((controls_allowed == 1) && (eac_status != 0) && (eac_status != 1) && (eac_status != 2)) + { + controls_allowed = 0; + //puts("EPAS error! \n"); + } + } + //get latest steering wheel angle + if (addr == 0x00E) + { + float angle_meas_now = (int)((((to_push->RDLR & 0x3F) << 8) + ((to_push->RDLR >> 8) & 0xFF)) * 0.1 - 819.2); + uint32_t ts = TIM2->CNT; + uint32_t ts_elapsed = get_ts_elapsed(ts, tesla_ts_angle_last); + + // *** angle real time check + // add 1 to not false trigger the violation and multiply by 25 since the check is done every 250 ms and steer angle is updated at 100Hz + float rt_delta_angle_up = interpolate(TESLA_LOOKUP_ANGLE_RATE_UP, tesla_speed) * 25. + 1.; + float rt_delta_angle_down = interpolate(TESLA_LOOKUP_ANGLE_RATE_DOWN, tesla_speed) * 25. + 1.; + float highest_rt_angle = tesla_rt_angle_last + (tesla_rt_angle_last > 0 ? rt_delta_angle_up : rt_delta_angle_down); + float lowest_rt_angle = tesla_rt_angle_last - (tesla_rt_angle_last > 0 ? rt_delta_angle_down : rt_delta_angle_up); + + if ((ts_elapsed > TESLA_RT_INTERVAL) || (controls_allowed && !tesla_controls_allowed_last)) + { + tesla_rt_angle_last = angle_meas_now; + tesla_ts_angle_last = ts; + } + + // check for violation; + if (fmax_limit_check(angle_meas_now, highest_rt_angle, lowest_rt_angle)) + { + // We should not be able to STEER under these conditions + // Other sending is fine (to allow human override) + controls_allowed = 0; + //puts("WARN: RT Angle - No steer allowed! \n"); + } + else + { + controls_allowed = 1; + } + + tesla_controls_allowed_last = controls_allowed; + } +} + +// all commands: gas/regen, friction brake and steering +// if controls_allowed and no pedals pressed +// allow all commands up to limit +// else +// block all commands that produce actuation + +static int tesla_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) +{ + + uint32_t addr; + float angle_raw; + float desired_angle; + + addr = to_send->RIR >> 21; + + // do not transmit CAN message if steering angle too high + // DAS_steeringControl::DAS_steeringAngleRequest + if (addr == 0x488) + { + angle_raw = ((to_send->RDLR & 0x7F) << 8) + ((to_send->RDLR & 0xFF00) >> 8); + desired_angle = angle_raw * 0.1 - 1638.35; + int16_t violation = 0; + int st_enabled = (to_send->RDLR & 0x400000) >> 22; + + if (st_enabled == 0) { + //steering is not enabled, do not check angles and do send + tesla_desired_angle_last = desired_angle; + return true; + } + + if (controls_allowed) + { + // add 1 to not false trigger the violation + float delta_angle_up = interpolate(TESLA_LOOKUP_ANGLE_RATE_UP, tesla_speed) + 1.; + float delta_angle_down = interpolate(TESLA_LOOKUP_ANGLE_RATE_DOWN, tesla_speed) + 1.; + float highest_desired_angle = tesla_desired_angle_last + (tesla_desired_angle_last > 0 ? delta_angle_up : delta_angle_down); + float lowest_desired_angle = tesla_desired_angle_last - (tesla_desired_angle_last > 0 ? delta_angle_down : delta_angle_up); + float TESLA_MAX_ANGLE = interpolate(TESLA_LOOKUP_MAX_ANGLE, tesla_speed) + 1.; + + //check for max angles + violation |= fmax_limit_check(desired_angle, TESLA_MAX_ANGLE, -TESLA_MAX_ANGLE); + + //check for angle delta changes + violation |= fmax_limit_check(desired_angle, highest_desired_angle, lowest_desired_angle); + + if (violation) + { + controls_allowed = 0; + return false; + } + tesla_desired_angle_last = desired_angle; + return true; + } + return false; + } + return true; +} + +static int tesla_tx_lin_hook(int lin_num, uint8_t *data, int len) +{ + // LIN is not used on the Tesla + return false; +} + +static void tesla_init(int16_t param) +{ + controls_allowed = 0; + tesla_ignition_started = 0; + gmlan_switch_init(1); //init the gmlan switch with 1s timeout enabled +} + +static int tesla_ign_hook() +{ + return tesla_ignition_started; +} + +static int tesla_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) +{ + + int32_t addr = to_fwd->RIR >> 21; + + if (bus_num == 0) + { + + // change inhibit of GTW_epasControl + if (addr == 0x101) + { + to_fwd->RDLR = to_fwd->RDLR | 0x4000; // 0x4000: WITH_ANGLE, 0xC000: WITH_BOTH (angle and torque) + int checksum = (((to_fwd->RDLR & 0xFF00) >> 8) + (to_fwd->RDLR & 0xFF) + 2) & 0xFF; + to_fwd->RDLR = to_fwd->RDLR & 0xFFFF; + to_fwd->RDLR = to_fwd->RDLR + (checksum << 16); + return 2; + } + + // remove EPB_epasControl + if (addr == 0x214) + { + return false; + } + + return 2; // Custom EPAS bus + } + if (bus_num == 2) + { + + // remove GTW_epasControl in forwards + if (addr == 0x101) + { + return false; + } + + return 0; // Chassis CAN + } + return false; +} + +const safety_hooks tesla_hooks = { + .init = tesla_init, + .rx = tesla_rx_hook, + .tx = tesla_tx_hook, + .tx_lin = tesla_tx_lin_hook, + .ignition = tesla_ign_hook, + .fwd = tesla_fwd_hook, +}; diff --git a/tests/safety/test.c b/tests/safety/test.c index c3f280644b06f9..c1555db5d57e80 100644 --- a/tests/safety/test.c +++ b/tests/safety/test.c @@ -183,3 +183,13 @@ void init_tests_honda(void){ brake_prev = 0; gas_prev = 0; } + + +void set_gmlan_digital_output(int to_set){ +} + +void reset_gmlan_switch_timeout(void){ +} + +void gmlan_switch_init(int timeout_enable){ +} From d0715b65623e5ace68f87702a91fb5178e05afdb Mon Sep 17 00:00:00 2001 From: Vehicle Researcher Date: Sun, 21 Oct 2018 14:52:59 -0700 Subject: [PATCH 07/12] Squashed 'opendbc/' changes from 42f8c12..62b7a01 62b7a01 Add toyota radar SCORE field 718a632 Revert "GM: copy radar header from cadillac (#116)" a5dfd4a GM: copy radar header from cadillac (#116) git-subtree-dir: opendbc git-subtree-split: 62b7a0115307d5ce84a887d5d71ec126eb40d592 --- toyota_prius_2017_adas.dbc | 17 ++++++++++++++++- 1 file changed, 16 insertions(+), 1 deletion(-) diff --git a/toyota_prius_2017_adas.dbc b/toyota_prius_2017_adas.dbc index 9d1646f04af4dc..4aae65aa408baa 100644 --- a/toyota_prius_2017_adas.dbc +++ b/toyota_prius_2017_adas.dbc @@ -182,80 +182,95 @@ BO_ 543 TRACK_A_15: 8 XXX BO_ 544 TRACK_B_0: 8 XXX SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX + SG_ SCORE : 23|8@0+ (1,0) [0|100] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 545 TRACK_B_1: 8 XXX SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX + SG_ SCORE : 23|8@0+ (1,0) [0|100] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 546 TRACK_B_2: 8 XXX SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX + SG_ SCORE : 23|8@0+ (1,0) [0|100] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 547 TRACK_B_3: 8 XXX SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX + SG_ SCORE : 23|8@0+ (1,0) [0|100] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 548 TRACK_B_4: 8 XXX SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX + SG_ SCORE : 23|8@0+ (1,0) [0|100] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 549 TRACK_B_5: 8 XXX SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX + SG_ SCORE : 23|8@0+ (1,0) [0|100] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 550 TRACK_B_6: 8 XXX SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX + SG_ SCORE : 23|8@0+ (1,0) [0|100] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 551 TRACK_B_7: 8 XXX SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX + SG_ SCORE : 23|8@0+ (1,0) [0|100] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 552 TRACK_B_8: 6 XXX SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX + SG_ SCORE : 23|8@0+ (1,0) [0|100] "" XXX SG_ CHECKSUM : 47|8@0+ (1,0) [0|255] "" XXX BO_ 553 TRACK_B_9: 6 XXX SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX + SG_ SCORE : 23|8@0+ (1,0) [0|100] "" XXX SG_ CHECKSUM : 47|8@0+ (1,0) [0|255] "" XXX BO_ 554 TRACK_B_10: 6 XXX SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX + SG_ SCORE : 23|8@0+ (1,0) [0|100] "" XXX SG_ CHECKSUM : 47|8@0+ (1,0) [0|255] "" XXX BO_ 555 TRACK_B_11: 6 XXX SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX + SG_ SCORE : 23|8@0+ (1,0) [0|100] "" XXX SG_ CHECKSUM : 47|8@0+ (1,0) [0|255] "" XXX BO_ 556 TRACK_B_12: 6 XXX SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX + SG_ SCORE : 23|8@0+ (1,0) [0|100] "" XXX SG_ CHECKSUM : 47|8@0+ (1,0) [0|255] "" XXX BO_ 557 TRACK_B_13: 6 XXX SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX + SG_ SCORE : 23|8@0+ (1,0) [0|100] "" XXX SG_ CHECKSUM : 47|8@0+ (1,0) [0|255] "" XXX BO_ 558 TRACK_B_14: 6 XXX SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX + SG_ SCORE : 23|8@0+ (1,0) [0|100] "" XXX SG_ CHECKSUM : 47|8@0+ (1,0) [0|255] "" XXX BO_ 559 TRACK_B_15: 6 XXX SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX SG_ REL_ACCEL : 15|7@0- (1,0) [-64|63] "" XXX + SG_ SCORE : 23|8@0+ (1,0) [0|100] "" XXX SG_ CHECKSUM : 47|8@0+ (1,0) [0|255] "" XXX - From 8f3539a27b28851153454eb737da9624cccaed2d Mon Sep 17 00:00:00 2001 From: Vehicle Researcher Date: Sun, 21 Oct 2018 15:00:31 -0700 Subject: [PATCH 08/12] openpilot v0.5.5 release --- README.md | 105 +- RELEASES.md | 6 + cereal/log.capnp | 9 + common/ffi_wrapper.py | 10 +- "selfdrive/assets/sounds/Icon\r" | 0 selfdrive/assets/sounds/hq_disengaged.mp3 | Bin 0 -> 30966 bytes selfdrive/assets/sounds/hq_engaged.mp3 | Bin 0 -> 30963 bytes selfdrive/assets/sounds/hq_warning_0.mp3 | Bin 0 -> 30965 bytes selfdrive/assets/sounds/hq_warning_1.mp3 | Bin 0 -> 31592 bytes selfdrive/assets/sounds/hq_warning_2.mp3 | Bin 0 -> 30965 bytes selfdrive/car/honda/interface.py | 3 +- selfdrive/car/toyota/radar_interface.py | 77 +- selfdrive/common/version.h | 2 +- selfdrive/controls/controlsd.py | 1 + selfdrive/controls/lib/alertmanager.py | 1021 +++++++++-------- selfdrive/controls/lib/lateral_mpc/Makefile | 11 +- .../controls/lib/longitudinal_mpc/Makefile | 9 +- selfdrive/controls/lib/planner.py | 3 - selfdrive/locationd/ubloxd.py | 6 +- selfdrive/loggerd/loggerd | Bin 1630952 -> 1630952 bytes selfdrive/registration.py | 5 +- selfdrive/sensord/gpsd | Bin 1171544 -> 1171544 bytes selfdrive/sensord/sensord | Bin 1159016 -> 1159016 bytes selfdrive/service_list.yaml | 1 + selfdrive/visiond/visiond | Bin 9122536 -> 9041704 bytes 25 files changed, 693 insertions(+), 576 deletions(-) create mode 100644 "selfdrive/assets/sounds/Icon\r" create mode 100644 selfdrive/assets/sounds/hq_disengaged.mp3 create mode 100644 selfdrive/assets/sounds/hq_engaged.mp3 create mode 100644 selfdrive/assets/sounds/hq_warning_0.mp3 create mode 100644 selfdrive/assets/sounds/hq_warning_1.mp3 create mode 100644 selfdrive/assets/sounds/hq_warning_2.mp3 diff --git a/README.md b/README.md index ae6b0ed66f6ca8..442fbd4470d1b2 100644 --- a/README.md +++ b/README.md @@ -1,9 +1,9 @@ -[![](https://i.imgur.com/VlKV6V8.png)](#) +[![](https://i.imgur.com/UetIFyH.jpg)](#) Welcome to openpilot ====== -[openpilot](http://github.com/commaai/openpilot) is an open source driving agent. Currently it performs the functions of Adaptive Cruise Control (ACC) and Lane Keeping Assist System (LKAS) for Hondas, Acuras, Toyotas, and a Chevy. It's about on par with Tesla Autopilot and GM Super Cruise, and better than [all other manufacturers](http://www.thedrive.com/tech/5707/the-war-for-autonomous-driving-part-iii-us-vs-germany-vs-japan). +[openpilot](http://github.com/commaai/openpilot) is an open source driving agent. Currently it performs the functions of Adaptive Cruise Control (ACC) and Lane Keeping Assist System (LKAS) for selected Honda, Toyota, Acura, Lexus, Chevrolet, Hyundai, Kia. It's about on par with Tesla Autopilot and GM Super Cruise, and better than [all other manufacturers](http://www.thedrive.com/tech/5707/the-war-for-autonomous-driving-part-iii-us-vs-germany-vs-japan). The openpilot codebase has been written to be concise and enable rapid prototyping. We look forward to your contributions - improving real vehicle automation has never been easier. @@ -14,7 +14,7 @@ openpilot is developed by [comma.ai](https://comma.ai/) and users like you. We have a [Twitter you should follow](https://twitter.com/comma_ai). -Also, we have a 3500+ person [community on slack](https://slack.comma.ai). +Also, we have a several thousand people community on [slack](https://slack.comma.ai). @@ -41,54 +41,54 @@ Install openpilot on a neo device by entering ``https://openpilot.comma.ai`` dur Supported Cars ------ -| Make | Model | Supported Package | Lateral | Longitudinal | No Accel Below | No Steer Below | -| -------------------| ----------------------| ---------------------| --------| ---------------| -----------------| ---------------| -| Acura | ILX 2016 | AcuraWatch Plus | Yes | Yes | 25mph1| 25mph | -| Acura | ILX 2017 | AcuraWatch Plus | Yes | Yes | 25mph1| 25mph | -| Acura | RDX 2018 | AcuraWatch Plus | Yes | Yes | 25mph1| 12mph | -| GM3 | Volt 2017 | Adaptive Cruise | Yes | Yes | 0mph | 7mph | -| GM3 | Volt 2018 | Adaptive Cruise | Yes | Yes | 0mph | 7mph | -| Honda | Accord 2018 | All | Yes | Stock | 0mph | 3mph | -| Honda | Civic 2016 | Honda Sensing | Yes | Yes | 0mph | 12mph | -| Honda | Civic 2017 | Honda Sensing | Yes | Yes | 0mph | 12mph | -| Honda | Civic 2017 *(Hatch)* | Honda Sensing | Yes | Stock | 0mph | 12mph | -| Honda | Civic 2018 | Honda Sensing | Yes | Yes | 0mph | 12mph | -| Honda | Civic 2018 *(Hatch)* | Honda Sensing | Yes | Stock | 0mph | 12mph | -| Honda | CR-V 2015 | Touring | Yes | Yes | 25mph1| 12mph | -| Honda | CR-V 2016 | Touring | Yes | Yes | 25mph1| 12mph | -| Honda | CR-V 2017 | Honda Sensing | Yes | Stock | 0mph | 12mph | -| Honda | CR-V 2018 | Honda Sensing | Yes | Stock | 0mph | 12mph | -| Honda | Odyssey 2017 | Honda Sensing | Yes | Yes | 25mph1| 0mph | -| Honda | Odyssey 2018 | Honda Sensing | Yes | Yes | 25mph1| 0mph | -| Honda | Odyssey 2019 | Honda Sensing | Yes | Yes | 25mph1| 0mph | -| Honda | Pilot 2017 | Honda Sensing | Yes | Yes | 25mph1| 12mph | -| Honda | Pilot 2018 | Honda Sensing | Yes | Yes | 25mph1| 12mph | -| Honda | Pilot 2019 | All | Yes | Yes | 25mph1| 12mph | -| Honda | Ridgeline 2017 | Honda Sensing | Yes | Yes | 25mph1| 12mph | -| Honda | Ridgeline 2018 | Honda Sensing | Yes | Yes | 25mph1| 12mph | -| Hyundai6| Santa Fe 2019 | All | Yes | Stock | 0mph | 0mph | -| Hyundai6| Elantra 2017 | SCC + LKAS | Yes | Stock | 19mph | 34mph | -| Hyundai6| Genesis 2018 | All | Yes | Stock | 19mph | 34mph | -| Kia6 | Sorento 2018 | All | Yes | Stock | 0mph | 0mph | -| Kia6 | Stinger 2018 | SCC + LKAS | Yes | Stock | 0mph | 0mph | -| Lexus | RX Hybrid 2017 | All | Yes | Yes2| 0mph | 0mph | -| Lexus | RX Hybrid 2018 | All | Yes | Yes2| 0mph | 0mph | -| Toyota | Camry 20184| All | Yes | Stock | 0mph5 | 0mph | -| Toyota | C-HR 20184 | All | Yes | Stock | 0mph | 0mph | -| Toyota | Corolla 2017 | All | Yes | Yes2| 20mph | 0mph | -| Toyota | Corolla 2018 | All | Yes | Yes2| 20mph | 0mph | -| Toyota | Highlander 2017 | All | Yes | Yes2| 0mph | 0mph | -| Toyota | Highlander Hybrid 2018| All | Yes | Yes2| 0mph | 0mph | -| Toyota | Prius 2016 | TSS-P | Yes | Yes2| 0mph | 0mph | -| Toyota | Prius 2017 | All | Yes | Yes2| 0mph | 0mph | -| Toyota | Prius 2018 | All | Yes | Yes2| 0mph | 0mph | -| Toyota | Prius Prime 2017 | All | Yes | Yes2| 0mph | 0mph | -| Toyota | Prius Prime 2018 | All | Yes | Yes2| 0mph | 0mph | -| Toyota | Rav4 2016 | TSS-P | Yes | Yes2| 20mph | 0mph | -| Toyota | Rav4 2017 | All | Yes | Yes2| 20mph | 0mph | -| Toyota | Rav4 2018 | All | Yes | Yes2| 20mph | 0mph | -| Toyota | Rav4 Hybrid 2017 | All | Yes | Yes2| 0mph | 0mph | -| Toyota | Rav4 Hybrid 2018 | All | Yes | Yes2| 0mph | 0mph | +| Make | Model | Supported Package | Lateral | Longitudinal | No Accel Below | No Steer Below | +| ---------------------| ----------------------| ---------------------| --------| ---------------| -----------------| ---------------| +| Acura | ILX 2016 | AcuraWatch Plus | Yes | Yes | 25mph1| 25mph | +| Acura | ILX 2017 | AcuraWatch Plus | Yes | Yes | 25mph1| 25mph | +| Acura | RDX 2018 | AcuraWatch Plus | Yes | Yes | 25mph1| 12mph | +| Chevrolet3| Volt 2017 | Adaptive Cruise | Yes | Yes | 0mph | 7mph | +| Chevrolet3| Volt 2018 | Adaptive Cruise | Yes | Yes | 0mph | 7mph | +| Honda | Accord 2018 | All | Yes | Stock | 0mph | 3mph | +| Honda | Civic 2016 | Honda Sensing | Yes | Yes | 0mph | 12mph | +| Honda | Civic 2017 | Honda Sensing | Yes | Yes | 0mph | 12mph | +| Honda | Civic 2017 *(Hatch)* | Honda Sensing | Yes | Stock | 0mph | 12mph | +| Honda | Civic 2018 | Honda Sensing | Yes | Yes | 0mph | 12mph | +| Honda | Civic 2018 *(Hatch)* | Honda Sensing | Yes | Stock | 0mph | 12mph | +| Honda | CR-V 2015 | Touring | Yes | Yes | 25mph1| 12mph | +| Honda | CR-V 2016 | Touring | Yes | Yes | 25mph1| 12mph | +| Honda | CR-V 2017 | Honda Sensing | Yes | Stock | 0mph | 12mph | +| Honda | CR-V 2018 | Honda Sensing | Yes | Stock | 0mph | 12mph | +| Honda | Odyssey 2017 | Honda Sensing | Yes | Yes | 25mph1| 0mph | +| Honda | Odyssey 2018 | Honda Sensing | Yes | Yes | 25mph1| 0mph | +| Honda | Odyssey 2019 | Honda Sensing | Yes | Yes | 25mph1| 0mph | +| Honda | Pilot 2017 | Honda Sensing | Yes | Yes | 25mph1| 12mph | +| Honda | Pilot 2018 | Honda Sensing | Yes | Yes | 25mph1| 12mph | +| Honda | Pilot 2019 | All | Yes | Yes | 25mph1| 12mph | +| Honda | Ridgeline 2017 | Honda Sensing | Yes | Yes | 25mph1| 12mph | +| Honda | Ridgeline 2018 | Honda Sensing | Yes | Yes | 25mph1| 12mph | +| Hyundai6 | Santa Fe 2019 | All | Yes | Stock | 0mph | 0mph | +| Hyundai6 | Elantra 2017 | SCC + LKAS | Yes | Stock | 19mph | 34mph | +| Hyundai6 | Genesis 2018 | All | Yes | Stock | 19mph | 34mph | +| Kia6 | Sorento 2018 | All | Yes | Stock | 0mph | 0mph | +| Kia6 | Stinger 2018 | SCC + LKAS | Yes | Stock | 0mph | 0mph | +| Lexus | RX Hybrid 2017 | All | Yes | Yes2| 0mph | 0mph | +| Lexus | RX Hybrid 2018 | All | Yes | Yes2| 0mph | 0mph | +| Toyota | Camry 20184| All | Yes | Stock | 0mph5 | 0mph | +| Toyota | C-HR 20184 | All | Yes | Stock | 0mph | 0mph | +| Toyota | Corolla 2017 | All | Yes | Yes2| 20mph | 0mph | +| Toyota | Corolla 2018 | All | Yes | Yes2| 20mph | 0mph | +| Toyota | Highlander 2017 | All | Yes | Yes2| 0mph | 0mph | +| Toyota | Highlander Hybrid 2018| All | Yes | Yes2| 0mph | 0mph | +| Toyota | Prius 2016 | TSS-P | Yes | Yes2| 0mph | 0mph | +| Toyota | Prius 2017 | All | Yes | Yes2| 0mph | 0mph | +| Toyota | Prius 2018 | All | Yes | Yes2| 0mph | 0mph | +| Toyota | Prius Prime 2017 | All | Yes | Yes2| 0mph | 0mph | +| Toyota | Prius Prime 2018 | All | Yes | Yes2| 0mph | 0mph | +| Toyota | Rav4 2016 | TSS-P | Yes | Yes2| 20mph | 0mph | +| Toyota | Rav4 2017 | All | Yes | Yes2| 20mph | 0mph | +| Toyota | Rav4 2018 | All | Yes | Yes2| 20mph | 0mph | +| Toyota | Rav4 Hybrid 2017 | All | Yes | Yes2| 0mph | 0mph | +| Toyota | Rav4 Hybrid 2018 | All | Yes | Yes2| 0mph | 0mph | 1[Comma Pedal](https://community.comma.ai/wiki/index.php/Comma_Pedal) is used to provide stop-and-go capability to some of the openpilot-supported cars that don't currently support stop-and-go. Here is how to [build a Comma Pedal](https://medium.com/@jfrux/comma-pedal-building-with-macrofab-6328bea791e8). ***NOTE: The Comma Pedal is not officially supported by [comma.ai](https://comma.ai)*** 2When disconnecting the Driver Support Unit (DSU), otherwise longitudinal control is stock ACC. For DSU locations, see [Toyota Wiki page](https://community.comma.ai/wiki/index.php/Toyota) @@ -103,8 +103,11 @@ Community Maintained Cars | Make | Model | Supported Package | Lateral | Longitudinal | No Accel Below | No Steer Below | | ------- | ---------------------- | -------------------- | ------- | ------------ | -------------- | -------------- | | Honda | Fit 2018 | Honda Sensing | Yes | Yes | 25mph1| 12mph | +| Tesla | Model S 2012 | All | Yes | Not yet | Not applicable | 0mph | +| Tesla | Model S 2013 | All | Yes | Not yet | Not applicable | 0mph | [[Honda Fit Pull Request]](https://github.com/commaai/openpilot/pull/266). +[[Tesla Model S Pull Request]](https://github.com/commaai/openpilot/pull/246) Community Maintained Cars are not confirmed by comma.ai to meet our [safety model](https://github.com/commaai/openpilot/blob/devel/SAFETY.md). Be extra cautious using them. diff --git a/RELEASES.md b/RELEASES.md index 6230b33fe05f9f..82f01208658d6f 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,3 +1,9 @@ +Version 0.5.5 (2018-10-20) +======================== + * Increase allowed Honda positive accelerations + * Fix sporadic unexpected braking when passing semi-trucks in Toyota + * Fix gear reading bug in Hyundai Elantra thanks to emmertex! + Version 0.5.4 (2018-09-25) ======================== * New Driving Model diff --git a/cereal/log.capnp b/cereal/log.capnp index ea7012bad397b2..f1b4b50b62510d 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -410,6 +410,7 @@ struct Live100Data { alertStatus @38 :AlertStatus; alertSize @39 :AlertSize; alertBlinkingRate @42 :Float32; + alertType @44 :Text; awarenessStatus @26 :Float32; angleOffset @27 :Float32; gpsPlannerActive @40 :Bool; @@ -1558,6 +1559,13 @@ struct Boot { lastPmsg @2 :Data; } +struct LiveParametersData { + valid @0 :Bool; + gyroBias @1 :Float32; + angleOffset @2 :Float32; +} + + struct Event { # in nanoseconds? logMonoTime @0 :UInt64; @@ -1623,5 +1631,6 @@ struct Event { orbFeaturesSummary @58 :OrbFeaturesSummary; driverMonitoring @59 :DriverMonitoring; boot @60 :Boot; + liveParameters @61 :LiveParametersData; } } diff --git a/common/ffi_wrapper.py b/common/ffi_wrapper.py index 264dbd7fcbd045..65b790a803469e 100644 --- a/common/ffi_wrapper.py +++ b/common/ffi_wrapper.py @@ -6,7 +6,7 @@ TMPDIR = "/tmp/ccache" -def ffi_wrap(name, c_code, c_header, tmpdir=TMPDIR): +def ffi_wrap(name, c_code, c_header, tmpdir=TMPDIR, cflags="", libraries=[]): cache = name + "_" + hashlib.sha1(c_code).hexdigest() try: os.mkdir(tmpdir) @@ -21,19 +21,19 @@ def ffi_wrap(name, c_code, c_header, tmpdir=TMPDIR): mod = __import__(cache) except Exception: print "cache miss", cache - compile_code(cache, c_code, c_header, tmpdir) + compile_code(cache, c_code, c_header, tmpdir, cflags, libraries) mod = __import__(cache) finally: os.close(fd) return mod.ffi, mod.lib -def compile_code(name, c_code, c_header, directory): +def compile_code(name, c_code, c_header, directory, cflags="", libraries=[]): ffibuilder = FFI() - ffibuilder.set_source(name, c_code, source_extension='.cpp') + ffibuilder.set_source(name, c_code, source_extension='.cpp', libraries=libraries) ffibuilder.cdef(c_header) os.environ['OPT'] = "-fwrapv -O2 -DNDEBUG -std=c++11" - os.environ['CFLAGS'] = "" + os.environ['CFLAGS'] = cflags ffibuilder.compile(verbose=True, debug=False, tmpdir=directory) def wrap_compiled(name, directory): diff --git "a/selfdrive/assets/sounds/Icon\r" "b/selfdrive/assets/sounds/Icon\r" new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/selfdrive/assets/sounds/hq_disengaged.mp3 b/selfdrive/assets/sounds/hq_disengaged.mp3 new file mode 100644 index 0000000000000000000000000000000000000000..a2e9eb2aa0887e7ba0fae8cdc516aa6ef188f90c GIT binary patch literal 30966 zcmeHv3pi9=-}l~gG8l~WIK(*QRM<1bD2Exx4hm5@q{cBxB1(0uIZ;T?)u==%>8x}| zM>8mj?sQY>E*T}MR62-g>~Bxp@AG}{^*vp^y{_+izvr3%W!7GMueE+_&2Rnu*Ioza zx!a%s#E9+z0aO4`0%8(ZMy^hZieDABDk>6i^I3?b0m$v@fDQ4!UJPFV0)POIMF5}* zNFGHckttLw2P?>mVrM&%J?8K1i+mO@1jvxYsBW&45nIoRh#kXYGU7m+h}g`Ud_uLS zet%+PYwz|wLUnhwoy=ovGZCTAqD|Ds{kt~*g}$znwILNw=AukS?4b$B?~OqMw^<&O zmHnM}miym%|9&FLI|1|Kh=e|=Ng0qbAZ0+xfRurMV+P={^Aq3Rp8frb8=Sa(I&skv zOkAa*l!2*YKq9#cHi9OV+*DC2#rZJXb7emE4q5Dh2#815(NTm>+5Clrtce+>}!)1^h7sQpx?8 zA8G28Ga!}Rlv64N{4oPk$^DogY3h_SAeG#dQz`}gF#}S`{g@wV>Xb78k5x%el1w?P zQow)CfW*lilO#*eF8y|n3`D@y$moIp}DK!*=^PX)yb+DIBRgE?%*+Tk z@!q)Q5uI(CTB^EedwA`|mcBIIQY+QI7p^S0X1qAz`YP)R?ix23hCe?zdblK>=TNSL z+`!kzE{vHhi&*d7!ONyvm?paH%c1r>ORe2>h9Q^c9gQd7$pVrv75czwv?VWTdz|AJDYM4Azh0UkXZ0b3j?p!X z?=7lffC;c~TSz{Z9YLNDiUzB`{x02v7 z48LM6UNZfa@h#)g0&7bCrmF?53yyYFxaU2ao_WX*-65<&cM9iXF(ksg9nET>h!k^f z2TJ!)+5;4auD2aX&@>RN+W`bKm4J=N$Bc+RX}M{4ks5#(Dl=At$(vQ&nteRg_ULnY~S+K=|I@!{B%C8GL<|!Hm?o%f^(J3=|Zjf&M7iclA7@E`D zXZvNNJapSDo~lEE@=sB{-%wK*5CU;IMp(A;^YnLF5AK_UfbZk6uNEDv`FQYM(&604 zu()(Q7anzi`@g`WgaG;<-g3SIg06u?a+YiqS6;{yZ-#;~B#0G0AHUpEQEAwiV}v~< z9PiJoXf^q&lY=YC^j?tIO(2%t@dkZYXUinmd&}l2x;LpE<-dWDCcQ=lSRSV(SLgRtnRSMPJz-E#mw1d zZ|;53h_F;E+lJUm#AWN>xOK1zF0EDVekAsJ|4Krb#D@5qB5#sG*?hi>poesOdgH;0 z<7Y^(!|V@S-KiZLTAb`ns~Z!@fWyXs ze4V}YHAK$N!`Pg?`KLds`_wFhM@mJdqusF21kj(%JLs9rwTOEh$kK?IVb`{$Vp zzC10=GVLStB&u~A>*WH&^|GEPoFjL>GTr{6>1*v-c+_TG`XSp;bmrvsy2zKzDFop&1P*2qoN0TU(yxs_I6# zPYs}&oOG$XEB?G{1S%C~Klwz}t@)~dj0MB%;A1c%^idZ43Nm+1g^W<@Sd4zPo;WSG^8HC~tn?h%kel$u>~l&RCsRR+UHXU36J@1lT+92D%1# zL*9%&h{F?8QXc9#zUnEY)HHh23~t$^wLxvOpg0o6YzEXpQk288=XDen_NZGHXRZH_ z(FBI+Qy{Vb3^D2D(DJT4aVDA0h)H0bHO8H?#wmU76)L9pFvc(N|8tptzk6sAcPj+d zCqnt@Srp+)8>fQ_PbfW}QP2Ty2eg85l-7~)Fw4k)cWa{|-cn83N*uSLr12?kb33Fz zvh#}BnfI_*%z}r;;BFXZtwgjmJjB-zljR#2DDW4$CXn8*6_vKw>1Zh)zQtb(I*};M z%Lih~Yp}{kTA~Bg(3u`M-SLYK@y}A^4{lk7gLAH&&w2;L-N?(q{{iV+_LyWqr}I6@ z1*BHqp@Y|5Kat)6X$SUA*LDQ7v<>*4CfPC!W}M|FtsSo!=UNuFu#mP)n%I*N=&&6R zsaGiRt#MZQ7B6=nGV!z%Sym8hmDpsK&+Tf%Z?4VwP?;>1ZgJS%VV~;Q8GrtQ7A7TE ztmeY|W-jnYWk9SQG?{)&oYEI}_MdnIp%^dv1=xSFBG5yW5YlN-gA8RtAZ9GVhC8Yb zZEiM(ba^`)=sw2lBSFO!5wu z;sbX*gol&)evIrK>=CBduKCOX?+Xzr@#~oZip@;x?XgU6baouc{J3{tl|06wHISkQ zylxp8jSbo&m#WyB4m5hgg!gv1IuBI~g)9ROcI$P57?#LnJ}3!@ML!i$lZMzXFf-&3I{<(6(7Q=!a`IQG7-m$(oD$1}0=l%@c?ya;6 ze$|cGx?=X|Hxwl9kiGD4BCJ@QI(_?EfZv!C31S-fS^{ z#7y7W^KA*@kiUy4WvmW<_gW&RcjX{p1+}RfL8|Gr^GDo1j;^dWqR)FSAE)P!t5rj% zU0G;XYIBa=6rLmp9+r{KBIgEeLkddlf19WHe(&Ik<8r90N_9MO7!+=}YLK;>hX1BJ zt^|iONW4lh}tKtu8a{1 z0vZ53rhMMaKPn+c-}>KKXJ>kjy;zg-50F#Bd`yO*nQ%dPS(ktFM&7`KWrOtkX$IcH zV8sNXD&AOBNc*nJNf%~{`uEtuWh zPNq9p^W;^grWX85+e*f5NY8S`A4_WJqxHM_UBo9-i;k&-T_aTxyVqE<{` z4YMY(ZX+)WD`A$!uXKRK$sGg0UKtl2+?MCgFl}Rvs>vSFeWwI-84$We2ul?Q08lK$ z3`*w|K%r?*sWF)p=V>G~WgW7%mn6hMY|sP)*y#fK>?i1ZY%^d>Wx%-yth#?F1{qT! zSB5RL5sZdbV7w{4vIdUnyNW3r!3+$V$s9%*JEDaE+7k^a-Te@hT&@={@^_=u-KmIGGUw9%SdCJ7)p{E%3Q1C(~Q=3yKY90R%0k z16vRW%(1m02+n_9elbR2kYI&Et1DbveHjQB`I0_w!?}?;yM(aqR%QeTA~Dr8tD1vK zubj*vYs5w1=$5Gf-33n1d2+eMX;ZLX@noZ>LCzaJn z?k-59%ea{3JNM_ingtlX__Xo+ijKHA{`JshT#>?^xtD6I(ISn>aTPD)n4Ss%PNJ7p zXW4-M2?n6Gg^hmPOy*f5&hTqvg?sCbgGPhrIeZN|SAYiyW=LZ6ClYjmvA_XP}^v7%s5P&HnHpWizGU=DuYm=gW;^$7fT1zfbc{TDQz}R6A;UY z!UWI>T_ymaQJ_o8APEKdI<70^?5*#CVa4T^Y!N*Qqo#(;>GdwDu8&J<=C`V5u;6i~ zhituK{J_4bMhQKume}@T8(ha)dRHQMh#OcqSKDO&A=74q!x(5Ok35~K7(ct=Igy~l z*C!vvZbJTzG=xFRrP1pRh$tm?LK&Xz`ap0ajZ8h4K;UbD$6^4QZmU+knea)#E`v70 z-A%gL#&o{G7@sX8Aj*N*M>Ai44u=M!_v|SObk>+Kb%`wwSWO;9?Vw=W9<@)neC27po(S(W!@04~j3Md_n4$2F5IStH3(b~Sd-$X79BT+pBg z0LX+!{wA2=<%u!7Sz+3wT7f=}>BHpt;rvR9!N^GepxnkXqaJQH^Mm_|g6Y(*FRYDc zs?o{B2-yHLo_gTM>d0lU{GU{A_SYORe=bKA(+ zJ?%OXv94;V@0;^EEwJkYiJ>nyT^F~t5Am;TFTD5p`1P!;G-@o{&vyKj;1 z80~39;c_m_UMpiqylHc)hVmqnLR?DqPWIZVlJDW`R10&&L&yIL-Ml7d{OxER(sCq7 zforZ*HWq*#0y8{GAgg(yAyR}9)EUMJl4TQ`l2p~rvkRgq{b`tFn~X|#rxjb9caMvg zU%8OXLdqld21-QDfI>M}puape*)Fpgr0^d}=JIJ~NkJ!JW#tU7cmEb3eg2(Gw`)cYP zwVL%Peq28&ODG4q16yfr39$~lN_8v_n+A9A;8VX{UU7Z@XvbgIHJlH=dFMZV5E)^` zr31)R1KD=?OwvI4lkAws`9dmB@bI0(&f(!<0WB4!?=s6n+yca*hTw zj@^{m#`RR%^auwM-HiYa3B`2ZH*b3tJF2>5y2jTK>#-UaSj^fLx=u|0#V($Z94OFo z=Zz{078%hXRuoO%EJaSK<2b!jUb;r|omZ+A2t&@ur1cUu*H$grp2po_3H8-GLZQGg zWKCZI5dkcY4MjAV6w;2?c9gu2%ySOuhCl9vm(RGqxeOZ3Ih`aapN)%pDS z(8!4W!1a`&{{L9v81Md^?)n(n4Mjl?9xEwan;BHSn_|cdMS}DgN{|My$6@%+ZT}d+ zYnR!a^t0mYTVYH$Z}^4&DZv9$Ktqyz=Z$79+b2u9ipEw~!L4-N$`%Sja}ly0NX(^pO1y zEqE>Yhhm)ca@o@wcw-j6-sOno!fCjUc`8c%USMpVh%s7X_CtVwi$v<_`m0bjM~;%` zwvOg&dd+3-jp>vJoE6Y*`b%g%P)lpEz5Ck6P@8b^jN4J~qqL`SR$n$Jp$)$-vKlIn z(&qX>$oX?S+_A^oHHuvRk|np>n1N}7%=_r4VR1X5=ob+O)|T&T4a>x!k{;eG z&*`(4BjL5fiRbcjV%Hwbsg$L2n^uH&t&M&0;`$%m6XScf3VUz12|b?Rl^=U&&sprGlU7ps4f#Bb-erV~7ukegXDhtOzuR z{TNac-ho1KC@ObTuuZef8Hnc^YHuvKchbgQk5Dw5GP1n>#i26iX#=wMH?7(q{V`sS z8Z<~EBuxLL(YOJ<#pYSVh-21soqmf#`BN&-v2EDGYt|Hvc7vs}_yBQe=U9sgbkI?# zUWCcsx^M{2x9&PV-tDsrz6TG$tBzIQdjx;}%qoZbp<9AIP_3Ys5(%W(_j|=U?P8yy z9H)msHEcQ*E?DPm9ud5qvOB4gVLfpD81;?l#)e%VHNSjLcj>Y2xhwulA{az3EVz2K z)vj$b0if^lMj4zY7}nh-1ggx)2I;50wY;GdPnx!u>&tMJ`eJk{@8}2@2U)9VvN2KLcl8N7kX?OS>3$bL!Lc!rc|8#d z#Xh3CeY$V!zC#Dv>gottf-;b@fU9n=XAhbjz?Uzq9$_(CW)Hs-v#@W)(bNQYPeqz} zg$40~XW#oEnFE6H?bPOZFGFT*Z#Zbe(Z;!}+_cK7Fx@G5^{D2|%u&;Rj*F?Iz4a=nG+MGObp3uJv4-k#jk$5@WoPW?rM|x!x$b`&ZI*6XSgYlH>n2K1=^fv z`XwpqPA|uGDu2RYWZas~ZdK08qBnu;Cw=6;>w`72!H3o8v$*CnP2H*etpv1?*OMn4 z6n=WQ#&T$@M8-p~q`f~S!AZ$oQAY+=Wx;%o*C4CbSoVU0oYIFh;i^nBC?<)1LCODO zMJS71E1)FQSxVeoIlEP7)ts!F@RU?kCUj8n1qxt?%sy9$4y9-`O!I(zJ)eEK;})7f zYfdVE6$l61VLtqtdM{MIMeobT(cfHc>%?CKVb8Y!i%jWDJ>dT*@v(9iVq7#bZ7(&zPO(92|Ewy0d6KZVJ zIAra*nrbV$byC$-hmdBB))&;X9d2B&K0Twr}UwhGe7MqV_YQN?*b?~ylRRz zJ%RFw&7PgU>VQ)(E{=+0ltM3oXUI{y`_Lkw4>ATW+jiOz?c_LjpR`p5sK$nbeBbL? zBk8R-Daelg+wp1?8`ppuu_%0$%grgA6@@i`}kIEZP4A06mQ_nhk&D`Y2?)<0q4$GYX=48 zV#vSgy_YaRs$4*SSvjoPiw*aMhzd$Eb^Cn#mMFL;lg zisIm94S*R>V+$&N8@hr>W!raoo`t{F6Vcwnqqqx=UDI1{D-J&CSgMsQIE3a4ui%de zx_|(|aqyd90hp`;2C;L1IMe88c;olsT%tB)vsSVI2Mc~yNk5%$a$sF9`*U) z>qhzw%1!9aJpwxZqbUr3l`%+nCA+mmdb70)FiMC{K4-2sOU^g!!{pOen$G*!;}{@O z4`QY*N7tLJuvC4a8lG?@)@RRx#vXcOsSVXsKE2>lYFP}vXx9Un={{R~%Bqw8?=Ym_o1{JBupFa2kq-n%2 z(`wjqw+syzRONxFM$~7vAR)eXO3AYK=gZ3g=Y2rv#&ZT3fWhcTmfSeoN6n-dp zUY8k8Re;+U<1KAFnrAxnWZ+{qq1AKiafGVb4X?G&!ebQ`jQD-U*vqjROdhX8y*Ae! ztp?<#iO97@9=Z$$Lv9B`&UyLd`%&F%zjXI}%9s!FdewUllld2RW-!2H8$;Qhfi3vK z2%N3gv%A{$Me1dB8kDG=^fv0TPZ#ey#iTZe@N| za0Z$|u$|l32zbn7+o6f$D^+}_(Qii?&NWX=^w)SsSX7K0mRwVH%=dm=jCJ^etU6T>ON6TOIr`Fm1H<_tO*czwZ5x zk0+nz)|y2cox{dy*5{;+lwDtkDup%SukiRfxCI`$V%^haFHD`$GcDsfcf_Ats+?ZuxMP&)AzE02BtRnFSp-@VCuWF%QBYJ?WZ$pg?k`8lq+v6?-UWo{HI@cNW}`(^?*( zZ#=hr@t!BXhaP9IKa#28I@@dp^QxSdtf=godY)g~Ww~|VjOsq9!#zH5R{YAmWga8u xhZd#TD{tb~nhV{+cQ$Hrys^{Nmiw;2{*srGNKRW)Qu<$Teu+P6q5m=i{|kH6n=1eS literal 0 HcmV?d00001 diff --git a/selfdrive/assets/sounds/hq_engaged.mp3 b/selfdrive/assets/sounds/hq_engaged.mp3 new file mode 100644 index 0000000000000000000000000000000000000000..dad247493ee82f85b24b4a54680ffac6f3a11434 GIT binary patch literal 30963 zcmeHP2~-owy6&t5NFeNClK??bQ9EH5l!ToTSp-x>rP&cd0cBJ~vmv4e1#tiH`hDwUd}u3-N}EB-PN`HRsGeM|F6HQ z#oNsa3!p;f1O>4GfDFVXhefZ94UdhE0$ly(p#=c?xI8FzrN1Y~9{>R$$lVtJG=R~p z=+$&4Ylg!Na0b)Xdc1nv@6~<%=FbD@;Ha={?Z*?=9L{*co?|6F^an2}qa*-n-M?j8%90553e_;fWq0{4UZ^s+E6Z^&=pN!x1 z;qkltDo0?V5E!N05gw{dPPvJKRIcay2*@e-eSGAl6OMqKauW`zT;cZ-kW=pa_{d8q z9057yCLB_^!tWy>r`-4Pk(W+50&>btIHYog-$y`Bx$om6FP(4%DZo(mzEBrnJa>{)lA9?A7BY+H5$iF0+ za8%_A|2_hvMy_!vGLZ<#{pv)bDcAKU5Rg;uPkk4F>Q@vpZW1x|KnJ7%xDn^3Y0y_pKN`l9;CYZE01{V}9jAw{#CG#} zzQC7702lxl;BZ-lgk*Boq{;BA)~f;V_=>?WCtnphuhknI+tL1 zf)C0u^vWI1lI52so1P-LXL$-OrghyP`E({?ueP+%_&GK~uqSH^g1jJDZ>xQp{>r!Xiia zI#y?;tLt4=ds~un2i|4NS&Ta`7iLAV7xn0>!^wLw#}46!_#fv$>jeeS8T`F)h}apK zXJH%bcRW4f(`H)utc)d40q-)T%PWKQfXNURSOysalTCo@%thNjwCx3-8)ej!pP4dW z*}Gk3G?-u4xaL{*bc#;EjJ#~o{(0_kzcBK>8T|nsXIDg*Y(MDkTZ&W-jBsC}gTIgd z8d;2Fn!m zb-G*GJLQVS8TD7Rn+znx zCQwTd2QKFE!9uu}`GoM+xf!3$as|lX8Q2J14EQ*mYj#cquVU5xr^2~i%LdZ9?~au9 z*7B>ie#t8zG3xCd>l2Y3#OyYV#7h(d6^2JCH-(3F(_{;Wroe6yqzZ1dy)qCnsQRWG z6DtbmjFfe#xzZ$SSKqOi8fn<4v|7;`^9;|!L>79of~f~OB=uUfMW?y>&ydvk^DihL zhf5cZ_kvzqpjMJCl)YI5HIi8oi{OM*V)w2{Mm7(6K{yBfAn1zef6<_wf{m#&hy*eg zQ_HoGp#Vm~_6Fg`0_yfVJ0*E9pQr7AkQfw#Aa78hklVdT|AsW@Cg_?%C-h?`9@;>O z4;R%lR`$JL88L6i7pRaJ18E8ut#XW2S*cgDl1_9oaBuqTyRhbCW!4S%1d-!g{{#Am zjX1H*4Fis+AC{eo9SM7Y^dQK=cBJQ1KUea{b{I6`uLFIh^T3_BB<8_83eNM|C$Y5M z6v4xodN4$)Gy84iwhY_dA8qN(lv6$V@1lR+^k6x%^*UEcXVvv-p+mE{gH;I9i*S*V zvAJ)*2SsA>&~|=7I0au6i4||#;8X4&d1-TIxH&cnD&+52tLf3$8rKu!WF5|6%sY3X z9r>(@WZU)eJ`IOnAK36a#3QI$;hyXzLm25Z>7TPDbI9CsqAJTs_5MhVPClF4}%f21RtxlB@-IG@A5nB|{N|x01}x zi_##8k6DtVh}xm)*ON2tqe(}-A!v5}*uxhCNa>2N{@30I>^Iyb`#Z4xF_`044!e`) zEF5xxeV);BP|A@i0bPhU9ldcgd>(KO`Zv15qr>zoI-7!9oI zDt)%zd7Os`!VN=Hp9jPyl3<#V#9!`C2Adkr_(1Ygz`eCMnIWEhX>158FJY5;{1@;#( zR|5*tCulYBN;QGLAoiZFphLZ@E-5}Hjs3qdvEL}iR%Q!F4$xibJvkeO)CpgVh^kx{ z_61=lr?g)T?v{K5RekSo0a&>9`MJ^ewGKqVivHD53tsRvBc^m zn?_Kjj;F7>6w5IWnWWDR`^*jAgsz~=k#`7ksdVgGCUwTc@HE9r__elEty_BKQ`=^P z+B!YjgCU=$82cM7}!!ji;=7lD~IF7e)M*+E?rxUg&f4%bib__6&FCX zaKG#Xc5(5*^xw&h-q8R9L5{xd0Dqim#j8C^u!MIiq*p5w3}7zc z17k2`cq3*QR7m#6FAIGv>${YC=|45eD*oY2exqCr*;zOe0Q!b!`EyGrE3V-XwFUr; z2BE~|O42{n@$X*&r`5C=biQwGAg^h9J~}$R|>qqUIX_J3zr{$DK0pw zJyiN4kZ~vMQ?Gm6z3Ur$5%1-pC{JG= z+wD&BGUY~{kU9s^w5$?VnAHWvse0|j-M&uGk)bJ*WSBR?S;V;7*3F4Y(DHa2^*-Mf`ys|f(&)*z*WI0nfS!@!g; zu+&YeDs4wYk3~4AaN2-om)K`~bTM_5-$` zU)?=x;|O=OKXlmtsqEXI75hKWSa3G)6c{9(3U0yv%FGGMoGtLW%6wOS49o&vgRbla zij@{U4K^$@5uodRTl-yA?D(6GUXM%dac$B|3hZhg)vc~PJWf{b*>+u-l2iSPXesr^ z@{0Kpm~%VgTWCDV2kQ;o(Kh4q7C{Ed-DU<;9^oY}lqDtAy_u_EY$YM&>DCM@P4eR97FfE>02{1Ipa@pv+` zNB!xXGpgn+J%I{HZ~;IOA3I&i9SzsqHGn}fpmcuJ9{euoFBO~tp9WJfbkGj>khzaq zHAf8}!eR*R!8KS3xQlN9Y64^|-~-uW=+Jb)0NpiIT>X3V(fdN=3r*8F3bW^3gcl9K zDDgKh35RvtA`kHQT5w<*MY4D@5nrj@VSs7X({@{h$xu>2%>+h?N2AjZ@&$|WGE>fK z{tZpG1=QV8$FIk^P<7$=FAI+XR-l;N8Huyp#jcaI7dW!uIu1-Et5H`%(L0;h*eCLn zrDw5E0GRF%+N&acr}~rtg|Z-Beu}aXL8$A=Q$xuQcJ zB+)gRC_CppYn`P6a^asdoA^dWDhi(FgH93%4G&@NXP-Js}uRIuFp8+7yi^d>M`a+BHCC;A4-|Hq> z8Ozpx1rS>-F`G@?`}9BAPU8#2PGXwjf)kj0b?Y*H5C0y%uv1-XOQiJ7?=Zlw)3d+o zj@eS6uD6`eBLl_+9B~Z|1byLs6~zipDhvs3GRd*n8h~IeDkf*^r2LCwa=JRsbO(I3 zld7aKQp}?!#cdbq;|V33dY?9s444ujwpw}#K{Uki0(y;j21kk@*(|7xU6)Wy&&)=U zul%H@pM{ePC0mfU$k5w07CIE=mlvDI(E0o+_Tfrj}2d%|9a=PBYdS7+#emi#1g zg`Gc>M7BX2+A4lP_8$Bde(l6vj6U^Z<%<@biAYO#4UUcp1B+-z7A*E^5 zVBFk*_^lNVeKoJPspb1b%_73B`Z%aZQGwkW^i6{E^Q(Rd4i4TEgGw}-2#$$aH4q$p zI5=}G94{rYB3*e4@DnrzxCv1(#0Zw8KJp1( z9lD71g_ZyfkR|X0GUY9TNIVdt@Bm{#ai16iV*~DscDah@X2f}9R9a@zJhqUYPdZfg zbkf0=J(CW1zF*gRxtA*|^=9ny)(nUWaMujl*99nikC9-+g)ddS$oq zh3lH9x)sd4dRM0=4Tn;uCpwx2J9i_~xUN+LIJ4#+YSM9R=`DN$T!UY8XO_rARLxR*^R{ytX*i|d zH)TieeKPBOBX`}V>6s^PI64M}+#hiM8ail*TpikoF6pZVt6I3oeKexHG%^DHV^;xE zFupY0aX6S12k+1#S1-I_P?x1Y4DTdaK&p8_2YOmS$8>Cv=qq9F@nPWYV&i!$0)O(q zr0ce+?-cU-Q)fH!<<^<833-X`+`>G37A(M>mCjaxs~f2q*X$l=Jb?5sS3gy#mnxx) zlDR+@Oan4hLLs{b_Pxs(iDaFjQT*L#<URmX>3EU9YDbJJr@I*;ktqYNZ}{d$E82U zQ#%)VJhBqqo+(G;QSQ*i3{;H{UlTOKE(Gn|2bo@%*I2t=djkfd&+1Z5>rKAvnhctM zqCPa%Hb}e6z>jP%tO?{XUcS}YTKxQ)Miu?j;Oydl?r3o9i9Be6&H-r9=DmLTz&#Vn<){IjQ=P=a;Hxv(r zG4}OwV}DR=NmNmN>4}NSp>qbcEU1fha~^Vk!8u>uvZ1g0r2glxw+5Zjeg~apH+Q0U z8SmenjGz+y99)2|<$|j>g0+NJYh$j9T@lG2>~rCR37Exb3^4#&u=m@0L@u0db=bJX zDq?lot5sExhMNPrKO+xklDM_GC;O)&EvwPJ)6qE_6Nx49IxNE<#$ZwXFDHI z+tFtqAjqVC<-3uXRW}QjbSo%&7P@-@H9|h$=cFnkYbt(!d0$}K;}+sf9Hn11Y#ta&j@z|maN|6P`Ka))*n!Tw3rs8>v304EF9Q3g`x{Q_^qjR zhxXcL+8LSuma8L^xJMr+AfAI-V2=P z5|=R>TvWkYzR&FR;Rn4R*-Y}LtxS_1Dcy8tvEE(Eio)s|1I$|c=KO4}?MvUaOb==R?y3O2jh{uxRl(dclkhAw`3(P2vpWNi-(B zswggbvw10K_3!* zg-9{U%14ElEizME=5s4Ca$e;7dpVI%2>62za4T2>d}b!N#MwzTv2#*fZZa?P_JHT%xnL--7Ni5MO#KQ=CNJc0W$-eM z)s&Azd8r9)_ict?y~oL$_Txv+BH2i2l?-)G=t0q^6m$iJ97G*dEPs)TLPGT+d{&(r z<@nQ|kDncUtmAXdS3y!^O2B^(d=}3U4c=hhv9Fz$1Zu*#wYJ?%9`k)}Zo~WiO3nv_Y>oB2 zSESsnAJlz5Qf8TCpGpZ2kJ3f?Ysy*vC8yW3RECTlb)Y%@G!6CvF}~w4Z3ch7I4m+% z4{O+K5OGL{_M_BEJPi^|ijCQSs-s}dWBu*VICWlrAAgm-ukFZo)^I$CHb=jgKyJ%+ zB4?H@K3 zqnnWkG9C}3v#7>{#M*EoO-(W&wsFbT^{ITS>tC~sW_LhItOsWp{OW!BSfLt6l9|u; zZ&Fu}bv%g-W;)lsdkF?|Y{7iY3b2H8kr}e(wuAkTg>x7LKPI=@2`mTpIb1KgIyF$W zT(pkQJhs({?Bcd?`#j<0ge%M2l4o{#-sr`2>Aa!^vbPp?itiyeUiztqe^7k0{?^=! z%U_OqR%Fa}q8#ZTO7l@mVu+0BGa4CvI^+Ppny>mDWM?|Np1iD2-)AyiZAbMb>vEsk zZ35|KS_w%}Q8VA|aQp76uXB|T{D#MrG`Y9LoqE;7*lZJY{&n{T6aX|>LoY335$h2i zHd&h^9Cm;mI?d6woINEg5v%&X8zanK#*tZfAYls;S?}io-YEKiNddLt22hoKm6`!T z^RjnE%}M>)>n(;D~GbE&o-^A^qPV$ zy3q(6`VSC+im-u5h z3tlc-AGmKNbINX)U?r&A>WcWn@OmPN@o>+W(LmLeBC8qfF7QSr~O?o?37?N(QnJW@KgL!LxTv}LIs!1BP>t<_NCtFNYSJJG4TSvS-FL3 z=vpoW4k+==;U?HCb$Q7~*K&}OAxB2;_)D_vZ(bTCD{GJfyudG}d8YS{F{{t&**STV z!LwL9(2@NKb-R9`5?jSl+4l$6rPBl2uTrW?(U}{UgNRIsqv>c6ophg(ElkfCW~3k7 zQ*IR55wyv5HUFBGok9(bz6|uG;P5~*=&l%Pd1~fmr6I2a1!)0PFC~ncx=QAb&90t1 zDyN|eccEYQJ-E(2h`i~lYDQi3hFMtN0&TKTEw`DK72xV_$HrO2t&3DTWM)MmY2a`{ zz&p@X!h^(Q_92=oJw&V` zF)r??NxXJZOIURab^hamy2ru40p*{47^fU&n8X&gH%XRAJ*nJB48ky7hMwy4`Z5gB zQ+@w`R`YD{#xz~9Ui!zExTPZRwJ0G zH~c@H=5JQcgXAP^ZS48_r}}4_TWCF*VcJwHBs)0pw%e$0{=5 zNiAl1IArmKY$8!biW>S3M@ga%`re!T=}CCi7h5GjB*qMHg7Mh+z&0t7onag^PC12h zIqsQ@A>ivBQqFHafEMo;TH7Z;nOJY)`4bP2UU(W^EIBgIh6F8!LhR2Iep61D36$sA z(AlmQIx1HDn`AFz=Mloi_$ckCcec!+O9U=t)gqUYBSz-Pyah`?ZSx9s4c_imDQwZ^ z?@{}5rfvf=f?R1mOo*FV=Mxf9>7)!CYN&oP%_XZ=(+CCU(gWoqM-o4^ugVp)Sqg|O zlV>{g8x%~msH|O^{aod?8AFijqL(fy%b-X%Y$*RIwm={h#QfPSGSM+@V>7@7)D)4*8-cI6yBCAQ`qJp-YC z{Bm{~L3o>2M&MWUbz#_8BXtU=EREl!3{)Itx9S@*&^jsGwjI~Bv^;Kk@6fhw50AZR zY`Kwgto%m84ep2X(1mAgk3Bs0bK@neC1vG59Ba|EtZ00=YwDe2mo%sQ-$>h)*l@zt zD#$A3*yR%mjcs6A5?E*fgAYRbFG`YL#+`_b(ZtQOZpkRU!W? OIR6rk^2UD}f&T!Bmf2|l literal 0 HcmV?d00001 diff --git a/selfdrive/assets/sounds/hq_warning_0.mp3 b/selfdrive/assets/sounds/hq_warning_0.mp3 new file mode 100644 index 0000000000000000000000000000000000000000..5dbe1a4aea9177869c96790e877e5cedc65bcaf5 GIT binary patch literal 30965 zcmeI530M=!y7xPKzyKkD1SVn#sDN7~>6Nm-wxn8_ul6o&pdPZeC~HozfY*HuH~(&U;k58 z-3c(++a3?0M)wK{;X#l-6q6LTB78|gY{J4Y0C`OdK(n9)2@7LGmL-V&1Y!t4P>4?; z1Q|ivqy@=rE^mVC1TcZ?rb02nHe!T;IVIFYaK( zTi74r`Z^C}@f@AJ2eSm9t2^@sT1)-h+VlXi@N;Vb3>N1OMx42Wtqt@BcsY7I4HQ8W z`Xi3spUZwu(H8x$W&Yk=!+KdT-$H4Loqf zLX5yr5ztDmSc-bXBsWw@F+X1>fJyGle6ZXhCxA(A$dO_Wzf1s=+?V-axkF9>liZLa z#TRIasrs- zh8!v8@XG`+$$gm*mOJDGFv$%$Qq19(31E`@G9N5=$O$05hp}&x3^`TI;Xfvzo#ggv zv$5|k{bNX2&QKD-*43e;iTU~y1Te|{2}oFxp(KDwZYXJDzWxLOOmcq$5>{j=31E^N zN}8CjKS2PK+@FAi6&Xqb|4?$q{jGdcEgj0%{(tp#m^nfh4sWE%4vOL_Hpctmv&=|> zfuu}tP8Q4~`y2*zV!AGwl4ipcQEo2X^&@=SnV@?tSMqc?#2W?IuZQ>=p9|Ka3J8)N z+m(>osF`JFs=l0FLq2boC=mBmIRN*B=m(R`b}h*Q3gyHO_POE?{n^9W)?ho^JEf1j z^jZ4F%qH1`?kzr74K&-g_Ka%(?FWCi4g^6ozm?g|$qSCP(#GX(38~cLF#pE&%#H0% zQ)tp9sjKO<@$o#>dTOCrq0uOOr-R>S1+`<0&$jVV{@>DH7~sO;Mw=uFYbnhJ2Bpxs z?Sy$tV97IATxOduxy4n(At)xA>bHI!`P#N~7=gu6^N5vN3IRIb0`Etej)%4Oa%+ZqCe?x$!e*yN|oF zjlJ8A!L4Ny?Pc)k0@KU3$8WE>p9u8&}Zu#4H+H+)gXbC1uA+4Ak7V zST+6dlx+NA-LrfeAVLOqQijA->V$`muc{hvd%f5M-xxN`&v1j^FZ_Le2bMl)f9w)U zz8~}6;qLWIOZV&zy>X=@sXhhm?h{Wm(CkEmK5Yy^%A3z1$hH-ax5QtKNxpW!`@F{} z4ykB3Sg(SCEgyiz)or}{Cp6%RbO$(&`woayJV4`H1w}$ks0qT0@Lg09P72N3|Eg*G zqHyteQde10`;|_*o%^cGE)^dY>5|If8ZKGk=SaVp2Q3%+mgmum12F$K5d(>b%&w^?Pj$E?e9A2QT|&KQ-y(KHED8 z@+L*=No$WL7i>)RD$q(!B*iafc*=WYVV_+$#VI+Xb?*9qGI+ih$D^=Sno|V<;R5E* zLU>E_3AY`;;y)G~X=`UrhNB8b7cp2#hMBfZ?zt-m*iIAomzR&qS$kiZa^?>6e?EpiAA`^u<6KYY#Um%CPw1-`9D|1L|q zADHiO!9ItKfQdpT*Ma4o20D$;vXdgtrOP{$C)9r1b+ofK4DICK?0HZ2qQ(S~5q$?u zPqtb_)072p1aCzQ@z2@&Y>B^QI|XoKjM+`$_w6_r4rJULUYTV2x4J!Oto-S;64eD` zsj8Mpt=VoEe-(N~yXR?TCAcq?^`m1kPwAbeaXutM8qFw(Ni*dOvL|-ysy|)4eK9ksM$MI`>X#Fogwm!l zuSahb#gF5;2$Yk{%qPGl*$tIj!jPGW2Kj7#IrUiwr-=W`vNbTv;d=D>@=vxvAZrk( zq>t9=a_ceZwpLkYpps)1{1w0dx9ZrB!mD-hr{7&*SV6R#{qFj-!VTv9&h=;XT%}Ra57H3a5h))^V@hs@Ziy&Injh}Hv=!=KhYo&KW~ib5)UBnO~UGQmcN z9o{H^L&jAM^YSmFK}$&xM8JiR*nq&da{ShOma~{v$&Mc$bBPTngp&xy#z5h;jJ%w+ z;L7H)>xeYGWTgEh`>gC!fi~;)ciGZD98(~djk26YcN3LOy1s@XRVOQz!Hks+JH~C! z-GVgEJ=nP~J0OsgKiRqpxzjT>YBs7U^a{^eW#y9+l~#9C9vWhzGV z*YW-E3j0{wQNNUl0;ZC#uB*L59%(&msWSEZ;q+SyDN%~&@ZmHZ39i)#muuF5B|-qI z_?f&cC!tHJpc|N_c7YnfdEmtV4KGWOjFZlhjD-^Pp=&gJwq?)$;CO+|Cf%V)XxR_Sj6e=v<7a_E9QsQ??A>~Itw4O)hzuX4tR7@rtbUcBsQ17eySZz;O$V&uq{@9A5t?KV^pSHUQ za_23A{J#723aF17Jc5v(B1gSXHQSGQ|QuHP65;5_O$*qs2w zo_L3r5Jz9VS@y0ujvcnoTC3H^MmQxCDA34b_-*=f2&N=4cBjd%WS>1=Ki56E#%!TuhuNo7&kpQL%Db9x?17r?qHGoYTUzp#`H!kP;3ZU`(>cbM=r3{XyFAPCm zTz!x<^SUK~`7?pFstU|YXL7fGnB_2q;*IY3Y#pz;T#8KwX4z{da7$QqK6t5xt8N4o z)?V3@ZPEBUZCF=~dX$Qjy{+&2+!)KeY)AT%z_NEvZkw*u*KioL=rN$+U`D$jQLS_I z#)sz?)u(s1YK1jmJuW9^+BDVSZ$_;%@Mk}^?Mhg8F~B6FjlX>z&wuQ~5Ei*=bMYFJ zbq@5p5n07-h0U@{lEOT^v)%rBHz(?9&#J19`K_ocP3xOgDM;`0nXlRZ8r{KJ&P87! z@3jT?f}4rjg_SsoY|u?q0g6PWDZv(2h}$Y#2A04}xqN7a(@3AGo@uft+_iiQ8>24O zcTidP7CoJc>ZXgaNe+Kp-&)_El<@psiPQVN#U4&SzE8Q*zxdrj(ADqZNU0xQ|JH2-iH2DWfGwy-pd+E)<+H}Dd-+0c1TP*>v|F}@KsK>dp zbHnMdE9hnxwYLRREYB1;g->G6t+6jW;u*d5d97c;JWCNPb?z=sAVTsB}w+xn3mGJQ4@zrbYMX5|JSnygMYCZRu zw#r`%4cThu1o$R1Ct~?l`W)d7a(hz2QGqE_#NJR~E0tJWEIbKs z5hmLGWMW(H*ZZ-x$;lYmc=W+>*J(Fwr`>tkFP3Jcw+iVC)$B3+;4If?n{PBNbFSGy zZ=L?ad(3NdNY9>DOFTvfPz~Xl&PE)KY6L0BHMnhrAPC9|x=Uxb3E7Eaz6*;^*!Hwy zdxB%owCJlJCpjaBG|1l1T}9s%t(sN@`Sfz}(y>cZ0gq4teodVX9{bT8+m6qgbf#_< z*9yM?tcAOPyENTHQg2%LbNvW&%SrkVU1?LtU%mSF-ZRg~FUa=^Bz?{F{?)24?5Wm$ z(ceWg@O3#{x2_PqV`T?KG=P)^E_y+28iP#%DtjHas*l$8_tO8KG0-5h2QK)9Ai|#s zgll#<9i2Q21mKgMzAvht@)|c>TBowAur(Lq^S!EfTZ(^iNiV4La5|sK=RDaLJ?mAK z7CD0KA6Q}gqD_jJZH?cn^<+O~AMAUaz2S-`+f*qR$(-z`L^V*XIF#%NGYjF~c`t6r zcKOVh5ky=~%?k5x*H@Dwb;``H8bbkA%gQGb=6_Jgjl4%)Rcw+^4|wf3ERsdpV^o_= z!KoIs6hDv4FK7@wdaJ#c_`F}~o!-0OE_{D#U3iDoH?jryFj@Lgy@q8#i{i)^t;uI4 z7M@>ZsE*288WE$BB&O-kTV5U)`s2L0)!vlZ49b#wQxQ#WE9y@(73oC$`sRlGH8p4_ zxxElRS$o4e88};_&qx%bscM@ZgZD%kAcYAuZP+9SfiT>+AgVeLbW?onS9LeL94Ci! znbqcCiHroC`H6aq>`EHP^CI)=aw6(Gs+OZ$(Y_S);%Ebnrp7Is$+xGOiBDy_2q%h4 zJ!>ziQzxta#HVO1Xr7vuIKg1-#bp~hFD1*o=D0S-jUm6cKspnA}s}J~zSa@aEbC+=eaM8M0mHXpw->yZQ|C>EszEQu#VmiUb zLQYvT>zHe#)ZV>>%e^xDc4~Q-H2C7(jfh;Pte-rEzQz!{gJC{yVK+^x?&zT}6-mo4dy1 zwc?ZNq{cPsF>U1RIFOq=$}aBm1;c2yoFAO+N*^a0360B*xa^=?Tc5Fqkn0WU7Ovl| zcPp>s4btP`zCr8HO0(0iC*}RkQQ&sXLohpaB&hUx%FD5rxXrAe0AAq*V4eUE?4Tb! znt+Mx97l?uEl;>V=6Ira)=)06-+NVE#{6DFKLCH0(tdu`6 zTH*)47pHt;P-9q64G@k1lD7zuhnVCba9(;FFmdg`EZv3s{VI5pe8rw&N9O{LA^Lc0 zGZ2vp1c}dXd0am7pG@=IQxuy{Bjcn%KQ{H|Sj(T^|90etyB#w(zc9UM z8`CBITPW5K%O{%hgYbouM;k-213L_5`ew!Ua0+j_J<)3(@xA5YF%e8Z2V zeC=yhFzK;Aon1${IlP!8X87V8hxy$r&Zj;ZyZ^kZA%FAPy-|HtgC78B?_qnK%74nw zat9J2er>qDY;;5kJ{xF{iPB0X>Q5YqPWh8g}7OfL9_^$9g-sVu%0tw-bQX? zk+m_AID!=C#<9>d(HrhQ`@sxymS=_cvBn$PF1`xWK674nCL?y$Kat*`}zxoxbY?oYAP7c3#$tdw_?-@>!DNqJ&~~l|yd0!TO@TLT z=IXu2PE6dEy?&zEqb#Go7W5MQ9;Uqz+Mus_U)AAz%Y5~1Sao_0j_a7poX5+1o1VnA zZ7k-*OeE_AqsQb9QoS-SEnf0d0rxy%u^=7n+;a@AyBPf$2o9(gK`UVu*+$jHVAX%z zarhGmVdq<=wICtq$L|ng|c+zX_9bVo@8e1 zZ}F4$eI>infCS)&o8ZAYm4n2;G|MhzlG_O6+CNduznncNIV*~@9J#6Vl)URo>0wYx zSoaJNJpYh5{9`M9Dbl zuB1eMCW_#uyJYc>`0h^&{9i?Amfg;=e3}ujgPua<~Ys8$kgNuGr8IC-N=obnM)m<`77YuRyNeYl9^WhlI8oZ`!Cx z(n{UexHrT|r~wx=#-AD34w@WG=Uoa{YC)<7Zo5IX1Y5a)=#?t#z2rqlkpg&?h z1+ObHk-n2y5TxPpyB!vv2=Ik010_VAbr4$^6||h5lRFvydfNDZ)Y72jh~#qlJyJf|O6iL2Nx-kwP?P=bp_ONhLQY3hC;eX4*V59W6mmHB?-U9}T1`z20=l}oUhsFXmCWO;y&&d{^pWIOcxYqtgm?@tiw0M_lI{sckVf#*5ou5Y9#<(cCWDA2jf4d~1HX_k5i5 z+P?XR#A8j?pN%+@_i*aVCMumxCk#jq>O>{ivQqhtR&pyDriGlxdWSDua38;2RbF@! zCxyeK&h7o--m^kpR5eg~O-+tAREzC9yD6Mp|bIvTt?(2m&M9U&N?20<&lwC99+4b)$Nye1JwKV;RW z{V%a$>v$zOr)qY8D9lTW$ZbltwzJz^;_4M_p66(hza)0VlreWws}H&cM*257dt?`D_(iCxrhOPVue#rVUXxN(k|wD&+e`_wyb%+nVuE!vLpe=?D_}=MI?+=X z&8LSbV%}`=o9@)MH!%3Nz#qId2+|$n-O=Qxd=z*4ff3`RzH9Du?<)@CYmUN$t9tGo zp1*&_zH6^o8J7LSv8~&a$-qHUbZA68!^fmQg48(d>Zf7%cB%Y?BfLVLjULg`hXHZUyRaw%_06MBovfybV^~NHVp+;dhq3p z{`4G9wi=nPrRSgLR=PiBOR0+%sYreK`9SK{88fQX%_!>386vf&dHU!)j*r=vQbe8i zzeHJBH@*ge!C4Ob&FQZJ8*4*L0FxZ1gRe{gliXJZjx~o#4%5I_CV)xqD+9-x`wulk B17O$y8+tH_sxutGs81qXUzMMd(XY+ocEmj zd;gqs?jb&g1$p2g%;`3(v-%UU-xp(u?=MFmoz2t@+sovqc3FsyFZa(_lVJD!M+^{3nJA5|*z2x4_ zN1r?F1oV;{cBFcT?V3Tj0lnnj z1CqYTa1zisy8pBHEC9KeoPYka?1(I_)ZN?7jUgNxfCZ1Thg7uwt~yj&5Sk zTk2eok{0ufs5G=^mC~_d^y)pV3~GT-GurvacGsoWjF__gq)$=I1djwce!|kn)3J2l zv!2iQ?O^{9_To-bau~hQA#3t_(;oBEZ|hCrwaNp=<4RMdREZ+3}omG15DUJ8ZN_9%-PYJCQYz^- zmBUY5Jwg1OAx07Y+JTQSe2(ENetj;V_= zAg`~KUf8SoD>&(A2jOftKXo^CkByA!5zh&+xWZ7ysm$rsS}J4|12u4rAPJj5dqA&f zh2=c$l9mQyfuuGh!ZW=VNg+_Hl1MStU1r~(`_`WNkTp$s#lTThJBF;PI!Wk27DCq$ zL)Ze@1eYRn;ibqlXxH>Pids+9dZx*e`O^a~wC&Hlf1?nT9&%R1Q$XogtSP}32bb=$ zZ47FEl>hqhROMj1Pjj=c5=A?)1o{;Fyv~1foL#`q-@qxk zmLI-gj(X4hqEXeJ)AIQr8%4x!iCYClLqq|Q?k+Gx;_ErgF2S^x)mO;zQOYxoh|)_X zQd(8`EAb5!0Te+M5P4Ptg3wHWM@ZK`ou0C6hrOG%!ouxht|`}xJF@f;$0jebdKNpR z{0*n{aqzLoh2m+)BEPV}eim6orl9D;jpBu3tXF?&pSvArf6m_1oj?6?&~;@Ny~cKj zf)Si?;g&BmMqaYo5^r-hRL!B7w1>c6lmk_Lo?56aVTXhh}S$A8yEf8Jo68_dJ;OqKnZ!2UHv_n+U^_BSfyW+9WzdJ;Cu7+Pi(5 z(k@c=j8Y)YHaH-;i@zv2h~wB3prol1Q)nen+Z|YC8mKC+Mt4;n5SQPjBx!BNnO?5{ z(Z+{^9(2c2BpPZ%EO5QZEFurNXT7P(^+9Qk8+8-1o1j6WaZxQ1USwJ}sFPM-I{4sJ zN+nv6iaroO?GJB%`)0^Z|1;J5@f{rHaI5G6^6p3^s^)^|6WKIUJ=fUeMNpMBjm7Wd zXy4D%e{(4i39*5#Q~@?a?w~q=&vkjl0Z>*qcb~ivWW(PB0h9{pk_s?Rk^vkgo1EdQ zu?sf)eezi~^ZAd@A6yl8R}KZ{HN!=MXP6?bjG4SGjClvl)N_kG88mhTL! zZMp%=Bc}6gN*_5%Gb#w_(OO#@A1YaBBKhHwDMEGBP7bPw!_i?x2=jm!B7lS;_-0ci zMh<)~BeU0x77&GvP>{;XXGBSW=!g2P2~=8-vk;uJc#~`!6RMT;ZKd8mZnRUk`->mCD|SkcVf)P{;6a5+a4?tz9K(?Iaq8 z`XI?SqK^?NEk}`MFAtUxEr5l_41yTTwdSyNC9c6X9*>7J?o)hnGeaqm6@*y8G728S zz~dElBPC|QUAyix=@-n@c3zBJQfo()RTFa}irmWcM_tazMkcbWPUzSO=PjLQBGR#0 zZI-a0fI^#HC+YYGxBY2y+oEg7UevQP1Tw1}_fO}>Rz5Er9~_)nOS_zR{V4jH)({xl zco^-gL=S&%ooaQ=eCK`J;(d^F>DRW>VOWH7x}NK2tB90^9f^V8KfVF?N zWE-&LB>@&s2yloopdqd}$&!p&Zx3)4I3|u1;ImrNWo;Cap^1U()N840sFkNd+)WT*rwcd6GDPZW-n~r7Bp)V zEP@#egbfT!O)SIbKm>ytH=$^C(w7Bwf!XRnM5*?c)T>88lhlU7sSHc)L^XLYO{_|Ya7q|R=Np&1xCO^ zV8J9Qy&}}%?9c;((;e8Fhc{Mf2JB`^(;F?Rn|iCVqz6jsGV!k$)%?;NQPP*t&wlKG zxw52rz}w(FilT3Zao7c((5JwfcLG>erGX^|8@y6BICH1T-GPAb2G~&Hp~pEuO2<_6(zI6>$jRSRR}#&JGI$JUoDbdTicMMzTTs{3HpuNjrk=5 zmPDxyv|6*R-NOFOg~FA@6TeEQ;}8iU9SOvZYne7dA(?wlZ9uDxw2xadlV9l|h!K7vFcbMxiHMD$ zAMe>IR|OKR_iYxVsLH#mIWZ(#-1r2mt+RdY*rETC5mKcX5N2LbJd&U5sG`m8a z=xoU0QcOC6sz#7m{9X&~->Uav-2=vwR^W~#0dHs*C=J*-rDn_m?pve{tb{^125k@N z;Nq67+W2g^pk-z3`SoZw1+{zfSRDS{K$NgU;u!4Ew~vVPu~(4h+Y(6;;*)GCNSzSuV?TI!sD&a3R0N9 zf)N$QwNiu0E&{`E$k~!G2tU$PlhS`@eN*n_f=Ss|7QXQ5*mOPozV0<`zNW|dl1BD$(F=&=F>Y_UnRJL`7H};Rti$D}^-%d^(7iX(Hy$r`!5`s)jxUUuSN6^-O&wlpFy~IlK^>77znMx_DB@Yq?i#z6LA2qhv-<< zPgeg!4*x3)113x_&rsW&z1VV#QT$@g7PW&Tsy0R{8Ah7;eKSG~BhOPt@Um|y_Eg0d z{~n#5fi)^xj<~?th!Y_QnPqsPs>HFjzjOz+nr1rrN1K{S$Lnj;-GvPoH5D>##kTAB zZoi@YUl-WeqjZ$3s;E<`gs|G`yUr$sv93xxu3;v;6;LE~zP?v%I`R!H&#Nw%uRAmH z876SufQ8vBZ0$9$gF=IoglpLRSzE!OT>PKknmSR6LgbLhb}f`m3(Pxqub2jAWG^4L z@Mhz)M}t+dW9Pv3#~aBohjegWg*!?9^5zCrfHWJ3WzMAg_T4(ky~1nw&)Y(Wxyk=P zcfg5KV#sU+qwVAd!8d(b6Sjd$`BY%fcg4YD6A#+*GUjC#ZZ-buw`gIB-N2F(PnBAN z6sH>Fq=JbDPJYTw%NPy(sxp8HbjE!r^dl^k&f%Z`G`GL_F9x9pIs98ls=LxzaqQgF z?`i9b7gA@5ny4mBfxv*y!u`B6>SG-72J`2);@?~A>m%Z;{Dk}M754IjOZ_^6fAo8- z;D7s(f~sm`S6cNo?Xggd}R%X`eAt)TqHMs6NX3>G5@_PRP1-*wo0Gfh4|s$!-% zvF9&@;7lqX5lj%WTB+(O3L9;=^Nhsm1Yt!)qK76}MoaLLlsKM}J8qZ3h7x9KooiQx zw-k>{Bh_NNY|b6kx#NCG%bqf;xP2!!As1tA2j0lLsTv2tff3t8qr=hOZChtpD=#;M zDP4qi0#gxmh1YSxEQfwBL{@!_z2Ij5!j#{7(=*W@OMjz5{){U{ig6KD6$UXiw=K(m zo^=PgyoeyI)<79mv!NtJ0d-)TQ%U9*w?^D`nY#N*;LNBK_a~Sv+*!BmCKAMYEnK)r0g$$Q(Qv4E*LqSRkdhgnXqKoaAv5g_<|bS_rOXXBa+DDo zS@RZM8jwjEwvVCPkGOdmMStoqP6?BWsEnYjUvl{~Y*(H2?Gk0=>^$uro!MY!Dtk$Z zM%UTbO3xlDjO6EM9=mz%^7?1RSmi-`v(X=Yj;#V|P*_GeUtLMtUVJEff6+Nm5OtTP zo&}v|jMgOYpTIrtZM$O3PC6rf;dhtB;$Lf{=;5ESbhqSR1U@J^oG-~o-mFzkl{}@_2Uk#|hQOL)EVTm0uw^rIXEMjEdr@E(D64m)f}R9|Lu1NbTEAh6*d29}Z=6Dwy< zdsRgKi1BrSKl+^}h*d`8x5e!bC=1QANNZ?<;*2OjxLbZm7zIB`d6jTF|D!j12?kW>F}Vs?yH@oJ;+&5b*Nyp>8%%1Tm*LtBq%D@F*`F4M#xxL!mhPtb6{ox} zH%<`Jo!JT*5m!c2;&MOtJp zM&S=$XcbXEZYvvgDQan*i8CDGZQWSn`Z0njJ&6co5G zZThb7*^`$`FRGY4nW;@rP!NNU!)|`p{0y@OtbDI7s5Ld`dqo``9SB59*IhHx#a-!` z38B0W-8FcHLRfYOLi$9gyN*LU@HLoGQ4`(eKWBrIgLW94lrI$KJ1|>2Qf`9Bx*fFIfH0dH!#z70Z+q*sjU$pe7mE@C#ojEL?g*i13)0X*B1>o%DzZP*A!= zbY%aER{r+Kx7IDN^-x5umQjefSbCM?=;^L|ca^WOT~p|sb1-Rlllo7Ast0DLUaz{_ zQ0zC)W!EJwnSg^?LCS~g^Vy->4X_U@=+MdIbL_DMb`hK)USCka3c4F~=+Mc|Lx&Dc zV?Jgr`Ge}Eu-SY6Od?!$`rAK+>AlKTS$;lt{}{{SXjq51#- literal 0 HcmV?d00001 diff --git a/selfdrive/assets/sounds/hq_warning_2.mp3 b/selfdrive/assets/sounds/hq_warning_2.mp3 new file mode 100644 index 0000000000000000000000000000000000000000..04371e0a81d5e44bb930785755404329ee5766c3 GIT binary patch literal 30965 zcmeHw2Uru^+U`smAqgS$P}ESQi7_PD>^9y%jD1YkiU#XZ39Tg4Uf{90lAxch&rxNz9t zn%Du*w~Di?$JdIhhmX(K3Wx3Q^8Fq^w?8W1o+kP0(`JSUe7-*od*HXboY~(i?jFA1 zu6*qc1o^tUasIgQwc_gc*L(l?_J6T5g5GEuMPL+xQ3OU27)9XU7y9tFN4|cN z`o5k1_U*$|`R#M`IEuiJLSTe)r3fZ%lyW}`(os2oj=(78{v4mt)*p_*DCK@Qq@x1= z9Dz~F{W(6Ptv?)rQOf;rNJj`HkATUa~ z{{lz=Z!tqBvmwESP3BJHG{>l+>{arXd)-r3{rYy@x`i2hMS&Y0xP1dz(^nIntt(Z= z1LnwE#E!@ac@!sH*Tr93XQZ`goJVDo&v|`7?Pg69EJ$M1iFa?Ay1C_m#ghR)mA(!2 z70lO5vyO7gPTA>{+Yu&CxR#%(WgLGX-#o-!A-=qx;dA~bV_tk&xMo?n*1S0LvbK;Z zq&pIm9S6{FWypPq!#L@Fl+dA&(9SofWah`07ULXeTqf2$TBEyS9of7v&&cd8JrN;0 zj%U}$I4D2ipP1lUsbnfmOW^0*K~gHoHDA({v|qLSOzS7zVEITWR8~36-J6j{3bi!` z9N?d;j?8`bbWQ%RDNC)}yVgG6o_BzA8OF6M_NMHBm}-U*Ar)8mn=K3=YSW4>3^Vpz z$zoQt!y95<>2w*mmZs8}`i*iLuVqt`*K&c6;TnolT!2aExkkn!c!!4ZFCE(eKCO^2 zIb`=1BO7MR&g>Cnl0IKfmn5{uE_rJkclLAQ!$2eIvlkGD7hf8e%=t}1?C)kJ$74`& zUhuHL=i7Wk`t@e;wBpQ%+`q#!AnM>9$F7D-$j%*(CeHDt`I+RZ?QM=mS~^aaXu;Je2WVi868N}N1qL`As(+}j8w-e<(cK1Ui`dI%ba#oxabp#Pz zN=sbB1DeodFE9NuirY=|mSZDa6}#6qVwvZSxMm%sA1@2_9-1?+Jv?iY;~}dcV5bO0 zKS4}z7UVCMLc4JOke0*>%J;wQ;k4c z+7d4|<$C~ETE;=CG_$@HG!w`_lbT?hAFRxc@dNA-YY;NAEOk6bx^O4-UX|8r!zpOl zZ7a<)NV&#d@iR)J^s0eQS{665>I@ox{FVRxG(V#=Nfz`T$y$nLOW`!%`uu}qqZQ6U zRY_vJ4k7wh;`0rMpWX^Qy=lnbyDxjk<(=E<{o4;iM71mq*4&86~~P|IVI)vB^(C|z9p2Nw{jzt*@L_ZSfEY?8#1T(~0#pgm z2HZ)uW?;EnkvGkqc0&OTOWZxv<@LcG%dhQred(U%cO6bzlbXg8r+wUT@ksNAa{6&m zO$}PN@qKmkU}`5i+=`++NhnT?aEa++l4h8=M7K)%)>F8D!?CcUQ*K}qnXx5%R(%}( zfLZtI!22gtg@p0jGzyhD_*FA*J^Zq}vwOzign?SICS;`yf`Y|UpJ3A4ezt1X(UXc zQQI8(X39{S3sly!N!Y2)@Mh6-Ei7s4`daxM)&ZKaQnYKL6=vZ1I=ah)Z2}|7z$$cVR*3oVi&g%ovS}9$fjYv+X7AB2g`H& zK8W5XU+cWmgbf)hKf^~rFLEbhbGEpe|(p(l!2boL`t=mnue z2Wo-t;sJHo^uo=!0u46z%wJyDuRe|{lp(-9Wg93{MS?LkGJ>Ffwbp_+Ne6Ft85=IB zXK5;H4r^RhjU%mZsRx?wXV!J(sMH7rpM~l5z;@`T+~QP%FO;aMU1xc7OeNiOxF0GqX+Rpy;#_MR5r&8)E$nbLfAwYY>jR0%8Dn zAq^D-Q6X6@BjZp`@DjnfmG zUL5y+dQFNaXj%ehlx$$KE*^j^-vNw-Vxy0)i&t;-!hYSpj)e3=GJ?6V2zo+1dle^* zJxR?tejt(4Vz4BD4%yZN4VLvJ*@9Tl`!?2L%aY5!@J~K35D(ScsdMWs6kHNT89~xk z+NbD2n*+#ldlFtrB7rcTPaK%IGih8z_h+r0rYBkLw~800V>$=L=Eu7S9m2FvL=8kt zP?-@uR20hj8>Ztko6^Jk(a$LhK0v;*`e;LWT{#(2MN{Y2%p=KaGPEm|?})Gx0os%f zfN*W)E4jy_=kvYSD|%i=)BDj)BeF$b&`z`;MF(G_xBny3-zjIN?JFJ5gS;LE3PcaA zs4Y{64c;T*=G4PJ*Wmy7rGLjOgb@P^RIs_qM5v!el`(;u^6@7Kk_M7nWQrQzjcYRU zqs?Z-`dy_hW;_R!+i@&gf+mXu2ncGJfl!Fzay+1qBPC2?c_^V6dPwZvgca%qYLL^g z`cnb1ey?IhVUGrX!s?w43!d;R&*_0n>47c7t9azXVnt|Co|bj`>u#gw*YoqjotU}v zhvTFXjb-y%!nX&BhCA=|w4tWtHHx^>nLtnY9N zx6Yh?5_M$VHs(Au$mQ=jR#H8*O1dM%wS6Xr$$-|-_LV1tL?}AM`R$UUi7Vd6aYj|* z&g{pC89Bw4%4NU<0K(;f_L%izV%4~J^L@XzW=8u>M@Bp7b1SWTB?7k*%}A30eK)v5 zk^oObro!QbRl;)`v!kyWm9C^G_^fQnG!tG;(TC?GS;G}b5u6Jif;SVU!fs+`*aO%B z>jEZ602!EjuOI^P*P{gmrWaUcl;GMm?R1!*%FnXRN$n?+7!J?q_ z_MPJ>W|uz0Eb0&FU2G)iX>fPKU;XxZZT#y}{gouh-|BNou3EXtB=ogTZ;S|NhE@F?L9l{LH2(WHAJKgVU?#m_CS?w|Vo90aqI6v>w z2W*uYiu>9>%px7WIMU0g-!avLenDTNclMOLWIJBAJsWzq`#r=4>L4%R0OYS)0IkHO zvcbTyZl;%ic5@2ohx#Q%Pfw_hq8D{#*U%+*oI{-=rf1EeBKYdXg?k<-xC^VB_J6td z+G%9$nEi;oRG`?Fa8$fovrv+tdo=mhBzDpDQ-viLUBZ$Rwd2LH_;w@-cVE0}gmRMr z+(P|YJhrd~3h&88Z>%XRW>U2KpM#+kp?J7JO*9v`X?_;x;JTUkr$Q4RiF%klroOs7 z#k*02=0f9ucxZz10TcjwL86*->OYvz+8KFS=yQZMV(X{2(j5`h=3eWHp z1Ia3uJ>QtSxfU{Qnc^$2$zk9?Vw9Fbh?u4O?7VcxWiS;Ll?d>@po}CX`02T5G}v_M z=4{E{csy56#NXPXmoO2ZwJn>Fcz3Ah`Jm;rY?$hx*PP|MJ2Oo9eHn z4K_yF-~iAOo-VP4w-Z9){@vWA2UdFQc=a2J@4F1%s9#S3<_V)2q_H?%p{<4jcIMx% z=mj_K>e%+%$IgWlU+_cFhv;zUS8-nt!`VPD4v*`n%*1o`Ej1>O&DQeR;k)s4RqevK zZBlK&2^~pHU+?U$z+3Bh`L%lF#bo7rIBLRqGd%xR(~_dn4*fvc1b)li->nC4EUBJ? z$;5n16vceJZWJw{fuOjQ&?5mf&68Hq($hGe;+p429{m*I2Br-g#5dEz6w}R%%I_Zx zV<%tNk+Sj~94KujI>nrdmKYo6UJJ&(x&k0|BC+zd$!|%Tm1Vw|8 zUP6!9o-7nMP=h1``fpMqe5wwQd(l%JF*!cfUgwOsk6?^s5!hlS>Au8~ArxQ33y}!G z-c*A#QT^D(_Q()^&KsT9f$#E4lx@H#r6agrwL#-or4x}+<4=ou;L%&sSmo4Pr=kwl z&e14PEhHzYW)V562lzzgY8*|;0Ki1UGv^l}*2J}}N|K6PxA+ZXGE}f*TVc}k%gop< zho4t3T0FwNe<&}%o>dQDefL`mvq_jTW89ur-lxICnEAH~*sPq4qp6mX%#>{!pOh~N zmB02jDOJ*;?yqDSfQFij`&Ww4caOx8V?D~KM6#?TQh3h2?p;0&1D)w+%*}X z5)yh>^nyYX5rx-wJurPrqAgl({kyX5!lwU{_Ky=p_;(V&UdE>k6W9pOfI z_Pih1pWlgYUx|678{Ch-K8>Qi%^|KPtaIyJEFOu|^(-3;<>OMxiH}!mSI%Qu&`1pK z3e!^=r!Jfg4!j;)8tkM$(=4mJBtU@Uim-q#ll9mU%<_OMn3j*i!F~JP(wGzAcyapF z_e@g|&IhG@nt~~ovOvTh$23L|Q!&CMG%yK(9*F!3s+o350096YHFS%d(6y5t1ReV{&>Ngwk80i_x6i2I-&Xu4nxm`f+(q|)7UpJy-A&2)rk z*ZRfYr0)ugsXDX1oc(0(0)o)MYoV>3mDyW6y7T00M`Mc(MiDP;UuDF`o0$3idingU z4Hq69bmv)@mN=ap_j1*-<)P^7lhx?UP;__zBW?dfSC*tBBp^j2=xyF+iEff#XqSmi z-!I}bmheJE5vz=LkD@mL+~DFYF0K{BOl{@d7V~airseB8mp|R zXJuRWqQf)3zdx(7MMWtg&s7=Y%9W0q{91{2Onof7pjp-(bFYKYuXH28Dh_2()q%T5 zAc2UZR;1Vvw*{#H$z;$V0o(G4fK3o*_oOs_`s&K@S#Hw@Z@&(oA{spW?E%A`C>jVQ z0n4EvU=kFi@_-KGY}o7ShdqCCnd-TvK9RiyEQ7XlqacRL+16q@K_#tM(Vylq|drH52HnLD|qa?{))d!f7 zJe<6}%WKTRdnd+hTfCOp1a!y)6+v>Ex-8G|mhtB#xq7SIhi;T*&{5N5@&JzQn&H3gX_^p-hHb-iZE?gJQ6m4F#M3kI@F?pc|V#+V5Tl~pk;#a z_AZODV`x2~iZ&r3|5kgnyGz_}%hn;@yEY3nzV1G31#q9o*WibA1+o5{0Z|d3GI=>& zyYD&ZK@swX&D6h$-#L)DENbhL;SGx5--p9GhUcKUUqtV*w;D3w)w6jams5+-Sgr|VqoP25Vqa*zPZnD@wZ{YeEOLuYxd44oJ@JHlYmU_} zntbzhjk`Tu$6cS1xtmzKSNmK@Y2EWa5`?}@9^Q5b)!XhpGQ=Tkq6ayJRB2sL>6;j< zE1w@QLB+J0(fafmDtP(KhRLmO298K8TS}g^Gu3T+wlxaBDgjyP#SHi08!p`ZG@w$C zxm{#C3Ei7`_{7If^a_eOqn(%qmL&NMSps9BV3j$PCJAMSPK);x_+8s4H%)=x{R1tUW=lRH=yPm9Gg74{jANyK{5d zE~r9tL!&YG?D(3pyXZSKfsVQJqTh!SM1$Yb<#5~dYew9MIbDGa(J>Ed4i*aT3*ybs zQmckFZC4LrZ$4&8Vx7X?{C_z<{I_?=1URAOgM-S2gg|A3#-Qr3VPE}%o62T?-9Y6% z;^57ryY4Z&8|gJUpGbjwvUmrxQVF_Ov>y_>`+RSOYlgdPM;hKM(9EP7(-@wd;&EsX z7QF%?Jwyx{^TtB15(8*eJ(*p1(Zl(5T@mC7?sUoM+Dh`uT73Sbcj3=gRQfh^rhq=ZFV>3)p%(J z%sS!Uu`>41J&RAvM?$;%(HWRK@dBOpISL)fG-}hM8TJ|Q$HBN3Plhus5qR91HK+X+ z9)6LzOb~hN-cl{*O4_#7EpZ2SO$ekEQoJ123Mv(b3wI8?tA(5KZSdxTi% zXAU~7_-~*0|CbMdCIXt6_YeU2s5;Fkfhr%ZnBS6~5w0(Fs=NL>^?c0(Qm<+Zsb6JB zvQo8zCCYX%Q4Y@LUogyCOpwL~{p1(!blYHYHHOt+%aAoeMlK~XDFI}rOQ|MzQ;MO$ z+{QlkbLrf?GHd5gOG}MCCRuBiPqC(K=9Ds+Ce|b-!*<#J6*|7M93uE`=52qAp4$dj zqW&rn+wVbtCJ_S7l+hFDbtFQi9U^2~ej*v9J%VHH_Vto-JxJ;#4TZ~QRV5x^lGHA_ zzW4DYD@q$5$dWOsYGAh-(gA+P1DnCC;c4J8suC8Sw$TvEjbj#(oI&wUziY4Z;R*+u zvjI*CgX^J<_Z#NoVhrw-ki%|G8MyMro#~h(@1CsCP65J$+r-Rv#q;irrQ)J z0GTt;?y6ORiwBmJ7DIr~)ZbB9V(4GVDaS}v{)9N!Vx2irnmRaDAG(WC4_jrJcGL_d26uo8= zt`tSPxT)DsovRW~eMJZ2@Cza@-+YydjkH^!NG6sxR^>-wC+P5t*s#JQc)zE$(QupG z)uvI{Y_WL%l-+P~nwkr;=rREeu_#i!1q}ej2d4tT%H~V>9R(b<8O@mMp<P%a|0XZ z22RIr&zob@WGhMSae4lNDx%C5^WsY>YOMgg2kjY!WnZuBG5gtsGZYP0bzHz3=wpgK zdC^iXH{d7~kbgXOuW$WYqk27w-P}$Y$(ktE4_@Of-kM*Aq+@aNCyTCE-+e0@_-aFp z1c$LmE*uO_g|CTig+{?dvxda;Ql;i_5Q)%!- z+`JF~EE$cHkM1TmqDBp15uEL2PY5YIVvX6!nNC8g1fUIJetAU*~Fzir^|6pY3_{iScKxwAEZ*NT^vxSYwYfqR3 zC0&)%nV;J9Jsjzlq1A4pH1B~-<35nD2RLVrfx@vgiXz%(XY*D~`q5V1y^mYA0@rD7 zvVs;9NE#BjL(B9*%NKvXHF@VoH5n;3LM|5E?Ol38^!dWfolh}Gpv8N5jA+q}LGR(> zq3X|3Wh0y7-CsllqMzZ7NH<&#=n4%Hrmzceh?yu7|_0xs#T5ck}PC8r&O)0!55Vc#=a!zBr`a$BST2U%=vid{lfY;jU)mT*d zT+iJPJzw66(D%qco1OoW*CA6Zy~q%G4vpu{hIqIUeML&E0@$zD(J|Ev^l8J{QK91p+ ziDzZfJJ~k z9EA+Sk8uUUqGadAWsH_hxZ#AYx;pxct5dcLPY`6+jmfBd7pCc0Gx?JQ=EPFQNXnLOP5O%jsFB#1XF@D9dgJae45S@Qepz>=Lu zx&1y-gP!EAdB>u9zf}KqVJ*_eD3=aRDUv6MmU_@CPh*=8J>oqS1rOz@(br#7174sX zMOV-v_meVo_>2`G=EIpG{d!8C?`IPNFKo~|KRz0atFF-Sm z^-M=LHDE&d?dJydkCxH`2dwQFa|3i5JW44Zj@C(b0hx`Z?)ys_;PuYZ?cnv}z8l~E zV&gse)2ClvEj{yyjlMlO@DXhqi8_4W0>kv&WDT}BlekxEqVYLdrWLkpqqFhPg_n#U zY@FP96nTTN?I-o*6IxW;&%HLT-8W+o(f6SH zR(0OR99?X04NH-mI^y*r-$4GZlZWguy(Fl#jHX!_PAy8s{mUEd)i)&=S9cU9+4H+xfVw>;=5SyC@xr?Vm5a4eJ z9Hm4R=^O45xGr1OHD}D?>1Xun&YpVP`<_WvOl9gQ=gX;zjZ9Oqw%obPf;oI&*JMj^ zBok70%6kVHV%N_V55mtyXiZCMw0LR2#VbtWE-arFQ6#nPM9XE+IBRkmHI~L2Pcrz# zx8?wC(-xypO8*KS85`jV&Wg-^M*H3_;iU89JhlMSpo zyXvlu?;UvyFv|6#WxX9(D33`+w3wDGANfQei5YHgCRf%x7^Cg=!SpgAka&I%j_6vwZ?Y# zj`x!|t4Z;YNc92IK~7_oW4f8wJzR@lzEeWBA0Vcl;SBLQSd@3n)?z!ubv`TcWOe#E zGmYl#DD}p7loBf`*hlRE>+rSfZEo3QxZfw!!h&pOkG-ya8!cB}!Euy(a4j_BEomG` zwbOQ?`SX=yBAcBv>~>q&eNHdc%aeK;ZAqF(Kbq`iXp97s(~)Q(2(bVtZJCo0a>T3o zBRSZZkF#fFpM5oEuktl2%vuQ0v;Q=>U&Th4(xh58)tHvaL&u6a2a_#<)nedHr;CW3SX|-D6 z&a-7~8q}vG*bf`L1HkFTMKz=8au~LF632tf4t2`F;|ko>(4KcCcwC${i+%Wo7k*nr zC<`K~aCjC$sDy~zXnd&0JOE2Rnu#a$gR(X;Qk{HKEXfBD_*|o8NBYtMcl5JpWcvQo zGF&}O(vI8CT|8@11Bu+dnG0w9j*xJyS<2{v&P0tFmH7Znlc-6hY0Utvg}Li|nG%2v z5PcH4fhgRDc(5zx0uUrrlE+QoBrrhMdcC?p?6Z;DEX+$do+i7JS^Y763t6ZU=77FY zPoip6-t$1w@r}-Tw!T)HGtfb~z)7a*yr88t9^2dD%Y)50d`0Z^gYI8MD5{tVIU1W- z3tXIvqQa_Lv0aXl)UCIV{TmZ{E|34bJs{nPS(#pSbbE7;iK!72%NhMuby*`qRSuTd zMU4|Q9rR^<`|@;Ko}GW%GG}QegjKOh1Bqk#orR8UiN0j15X`Ja06) z<~&ZIj3LdfSxm95X{T*gHWCENO(3AO0qkxpKNT2%^q@3!Df(4kW4)Py{loI8Hk0Ee z37Vc_SW_qEFB98kXO{_UOcKSHy2J19WElsEVVaHvz`c=VP=(U53=p|Sc!ZRKTr$q) z_kt?(zP4prAxJk7nLDK@87p~($-9?Wd6J6m9J9ASKJVBGsN(Ex7Z;ZmEq}?fzbTPO z`t{oshm-UTl*L8TM1f$DGMk2Xt+sms~D6Uaf@uv1EPE#h8qSuLibGBDMA|_f^ zqmLznVNt`ql508`>^zZ9)X<;=`Qt@qCzwOz{p^JX&TriyN&Oqwg)Tdx)_`niA3*u$ekkBREU`%w@yxYq+n9~uI9ZvbR(Zv z$B|nJ6R<#;TyDg&kXrx-avN5X_D8B)k@KOQ{?Mgb-t#1!37HW+rSoqBv06WquAagi z2dtOdDvmRQ#B<~&B_~WH$6YWpjDEx{Qnt(8SSE5JOC;A*6fsSBRtF2CqXk9L6+I!h z=HK`umNK$wg$@PayQw5iK+BpIr;)-`npk^OZoM(B@W3>qxV6^KO1m42PseULAM3{< zvD==-jI#g)$ABx^W5$o4()-cHvtH;UHzv;Og9yjBU$FVw%XUn~VtV#J$zl4wuT4I#6dg-{f!-{oBYZua|Ci*>SGpe9{ks$xCViQoHZXcAA=^}h0Bv+b+j z>I~`%i>ZWlmLZERb7%Uk@+E)Tw~mfiyUd5ztfLHCF2-@G>%jAb;sm=;J;amTN0=3| z^w|Qa_1n|G(%|c%o1NhBb7|LNi`H@W&=Z1=Yw?5ku89(F=m9qd5&&^nzWrsWE2g0m zA9N4_-1d#B9Ov@KxBt(V)4y@&JLTdvFH6z;EHB|429}3TuCRDUM~P+Fk3&Z7uIK%KVLRaHP#P~8({|G!7tk4UR-JZl zcA?M&?$PeHC6`)fpjfE!Yne833_3uLwGTGlzJK{ivGkU0yyB^A)vj=RW2uAI8}ZK? zd15z$=k1AOnzx+JOJ}%jK5|7jk8=XnKbqQ^Vm6Rm4>>=Hk9C>r9|KJlUw}x!STdpknf^|> zC6r4elw*sn`__HY52&;HjV_87PfDGyLYbrP17K|f2^B!2UgQ~j{fCFb%Dq||Q%FQ= zuz*fdEiou$jd{+vVVcr&%7@0WZE$-2g4PyvOeP&lXQnuvwAJqoPWrMg_{_$Z^2MtX z=3LlK*06%i$Po9eFL;Z_uakhcxOsuuQ)SlS>GBMXf}$lBc{yU|9DXDJT@L>!zcI`? zCod~6r=%&TC8u?Qp7Tuh?Y!{3tjZPq#!wpvy1$h`6%)>*6=WpnXN#qKgP1_1zPQoG zf?<-C07>jD!6tv!TF-_gLmrbRj1eo>8j&4#<8j-jpK>O%A#&$CUnrArO~Gr^7_{-Y zlJ+>pp`#MD`ICl~Y4B?YU&i*_E`~I(Y_Ef3_ZsE=pM!jPhDAQw@14W67ud^^=2Zy} zFXWiNytu??dzEle<(de)P6t4lg47WS_zW7Jkv10_s4^uv%@6ieN$M=VQI2#_;4NM4 z{B}r}%v$qomCo&?Pc*18xUy)RI5lsLAvsX!yqC)GcV23nmsZOCMbAz*HaLbJ=Ay%| zooO9zmuDxN=+~0d;u=HocNyqyay}1AQO6~ynL$jl7>b@0- zpqpR;d9e1=255 or cpt['NEW_TRACK']: - self.validCnt[ii] = 0 # reset counter - - if cpt['VALID'] and cpt['LONG_DIST'] < 255: - self.validCnt[ii] += 1 - else: - self.validCnt[ii] = max(self.validCnt[ii] -1, 0) - #print ii, self.validCnt[ii], cpt['VALID'], cpt['LONG_DIST'], cpt['LAT_DIST'] - - # radar point only valid if there have been enough valid measurements - if self.validCnt[ii] > 0: - if ii not in self.pts or cpt['NEW_TRACK']: - self.pts[ii] = car.RadarState.RadarPoint.new_message() - self.pts[ii].trackId = self.track_id - self.track_id += 1 - self.pts[ii].dRel = cpt['LONG_DIST'] # from front of car - self.pts[ii].yRel = -cpt['LAT_DIST'] # in car frame's y axis, left is positive - self.pts[ii].vRel = cpt['REL_SPEED'] - self.pts[ii].aRel = float('nan') - self.pts[ii].yvRel = float('nan') - self.pts[ii].measured = bool(cpt['VALID']) - else: - if ii in self.pts: - del self.pts[ii] + if ii in RADAR_A_MSGS: + cpt = self.rcp.vl[ii] + + if cpt['LONG_DIST'] >= 255 or cpt['NEW_TRACK']: + self.seen_valid[ii] = False # reset validity + + if cpt['LONG_DIST'] < 255 and cpt['VALID']: + self.seen_valid[ii] = True + + score = self.rcp.vl[ii+16]['SCORE'] + # print ii, score, cpt['VALID'], cpt['LONG_DIST'], cpt['LAT_DIST'] + + # radar point only valid if it's a valid measurement and score is above 50 + if (cpt['VALID'] or score > 50) and cpt['LONG_DIST'] < 255 and self.seen_valid[ii]: + if ii not in self.pts or cpt['NEW_TRACK']: + self.pts[ii] = car.RadarState.RadarPoint.new_message() + self.pts[ii].trackId = self.track_id + self.track_id += 1 + self.pts[ii].dRel = cpt['LONG_DIST'] # from front of car + self.pts[ii].yRel = -cpt['LAT_DIST'] # in car frame's y axis, left is positive + self.pts[ii].vRel = cpt['REL_SPEED'] + self.pts[ii].aRel = float('nan') + self.pts[ii].yvRel = float('nan') + self.pts[ii].measured = bool(cpt['VALID']) + else: + if ii in self.pts: + del self.pts[ii] ret.points = self.pts.values() return ret diff --git a/selfdrive/common/version.h b/selfdrive/common/version.h index a8edf68845b620..ab4726817a77a5 100644 --- a/selfdrive/common/version.h +++ b/selfdrive/common/version.h @@ -1 +1 @@ -#define COMMA_VERSION "0.5.4-release" +#define COMMA_VERSION "0.5.5-release" diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 70afd6fcc998a9..470be768b3b4b4 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -352,6 +352,7 @@ def data_send(perception_state, plan, plan_ts, CS, CI, CP, VM, state, events, ac "alertSize": AM.alert_size, "alertStatus": AM.alert_status, "alertBlinkingRate": AM.alert_rate, + "alertType": AM.alert_type, "awarenessStatus": max(driver_status.awareness, 0.0) if isEnabled(state) else 0.0, "driverMonitoringOn": bool(driver_status.monitor_on), "canMonoTimes": list(CS.canMonoTimes), diff --git a/selfdrive/controls/lib/alertmanager.py b/selfdrive/controls/lib/alertmanager.py index 9f92fe44c637d3..99bb9bfc11f93e 100644 --- a/selfdrive/controls/lib/alertmanager.py +++ b/selfdrive/controls/lib/alertmanager.py @@ -18,6 +18,7 @@ class Priority: class Alert(object): def __init__(self, + alert_type, alert_text_1, alert_text_2, alert_status, @@ -30,6 +31,7 @@ def __init__(self, duration_text, alert_rate=0.): + self.alert_type = alert_type self.alert_text_1 = alert_text_1 self.alert_text_2 = alert_text_2 self.alert_status = alert_status @@ -60,475 +62,554 @@ def __gt__(self, alert2): class AlertManager(object): alerts = { - - # Miscellaneous alerts - "enable": Alert( - "", - "", - AlertStatus.normal, AlertSize.none, - Priority.MID, None, "beepSingle", .2, 0., 0.), - - "disable": Alert( - "", - "", - AlertStatus.normal, AlertSize.none, - Priority.MID, None, "beepSingle", .2, 0., 0.), - - "fcw": Alert( - "BRAKE!", - "Risk of Collision", - AlertStatus.critical, AlertSize.full, - Priority.HIGHEST, "fcw", "chimeRepeated", 1., 2., 2.), - - "steerSaturated": Alert( - "TAKE CONTROL", - "Turn Exceeds Steering Limit", - AlertStatus.userPrompt, AlertSize.mid, - Priority.LOW, "steerRequired", "chimeSingle", 1., 2., 3.), - - "steerTempUnavailable": Alert( - "TAKE CONTROL", - "Steering Temporarily Unavailable", - AlertStatus.userPrompt, AlertSize.mid, - Priority.LOW, "steerRequired", "chimeDouble", .4, 2., 3.), - - "steerTempUnavailableMute": Alert( - "TAKE CONTROL", - "Steering Temporarily Unavailable", - AlertStatus.userPrompt, AlertSize.mid, - Priority.LOW, None, None, .2, .2, .2), - - "preDriverDistracted": Alert( - "KEEP EYES ON ROAD: User Appears Distracted", - "", - AlertStatus.normal, AlertSize.small, - Priority.LOW, "steerRequired", None, 0., .1, .1, alert_rate=0.75), - - "promptDriverDistracted": Alert( - "KEEP EYES ON ROAD", - "User Appears Distracted", - AlertStatus.userPrompt, AlertSize.mid, - Priority.MID, "steerRequired", "chimeRepeated", .1, .1, .1), - - "driverDistracted": Alert( - "DISENGAGE IMMEDIATELY", - "User Was Distracted", - AlertStatus.critical, AlertSize.full, - Priority.HIGH, "steerRequired", "chimeRepeated", .1, .1, .1), - - "preDriverUnresponsive": Alert( - "TOUCH STEERING WHEEL: No Driver Monitoring", - "", - AlertStatus.normal, AlertSize.small, - Priority.LOW, "steerRequired", None, 0., .1, .1, alert_rate=0.75), - - "promptDriverUnresponsive": Alert( - "TOUCH STEERING WHEEL", - "User Is Unresponsive", - AlertStatus.userPrompt, AlertSize.mid, - Priority.MID, "steerRequired", "chimeRepeated", .1, .1, .1), - - "driverUnresponsive": Alert( - "DISENGAGE IMMEDIATELY", - "User Was Unresponsive", - AlertStatus.critical, AlertSize.full, - Priority.HIGH, "steerRequired", "chimeRepeated", .1, .1, .1), - - "driverMonitorOff": Alert( - "DRIVER MONITOR IS UNAVAILABLE", - "Accuracy Is Low", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, None, None, .4, 0., 4.), - - "driverMonitorOn": Alert( - "DRIVER MONITOR IS AVAILABLE", - "Accuracy Is High", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, None, None, .4, 0., 4.), - - "geofence": Alert( - "DISENGAGEMENT REQUIRED", - "Not in Geofenced Area", - AlertStatus.userPrompt, AlertSize.mid, - Priority.HIGH, "steerRequired", "chimeRepeated", .1, .1, .1), - - "startup": Alert( - "Be ready to take over at any time", - "Always keep hands on wheel and eyes on road", - AlertStatus.normal, AlertSize.mid, - Priority.LOW_LOWEST, None, None, 0., 0., 15.), - - "ethicalDilemma": Alert( - "TAKE CONTROL IMMEDIATELY", - "Ethical Dilemma Detected", - AlertStatus.critical, AlertSize.full, - Priority.HIGHEST, "steerRequired", "chimeRepeated", 1., 3., 3.), - - "steerTempUnavailableNoEntry": Alert( - "openpilot Unavailable", - "Steering Temporarily Unavailable", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, None, "chimeDouble", .4, 0., 3.), - - "manualRestart": Alert( - "TAKE CONTROL", - "Resume Driving Manually", - AlertStatus.userPrompt, AlertSize.mid, - Priority.LOW, None, None, 0., 0., .2), - - "resumeRequired": Alert( - "STOPPED", - "Press Resume to Move", - AlertStatus.userPrompt, AlertSize.mid, - Priority.LOW, None, None, 0., 0., .2), - - "belowSteerSpeed": Alert( - "TAKE CONTROL", - "Steer Unavailable Below ", - AlertStatus.userPrompt, AlertSize.mid, - Priority.MID, "steerRequired", None, 0., 0., .1), - - "debugAlert": Alert( - "DEBUG ALERT", - "", - AlertStatus.userPrompt, AlertSize.mid, - Priority.LOW, None, None, .1, .1, .1), - - # Non-entry only alerts - "wrongCarModeNoEntry": Alert( - "openpilot Unavailable", - "Main Switch Off", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, None, "chimeDouble", .4, 0., 3.), - - "dataNeededNoEntry": Alert( - "openpilot Unavailable", - "Data Needed for Calibration. Upload Drive, Try Again", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, None, "chimeDouble", .4, 0., 3.), - - "outOfSpaceNoEntry": Alert( - "openpilot Unavailable", - "Out of Storage Space", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, None, "chimeDouble", .4, 0., 3.), - - "pedalPressedNoEntry": Alert( - "openpilot Unavailable", - "Pedal Pressed During Attempt", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, "brakePressed", "chimeDouble", .4, 2., 3.), - - "speedTooLowNoEntry": Alert( - "openpilot Unavailable", - "Speed Too Low", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "brakeHoldNoEntry": Alert( - "openpilot Unavailable", - "Brake Hold Active", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "parkBrakeNoEntry": Alert( - "openpilot Unavailable", - "Park Brake Engaged", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "lowSpeedLockoutNoEntry": Alert( - "openpilot Unavailable", - "Cruise Fault: Restart the Car", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "lowBatteryNoEntry": Alert( - "openpilot Unavailable", - "Low Battery", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - # Cancellation alerts causing soft disabling - "overheat": Alert( - "TAKE CONTROL IMMEDIATELY", - "System Overheated", - AlertStatus.critical, AlertSize.full, - Priority.MID, "steerRequired", "chimeRepeated", 1., 3., 3.), - - "wrongGear": Alert( - "TAKE CONTROL IMMEDIATELY", - "Gear not D", - AlertStatus.critical, AlertSize.full, - Priority.MID, "steerRequired", "chimeRepeated", 1., 3., 3.), - - "calibrationInvalid": Alert( - "TAKE CONTROL IMMEDIATELY", - "Calibration Invalid: Reposition EON and Recalibrate", - AlertStatus.critical, AlertSize.full, - Priority.MID, "steerRequired", "chimeRepeated", 1., 3., 3.), - - "calibrationIncomplete": Alert( - "TAKE CONTROL IMMEDIATELY", - "Calibration in Progress", - AlertStatus.critical, AlertSize.full, - Priority.MID, "steerRequired", "chimeRepeated", 1., 3., 3.), - - "doorOpen": Alert( - "TAKE CONTROL IMMEDIATELY", - "Door Open", - AlertStatus.critical, AlertSize.full, - Priority.MID, "steerRequired", "chimeRepeated", 1., 3., 3.), - - "seatbeltNotLatched": Alert( - "TAKE CONTROL IMMEDIATELY", - "Seatbelt Unlatched", - AlertStatus.critical, AlertSize.full, - Priority.MID, "steerRequired", "chimeRepeated", 1., 3., 3.), - - "espDisabled": Alert( - "TAKE CONTROL IMMEDIATELY", - "ESP Off", - AlertStatus.critical, AlertSize.full, - Priority.MID, "steerRequired", "chimeRepeated", 1., 3., 3.), - - "lowBattery": Alert( - "TAKE CONTROL IMMEDIATELY", - "Low Battery", - AlertStatus.critical, AlertSize.full, - Priority.MID, "steerRequired", "chimeRepeated", 1., 3., 3.), - - # Cancellation alerts causing immediate disabling - "radarCommIssue": Alert( - "TAKE CONTROL IMMEDIATELY", - "Radar Error: Restart the Car", - AlertStatus.critical, AlertSize.full, - Priority.HIGHEST, "steerRequired", "chimeRepeated", 1., 3., 4.), - - "radarFault": Alert( - "TAKE CONTROL IMMEDIATELY", - "Radar Error: Restart the Car", - AlertStatus.critical, AlertSize.full, - Priority.HIGHEST, "steerRequired", "chimeRepeated", 1., 3., 4.), - - "modelCommIssue": Alert( - "TAKE CONTROL IMMEDIATELY", - "Model Error: Check Internet Connection", - AlertStatus.critical, AlertSize.full, - Priority.HIGHEST, "steerRequired", "chimeRepeated", 1., 3., 4.), - - "controlsFailed": Alert( - "TAKE CONTROL IMMEDIATELY", - "Controls Failed", - AlertStatus.critical, AlertSize.full, - Priority.HIGHEST, "steerRequired", "chimeRepeated", 1., 3., 4.), - - "controlsMismatch": Alert( - "TAKE CONTROL IMMEDIATELY", - "Controls Mismatch", - AlertStatus.critical, AlertSize.full, - Priority.HIGHEST, "steerRequired", "chimeRepeated", 1., 3., 4.), - - "commIssue": Alert( - "TAKE CONTROL IMMEDIATELY", - "CAN Error: Check Connections", - AlertStatus.critical, AlertSize.full, - Priority.HIGHEST, "steerRequired", "chimeRepeated", 1., 3., 4.), - - "steerUnavailable": Alert( - "TAKE CONTROL IMMEDIATELY", - "LKAS Fault: Restart the Car", - AlertStatus.critical, AlertSize.full, - Priority.HIGHEST, "steerRequired", "chimeRepeated", 1., 3., 4.), - - "brakeUnavailable": Alert( - "TAKE CONTROL IMMEDIATELY", - "Cruise Fault: Restart the Car", - AlertStatus.critical, AlertSize.full, - Priority.HIGHEST, "steerRequired", "chimeRepeated", 1., 3., 4.), - - "gasUnavailable": Alert( - "TAKE CONTROL IMMEDIATELY", - "Gas Fault: Restart the Car", - AlertStatus.critical, AlertSize.full, - Priority.HIGHEST, "steerRequired", "chimeRepeated", 1., 3., 4.), - - "reverseGear": Alert( - "TAKE CONTROL IMMEDIATELY", - "Reverse Gear", - AlertStatus.critical, AlertSize.full, - Priority.HIGHEST, "steerRequired", "chimeRepeated", 1., 3., 4.), - - "cruiseDisabled": Alert( - "TAKE CONTROL IMMEDIATELY", - "Cruise Is Off", - AlertStatus.critical, AlertSize.full, - Priority.HIGHEST, "steerRequired", "chimeRepeated", 1., 3., 4.), - - "plannerError": Alert( - "TAKE CONTROL IMMEDIATELY", - "Planner Solution Error", - AlertStatus.critical, AlertSize.full, - Priority.HIGHEST, "steerRequired", "chimeRepeated", 1., 3., 4.), - - # not loud cancellations (user is in control) - "noTarget": Alert( - "openpilot Canceled", - "No close lead car", - AlertStatus.normal, AlertSize.mid, - Priority.HIGH, None, "chimeDouble", .4, 2., 3.), - - "speedTooLow": Alert( - "openpilot Canceled", - "Speed too low", - AlertStatus.normal, AlertSize.mid, - Priority.HIGH, None, "chimeDouble", .4, 2., 3.), - - # Cancellation alerts causing non-entry - "overheatNoEntry": Alert( - "openpilot Unavailable", - "System overheated", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "wrongGearNoEntry": Alert( - "openpilot Unavailable", - "Gear not D", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "calibrationInvalidNoEntry": Alert( - "openpilot Unavailable", - "Calibration Invalid: Reposition EON and Recalibrate", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "calibrationIncompleteNoEntry": Alert( - "openpilot Unavailable", - "Calibration in Progress", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "doorOpenNoEntry": Alert( - "openpilot Unavailable", - "Door open", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "seatbeltNotLatchedNoEntry": Alert( - "openpilot Unavailable", - "Seatbelt unlatched", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "espDisabledNoEntry": Alert( - "openpilot Unavailable", - "ESP Off", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "geofenceNoEntry": Alert( - "openpilot Unavailable", - "Not in Geofenced Area", - AlertStatus.normal, AlertSize.mid, - Priority.MID, None, "chimeDouble", .4, 2., 3.), - - "radarCommIssueNoEntry": Alert( - "openpilot Unavailable", - "Radar Error: Restart the Car", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "radarFaultNoEntry": Alert( - "openpilot Unavailable", - "Radar Error: Restart the Car", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "modelCommIssueNoEntry": Alert( - "openpilot Unavailable", - "Model Error: Check Internet Connection", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "controlsFailedNoEntry": Alert( - "openpilot Unavailable", - "Controls Failed", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "commIssueNoEntry": Alert( - "openpilot Unavailable", - "CAN Error: Check Connections", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "steerUnavailableNoEntry": Alert( - "openpilot Unavailable", - "LKAS Fault: Restart the Car", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "brakeUnavailableNoEntry": Alert( - "openpilot Unavailable", - "Cruise Fault: Restart the Car", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "gasUnavailableNoEntry": Alert( - "openpilot Unavailable", - "Gas Error: Restart the Car", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "reverseGearNoEntry": Alert( - "openpilot Unavailable", - "Reverse Gear", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "cruiseDisabledNoEntry": Alert( - "openpilot Unavailable", - "Cruise is Off", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "noTargetNoEntry": Alert( - "openpilot Unavailable", - "No Close Lead Car", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - "plannerErrorNoEntry": Alert( - "openpilot Unavailable", - "Planner Solution Error", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, None, "chimeDouble", .4, 2., 3.), - - # permanent alerts - "steerUnavailablePermanent": Alert( - "LKAS Fault: Restart the car to engage", - "", - AlertStatus.normal, AlertSize.small, - Priority.LOW_LOWEST, None, None, 0., 0., .2), - - "brakeUnavailablePermanent": Alert( - "Cruise Fault: Restart the car to engage", - "", - AlertStatus.normal, AlertSize.small, - Priority.LOW_LOWEST, None, None, 0., 0., .2), - - "lowSpeedLockoutPermanent": Alert( - "Cruise Fault: Restart the car to engage", - "", - AlertStatus.normal, AlertSize.small, - Priority.LOW_LOWEST, None, None, 0., 0., .2), - - "calibrationIncompletePermanent": Alert( - "Calibration in Progress: ", - "Drive Above ", - AlertStatus.normal, AlertSize.mid, - Priority.LOWEST, None, None, 0., 0., .2), + alert.alert_type: alert + for alert in [ + # Miscellaneous alerts + Alert( + "enable", + "", + "", + AlertStatus.normal, AlertSize.none, + Priority.MID, None, "beepSingle", .2, 0., 0.), + + Alert( + "disable", + "", + "", + AlertStatus.normal, AlertSize.none, + Priority.MID, None, "beepSingle", .2, 0., 0.), + + Alert( + "fcw", + "BRAKE!", + "Risk of Collision", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, "fcw", "chimeRepeated", 1., 2., 2.), + + Alert( + "steerSaturated", + "TAKE CONTROL", + "Turn Exceeds Steering Limit", + AlertStatus.userPrompt, AlertSize.mid, + Priority.LOW, "steerRequired", "chimeSingle", 1., 2., 3.), + + Alert( + "steerTempUnavailable", + "TAKE CONTROL", + "Steering Temporarily Unavailable", + AlertStatus.userPrompt, AlertSize.mid, + Priority.LOW, "steerRequired", "chimeDouble", .4, 2., 3.), + + Alert( + "steerTempUnavailableMute", + "TAKE CONTROL", + "Steering Temporarily Unavailable", + AlertStatus.userPrompt, AlertSize.mid, + Priority.LOW, None, None, .2, .2, .2), + + Alert( + "preDriverDistracted", + "KEEP EYES ON ROAD: User Appears Distracted", + "", + AlertStatus.normal, AlertSize.small, + Priority.LOW, "steerRequired", None, 0., .1, .1, alert_rate=0.75), + + Alert( + "promptDriverDistracted", + "KEEP EYES ON ROAD", + "User Appears Distracted", + AlertStatus.userPrompt, AlertSize.mid, + Priority.MID, "steerRequired", "chimeRepeated", .1, .1, .1), + + Alert( + "driverDistracted", + "DISENGAGE IMMEDIATELY", + "User Was Distracted", + AlertStatus.critical, AlertSize.full, + Priority.HIGH, "steerRequired", "chimeRepeated", .1, .1, .1), + + Alert( + "preDriverUnresponsive", + "TOUCH STEERING WHEEL: No Driver Monitoring", + "", + AlertStatus.normal, AlertSize.small, + Priority.LOW, "steerRequired", None, 0., .1, .1, alert_rate=0.75), + + Alert( + "promptDriverUnresponsive", + "TOUCH STEERING WHEEL", + "User Is Unresponsive", + AlertStatus.userPrompt, AlertSize.mid, + Priority.MID, "steerRequired", "chimeRepeated", .1, .1, .1), + + Alert( + "driverUnresponsive", + "DISENGAGE IMMEDIATELY", + "User Was Unresponsive", + AlertStatus.critical, AlertSize.full, + Priority.HIGH, "steerRequired", "chimeRepeated", .1, .1, .1), + + Alert( + "driverMonitorOff", + "DRIVER MONITOR IS UNAVAILABLE", + "Accuracy Is Low", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, None, None, .4, 0., 4.), + + Alert( + "driverMonitorOn", + "DRIVER MONITOR IS AVAILABLE", + "Accuracy Is High", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, None, None, .4, 0., 4.), + + Alert( + "geofence", + "DISENGAGEMENT REQUIRED", + "Not in Geofenced Area", + AlertStatus.userPrompt, AlertSize.mid, + Priority.HIGH, "steerRequired", "chimeRepeated", .1, .1, .1), + + Alert( + "startup", + "Be ready to take over at any time", + "Always keep hands on wheel and eyes on road", + AlertStatus.normal, AlertSize.mid, + Priority.LOW_LOWEST, None, None, 0., 0., 15.), + + Alert( + "ethicalDilemma", + "TAKE CONTROL IMMEDIATELY", + "Ethical Dilemma Detected", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, "steerRequired", "chimeRepeated", 1., 3., 3.), + + Alert( + "steerTempUnavailableNoEntry", + "openpilot Unavailable", + "Steering Temporarily Unavailable", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, None, "chimeDouble", .4, 0., 3.), + + Alert( + "manualRestart", + "TAKE CONTROL", + "Resume Driving Manually", + AlertStatus.userPrompt, AlertSize.mid, + Priority.LOW, None, None, 0., 0., .2), + + Alert( + "resumeRequired", + "STOPPED", + "Press Resume to Move", + AlertStatus.userPrompt, AlertSize.mid, + Priority.LOW, None, None, 0., 0., .2), + + Alert( + "belowSteerSpeed", + "TAKE CONTROL", + "Steer Unavailable Below ", + AlertStatus.userPrompt, AlertSize.mid, + Priority.MID, "steerRequired", None, 0., 0., .1), + + Alert( + "debugAlert", + "DEBUG ALERT", + "", + AlertStatus.userPrompt, AlertSize.mid, + Priority.LOW, None, None, .1, .1, .1), + + # Non-entry only alerts + Alert( + "wrongCarModeNoEntry", + "openpilot Unavailable", + "Main Switch Off", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, None, "chimeDouble", .4, 0., 3.), + + Alert( + "dataNeededNoEntry", + "openpilot Unavailable", + "Data Needed for Calibration. Upload Drive, Try Again", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, None, "chimeDouble", .4, 0., 3.), + + Alert( + "outOfSpaceNoEntry", + "openpilot Unavailable", + "Out of Storage Space", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, None, "chimeDouble", .4, 0., 3.), + + Alert( + "pedalPressedNoEntry", + "openpilot Unavailable", + "Pedal Pressed During Attempt", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, "brakePressed", "chimeDouble", .4, 2., 3.), + + Alert( + "speedTooLowNoEntry", + "openpilot Unavailable", + "Speed Too Low", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, None, "chimeDouble", .4, 2., 3.), + + Alert( + "brakeHoldNoEntry", + "openpilot Unavailable", + "Brake Hold Active", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, None, "chimeDouble", .4, 2., 3.), + + Alert( + "parkBrakeNoEntry", + "openpilot Unavailable", + "Park Brake Engaged", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, None, "chimeDouble", .4, 2., 3.), + + Alert( + "lowSpeedLockoutNoEntry", + "openpilot Unavailable", + "Cruise Fault: Restart the Car", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, None, "chimeDouble", .4, 2., 3.), + + Alert( + "lowBatteryNoEntry", + "openpilot Unavailable", + "Low Battery", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, None, "chimeDouble", .4, 2., 3.), + + # Cancellation alerts causing soft disabling + Alert( + "overheat", + "TAKE CONTROL IMMEDIATELY", + "System Overheated", + AlertStatus.critical, AlertSize.full, + Priority.MID, "steerRequired", "chimeRepeated", 1., 3., 3.), + + Alert( + "wrongGear", + "TAKE CONTROL IMMEDIATELY", + "Gear not D", + AlertStatus.critical, AlertSize.full, + Priority.MID, "steerRequired", "chimeRepeated", 1., 3., 3.), + + Alert( + "calibrationInvalid", + "TAKE CONTROL IMMEDIATELY", + "Calibration Invalid: Reposition EON and Recalibrate", + AlertStatus.critical, AlertSize.full, + Priority.MID, "steerRequired", "chimeRepeated", 1., 3., 3.), + + Alert( + "calibrationIncomplete", + "TAKE CONTROL IMMEDIATELY", + "Calibration in Progress", + AlertStatus.critical, AlertSize.full, + Priority.MID, "steerRequired", "chimeRepeated", 1., 3., 3.), + + Alert( + "doorOpen", + "TAKE CONTROL IMMEDIATELY", + "Door Open", + AlertStatus.critical, AlertSize.full, + Priority.MID, "steerRequired", "chimeRepeated", 1., 3., 3.), + + Alert( + "seatbeltNotLatched", + "TAKE CONTROL IMMEDIATELY", + "Seatbelt Unlatched", + AlertStatus.critical, AlertSize.full, + Priority.MID, "steerRequired", "chimeRepeated", 1., 3., 3.), + + Alert( + "espDisabled", + "TAKE CONTROL IMMEDIATELY", + "ESP Off", + AlertStatus.critical, AlertSize.full, + Priority.MID, "steerRequired", "chimeRepeated", 1., 3., 3.), + + Alert( + "lowBattery", + "TAKE CONTROL IMMEDIATELY", + "Low Battery", + AlertStatus.critical, AlertSize.full, + Priority.MID, "steerRequired", "chimeRepeated", 1., 3., 3.), + + # Cancellation alerts causing immediate disabling + Alert( + "radarCommIssue", + "TAKE CONTROL IMMEDIATELY", + "Radar Error: Restart the Car", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, "steerRequired", "chimeRepeated", 1., 3., 4.), + + Alert( + "radarFault", + "TAKE CONTROL IMMEDIATELY", + "Radar Error: Restart the Car", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, "steerRequired", "chimeRepeated", 1., 3., 4.), + + Alert( + "modelCommIssue", + "TAKE CONTROL IMMEDIATELY", + "Model Error: Check Internet Connection", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, "steerRequired", "chimeRepeated", 1., 3., 4.), + + Alert( + "controlsFailed", + "TAKE CONTROL IMMEDIATELY", + "Controls Failed", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, "steerRequired", "chimeRepeated", 1., 3., 4.), + + Alert( + "controlsMismatch", + "TAKE CONTROL IMMEDIATELY", + "Controls Mismatch", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, "steerRequired", "chimeRepeated", 1., 3., 4.), + + Alert( + "commIssue", + "TAKE CONTROL IMMEDIATELY", + "CAN Error: Check Connections", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, "steerRequired", "chimeRepeated", 1., 3., 4.), + + Alert( + "steerUnavailable", + "TAKE CONTROL IMMEDIATELY", + "LKAS Fault: Restart the Car", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, "steerRequired", "chimeRepeated", 1., 3., 4.), + + Alert( + "brakeUnavailable", + "TAKE CONTROL IMMEDIATELY", + "Cruise Fault: Restart the Car", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, "steerRequired", "chimeRepeated", 1., 3., 4.), + + Alert( + "gasUnavailable", + "TAKE CONTROL IMMEDIATELY", + "Gas Fault: Restart the Car", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, "steerRequired", "chimeRepeated", 1., 3., 4.), + + Alert( + "reverseGear", + "TAKE CONTROL IMMEDIATELY", + "Reverse Gear", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, "steerRequired", "chimeRepeated", 1., 3., 4.), + + Alert( + "cruiseDisabled", + "TAKE CONTROL IMMEDIATELY", + "Cruise Is Off", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, "steerRequired", "chimeRepeated", 1., 3., 4.), + + Alert( + "plannerError", + "TAKE CONTROL IMMEDIATELY", + "Planner Solution Error", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, "steerRequired", "chimeRepeated", 1., 3., 4.), + + # not loud cancellations (user is in control) + Alert( + "noTarget", + "openpilot Canceled", + "No close lead car", + AlertStatus.normal, AlertSize.mid, + Priority.HIGH, None, "chimeDouble", .4, 2., 3.), + + Alert( + "speedTooLow", + "openpilot Canceled", + "Speed too low", + AlertStatus.normal, AlertSize.mid, + Priority.HIGH, None, "chimeDouble", .4, 2., 3.), + + # Cancellation alerts causing non-entry + Alert( + "overheatNoEntry", + "openpilot Unavailable", + "System overheated", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, None, "chimeDouble", .4, 2., 3.), + + Alert( + "wrongGearNoEntry", + "openpilot Unavailable", + "Gear not D", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, None, "chimeDouble", .4, 2., 3.), + + Alert( + "calibrationInvalidNoEntry", + "openpilot Unavailable", + "Calibration Invalid: Reposition EON and Recalibrate", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, None, "chimeDouble", .4, 2., 3.), + + Alert( + "calibrationIncompleteNoEntry", + "openpilot Unavailable", + "Calibration in Progress", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, None, "chimeDouble", .4, 2., 3.), + + Alert( + "doorOpenNoEntry", + "openpilot Unavailable", + "Door open", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, None, "chimeDouble", .4, 2., 3.), + + Alert( + "seatbeltNotLatchedNoEntry", + "openpilot Unavailable", + "Seatbelt unlatched", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, None, "chimeDouble", .4, 2., 3.), + + Alert( + "espDisabledNoEntry", + "openpilot Unavailable", + "ESP Off", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, None, "chimeDouble", .4, 2., 3.), + + Alert( + "geofenceNoEntry", + "openpilot Unavailable", + "Not in Geofenced Area", + AlertStatus.normal, AlertSize.mid, + Priority.MID, None, "chimeDouble", .4, 2., 3.), + + Alert( + "radarCommIssueNoEntry", + "openpilot Unavailable", + "Radar Error: Restart the Car", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, None, "chimeDouble", .4, 2., 3.), + + Alert( + "radarFaultNoEntry", + "openpilot Unavailable", + "Radar Error: Restart the Car", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, None, "chimeDouble", .4, 2., 3.), + + Alert( + "modelCommIssueNoEntry", + "openpilot Unavailable", + "Model Error: Check Internet Connection", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, None, "chimeDouble", .4, 2., 3.), + + Alert( + "controlsFailedNoEntry", + "openpilot Unavailable", + "Controls Failed", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, None, "chimeDouble", .4, 2., 3.), + + Alert( + "commIssueNoEntry", + "openpilot Unavailable", + "CAN Error: Check Connections", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, None, "chimeDouble", .4, 2., 3.), + + Alert( + "steerUnavailableNoEntry", + "openpilot Unavailable", + "LKAS Fault: Restart the Car", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, None, "chimeDouble", .4, 2., 3.), + + Alert( + "brakeUnavailableNoEntry", + "openpilot Unavailable", + "Cruise Fault: Restart the Car", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, None, "chimeDouble", .4, 2., 3.), + + Alert( + "gasUnavailableNoEntry", + "openpilot Unavailable", + "Gas Error: Restart the Car", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, None, "chimeDouble", .4, 2., 3.), + + Alert( + "reverseGearNoEntry", + "openpilot Unavailable", + "Reverse Gear", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, None, "chimeDouble", .4, 2., 3.), + + Alert( + "cruiseDisabledNoEntry", + "openpilot Unavailable", + "Cruise is Off", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, None, "chimeDouble", .4, 2., 3.), + + Alert( + "noTargetNoEntry", + "openpilot Unavailable", + "No Close Lead Car", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, None, "chimeDouble", .4, 2., 3.), + + Alert( + "plannerErrorNoEntry", + "openpilot Unavailable", + "Planner Solution Error", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, None, "chimeDouble", .4, 2., 3.), + + # permanent alerts + Alert( + "steerUnavailablePermanent", + "LKAS Fault: Restart the car to engage", + "", + AlertStatus.normal, AlertSize.small, + Priority.LOW_LOWEST, None, None, 0., 0., .2), + + Alert( + "brakeUnavailablePermanent", + "Cruise Fault: Restart the car to engage", + "", + AlertStatus.normal, AlertSize.small, + Priority.LOW_LOWEST, None, None, 0., 0., .2), + + Alert( + "lowSpeedLockoutPermanent", + "Cruise Fault: Restart the car to engage", + "", + AlertStatus.normal, AlertSize.small, + Priority.LOW_LOWEST, None, None, 0., 0., .2), + + Alert( + "calibrationIncompletePermanent", + "Calibration in Progress: ", + "Drive Above ", + AlertStatus.normal, AlertSize.mid, + Priority.LOWEST, None, None, 0., 0., .2), + ] } def __init__(self): @@ -565,6 +646,7 @@ def process_alerts(self, cur_time): ca = self.activealerts[0] if self.alertPresent() else None # start with assuming no alerts + self.alert_type = "" self.alert_text_1 = "" self.alert_text_2 = "" self.alert_status = AlertStatus.normal @@ -581,6 +663,7 @@ def process_alerts(self, cur_time): self.visual_alert = ca.visual_alert if ca.start_time + ca.duration_text > cur_time: + self.alert_type = ca.alert_type self.alert_text_1 = ca.alert_text_1 self.alert_text_2 = ca.alert_text_2 self.alert_status = ca.alert_status diff --git a/selfdrive/controls/lib/lateral_mpc/Makefile b/selfdrive/controls/lib/lateral_mpc/Makefile index 65ebd876d28668..97579e751c833e 100644 --- a/selfdrive/controls/lib/lateral_mpc/Makefile +++ b/selfdrive/controls/lib/lateral_mpc/Makefile @@ -4,6 +4,7 @@ CXX = clang++ PHONELIBS = ../../../../phonelibs +UNAME_S := $(shell uname -s) UNAME_M := $(shell uname -m) CFLAGS = -O3 -fPIC -I. @@ -13,10 +14,12 @@ QPOASES_FLAGS = -I$(PHONELIBS)/qpoases -I$(PHONELIBS)/qpoases/INCLUDE -I$(PHONEL ACADO_FLAGS = -I$(PHONELIBS)/acado/include -I$(PHONELIBS)/acado/include/acado -ifeq ($(UNAME_M),aarch64) -ACADO_LIBS := -L $(PHONELIBS)/acado/aarch64/lib -l:libacado_toolkit.a -l:libacado_casadi.a -l:libacado_csparse.a +ifeq ($(UNAME_S),Darwin) + ACADO_LIBS := -lacado_toolkit_s +else ifeq ($(UNAME_M),aarch64) + ACADO_LIBS := -L $(PHONELIBS)/acado/aarch64/lib -l:libacado_toolkit.a -l:libacado_casadi.a -l:libacado_csparse.a else -ACADO_LIBS := -L $(PHONELIBS)/acado/x64/lib -l:libacado_toolkit.a -l:libacado_casadi.a -l:libacado_csparse.a + ACADO_LIBS := -L $(PHONELIBS)/acado/x64/lib -l:libacado_toolkit.a -l:libacado_casadi.a -l:libacado_csparse.a endif OBJS = \ @@ -67,7 +70,7 @@ lib_qp/%.o: $(PHONELIBS)/qpoases/SRC/%.cpp -c -o '$@' '$<' generator: generator.cpp - $(CXX) -Wall -std=c++11 \ + $(CXX) -v -Wall -std=c++11 \ generator.cpp \ -o generator \ $(ACADO_FLAGS) \ diff --git a/selfdrive/controls/lib/longitudinal_mpc/Makefile b/selfdrive/controls/lib/longitudinal_mpc/Makefile index 77718adfb4df9f..17f78eada990df 100644 --- a/selfdrive/controls/lib/longitudinal_mpc/Makefile +++ b/selfdrive/controls/lib/longitudinal_mpc/Makefile @@ -3,6 +3,7 @@ CXX = clang++ PHONELIBS = ../../../../phonelibs +UNAME_S := $(shell uname -s) UNAME_M := $(shell uname -m) CFLAGS = -O3 -fPIC -I. @@ -12,10 +13,12 @@ QPOASES_FLAGS = -I$(PHONELIBS)/qpoases -I$(PHONELIBS)/qpoases/INCLUDE -I$(PHONEL ACADO_FLAGS = -I$(PHONELIBS)/acado/include -I$(PHONELIBS)/acado/include/acado -ifeq ($(UNAME_M),aarch64) -ACADO_LIBS := -L $(PHONELIBS)/acado/aarch64/lib -l:libacado_toolkit.a -l:libacado_casadi.a -l:libacado_csparse.a +ifeq ($(UNAME_S),Darwin) + ACADO_LIBS := -lacado_toolkit_s +else ifeq ($(UNAME_M),aarch64) + ACADO_LIBS := -L $(PHONELIBS)/acado/aarch64/lib -l:libacado_toolkit.a -l:libacado_casadi.a -l:libacado_csparse.a else -ACADO_LIBS := -L $(PHONELIBS)/acado/x64/lib -l:libacado_toolkit.a -l:libacado_casadi.a -l:libacado_csparse.a + ACADO_LIBS := -L $(PHONELIBS)/acado/x64/lib -l:libacado_toolkit.a -l:libacado_casadi.a -l:libacado_csparse.a endif OBJS = \ diff --git a/selfdrive/controls/lib/planner.py b/selfdrive/controls/lib/planner.py index e2defeeb937c46..89ca649504b277 100755 --- a/selfdrive/controls/lib/planner.py +++ b/selfdrive/controls/lib/planner.py @@ -44,9 +44,6 @@ _FCW_A_ACT_V = [-3., -2.] _FCW_A_ACT_BP = [0., 30.] -# max acceleration allowed in acc, which happens in restart -A_ACC_MAX = max(_A_CRUISE_MAX_V_FOLLOWING) - def calc_cruise_accel_limits(v_ego, following): a_cruise_min = interp(v_ego, _A_CRUISE_MIN_BP, _A_CRUISE_MIN_V) diff --git a/selfdrive/locationd/ubloxd.py b/selfdrive/locationd/ubloxd.py index 5b597c5be72f36..08a20229505373 100755 --- a/selfdrive/locationd/ubloxd.py +++ b/selfdrive/locationd/ubloxd.py @@ -142,14 +142,16 @@ def gen_solution(msg): 'longitude': msg_data['lon']*1e-07, # longitude in degrees 'speed': msg_data['gSpeed']*1e-03, # ground speed in meters 'accuracy': msg_data['hAcc']*1e-03, # horizontal accuracy (1 sigma?) - 'timestamp': timestamp, # UTC time in ms since start of UTC stime + 'timestamp': timestamp, # UTC time in ms since start of UTC stime 'vNED': [msg_data['velN']*1e-03, msg_data['velE']*1e-03, msg_data['velD']*1e-03], # velocity in NED frame in m/s 'speedAccuracy': msg_data['sAcc']*1e-03, # speed accuracy in m/s 'verticalAccuracy': msg_data['vAcc']*1e-03, # vertical accuracy in meters 'bearingAccuracy': msg_data['headAcc']*1e-05, # heading accuracy in degrees - 'source': 'ublox'} + 'source': 'ublox', + 'flags': msg_data['flags'], + } return log.Event.new_message(gpsLocationExternal=gps_fix) def gen_nav_data(msg, nav_frame_buffer): diff --git a/selfdrive/loggerd/loggerd b/selfdrive/loggerd/loggerd index 1db19dae1cf737f295887bcd35c9d87172494615..7a058b743f741923ab17503c214f56134a6a54ac 100755 GIT binary patch delta 77 zcmaEHH2KBRF7M2#)7Pc1l7LFFq7OocV7M>Q~7QPn#7J(MQEkY_M7){$% ZPY40AFc6CXu_zFW0kQaY)e{njr2s`M8?pcZ delta 77 zcmaEHH2KBRF7M2#)7Pc1l7LFFq7OocV7M>Q~7QPn#7J(MQEkY_M7){z$ ZPY40AFc6CXu_zFW0kQaY)e{njr2s_?8?gWY diff --git a/selfdrive/registration.py b/selfdrive/registration.py index 4327ed3a87da03..9b7e6964ef92b5 100644 --- a/selfdrive/registration.py +++ b/selfdrive/registration.py @@ -7,7 +7,10 @@ from common.params import Params def get_imei(): - return subprocess.check_output(["getprop", "oem.device.imeicache"]).strip() + ret = subprocess.check_output(["getprop", "oem.device.imeicache"]).strip() + if ret == "": + ret = "000000000000000" + return ret def get_serial(): return subprocess.check_output(["getprop", "ro.serialno"]).strip() diff --git a/selfdrive/sensord/gpsd b/selfdrive/sensord/gpsd index 9d577af8d867347ae8ddb17276907ce68f6c45b2..cc5d8d9eb88ad798f6411688a6431fa4cc998b92 100755 GIT binary patch delta 59 zcmca{!2QMn_l6e67N!>F7M2#)7Pc1l7LFFq7OocV7M?AmC42O%VA2 delta 59 zcmca{!2QMn_l6e67N!>F7M2#)7Pc1l7LFFq7OocV7M?AmC42HW2s# diff --git a/selfdrive/sensord/sensord b/selfdrive/sensord/sensord index 94cb27d1cb9dfe185992eb58aa07547599028321..63e2ac82d6ff1513cef120a2efe4d9f0ebfa23c9 100755 GIT binary patch delta 57 zcmaEH&+WxMw}uwR7N!>F7M2#)7Pc1l7LFFq7OocVEj(*)Gn%%qyUhc{ygF7M2#)7Pc1l7LFFq7OocVEj(*)Gn%xoyUhc{yg$2Hk2D zY7?_MsnQx0YecNEVu?y?L~0{a8;2^ucEkXcO=I?d}ddl<4wRn6-9;_|9iOj7ac71 z=-^>y9RGCu^(ynd|E;T118hI-?^4>#_dP#T>ui?|KUDGf4Q8|wzu~Dd>J5F>Nb#u$ z9UmPZ(>@(!3VWoi>^w?Q`YWxg(PXcc*ZazNKgCN`QRY)U z)f1d%yqD@p4N#PJMTkpG9#bZe@anO$0q@UMle7}|Q$?XQvO`7Uzdp{WXrPj4m-FN% z{<7J?KqWq0a*g;UqCH~()w^W<15F-NlwTer1xH*8IV$jfVt$PR0qT&QxKnVW;RrP> z$EPS~iW-gh-S^3QG87-90d((|18Ak0+i38ZD6r~VvWk&Z;Pj*AlrGuZyfhPOsx$2} zeiK!61Mxky1X-%*7-~5CZ&}Z7;{9ocawCQ*V*HBYCE+Bo1jgEESIGt@5x0xC#>nC; z8mCTC-V-A>WF82JR}QjAi+-+dDcp9 zrx6%$jhUFUQqF{r;zv_w+m( z@qS%4FpnCzOU$8}6PMFkQauyMCp@%kXeE_@&@P+VyuD+}H0r5qlpNU-YGC0I*+6K8 zY?zblSsFnvS{j~-NwfsJFOxG`q7Gfm_5V-u#BeEGXYyF9Ql#V>Nd-=z27Fs&fuYo) zK~&KOS~8x}k7(xNA2qM>uPA;MEdd+a<5Yja#_J1nz`4AhZ-6-s=BAI7{9UoaxU4xB5L3yn!0&^lq0AS|GPQW zP6elW6gEQ< zP)9Sg#&Q^9Cy69G*uI}iyP!t?vB{i&(fB&5$W0Azq7HpU$%O`Tqeue70TZ+|d=)KH zJ&u><0P?g185-CIBk9Cz3DqCFkG5I<7jn(UQGxAL(cYpgz)5!)ClSSmsG<=fz?h-c zG}RvBy=kh4Qu6XH*d+%x@oQ^&t?+82qA(=O2h@N){?r8TA5MrR=zP>7S44@>aVrfx zI7n0|UK!wPDZU8Y?;B>umw>O@AnPeh9#gpCz|&HwLV@56Sy2tR?+qDW2fm58(k9Ds z{k^u!czY8cp(x8qa5M>u(ltaDaHaZPJ}Bk})nAsX2Y80K7x>(_WxNmgj*8@dErS z50dd2;7f>SftL&}+E;QQOmfPK^1!=^7l7A^7lF?kEbA!&-$cADxY53qszcjkfeIAR zh*yE{CSC(RbBL^`4m?X-8Dgcd@E!588qOxZlVQ<$!B6vOMsa2^n7izMOaoc!KIF3vRS;rR1ic z%Ze&cU@!3+@C;Q{2R@17m7#Je*gcmJcl7YnjrNs1RpjguOrFWf4!M9YeNu8yYQ>^K zF)yg)GsFo&ynMhNKFI^X z1K&+N0X+J&jL$T2v4oXx%MoOo1Vu@FAPeMxZzrAyUfv_)i@-yd$@)vcxBNkzmqq(Z z8H8TX%Y$?UxP7zaRp4RbHQ+_!%5ky-oJrZs<$Jr}M*CI@7ycs~a6o}+HOZa8mwzm| z3%LIi$=$%KpGofR;b!|vcA4yvuSYQYrR4jI^RRgNfp0oS@&NE@$4MRpo^F>s1U%3g zlR_ATDm4%RzIUjMj{>)kl3WA6>IBK-z$eX+JRJjpXCec919d11yh1z&eDx67Kpyxc znxO*m7$-$;j4V)u0t$_+1bpV1GQI*ly<9G36?kTYjITBGn6l()Db$+<#reGC%JH&7 z?r4#?9e9nn1NfdzvK|+3|IJ3dG4ZemggIMe0S|EJA0_t!-}Z{+KH$r@N$v-}mUzJ6 z#)jaLE!rvzgi`H`2gSlrY-CBQ5#Wo6M}g1VF5@-e@wX&T0I!+zp(ts|dyF~phAfbQ z0y~Ijfpfz-;M{Nlxbr7+fs0LCEKId58!j~oV!_^)yo~%Gl2?Gwtw>%2?)iyqxDI^Y z4iP`o@SR~YfEOrh2;yZ2?xuzvz~`otiwC6~OYAW>D1o!(&8P?XP`~6};6CC$;9Jg- z@qXZ|C_W&0&tk5p0wE|6Ss{lS2JV|J8;Ahch)01}=E!)hiHpT-4M-u;Bq-uhtZX<9 zd>~bn0Ujcr19fB(^IS@{k$TC@vLvW*gYn!v+ zIz$1_A-L}lJa7me>fvVlO6U#oNK?GRJ%af@LOcSzxL3wUfol}60Z$N*1JAq>lNBXE z$Wehb@FMXH@G|i%aPDXh_@;;Dl9Xd06zCI=3h;3;`Ru3)d>cIrQm7oSG1p@UKJXS< zkAt{%m7Pa|2MX|KKVIPcyw3-mpCt!@b3LJE9j_-6u6H*jM9Mfhfaw@@HBA#fHE^YCe}c_c&hnxfh-i@k6LoT`SE-nIDf)g0L~xH z6q(29(JFreT4I4XuUQ#5FIfdRfACNR&P!GU9^(%T>LBo%DI=O^h@Tldf%`_vI2Z8z zPh>K>fk))C=a}LHfh+O@-$M_p1Hcz0WCLN~Tu%h}Zi8%Kj|aH%S+mi;;st>}VDJO? z$uATr0pP}`+{P;eyh888z&$BB(~*(G%=WD%&`5}40a|+vIB&l=@G{kt06y&=*>Kw8 zvVH3d2pLN-2c+=!%L3=^mjfQ42J*mp`xSs^V^p9B0&l+(@S*q05mbREXlZJ|gS4%c z6XX(cZjB7b%@M}zAY`^n!3li(BX^huT)@4*m)rw<%ZZYEfqT!A+%I|0`QOndg#Z-b zibBA71YzJjfGBW|*P6Ike=d+{62w)JI+O;^9m)bPmE-_&z?Z)#c>%dya3lYUAaKKF z;JcT~Proa`wUXpD;K5e8ly%@d6ZTPX{$Dirc5{s#LNH!E$s)N6czU(uZs0@fl6!%7 z-!Esv*TaqRD+(u9phqzIw!Lx$LEy`csS~d-aMzJ?CL+MceP417xcB!lSy3DWUduFa z*X=Ss1Dr>e1I{y%2hK}VjDb+UQBGY6cx9F372up)Rp0|ZmmRGG=k2F_OD?f>{!gDL z3phyNwcqgr$(_K%KbG8m2<`#SGv{mOF=hK@vLb)8pm4)M;JlV0;JiB`zjKWk;sMUS;sri3e7o7c;s=3^B>Ro`6kuaX1LtJS0_Uq@4mdAmfjOW5d3zLDpz}YEtPGrIq5_UUB{hfg270XXgq6=j|5;&I5}8=iJgv zKDTH4akj^yfVUzq9%TI#xyTbmADxwPT+A_Kyd-ru9fj_;9Vify}&C8`PD4H$y486F+3Kh&>(~+h=+hr znlGyk0}m6A0OvW50;f5SDH;eo$#LL3$qC?&1+qhF;H%w|XMpn@XHDLaTs+A+DBz?9 z^1w^Pi@=p+YV$3#V%kF4ehuU}@jCE%-q*ybck6So8BiFE+CCe{f8Ppk_#Pplg_ zXRil1Wv}7|p1VR0z-RJ?iB)JN{7@iI1p>g!#KXW{$bz6t( zxHr}R_E`&-ERmU2fv5=aD)4UNb>L~@_VLYY8M!z0?Cl+~)g*gBUQ65yJWt#Qd>e5; za9+j$aBCTZAnd1#Lcn<$!@zkNBfxnXqriC?HIpA?8RJlZmoWjn7kwc(3%qh~YU&*w zYT@40;yY$pmzo+x@uj8?oG&#>NAq&=rN$1N=hp$;nqMafyiHudd4Ao%d44^>d49dX zd47E+pVo7Z;ceoF0(_|n0H1VC>ccxbtV>D+WWJJCqma`kORc)z?TxYpV*v% zQQ}VE4qaX>Jitrxed@rfezE0L)(0_N#QnhY!~?+h5Dx-hLTADd@THQ+lrRXqh!Nnt zh*99Yh#GKS#5izX#DvKY;xcI{z%G*k-bEwJ1K0G_g1b7@ke<5xu2~BCA zap1g+3E;epY2dt!8IvDm8M9D;moW#tL?bH#ccoL$COT9lo%%2_E9O}$=gV3RzI(lbl@|D#5)Sy%- z<+i5UHKBRAd8*yOd8$3Yd8)m@d8&QDt*Q2dz*8Ln&f6&noToYjoToYroToZs@`GI3 zqELXRS_59VA+@<%T-u^C$1)(dE|WY9d^_VfoVHL)wTH7#auSL%!OEOmP{HRBiJ=6qM`I`Kn!H}#itiaI*FerbD|sEb<2lLgscY{SU#z^} zF}u2166fURekER%+y%U_Rs1@jc)5YQA4x5~zvF^=RLl=@op=B^cPI?p^S+#}NNWD- zL3giqsE+qj{a4RYL+__9Sv{*Q^b(B^iY4ApJ-d3=?EHIDc28*@l<$4XJ;1ZXy};97 zre^=L%arG)Ye~hs9G)ch4_)FrN%sPgIYR2_22{I zMz)rE{efAkXKt!3BMzJ&r)Fnnsr7K`?u@vmeJs1@OI?r=1I)P9?6TC6YdX}*$Em4n zW~qhyQn!d7k^56y#gA#fO!a?IRQO41hWJtYBz2wm;rKN5;Da48&!@7c(A4G?JpVJv z!@$GDBfwV>j{?7qcpSL-rlZKdJUGfa@0`V;Hq5EWf4tSJ!9{9j7 z%=pwl9~yn`-eGdPl_6%HOY#cvJ^z($)qyK@XX?VW6HaOWt=HQ*k%$pW3pfr z^xecY;7cEu@p0heek*wb_?-2UXMl&!kcoTEBmH8nzmqXJh?!*kp%L-Q1K*ODya3#j zmAnXi5yh8*Yt)AWq7U8A$+A_5$rG;uU$jZa*MTd4kX$*fd7)ht?*N{mKKwk}FXk%9 zvMz|3N!$&*^#vL40nYQ_1-_o@@dGbVABH{JFXr4L>kL9nn0N@d_fIlD44nHA0bZhd zG~lk&Wj;LdXusLTmt~y^hzZiQJPn+$@fqOa8h_-vj@iCH%jyasmxvdEdta6DCE(82 zQn#$@xH9svlxrYs#1%Ob%c|Uu$an|v+?UeY+`vo3J*f-U4@!9+b1z&)H3uMaHSrK| zYwm&9sOC6u$9`w(xyQ~rH%s;9K;K5Z0Gvlw2JR8{oxA?5bIVjtk@;oK$bRAu;M{LF z@PMfA@9W36M8wZNkB@K3h@Yp5pC$40D)F->e%>#BI=*tIUU~eiA=Aoo#_LdzN9bdJ zbJmdUZ%f_nYu=-p&{zIuyc%7WdiFQ7VoU!le~mv1VMAY)Tmv3{P4YN!{;m83aQ?0Q zG;sQ@{Fssf!Thy+;fGn^{9E}s;QU+pdEoq8`32zoTlqzk$9kT9^RMNXpaB0?ei=Cb zR(=II|5kn#IR93Dt&xlN75=sSdZQpX|5m;-y?F%-v@~|$ttGiM4&Y0PyMV{V`_%s2 zz$*t*g&qj-5%&V`MHTvhFCp#+UM3z)z3}9qRN_f-<8V{z!6#>_?we8{iXV>UsR_UB zP~FQ@3x3-%A+TKjUQK33^RT1D3&3+fNp1dZM=XE7{1xmf$U_5?*MRe%m#72hL{`ph zZa&m0>#+m364?O)C$bYbC$bATC$bwjC$a}PC$iV%B9ZvJV4TQ4D6skhIRZcMnHNeP z06y{}$%DW-kwcCAyoN*$HwuF9r6q^}4}V8CpaBowl6rQ-tk|N6lye}vua!IxoL95} zoL966oUN$@+*;8x2)v>d;H@{w4po82iPwPlS}x=3z?c6-a%HBGdJQYOHzozUDfFx~ zTayDgTayzwTaybouc*6`i$8T{S(B$x5ZpdAb>Htg+Fi5~0g&er52e=pZqVHu9c@km z5eS@nZEDQMjy4C$36SSpo4Rgehg$7QJt%%Sewun+1bcrf{lRkQ zlm)`Tv$Ql3;H|VYQQ%Aeoci$Dj+l#zr9qxUJOjKJRhI?6gm?~knRo$s<#sclQ~Glk z$JTbpzqa8#yEz*;dtAWzqT~in*`s)Xm#BU(a7rHWjY<$Wd;GvTdjh~YdxF3@c|ySX zniMv9L$=karx7T?7o{k0wlEDiAFkrS`I?kyIY5(sP(W#D{;sQ_n>r~+q?r~zk> zsGD5m93EVi+07HhCSeE89^nAa9^nMe9^q=_qJ8U_<8BlLXOr*%XOHj#XOHj!XOHj$ zH$1{eFeVc_n`=Ijqpq96oTrN+E8D;9c4u1*%@D)Ag}%e#PE-UZz9F5o@h1%l;Wz%B0r zZh04Q%e#PE-eq!;yI=FJIn9Y+c^7cYyMSBX1>EwkMsDmKKH#_;1;H)v0&aO1aLc=Z zTiyk{$GbqVybHMHUBE5x0&aO1@KEPK(;A|4z`I7SmC2|Fb>A!Ev+cW5Tg4B@&r@H#(h-~Yf=rSU1kct0oSn=8oSn=GoSn>Na*@gCWNs+HPUZn#pb>k4vy=INvy=H7dE?{5 zK%*db5<6KCI6poN0q^x<>XScX0DXy3X_CK`o?cFC?!6 z-~K?*{Isj(UJsTy(_ug22xW z{Hc#$ACxM*?r7Uf8!`xyo=;LAzTUB556MxG-89!4aK2*3f%6qJ0bE=$Z+t_1g`b+q zf$XAY^1%6uSpd#g%p!2UVwQkgSIi0sS~4|t`>a?!AkQ<73z}DaB%R2dz%3gCZrK=c z%f^8B*cb?wjRCi847g=uz%3gCZrPa0MH=HZG7JSQ8v}0H7;wwRfLk`!$c=5pr~O2u zAUIzm)4(ko18&(EaLdMk_t+Q+mW=_oYz(+%W56vN1J0-Y$^~F!LE6++C{UqOdJXs< zIz-oj^J!n{Y))!E?b|JG%)fZ?Y2RT9lJjZb37k*+F5rCHcLV3sz6W@Zje*c(WAn@6 zyEJ7-+fdq&L5K`?rY8@sT1#rF_*0=H}oxMgF&EgJ*gV`Cs#HU`|XG2oVs z0k>=nxMgD|7is)88-oItjRCi847g=uz%3hV|C4oi@H6LBZ--NaqMt_d zsXKSiimkd@E}-&VURk+-tA0oe3!H7t0i12j37l=r1>CYRHwbKF9^h(WLny zvhc&yx@yOQe}{v9(urno`i z&yPI7EgJ)F*%)xk#(-NkW^$3nU$ZeNVA&Y(rSHlShk;u*2Hdi-Ms92)%f=c7!7UpD z&YvG8fcsX;B})U}^p@;s2Dta_W8}AZvLLuc;62%%1Gsyh8JD{J-{M#6s4W-7 z%pvXu?h%t`ygb02Gf6bazG7t_FbFJ^%AUd#gLy_hrkLH1%E3h-Vm0Oun`5jgL~5^&y&*~~ z;z;3z0@GqL8GXPV#Qnf`Ycf6nJV5b5iyQMVUfM0R3oJqMbd+`h@B;A&aMv;!9|c~e zcn$c>!Bij)!qDZZbsu-MucevFf?Oe#D7cSt|>B0j-;GWcsPdn7`J*n$H zofY#vCznElsO`k#z}eUmz}eW+z}eU`z%66Tg22X>1J1^l2hPS;0M5o%1kT1*GWkJ_ ztqcX&*ebx;*s8$U*lNJp*y@eE(b$ylH5(5fGVH+F*c`yw*qp%G*j&IZV{?PR#^wRe z#^wdi#^wXg#^wj^*d%i<@V#NuSooaB_ew!1z`th@0?xl@5C*>Y_p*Tqa%wngaoN7& zH2xE_hQV2aG`6)=AP$^=&maMu@0HTPw^2PA;MUjevLLjcl$!l{NBcI~g+-9FYw6Mts!Rk_G%h#L79$uq$Dekuz*K=C=?Y;}3y zmemzN;QOf}aJISu4A_Uq>Ur`8pZ}Ze2$;5coP82hP{g1aQ8Nrh)TyGy{Aa#= zQq56_+(29d&R5MiaK36Lfb&%|4cxkFW|%hG^b zmIl1X(iSu?re$fsElUG#SsHN5(tul*W^$3zc)j#M0n5^WTb2ggvNYh9r8RP6OY!r^ zV51;7UoS(zElUG#SsHN5(t!6^8VHu90kTb2f#zhYbm-eYMCn|DF$ zN%|#+**eBCff`gE_|&> zZAKxs7qzJYw|ot_n@wFq#_*PuW7*9*W$q0*Al?l*V4eFlv|la;A{NI zBMSxikw*?VKk~=}kI$CLTL3#rRte9hBG_}VyPUWg47_W@^L^8;sJ3jk+d3&}PM zqRrSysyhO)A>vWs>}wiu_O&>0_O%3X%hxg>XbQ4LJK+960-00(h8m zD}BWwd@Tb7wDV*#W`WNoo&(N*F(wb3|6)wR;>P@o7oXRPmLNI*$(R!GUes_IIQv=! z_&AEM0=Imv27>UlsSe?5BWbD}KWNVS5OJ42-64D};}E_!l$Zx%gT%eS+1Gr)+1LEQ z+1G-yO;11JYXhn7FvJFkM}V`hMS-)gX~5an;=nCmOM{?f^w;|dU#nb1mp0G?-yy#P z?x*j;lz{X1V9LPR*DAoR@4-|-;ODkA;OuL4;OuKkxOwH-*X+RA*BmAnd5ym2gaYhq zF5vt<7&mbCH4kw1HE$y~_7(e@uTc=3ea#P?pW6n2XD*RT76i`Ug9!n*z6TQqfxib6 z0nXopi6W<5(SXmqSav85oWBQ?4iD2)18pZP@KXg@2wYA)2b{kMlLyX^nhU@K@9AyF z*g9f9s;>h2QsPzM{AHIKaQ?DO9XNm4MY*y$7wO9``k#)mjgGDQwwx6g1bNSw+zp&h z5+2}ulJElO9p?jXoh1Aq@JS*7oOfIhIPbU+aNcoY;Jo7^CO^oIi$Ve3aT;(wNyLHk zj!OXN9hYw8jXN&WC^YQ2EO0(apCn4a`6N*W&L@cqa6U;? zfiI=ps$F@AlSCZ~D0Ep+7B^?|ybEQL+JOfs-T{0hai_(N`4=xfNw_RQ@;L$81;CX~ z$vwdNB;f__rg$H4>kG7g5cmtULH)JC#z|qY&C%weX$wQ_lJoVggKZrP+@!}rUqn0s zoKF&I;CzzE0C!H(FKH9L<)ZoupwA;-1kR_25^z2}l!5cpIfjun@oINc9oINcHoIOng z&Yl)GxyWfeMI@jAds-Seds+rKds-Gads?oM8+(dR5&1?za6Uy8fU~C+fwQNTfU~ES zfm@zd0f9ZO3Y>}dhu+isTi1c6(g76O4iEuvpLOn91a znDDgaG+GT}^9%LG!-S_TB|QUrj(8S0ds+@Sds-g2@U$;PJFz8HUm5f)@d|MEv?_4+ zv>I^sv^sFh)9hC_=aX-Z{;W%Q*{bVkc|qS#+zXuVhr$3y(|FSx+4mLz;{F; z;Ou2#;Ou1);Ou2l;Ou3Z$we-sm&Ks~dszZF-w~yOvzKLnvzKKXxv`hn%W{o^;Ou32 z;Cx3^0KR>xT*@MFz9T9Dx9*6_An+Yg1vuXkRe^hcBpa>)5C28-I&i)tvj1?He$xos z39-GDY|bAxC#jn%b^+%*A~$fpBk};}Uk&g94@S)P^kE}y{bGBl69EWvQ73}H`F1G; zoNt%H!1;D50-SG`o){@^mt0{vWeEt%5>Er?qeTWdA1$)Lc{}ESTStpL2z<0C0O##k z1kT&B1e~{H88~mpipdYM9jj1)w_^=BA1&&@c{?iCH0Ks?M|&d|?OWT?(I_-*M<;MT zTDXAo(ZUU!j}{)_*3rTX0v|1W!1-w52hK-}0B}B91cCFfO^2?5qeVC(lQ9eh#u1MI z-%Uvx1zx>I)}sO6v_$f_#f|wFFaEXZge6GMzc!r)&c8OD0nSH@Ebw{P%7$~mtp~4p z5X6Jm#cuK7HA5pTgT8}!Rln9PjvghqcnF#%R)^T_#1&~i*7b*v7Ixr#v~U3D2d^&R z5&2%fe6%pN1U2S?pl!sx!1>(a1J36TKX5*G1b|!Tjt~gtHM%-R+)LHg=o7|>^M@lU zmm&jk+m=b517D0h|rb37iej1)L4f13WC>>jyf7;ccMCd=OM4?g!3>7XZ$N7X;3R7Xoe>UIc{d zL;8a!8b-HHu6+jdwZyZ?=|3@&18x}|aLed`_ZS@rmeB#Xj1IVEbigg618y0e$wi{$ zjaD5BSVs3F$RC;sJ8;YBfLlh_$c>H0H(IVnq0#7oTSf=mGCJUv(E;xz}HfI0eFwmfgp_T#)-n{R?}2fK`#@p>nkP-qpM65M%PWuzO*?} zOT-<(Eu#Z&869xT=zxdid;OY8!su2}V?GEf688hQj1IVEbigg61KwkFAcWWI{ZAG~ zH|KG>$f5olGC<&bqRRqjqsswjqss%gjIICz8(k4N8(j%F8(kSV8(jrB8(r1pBGJ+4 zYEXcUt`3|}bjtP3dBsL&2hK+4XynF5W21963WD>A&IO!}&JCQ6&I6o{&I{Z!Iv)sZ zbbjD$bOGRObV1;3bRpntDYwGc4?EU06kY;0x`^I>ifvFV3g!0vmi!L5ZzK5~@a)r) zCxAyOJ`LRcB;~y1F)K9!BxIog`&tgTHzzB~1LyzfQ~@|Y3okWs{eNCtTYHEmtJ0(? z%4*^@{bR4Ny1*&I>Vm|S8=6zHo46e~Tb%951~@-F&jM$w%K^6@ zp65Z}hvx<0Y;{H8Y;`5zY;|SeY;_frAH?daP=Kwj2Am(B*MYOuDL-z`H?}%^BX6`i zN2AbSbxz>?@Z1I5@rGP7H*kJ8_oFAUYf%C)j1aR?nqOGTikFeHKeL2v}#Ph)U`FH_1KOZjw z=jY=k;PiZafKma${-}QE>9!kU8}`Z>^hKL}Un}Hsx4F-|w@Hi{)wYlx59Hu$#CYc#vvz0QVe_EjfV~ zZ1P~?M*f)j``h{>(`^^`_B|p0TZ#q!h3Vo7>Y8D5tHCGq*)zoU(XNvfIBsn2;PR!C zJAreSx`1aX-VL0y)C1hgQZERcr9R-CrGDU?r2*iar9t4Fr6H3aBum3kfU`6Lyh0<6 z0_SUm2As1r-pCuXG|?zDWN8{WXK4ob>g(l_Wr3H7=YSV~e5`VqaV#z97t9cOk(en? zR!eDAB?!(CF9R=9J*9lf!ChbpFLZAw&HtQ|L| zy&~K6fWCa2v$@TJ6+SaVwR+9NLbU30_*-$z4nLBtZ`Zsb&>2l)Q~ zqr?W@Em|^Oe&B)Uq<@}xp6%iVj+Q}YP#%KZ#0$WE#7n?k2V`Rv;ECVsAD$-;582+b z9lO>%9eas8fIE+r@lND@C3gYmakzogI4)H@AUONUioC!z;y&O!zyNSxLI332;!Zj; zOxCA?o+BOyzMXgixaN}eq=EAQGr+9@WdH@>XHw}cJ7NbO`iYEp0FNInEw0zEiXUpH3_)H_M)8tC5l( z->b^_D)9AA$!ox;-KmfHj(7r+lO0!Fw>4+R>i)7FH}H`c$vxu%9$F{ky};w6B=-S# zjyK!WhkaLkbuscM*~uUTZFoZ#4gs(9c9^Rc2HyR$tS16|$wRW9DDdc;CXXo^3dhTe z;=mXEMDhgi?y%%(;Qp6wW=Au?XC`HQ*5t9CjlSqY+0z^p&`yv%4}9-%Sy2JFpVF%c z+_^~BQ)=YLi9W7Q%Zkd4g5aJv^j$&W$-9r&`(G@6=Ev$Y#Lrl-l#F-W-kdkx&&m97 z0(Y*F4ZDB`UzgksJUm=-4{*=ry^I-+DP9m-|0N6ffM+j}+z)&;33gZJn8?7ybXziKIux?Py%?3I*?&fpsXhieCB;JK4WtIf8VnWZ=2_kEC;dnm-VTa32&IWT-H?ty%v?_O2E6;%J?$y zRn*rC@Itq&rwV+UJcY!RItY7*$O85|nv-f0xu*koxS#Bh6Zkw`au@KCx5@h5CXe+b z+wT9#0v;&P+DCFP@XArLA|LR`P}y-m@I+QM+)xQL^6v`}x66uxje_9Y_Q-Qk2zW2b zyD;$D4%yKN@KxW|XNSa6k8?;p4*ItFk|%(7(~PHqk4(t^W`I{em;KEGuNTdI6;pB` z6vxSi^T1~wCmSdL&)q9|5qO=>Z6)Adn!vKj^&95frnZ#_%Q|Wh>$y+gI$vA?mR>7$ z$DPgT7auI&JAr#nmt$}NANg}xj~jUYBY8jO0lwiTvz|*8F9`ALWko*VbI8T~z@yaB z0Pr0T=pQZ+hgFTrg+b3t*HR+D_lD&Fqreq9Tx!6*kLx!s6zw?fkmb^#R|ZL*0X|oe zJPSNRcNsb0+7|uDMYg*pIIf@t1-(x9e|6yD@9J9@iQO<~mdsYi%I1Zh`)k<`C-AP9 zWIHb4Gk;184ZQSId6e(~PsmHXI23`P>@;sn6d&+Kbie2ap1)OgGyr_sU9v+V;H@iU zeAwi%9^+f`gcKrBKzY<@_>~d`zM3l1fOjpE4ab2GeO1<Dd>;4)VPHo4N&y7TB`Ycd&yA54m4GjzX9H#6^XTGP1-__F z)?ZsW>}aEX>w7}wcKwzgh@^}kD;u(}YEH^=aaqs-eA^Cr0&)Vc9WLWt!2P>qyc>AL zYqqDK7`Ba`kf~83LXdl+?3^F?z-{`SVeyQA99_9XpwBx-e?4rQb{yOy`O;2wS$u#K{1kvsCgda5r80a=;aOev=38+#)BWVDg6BOM6bv zL=g(K{!ahf5?jYa`*pGd70_1`uL6&MbfXcvcDnV#Xp+$ z>yP|U+y^`95pfiPmTr-SHQ?Rfk~|K4(G`*>fLAxm{h9{8t(Vye@kkkj>}Xk07Wm#j z$yvz(FVI;p4?NT^>nQ?Xm67$7OfEJ*f4wy_LjT(};(<=3uYP1i?BF6@N9s_)eviDY zC_isbj{=?f?7&B!tKTB(Q?-=-Tk$jIl+&+xATIl{?64Pje7J1K2fTEVjQ0Z{M^7*U zz&-uUfe%nZAncf`Uw5q-@W=;bg&OFdRykvF%@Queow~b zAujx|zAw*Qao{f#PXIsjGZ~)- zeh%>r@IO#JS(C?lQfws^$U%X-iRXd;l6V35I^q@JzPjvawULYV74NAshwOCx<(bgj z^0Mp%9w+Vso*?c4o+j=Eo)O$=U-5&$4FrH^siF|@9Pu#lJn<;-0Uoo4&iE-#Xh zI7ERo@DjymftQKrfLDkYEH2wuxIobo%}ZfKma%w2m*Ied>A;#M}WI2UX#4%7X^5V;!wat z1=7GdJ_FoG@j2iepKsz~{ryy+*d&ODQnWNB;6aM70O$BB@DRndW$SFQ7xY<4%PH=)ux(E~q5sv~76W4%8h{u6Pi6?rv+W0R=STY2Xp!8Q=lpS>Qh6xn>?yf+Xad1;tOi z06avz2s})@1Uyc>3_NObk$)8s;=h+OQ3al%ifX{q#OuIw#FdYlmn=)%Zg3<2c?k+6 zIG{kDxD$AhxC^+CKEiVYue>e?=5OHU{;Rz#g;0ZF?7zZR$-}@S6t4j<{Z~HOjnEfN zY~thOw?#ej<8M*l*ZJW_J4!@fvs`@VF?yS=Ro}7P)@rNhuLuAC*BWlc>kezKcnION8|4h7pklqh4M*M{Un|lH_?tR|2@Q9HmWv@H=Rg03WeRV+h_fbmr6GkV8 zDayxon|9wFGnJD2+9ULv{$xAu=oR9P(nqPOp<|N6eMjhz{KN#xU{8P{0c(u>CGqUR~2oOh9uf6?&Nc#c2VoK^+6A`iBF3L)?0>+8E~8a zY|-{Zb;NBO$GmJi?6B5EpbJ})GZu~C_~l=0 z?ds8^1)ccJ%&&}}lYT#Q2{<+;GySd$|?vpJ;|JxJT>!jS>DA@4igCvOx?qF(WZKnR!Tk?cFnbC3m(ATQ}v4 z1A3udIaz4A8Mz~pnT0k>^9ZfNT4btz;IFne)zMEM@}~Hi8KzHp({|jD$zmK+#J@L3 zjZS`k?8(WI;{X4vMH$mI?qvO%H*IJ2dC%L@ZNRSh$@=qe+D;f`jC_RnXFy~03kRN@ z?Amj({-vny;NrZ=`iXDZjyvO^CD%_*YO2!jc|bpuK7XjzdCoWJ?Z;`I z(+{Q>#wHi;AD6Vbwa!z%JP`YO14e-8!1R-}&XW#RfzVe7ee}WffSCOCqm%PRTD2ca zcaKT#6#C#VV+R>wdSY^6X;N~9NVI+jtH98W4&JME_WlOlrfZ$HZ_r;5`o5UR#;;8= zH;~pkKmG=Nr_ew62HkeQ*17W=^ff}i^zCm5m@cyKwQta05cmvGGKpC8bTJ^88F@9oOBHum|4t=-n& zAjZBntYpE(Vpk5=Pk+buD|Prr{hfDg*9{YTNsPZF_J7IPxes0>($DaL*2&4Pyx~#jNn0H>n(^bq>E!>-<-Xeatb(E8Q0zI50?b*chDI zjJZ{{DP|(R5Y#&F6voh?%dKqa#g63sxxz@A^%9kjnH9|cuGV?u!2^;DgHw_(h#9=@ zP`cO&?H6dBi@!l%A#}sJ{&VW@uKxE#+tvR!R=xUz5iM8mzeazjVmo16NztYy`;Rc3 zNtrN6{Hz*NPa`!Z)SQ|1(~^e$p19LCv{z|H!L6Ua)8>qoj5wuqnt5$duhTkz-)=0m zqpo~c+3@1zmhQ%SDnC~CS#?c1-L%-@OSR6&j#Ikd>Z_DK|7_O2s_J_ttSXa?az?SFT8{?96VS z`PIpyaP>liDJyU3UfG%1I#YjQm(AlUnaY`l(re}6|GcB~<(FoD^;wH^U1gB+Rc7(# zjR$twR@sJHsbu7VdIP1BF$2p_-}uOG+b?Wt=eIV_c+d77wePCS)$Z&=Ew5E>Jv@2k zW%{qHwo&RwZ|kpCZL`(Czpb}@V7pEo{Wtxt4{Wy_Kk+gV`>y)h?1B)An+}9sUUp+RKToKheuRe4@ zvVED>`Taxb#nY4Xh5o%m>2uCVt`Pb~htgNu#_EIqZM#T4=5qaq|F)f}78U)ef7|9w zD^*W5*1vUS-+i}s8e=n3%`dWMf{`^-4DG0uNB{Y@&gw+t|My+ld&|tP#uR6M8OZ53L;U^|*fTe{C~{ zej)0s^id}46!pDT6Pb8);k2Dc6iyQ>k<<77*LH$Ao$i)oSENNB@tJMhz~<4+QH|-; z7k(y|ck?{`+0SfKVk3Jcb>SmoL31M66Jq*vjhCT!etnRf|86|tF?0d+;h?Gz_BacNq2g=%jks_;9z3-Q{;~=!at0uZn_{E z`rN~k^M(H0q4exw$rprf_)kN5xl4@l;(BIFh)aU0pL~!8wulBqz(dUyNMkZ8s2-;O z^GnN0aE9eUS(+nEz{%Jx%|?L!Zp9xao#&I4`6@`_W+Y08H8PSn5HZ#!EGg((xz-M9HM>o zz@#{;B(D=%s8u=HWQBqHTZgHmj@&Xp+}{jHc6kQsM;xwRroJ#*|H0wv0yTNE{>tI% zm?K|1F)8k-bFO6t{eaM8OO7$?>LcpPv?wQw{^Yt}8jv)M-B@Kvcic`lkkNn5VZ!=C2{o=U!Bec$#i20R>(RUo7 z_GwKt$oi*8sBwSJ7?k22opj%9AJQ%gZ|Pnd#jVxbEfOD-s+9&dDHbTd#h_5=7br2UASd*vTNuV{fQ&hSw__7 zM~VdyQJ3~nH#9_vTU{e+SgZPxp&osdnrKjKQhnkm^*r^%U+e!nN_}IpSeVaWJ;rz( zkTV|#^g7mDm|feAg*kTJyW-CK;{HnaJvSb`?EMkGWyVhIT6C;_#L;SIWJ0Mplhc(I zol8CtDfNf?l(0Byid0C95&uRf$0lc=Gj`)EN2|x%Ca>u&ZUB6byG1kh_9K&(BYerq z1Gk^1^d`3ENOAjm`)QR&1heA$=)?M{-&QZ0zVVuV>hUe34pE6w&?>a1kN(s^^*ibX z(>L}xM*PWL_2$CHDaWeM+SH4u>z@u%gAVB?#+>HIi3b|v^h=%UZGGEYdpfwLRsWAu z%(G~C%3$?ywQu`T4dPMyxkJ>;4!>ynSJUTD-}uB3^&?x~_P$A*HI%;kW5=np&4BMs z-}vQm>IJqVdK;T^MM1xCn0nSAn|RYA{`C_7%*8c25*)8TF-$$?TZ(|noWbV2F8Y_4 z*XeRzjT(*=|3?3JaB}wJgZ2L#rVj7>rvb@JZf#2%6?JWB(}%d!392$gKi?&K?;oP; zE_ICh{ptFPE_HZ+vC>c9B4f>!jtm%CL;g@V5V%|OM`cQ7kcg1y6{Mtyj z-RRFx3#S=B_l>YU^O@M5m9w?elshE5{7kie`HQx?@5NiDDL-Ro6HGi(y;Q_qJzamG zT`c3kq56N?)v4;7q59b2YKNJh;q%{&<9XnN7WRy8hNkb)D%@# z#8F~}MV1@$WU^kz>MxE`hpQr!-ybFBV7a0X_?9|5W>`w?SaHd9Cg<NIt^qwJO-lrbOR{Z&*7*wv zXw=tqX`RV~=|%^a4^FQ5m)3d5q4a5O$@%YTohyWHJVd*>mvO5)Ouy8vJ~_h7z~Xo_ z1N*;wK>w^|=(@sPhvi*AsZTMrYKMN}Xm#+>R!aW<#N_PjPt?CVT0QP;3*O^N&OXnR z9M)U8)@QrpKEo&W?mD1rKTw|0Zl;=?Cz-8$Wbmt$X9~>Mo}@oFT5XS+&3Px7LGKtr z*NDQ0*C&5%QCd5a3$+Q!`FCoa4jQwvNtP>#ay*2}P1LY5(X8`jq3spJ(_TF+uPm=m ziJ$0u#u~s`6MH3R|Ncb%@-b?AA9L$HF1Fr19)0B)b?^~p*H%r`9~+}y)RTCxPwYuD zae^H*Rvq8R%DOp|^z+B6(|bT-l79bK^_)RQZgG@p2&IY1uIeQHOHusbb$d?M&lsm3 zbA(ZgnnRyZ-$6#-56&JAFFTQEg8im2@x5<~NE1u-(>srD7ZQrZHbGaj`kKLmkt0-t@1; z{c*y6!KmbD@w`ZUpfiy5pLeKpoh32UlITjw*oM|nJyY~AJJjXQ(g2}cB24W^avsg7 zF2_{;=O?P-5s7cvbp44F)undH7fsd2dQ{Iy`7SqAK40Es4698HYrwjFy-oWn*>4t? zRgW5UmfjPs8qcz3{GlhROF32lk4If?E9t9FQU|M{Q}stqQYU%MYK>rZOGB_Y=KVrc z`^V$Ye8w1tp$~7=$4%1*Oi=S9&0%ym48w?A@DkTFa9x)+P5;jX)g36Ajzy7OVtURTBrTxJ7%&)~BV(68DSZC5{`!GQYMZ*Ipbt4&ojddEEoQy)dDK%{XIvyg{8HaO;n1aH#lNS8OAkE9 zx9srqe9PYCv5)iWPo1oeI^u#ee{YOOubeEFW2jgE@?>Gv;=6vsCaZ0I=R1-gq!eS9 zmR!k#e)eQ>Y`UkQ$0n;YX#iQT{>o%)ILayd5mQtTX}(kRGp2}6|DvE@Iz{yoU3!Xs z{}j=N$l~Xx7*oX4X=UiPQ}nT3b!5!UU(<#6o@ToA3tn-i7YiWlpd>C6&AKL@=$s;s z^oP<5rzckk{i;Lh#*LY{%~@#aF|z@At~4x9+*G`9pLphN1vGTP(6b%M6}M}h7amF< zcVhAdp`Uvwy_YAsBCd6w$$G4Dghm59Jjv;Ih-b$ffcm_Xk}HHh@lbm8q~uPak3Ezw z2C!3j`UuivO;c=iK#ZVWJgFOUs0zdgb_#vKp>#2THR4%lpF`K3+d} zsyh4lkEID3ORf}$CfNwh_d}15vdP6;KvZ0s0s^Aq9Y7Qm8gKzoQ4vv*JDq~EDvh9{RHUJ(bZ`Md5fvp= zFN;^jqSpn*hPo8JzFrFoRgw4i%$$=sGfmDP{Y*38-+9h+wrA!{k|%+w|FQTD-JJiQ z7ykcK_LaFwp}c>y65DIz-C1557<-3)q*-d(SdHy+kSM zx*6+h^N45Cy3ii5BvV(db@paY+>ZA&#uX^5J6Q_rQE_L1Zaj1Q=>nybv?szw+`O_&1?nv_&G#s7m+fmog*DyZ^Z`Q_#`6EY~=j79K<~N@VtVW33Ob(SV z^nX<7*VRrfjQxem=&LrvgHkJCoZZuU6ccQ%tNUwCQ^45FX0yGX&q<3+U(zQMg(tfm z?k#UjAEsQY75gJIam}U~MHTyY`6E>MG(}fiqXqOF>(@(s4HK^RZDSg`hu!SETd|+W zL0bjw#VzbNj()@A+utU5w0}C<9syk)2<>s$-3DC_jF!?a#xly^nS#-U5cX+dTsj=V zH2AY|%Wx%EdopyY9qMk6zYh4T>E%1+dpdNg75=|Eb(8FlE@z);QM&e;XeTovIn&+gWt2eeQ!u=u{nTBXfN_iysS}I*R{)#~)T>q^1Yn zdU!B&s*hiZ7-=JvvvZXH*-!Td5A$uS8&c4a>(BUcSD|k_JsmvI%}_@ueYKHK1y=96 z!Z(UBAV@I=b-Q7l_517Z`txP}(bhJ887J6g!f0 zUNbJZRLO4He}mt8%z58a#*|By!i)bZ!vr1bcJdN9<<2hc8tISlgy;coJL_FtSD}-ER6EHht&2ZDylf(fPK`iGq#m@W0jYfYa!gpYgAz z#?|0l7>%V4NYm3I8!+q(e=U2=0RW z<{mz6WMQVA_*c3y^>QUsIj5O1?{ek!oDZ#?<7T>7DnP)ppN(W;ytB@Ul&70;~7pG02iPPYHL5zmCU|aW`*>cwusGi_4HS+SYpST8|=5MXLCKh zhCcRNvHG)HZ^s_8SJcON33_V}Ot1fq0Y;4YI+cEWAQHlI|J3HC6bfovvOO}D$J?w? z@DBx^h=s)Q*xKJjSN8~<%J;K^<$2BRcX$3QR^Ju`2?NC6X==bw@8ZjUIyE?!m-gBWD#xSX>cR^mOV$^he`>zJ^3*V2q<0J7;6Gub7|-V0Md;nV zZu!MIzJ@ydZ;jRinUUh|zJ`WJacP57b!~I=eII8=mR#oB@y%za&ok&A^`PS0W{FQy zPo+)=4w(E5lW2N{Ssn1@* z>uhfSovx7(-j$j9Ii_Aq?5=J&&-l7Xd96vQ?|4_EEUc^$d@AS`DSV<^Wcr0U#?Wa> zjfXs+6Pf;5t}$RbJr>CH6?cHG?enKAd;PYtkvA%X200BRW5e?z(@TR^KpH@!i-spU zfb+EO+h4j-X{WR!k0LL9OiKixps8wROubR*>M_{6dt`dM9#%wJg@xP5An_GFw&%`J z?p1o0=IO&v(d}hl++r-j9mL~PLVe7e0)6o0v9!D;ZiXKmZoF}ea_@M-tDcdZHi+NR%b0yDZnDZdAhaqQJ8~~K``Y!66prtWhvsJ*BX3jY_82uB4+!rZ zX-)N$0mY)VtIo0Q@mHzW6UrFU8>B6Z)w1AUCKw<|k) z^d9c}A2;wT3>?92LnjzG1_LL^0E!Kmt(@740QM|Ya{JWTN`}8VE4qFD9ZF6!_`1F9 z9_6Yuf2r}`e=6&6SfMGC{iWOMG^JhJCbzWl{m=OG5hbt54Eir`rE<3Y-&HGdj?+%Y zij_*54W3x3oY!O~i9cSc^t2?~|6Hj|Olz_^nAUgu#3z(LTZ}J-Tczm#Qs4N2cvEp8 z#&1w0icxRaYfbyce8Zqf5RVUkNyR@NWIVTCDedSknKl>~#KGIgR46^MmR*&;15|LX zv2X(oy07>mmDQd?jQsJea!t0oO6(G+ zKR+a*XJQ^2{^yh|W6^WUAGJ+pggA9mAGnu_qX%w&QQ4QZ3)6cy{;Ke2 z&85vlBh$NHxP9bHO32@QFP;5rq_J|dvS0D}jmcY-?29+}BDYkXHgFX&>wLa#R2r9% zNX@WrxH0O8rx|Hx3taCJeDUV4FESNcYvMp(_zphpwMFUUf5`Z1i_#T6Yy7cAIbUNQ zZ1ye6j1+FZ#JawO(%}BPb{{3&r^$tm8}A zwlkDrZ99wC`d1&{ep!RH6^+q{8#cKN(ecs^hDpbZHW(k!anJ^%o{s%C7@6B}?7qRcfR3Fv7*pujZi7*RV~6J0uG_Xd zSamLZ%y@O1a%uZoUT3VWb-vzc{faVB*}cIy{0ercpH&!ty`p6LYmNI}QF{@Z>};jUscZXpD-?ZRT-+>y}`KuRV62T8TQ4mH1kE?-tYS*{@3a8^zkHW z)MNM>JIN0ipTDY1ZFBTd-|CHcJVj{tA>-2R%GDiue98O5XZ73FPZ=+6S90=8p2SwW zik^d59~!~L$nAUkGXHAjfr3?Zjvjl_Ez_+J;Bf?WRf~aUQ;g0 z?g~g(vf`En4Kr{LRnk4jdQfuaK;z0C@asEc?ha-90Gg=&_{dY%gx%FWNBMT-DPQk! zj;~-^PR&;T&Rx3;b`m4oeZC!QOn#j$99N&z7 zIW?=4oyE-xcKUxBX=raKyV6RJ~JO+Ngga-roRscAjE}x{k+hYM^%}ynB zxn0SZ*eK(E4UePpJ0~;3c&G_J*`Jylz1~s^I&Quc-+eh+;oA{ty6Ylz=H_1b4$SSFE8$V_-`{4F9OK`pg+V+=sON$tJPQ7UgvY^;NVwji zSp5S0Pi&2i|NTn|Dm|MT>3ftu%8HT3#d{E!{ueSrmvR4^(wr#Nq-hrUaA%e-gWF>6AedS&yO+m<@ zN}jNb(6gx@-tvSDfd}zy>WGBLz`u}i3OUs-P9a06AfBF^zuzVB@IZF{ZVA_ML-M+W z)As3Qkx!rnBRCL-z!U`@9;Kit;S}@Myk+D}!8;~ZIUk*zu0$HJwV?|ZJ*x2a@I{m( z^yz`zzI6ema>5&@jW01bp8B~3zSxFOWZ^?B$Hw~bl@#BO(UY4hP4;{3ORMvd&GExB}^nE05<4li@AYSi#esT5D(MfG+mM4$G2;Ku~ z;6^%njI<+1TCJ#_`Q3*4K8uq(qQk}?f+GQsjngC0BVAThSAH+r(A=%LgB%&@I8u*7 zVvqbEUN60HMRgyS5x0%0WFyzH5%<{miX3@-k!bkqLNRx%R>8qt~W(b2@BDH{MtN)uCrA1&s_xV4 zrTWSgjnQ5qBW)ccLp(+X;&q=1i>jCQPHkiZ*}%8LxFctIY;?!#%ECp}qZ`}M647WC zjHLONs55-!ch$7=HFU-Q%Jq1+6uXaa#wpfL3Of_?0q|Zsv8^=Sj~qq(|mw;%{*Vj5;$PZlWh*aoAdbs|JdQT za;_0K4xbyyX|sTzTj*=(eZJ9hNFXQwE`DyYuVL?b7^WmcK9g&fW5~}lrVI&WYg5@d z9~RFHDp%ils$9)AxGar=re>bIgPQTqW9&C{@FxnrVefSCsqOX*C?L)Jf`${&)UNky ziQ)a#BdFc&OppI#tcVpBNB4WiiW##<7nKX6dsr;5iOyf1VSXwa0Q}^LQ!x$iha&G% z&|r<=aeIW00CPVVAoL^z;}ZgNH|LXy8_Ukelsd@IA==apF z#Lpp;q@h5vA@0XDh$MA`Qx9>F>sF$2=zMeBUG~wdc2wBK7=~EG5K|HoCv@y(qH+=; z^w7nlM{OVxId*w?kAPEthgbp1isStQgKJ>D7$3jUVBX02CgMiRO9DAr_waKsVS1xd zYwjO-+@AZhINXX67-Y9{8b7xkEg$3`Ox>!KmnCkv=!WQ8u6Y9$G0l-cJJ%iJRb2Bn zLMJr73U_b$cuz1!SHs_SH_aC2eWrQh6?<_MlgMaafYA1{cfn=;BV`l%4_lEy}g11 z-r@ae2b=CycBfgqV;go+OE6|(f!Ke?Qx}j&lXri`5A_CXdol&|9I&SG0ted z1+OWy$GMingBa(5_BemR&wYw<9+-TbKjNB0sF7*Bkv0?@9i7iMsM~M{}vBOGw-vZ$j3u~K$tL>F|Bkzz}>NKmfN8iiOea||n zR;(h!>@C>yf$<4VeG_DC7x{05hXu0wb`s<@J*?2RImqtEF5*@FXjeZRk?Sgc?q^p0 zk7D)drcbcv1GBm)+&t06#Y7Q z+?V`ZD}O_p?YVZ4pKI%HsQWv-3xr%(&4sL9AGredE2d;cVOpZU=X-cXcVc!k?q)2H zm9?%iVerIk&gf^(5)63fXDN3s-Ep{rpUYwnr;84!o8ts~J}_r~W|)_Y4uM&dC+av% zlV_MvzGi@X!p?Y&Uu(Nq4jmqe89Sdll*=6I;&!N?V9*C~rO`b+!`y$7&aY)=I-y z>4lYM-XR$94#H#HxiP65u#s!VvIdM121UaS^ff{SK0tf9lb6o!V64zW_b_Ffck>Fy z*%esb-tH0A-R*4?-M)zHC;A)m)6jBWphXjLoU#%H?&Sq0qk_K~7hi$ZJDZ=Iia7Z< z49mDs16}v4*0)TogdFB{5#wTmvUr0StJ>`hOFP~nj9DELca2Ivv$6AbG*F-jh$Bnvd(;3(ATtOA$*(N<|^FFTU~1CN0oG~ zlu64`+C3k;n6GfDhD8BRU9+?gHQkwBV%T_>>lY$y2>L!v9laP8u-j!}V=*c?J9*gH z%#AL`6oAI3v9O`wnHIa{oXWd^ai{On&1-lA8LQ}i2JgH4f4t1Y27}fF4ME^spv_T& z0q^|0jXSq8bpwjIW)*9|N@2cI*f>Y1zz1kKp_7+R*yts+&^=7q=H+&@rphwa z-R(};xQ^?~C~TnRyueJ?I5}a1Hp14FS%(Vx*s5q}djx&WFe_}720ymLMj7|T2>u_!#tbGcM`?6Tsd&HkFqc+gQGip|v=~lJ zcfx=eHr8_e9)t}+U)jvji(w-|JA13|-$Mm`l822Y+~|jx0?_!X_zfP~!}@Lr?*hi1 zzDqaH;SFT0qOc9`yZk;|c-UajnxJ6_gs_n(7_fTiZhp<_Y>wd09ZcPTYq;i9)_{Y; ze5J6FCRE@9w48{NmrmF?y_sDL;i!9KZ2}Y|uv88m3xQ(3`?Wmc~zgk6GUvqjHGN=p)Xke87AzVq9#`9^M|ts+6{gQQ5^< zIb&9T1i^(t>APJp;2o7Ou?MmI{n7IGFZg>lKlL;7_eWt6Fb3-cb3Ws%2?!dGvs2{0 zRf7;T-r(kr+2*VsY_d!}+RP3b?{R(tL8BL6IRWJuX4?41Py3> z$5d!7#F*E3iqF}s@;h$Zj(Qex0j%C>S_dyD+RqbXw2ch7_oW;jRGbu zM``zL>|)-?rOlOwjo{QZOQ%rNogg3vjk#RkN@?gV=v$;YdNF9s+{S}OTU2mX@}N<~ zjixINOQ7*JFJ$}uc8R`g%e#Par|;6uG~PhQDyFqdOi%x29yA!F`I)XmkeHw8=E;}r z^;!;%cY1c?&Sj-;z&Tvgg*70n(0Q1lVV_+iRNw=&oQRQ^JZPkwpE6A`cVaw`T-oNI zxLLQ>NUmLhHB5&M)!pq*&^UuT)I&kgfI(hhv}>H4pyA^MdZB_djl;MO(=NiQv!Bv1 z<4l@((QEN=`B~;>5uM5{6rOXWo9lQJ7^~>sJ~0qa@GfA?>VgosFb*q)^4@XSX1mjT zhi`!8;?uZvp3Pkx$XpyC^gFtJo?y>sESQ8iaXULj?z z`)J%;RB%32X{hVTIyL7>;!j_Pn+t>UOHdx%9^I~qeIRYeAK{u|O2a58k4D_zeoNf*1ssxdd(=8m_B_5*`D;K*B>KbTwb( z_-L-%0SNkv0uK*es;k{4JO-XE;h~Yb+Cku&w~J#Cv=jth9vY>qiiF3&f5%=Y~!V#6T3hP{M-~5C+Z%FqI&99pZq*Kn#4hgomz2 z9FXuB_{+43Pvt;p3gUo-$H3Q1cxWo(fP}}uwMQj_P!ZyQgvY>3Bs>&G9FXu>Sl86M zB!bX1!~qG9flrh0&~(HB36D+J5C|lK&<%(K5*`OHl<@G4hyxNH*C5E32*NiZ4oG+$ zyt{#4YgFC+zTM<7Tg0FQ#35+0n5I3VFs z@HHv8M&F1E-hmr}6awN=@MRJnyc2Oi!eij~C+GI>*@W)G4MB2&wJ(T)-y-3mIfw%i z9s{40lxz0JBXl?7KvIFtW8jxbcxW!-fP}}uFG$9b0@(gi>OF`9$pnnY!23#gXddE# zgvY?MlW>i1y+ZdQ4kQt99s_SF;i3Bw2P8ZW{yVmRo;aW-_I}~}5eFIz5y@UmAR@E|T$ri4eq z*GqV?7;(VEHP1dntuFOl$I3F3g8Yp#2;7zB5@1uh<1h&UkOG4N>; z9$JJr;NtW>OQDNn5U4JJn};4m9FXuBc%g)c9zq-tIo7*820^uLASn+&jW{6Taq!&|9$tqyph*OA2ws-(a5>_DgvY_x zOL#bn{r?(?AP&K!60WaD9FTB-1>%5&M=P-Zzh5E|0SS+T zx0LYkCd7f%9N$cU;P>aPb)I~gJ&!mb;c@UEBs}~A;y_A{{lEW31cH0>mT><| zhyxO?gYQnot^NOI1cFoo+J1w-EaAZ|hyxNH1z(?n+x!2QaYK+oVD10GAC>UnR>T1b zkAjyZ=WPGK4L1bI1@`_Q{4NO(zk)a*;c@V3Njcm9hhIe;NGhCY zi8#=hJNy4A1ix=e9S4Ft5eFnZ3jTwH2j4;*XvBs6e-wf*8VQ{JfADR@0SS+R@0ak< zF2n&Z7x(`$2wwLJgw1IvhBzSMad1<@!@Cg&JlwVak3+D=BM|S1!c~X^5*`O%CgI_C z5C_~`bKP>qA-LZyaPjcFhyxPt{}cWH;;m=5+2-(I3VFs z@IsN({lCkBeTW01z{8{9`4S%7k2oOVQSj~p*SvSVq4y961c8^wz&l8I=--F~5*`Cr z9IiFG?GC?>IAErZ199+r2@ijOI3VG1@FNM1UmWtbF#I9nKtj-%$HA*5JbVCgK*HnT zyE(`BH*!G#2yuW5l5l@D;(&zf;HHH84HBVsyB}_?6f+qkj%wO)$cA z7-c+`gOe8+@6)UPhCdgFJYz5&(v6vPXlAU<4Gd9EZZQ6n8^~9F++eiK!}0J2BYQG##!q z7SJJNY@x#-<6AoPGCKFbA=|j32b?^^c(6yHpK|mWI30Q$8NG1mVvMFk8)E?-{Kl4E@DN>dxL4pz z{6-aBMvu3#Zzez2)oY%!0?cO2{>@nbZvKU?UM1s)baj-3$G_Co0vAV+5gmwsrK{(; z1Rj1^SI?30ww>~OOL#D@t9c@)AR{^uJc1u^5(QpftE=rKJoJsOrpfrXy6O`+U1VGi zguc_&lh39eg7Ejc`acQR>vXkF!lOrZwZ`FEqcM*DpsSxbg2wzuT|FS-vH$AoUK#&M zS9c{iK4j?af!P1)>T3x>V;=umS2s(z{})}|DB;0+T`lJvJ+L)jK5I|GTcvknrFix>{s&E$KQB{fRgr zF%Uk5I3VHCzYqr`Jaigyz~UJHWIYh_m8j=Q421n9>NygwDdDO zH7QX$NeslBmZlynYbJ7a@?Mu|x zBnE;VO4Q8~9!f7!H%fT8V~JWGlnDG8CF&E;SczF@1oA#=s8u3=3W-_sC^2gtOU$}Z zsT{ZdwDCGRYEo9aNEoSkYw#ms$EG4N>vrFck^OzEw}W{TvxacK@~g7yK5HuL_hr3T zKf{QhgOC5e{5Ly$DK|3+GBNS!Ie0y~`_t7&7ran^^wsz6e6GD3gjB3u%_wY~M2=8y zqld>vE?&22`gHZo2O8PnX&Aejr7%L-OSzE_9wTk=df)m-tB6I1rEj~=%t>2N6OSqA2bB4#p4S3zce4@I=6{&4}LN>Hvj**ET zBjfP;=J{*3Vtjv{hf31ux&7xMt;Hw%0`z8lW?Ue0F; z{BDQu;(WHvYo`kNWMM<2oZJVwXby52!HGJES|H&p%Vm^Lc}>1yUMDJ?hm=OpD!x)R z6MyubrV>Ar$TA&$H|lY`ev{jt4+k!TUQ9T95PAQ|0TRE=g&I$dbnQBP?+@3&BF28lb#$UD;cS+971I=uW|mga@CQWGg^aVKT!Mmz z=|aZYkXXSiG4WQGc>!1#B)y#PE5D1Juq!}jDcH|)C7#VP2QWK%8hJ6>X+dou%j_*W z05;K;c{a<;6Sy^BR`c=hWRBoHwAk(;i*IxIMVv3Uxn>DIb_9dDV5Kdv=E7_CTu_P^ zSvhX_7+=b@tB_-DG@Cc)EloOahH|ZeIR-7w8_XH4(WLo17nZ>R65@G0O|JEx$<>SL z@(@AOpxfP{@qEeQ8Z70yQRwN#?w%+uQF!YM_Ha|hlcqjVj3n&9#sx#PZXqtO?-ng%Y0Teu+r`Q zI>xN>V4u2D*k+lA$a4!Ctf4+`5A~b4gQU2l<>BJdo4T22qQvaw<4eo(118KvY^N^F z8{>B3pMrzLs1e@0wsV<=deCyBBN8uI%Q{^%*YFB(0ip^l!Jve|e3Wxs7ZQBD!9SY9o5J)CsLmU1ydb8m=K_0U6HhY(#i(m!|_PmU`D zt_56U{QZJJM@=AeI6;73g3@{8#Qx1Rd$7JMXN+cF)-W-{Y?hhLG{vMr3R?<$!|=yv zXa^71h6%ZGTZt8*usB7Vfc-uMxdbswEeF7@S?bDE`{66|-_QPtwC;THSQ>PFthxusobEdY^9IA{qcY=E|#^ZcY=pjyL42=3trVAW~xr736_gPPj7erkkCZhKA5` zU>jdC8RkW>uTkXBtFSAu1Rpzs!Q6r81b*D%{W;%cb8AUmWv>$Nin^FoXF2_7=dx0xo7G|#b>G`(pe>~8n)08iViVM1*dD?njqDP@|Kj1@7% zG{)YXz2##0O``Le=96N1FmK9UEg}fK6Xex$7O|@AF1C0_q^_{KFT;G1^F0C==Et*~ zzh`r6eth=0HRNo5Xo=m#b}s%9H*sjKCB7z+Mb)+Qc%EwyB9snKK0hkB=2OfeuJO!| zHRZVJvsS<%c*sQV36g6@xS_8xiJ-}=a(8iv_aI|*ur!=0}Fvov~tOnC3@D9F-?-95c+$V)^$(=QB*LgJ=No zll5-TTMFD7|J8i`XPX0f&(sQC>I8kuGZz6wOn%=JpfJKF?Zv%RlJKC{1p?ZVmEcMeYIQe;bKnVMU3rYW$np_vclw> zFO;X;w_?wfuRE>TT@ygoE*P;|TemLhHDL>HNpoajV%noUI_FzIiR0OgKFhVOkoBoB zdC#o1G<5xMi!8Aa0<3mb~%VbQmJOs36wI^?JYr#OxK=;zh z=aqL69L&>&rIl-r;F?_KpeK#-uWL?^wI0$~T}*k5G5ONt?mWi-U1P_GUFfBnq09-& zpM;B0dtN~gyMnr@#y>{}x^!ljcX~Qvt-M}HgNNe4FV-qqe9zU9<9?WZAvQ}qO=!h6 z1CYTCn!FxJdPhq{$ZGsL^RSq4r=Qc!t&Ej3Mp=#Vpw&)h{XB0PgI4pyNPC=EKj~(L zV4&s_*8IEe=I_Ox%xd4j)D1YqHA7ef28J|Ynx~t~g$nWp@`*sXmz~?)5~iURT5Hsk z>9|lqreoIWZ}SR=BA>OOKiZ`HE;}=_)?)dQz!~|xz*b)15_nkPR3PRlI}*r9=%3^I zVWd$VS1Ts<{_sdGmJ_S_#wp9ZlG|VC*Q_qGy8Wt^s@Uzyt`#cp_9?u; zV#Kox`7k}@(pxFA*)XYGzZ?yKo*F4~8YX(aQMa9LfL7v;3ZlG)Y@CqKncoPVe8OH% z1&oWs^b2D}j8zpn35S1Rte7#Yhr;eO&~eg)aRWpKD5TEd?qD;q56uO0Jis7hx46@CYyn>hP3TSpOt;B3? zAqEvE3axvJN1?5VLNLe+%yboS*61o;!FE)D-`2Dpb2v@!WnA+HCJ;1vl5BbKQv^pXCxj?;7Pr5Lq7VdDw;z2<6}w$2csLP-&gBK(LlnYKSz7u& z%haX9Fj>iSSrqEa^&g@E&{OY@#p?`DjC_>-8`L%KVw^bXQkQ3xWdi$3Pjq^o%t_d?ck`qXX#cZj0UCT6^x zmlLAU0bcG9mLWK8OvXD=sD|UO5ru60A~3%f`k3Qdl*SJ{+Rb%Gq4&7vd(0qc@(!^m zB;+>fanP{uVsvj+U= zi9%z93i6O8+HxXHsgs>3RLC^++n<&bi807FZ{`&ovn!z4+TtC|)|Sbm(7ZApg-##} z!5}ZN&sD&QGP8IEf1m>VBBSk?!)ba?4x-P#irZ+zb8wxV?0Wq45q=E_W_~w7cL*qfkBaPrWO08m0!z35r5l$lVK3UaLZO&+6o<-pE=}z_>U}QQktvs!FH_>}~!U z-b0L8Jro5OhABcCD+)p6jY6;TEDZBQ~y{g&=YD?L;&;GNz@+&N^GPSt=pT!S>zRs#kUx*w19 z5Gu$+4rT8#3bo`d7{gjHQj9|B=IcTQ zd0_TjffK?oZDE=sIO-mzEb~9yiLn%gAh5a}3BcXm?mT7sju#lG;7297evLjV^-#<`OfyNN(vA!w$`g)m+HCz^30m<8Z^2Z%1>7NevND+&FQ;-@coPRs zD@TjfN}N9($TMELK9Hwv#$%?<)9IT>H?)fsZfIxc*}GC#Ux4LeuwC037f3jzPM%AgzVwmQ0aaITlNkWNQNqLHboF`( zkAqJD*HU$Hc)YG&Au|9zLc+rnboC+$kAn|>^0bz6jKf#!YJZ6V|3qCqQ^IxdZW8Xl zMprYQL|jeP13Cn)Wd^R*)us}zgP+1qE0ul!BwhVglL&MOev)wiWL^DM!gcVkB;0=; zG7Eho5$F)SFX8^{b@g2d*THv6xPJ;V3%w!{=u;2}Bs@43aX`YO;AkttC7>6LCPo%b76gJ+0`NHaPZA!Ug*YJLaqzEFa4WM=_*Py0B!z%73&p|Tm+BbkZ>LRMhOqzjX02mYy6fg3c-XV0?vbT5eFnZ3O+)@ zL-!yKH0H=G#9BzXlLt2zBzR~Z;(&z5z|WL$N}b%T5y$u^9DpFBk-*`UJGr%l$H1FP zc<6q_0c;9gaX`DlsUQZyuU>(`L-P>_Bs>QGt%QdjKpgOJO}y=nLGX!3Ao9=x!~qG9 zfxj!^;eR3yxH*zO2rZ05@QPdD;$d8_Uy$%P_%jk7E=C-1aZ36iIsn0AE`gheb;JP) zkApub;o%a*0g+otA4CTrm@5iAJEQPI!~qG9gWo9O;YEl80@u7-uQ&t~1c8@_A4D9G z@HqGg3D+M&9B{bSXz%A=j5y#38gU)Gzl8gjAPz{l4&E)nvH$b7Ft`+PAR%bXqu{M2 zJh%*TK*FQor?3UK;sEXcybgqxBMxvu5*`EpNy0-b5Cz5h?@Kn#KmnSnKk z0}>tsZz|!TGQLFU4vkO zMBv|mI3VGaTlqE#_dkO;AmLgFg6ky$|Feh#60U<^A>sb#5C>9oEuuqkQEEZNzY%dj z!gcWe67H`=97xHr|JNbtmQsM<-7ygdBs>b9m+W$u(IJGKu90)y+I3VFM z@Sh|+^aA2Q3U2NHV-S3mLO}cf(2Ixz5*`D8U&2E#Ar2(x_WnNx!Or9YYyThKj5r|S zaqt%;JiG;QASq}2|2PC|lM3wpzy31ffQ0+EA`VEn4*p;=&iDWRZHNQO1RIzG;BzJ1 z{|e%OgzMlpCgF+wzyDRlfg}RHJC1@+knrGk!~qG9fsbg+o&A64HN=6&0%v;;K3Kv- zI}isXJO+MdBQEU!L$4zaG!h8gbMOoa550jnAmMTFrd}@Y|HE%04m_GV4#dHKmGJOR z!~qHSzlAv9;jaC^4#8I*fw(X5zl}H`;X3&H5*}}rmH)1rP z4oG+m{5A;>{R?qG;I#jDI{?A;g22l|dk_aCJO+M+gopPc4mezEwE2ufaFHWu#PxlM z0}}4vk2oOVI{29hj{Tpvh5q*t2NHtDTnEpPaR0v%2P9kvZ^}9C{~9^)KH@+mbsUI- z|0?0Z4-f|=JPQ6T<4O1b!4DA!ASl8&K&Igj4wkwmDflN69y)+HAmK6acWtgEtswLf z;(*Km_$v|~szw};@EG_r7Ds0BWGxIGL>!P9h=V^S;o*-F2P8ZW{vdITe^Lj+pCArM z4EXzifP}}uTT6K8E5rd!B8Wk7sx-BOp~Hv+5*`Ep zNy5WlWB>oHL=cDID+v$RAPz`)9Q=I=*W=j#zbg^=k01_6xDNh`g!^j|2P9mt)es0I z0{=IN0}`%-KPKV+ZxIJ1JgPzPphOV-4sk%jqu_HTJor80fP`x?2yT=JLUo7(5*`De zAmO2-hy$s)7KuSHBDEkA`T=o3!eiirB|P*a;y_B?8}DvIaAryY-k$$2;y|hKx2}OJ zl_!@Q_b&>Z>tAkcS%ehp3yh<5m~8|f#35{4`ykTDPcW7~h~(y@jGc5CYWza1ztQI* zyvj4Kr$f3Cc?c()8vF1{Il0XE>!Cn?vmck8Hhfnb7vu*1*6c9;FPdQ7j{lX9mKkdn z2hMF)MSQ&R1@Tvjk2BijfmbdwE?5FyMqD-S$GK*Y5dVkqBK}9R_Rp7~(z}h;OL4f_ z2;tCd5(G6@8vhJJaD`Dxq`>%!4g-z$%Wyc$7(s{5#(m3>qy6RO#{`g_Wo%HHT;~6@HjL+#X$Y}it4!w*J9kPwNbZBiLCda{i>@66CCe=dRrL!O;_Jb2$Jv_aS;gh=hhKx7p>Q>Hi2h_-c z@b9|1i3^f&{SRHOknrfAx>_dTu~WLbig7L37{~t7)#VZc@qW4a3uPQh!{^I5l7`Q* zxt4sAA#3<7i2*;7f=`$5Ad-Slmhcdgf{(K}#y?pPgpn0|jKqMBq~OCOJc^{?LnSKvJ%C*pvFN6$nYknq@9hyxNH?=>BPKqBz>K^&0qU|+-m36Fsf zHMSUmp}8j)oR!;;vD}OCB&UzwHsQk3d zxP^{iE;C+yB9NnXdCy)+zJiR%1iE*rqAyl=wDM%_fMHt2z74)e&Qg4F1X(QVe7u70fe35i$DfHArU-*tMp}UhDZHKYR746E1{2flzL6mmi@CIL4i3E-No(%M|?lVo+|Q9%ee*rk7yWf)EgFqXvuPWo zw8sDa(Z;23g&N4jO0Axqa&f`WpU%_4{FYQuEA6l>aipNc=LvV&9JX z_P*5*fIZc(WyJZ3fv)C%alX&vk5-SK^lbgoRv%kGF|c&apF(EvEK|Ea-TsXMZuDyu z5{(?f>!mN0RkwKL_4=b1?z4?#{N*xoIc!h{6mH`KkB$9!J$gl1_0pw{Z1CSH$TEk* z2>m<&H?k9j8er7U%HP%8L5>VCs$2Z`_4>+-_SN?e`1UXLIMSDFT;kYx-eY4UUhm5_ zsz)bm;CBkVMmm#`p^lLGZ(Kb&w3I+n6RyWA8gFP?-Y1#d^z<0X!|Q#yYpX}Uy{*2*gyh{CAtSlm zNVb{ovC$T){wtJVyR%ho1*Hdu??KiILf4q@QEs7nBj_$WM6P zB5Pgs%$K&+_es(id_OSDoI*x=IYw$cM!v-BJ{PX5-uGg1BV^+WvN6E1@u9~?SLEJ( zz*m0PKAhjze_eG8+m@De)?NT(zhmu}Ol7&p)1B1*)k|>wSd7g6W00utfNyXZ7b`2X zzoqG9zR3Alfse;UkMU5L7JhOvQvadWI^=RfDu3hc zPm~NTVR9;xo&r)1_H;3Kzu^8VfB9W&xUuP|;X~-f-2H;KlTzi9B;6uY>VSSKj_ivyE5*l3_bvhs-paGiEga?6)I6 z;hU(L=4oxAzh2rj-m7Cx)Skcm>ZbJN18e4U}&n=`?bWk zWS{Z~s&+fm=P|JY6m~{G!+Zqnw@d8Nw;TYc(a#8q$@nwOMWTJAzqUtT%k4{F!dcMvP62VJS=gku>Q-uDeI8UrVIHd(6VI>AGN z)QWW6yo%o!9>+8_Fkm^+5y@SxN;1uRc?AeMRDs0@Is6XJ5py{25*+UcW^e)G4+O^Y zPn2$L@8c&Ccb4GfcAPx_c777Ur8lZd)#e+x4#B1F-@d^m#@|0v(%Vkvrx8x}{@Z5^ z_zz~{Kln+kq9xE4VVOHiG~M*Grk68DGw72-F`0gbd9uV_rNyMdGNw3Gd&Ehm|343} zRTAa3{G$w76`-&<%Z@O%iy5|Nm@AP!a%PC-CyUN!nAKu=uur-tD#p$y!`xqTo9#JO zK-1Yfxc`THb88JEhHQk!;&(e^_Z{bmAqg&w?P1OlIlzsVKE>Gn%ugb6jKax7IN9PG ze$v?TT%coDVFrJ}$zs@eFEN@Q@zcvOaPP6v+`~_U?%rNJ%4k=>H9!+GN zPkjA9!@Qko3P^)hX^&^w$IzRa-hIwD|5xtjd4xtJZ zv_^C`KlwF=83l`~+?|rkJB2ZOMBRzlGkK?yW)B}xq>yKMLE3n@kU?I{Z!T7V!s3Yf z7%OIm?GZ)g!ib(IW`jbS_uS6^k1?w}m^XubU2%WAFbS*?Tg}&4C$lx{ncw;qG!)g^ zT}G>CbT03*?^%~2H9T)BWgPiX^axChS9?W|jO)KvviiL($ZJ|z(Wx}ZZn?g}-MV!# z{E-dW*GfkJ6a3`Qto|R}^*<*VEHdJ#W8l;5Q~}ya=`5|b4zg!w6*qUxHfP-p^0AMbfxEXdCjTJ0qT9_GMM?V$5orkdM8)hl}~xyD(NmWsUYnFe5q$a__99 z4X8CE(jEUsU&c>nG5?S?-SIEo{GDB;E&ss88F`E`yZ$YxU;9CjQ_3962R0+y@~XO6 z_1l+@JS0~aE*;&uCYQN`{OO`Q)q?#ZF#GbE$gQqfzhkqHiOSJ0HC^1p`G2@WwmPAQ zU4b=a?^vYv!6OknkvHWM&d%pf{l)dYFw(GR>F;&x=_d?qz1GpJ=LPzqf`74a>S^Us zt{H$i1x*q1uZyjutS+=uFK3K4i_?)~op(Nc>PzI)k+t1$;|g1)MJGXqvphP*m`4@*awE%_Zm| zXo?29d*~m$0gPEaw7Z4#!&{?0g6Zp77omp=c@MF|_9OyNTpRE^M?!h}og-@^Qx-Z* z)+yY%VRi$o1{Xh!2A@-YSIM}72>td2O(s5xZs!F?ViKWJyTDqt(r5hjosy|d<9rMZ zzGL@@mAzS58P{^nSo8=qMZ=I9lL8^qsPnm##+)u@oX;1!wD@_07^^6x^y^j@EiM1| zf7%mj7lZbkfk5byUznyG8ml+%=C>%BW+r!TTqcsLgj?h3_Et`}KE(^n^EcG(=EL-edzf0~ zBpOl5_482y^p;}+r$#R38V&h*HHeDlgc^=xIW1h@DzTi-WvwV+Tx{V0-a^I}?skT$ zH}4_FtR9NHhbdPm-`VP(ZG1Upo5Q(xMr=nQJ+D2}mct(XVo4l+DmNCZQ*r)uRhx)W z{It^5X!m-c6~2vfT_(P9lxe+n8y&8z(_sp4-In5Q;!=D}%Edz?bak?X$H2!)c<54H z9pmEkZ4|+Q7zD#y0yhth)YYL99s?gJ;h|Bw+E3*8ERNd&2zrPD4-bvj)h-eq15cOm z&}I0joxthcbGHK!1O$PXhsNNucG#+<8lo8ZF$oV{j*r?oTx&GOF$iiMK_ec%0-v=5 zFTjTg3-JdBOT{6KgCCUe@Rj(eU4rA=2#pLtP?Zog=9KF24GE`Ihg&6_G97N>oW70F z$N>l{xF89qREK2}PN@!8NqAVrN9`Ebl6D~k3uOkz>FRt5r&Nb?B%CrG&a%0dd<-F& zE-|1_Kpc>8|J8^C60U=fu{g#*Sr1UE!(kEwQShM>9=rx|K*FQo{fN`}CvzZpE#iR8 z0C*P(4^BcHknkvYD{w8aYS2QsCB>k$WJ2EY$V zcyJ2hfP_cE-z&yFW=aR9A`VCl#K7N>@K6!rfP}}uH)#?9r8=yTa7uMpCgGuJhyxN% znGUt(5&@+;Tqxm`>TteMc?5{^uVnmS7&pj3y`C7ejX3C}Si7 zN_99)!sFmWB|JO>aX`Z38U+0$0!nq*L&7Q5VHXM4Z$TW8aLqppfj}bA!2=TRzZG#n zvWlYM^w=fED$^pt+Yks+3nEeQS_u!{jyNFUQSgH)IkHg%XCn}#6d+jyc$I_)??4=o z@F@7!RGhL=1n;Ckkg|&+QSb^058j11AmLH)RVlcYjUqS)Hv}mJl#L<^zEHv`)!}>z zkAcrg&h2azp}DvrNG`DU1u^jH5>BZOCrdbGIvkgjYxc$?G!Jngsletj@L>{8sSbxq zcno}CGOn?m52ZTnmrTGor8?{(;gssIi-c3A!}KH^*(g{K%tstZBH)}-9R?(vQXT$* z?Olp>9*Kh=Ys@Jdh3!Ci0pdVoL4wD@YbBgg9UhW!%5-?J5y$v*2XtHu-fJXqc)WRL zewBpl#fSqE?$;3qyj&ADpHT=lc?ALwmLLvDcoe)$!h;JD2RvL8w@y(AmU{#u4=zF+ zknkw@dMSd1wjZ zfP}}uhe~*8DdK?0asTgfAPzx4QQ+a>Wrzb39tZCt;o;?o0|KZ0zuN%_S_uL#*H<78 zNVxxD#DN8=K6CB^g z@(O~bhyw{hV;%*slJH;zaX`YO;9EJz_&0XoQN#f*NWx>_6%rm=g*YJLG4NH4)BeAa z1EJN312O~P3ne`C7~+70$H3>pC*v@ehdVi0VS@Nfm_h^e&NH5_#&`Dj%{y(BpKrY072ivLW1i9G zAkMvjb9v_(eY@e@x_QPw58^xitL7Om9z>3ShrkNXHU8BN-|@eX$__SuC*7=h#+4s~ zPa!_YxG4wxAH)Y5YjW^~`(egUALASI=NiFJ@a6wLME-7P8t97ueSfzy4fxv{J3k2w zY33(9z)m!9{2t%|cA|mr?=hzQ2M&IYbLIW*L<9dO-rq_zpuGM6lzj7Mxg-(d1 z6)C5XG^FMt38gWoaE*c|eQ`>ztKI?EyF)2HTlS*sr(_dlUzHUtqILDr)@|aV$I);7 zhY=`;7i6UkeG&ZYth50yfak8xO6yStu1B=C26ESArFE);palcv@U>ZKZC?Nv*CfWh z04}aUjHwKtu16cT2E;Xo^(rG&hHuD9tMvl7xTVnVMet2oX&#l}*wMD{p}1wxsS-kE zxVS}-zW^>S34HSA{~p3YTe8yb*~7(-wmk!bwq~VWw@0W7--ZJcz5qVxU{>0K=Wx8ytlGn@@3PW9dXDgKc2qKN1sOwLZOer=21_VRYB9dG?rzXOZPj4K zfZ>AxKMm$tFb(WTL0M_ybLu}(N8ta7m;6)8X(fbdv|NFo^&fa+%kka`!vRqcQ0c^Z z*?VwIdHH_5{*yP#=mPGgsA$JsYbUZC@1Bl#N8o`Macbg^P{EIm7X-Wu)e^R7edtuj za^($5DV9UScl%nzSKTNsGVHElQOolQz83j;zNV!n4!siBR=SX6cXra zu^cG*k;4T!pudoRk*2Xiz9aO_pbORfqnATSqG18Y_!Md5Bj8TnmPBJ_+9Esnzv{aL zM9-ZnBvb6wybo0!O-VK@JV756}e{TQ?_$<2Z$9!9<8e zFnbcr)2+9eN3@NX!soh@UB@zHXt-sNb7op!@N(BBpycV>QvOqnhxm{(?+qGtQSR(p zS;3x!TZSx%fHu^KZb2t5${9`YS^PbGznwcXprkt(5jIZyJbp7iqn{u?Si^69LO%*8 zf+6t?@+)#__#bjuzfdrjx9{c6qPY<=&RRgilf;>)1 zKL5=Lk|CzNJI_TI6sdnc@0po)e==SELkyepu8I3$~@hzcS-!orI`V(R{ z)A&E}qozTS+dZ%&Wap23iI(>&@TJ^8Wp`YBwCPW|PPLinjOb{RUw!)PPubt0o#>s6 zuLY?3CBzxdlz2&Qz@|;6*DuLol7T)IrFH1oCAqFy#7`O3&|8dVkdt9!$wYFzEQchy zpnSKJp~*v(i{2R^+4*3hl0@YSiQa@X5`h=op+2<1V43pT2S;P$M&~2@uQ0`CK~$yriBb*Ech*z8(CzG;Q?<`DLcnu7Fp} z1V3**g!0Nv^Vi@o?3Jd1K={+!k_!aS7Z3>c&P=Or2M2@tR1)>WeJqK9EB^~V!pD*e z_)|zE;bk#i_H)(7VWJNdMj+_$iuoaW*rUEBHy|_ZA3Jze2?YCRrd^suVOJ1?4#}Zj zS8!2OJY`*x0~%@)e=gCC`kHOd3d&5|4SHp=bRw_1A^Yjua{kkO28-!}JNY&M`}Pe=LMl1Y$g6Tl%gUoH@P)mv zm6`V5fAzrzmuhFGO`SvsugXKFL+kF!Qo$l!#r3N$7WilyCg$?J*EOxX6}+I1R+bGs zaRtIJl3^pXu_*Z68YtKA>ky~c-T}UNPS?8ZY7s8%UYErDC%yOO*|{)bBC~~wte#YY z;ClhL>303c7X;mxF!!26_E0N9daTUvl+9Bc>q9EihObKSDC}cnM<~ zaU#$X{$}20ZA$qxw3u*K)F1^4-&thfM$M0!V%*#U7fRzzHEngq*U;)z!kyx2^SRh` zF>F@L9dMDMk6oVI<=;^%a6Ihtt9V6uj9vauxuSfcT|USzzn@ulPuD$vkzpJjY*B#0 z&o2L)R8cuTkDG4yP!wAM7-yGvwac$+Qh{?TrXoMiE+1o;-`= z=vq;Jt9nJgk8?%7mRChS&JKUKOGSBGyL_MLba3dh(5V8co?Sk#T1B~^T|U#XqTFPc zU+hp(?qruAXR0VK(QSlgKW2%%ryh74&f4|nmYKf4DPIm6U$c_oc;I3v?crkB2>%={ zg2GffaZBzkHKT~z*oTOuLAP=LV*puh%L65qZr_%>v)ivz@*O#aoqOFn|Bh^y+5Ok) z%lmSZ{)L7<(UuD?hG=;YM~r8P9-^66Lv&B1f;$l?XjZXdZA(&NZOf2}VV1=9nQ0>t zDEue+HkeFoBKI@{Kz?5aaCbDZ9# zH;|&s8l6xvP0Q)PX(!IlO#2XY9@_#>4=Q{r*XfjfMK(o7G}4_^xx;}c%?|d9vE*Pm z66=vr8tblk*X&@|X7H}=1tV0$fLnb<2z+X z0wbbPj3wnjOG}_+7@sJ8xFpp^v6q95VvJ7F3lyh-T3^&@QBHMNfTcMo_XFh#WpX}y zZOp;|-p(yM7`9QYlr%QOn^_i>$$ks7xp7Ek0p5$X40$KkGH7aM+TQ;XjDSNhBCOa7 z_=^O*@-*qRiwu#nd>8;GP zLaO`M#H}M0-bP}djG?tEk8N@oU)^WmGP0*{@6jTp7m3B! z#)}ixF!DgQaSXLE@`&F5;#soc-39G?U3TV|FZ9GxCw(+FWVykz0I67s{e(zP=onVi z1+uN4uw4tr&{hzy`7h!Z#5Dn!&p(Z!XGZSJ-Wfx_CLS^UUx=b-0&yGCr*H3qfzhqv zQ>Gn)(k zYkURVW;Q>frzRdm`3^j~Wo07Gu(B4mw?k&y`2Qjz;DQL?Bgc|+H6H7~?p1vdE+Kt@ zL72qFAm~@$^`McCJZW&{HVjyZmxNmqU&>5t^s#oJp z{m0u_`RYGd@uET1cv6*VzCA)`B_%Vh45Z3+{`s5`aKQ@T4*`D>E9aquLMu*;wyI8i zn$$Q1rYI?>zNHY>rn{G6qxM{@E^LNRv`|w2QDw9munC?v*yc#9wK{)EGHRF&>ygog zTc&FdevK@3f%=VNL!DUHQU}l9LhIbi%kt`3LQp1nsD-pUhC!>lv984r&p*kw=k4_^ zJ_26;>=9-05O8LL&x*3R3b_8pyNywI;yamKMVv z?6u%hOtGFS7s6t})w2rWy^L$){+I9u0k^zfF9_&r6`{R690wGH)ankcyuVvMg8#`B zZYZnD)PyQbHG2V5adu2KdIbj*s&ds#5Cc={|Ancne>0U@g(>&{Vrsf={(9SS<@6t- zaD(pUR0}bQHpn*i1?%N(3k|Hw`eoF& zW1ZFsqU-F4t{P6KK{WCILUea!qMAHB$iEi%cK*L|#LI>(3l)67H z+jJKrRUB%tG^0J?+?#D2LZ`!dvg1~e6T>@tFhxf2B=_0pV#zsv>0;t(V4n@N38(> z*z8fE>BIJ=SGy;a8sy!r%E}z_%Q_lL3$Vhb?e%znb5W8eIqA9N;wYj%4-DjkgwL~mt1cQ(wl;*EY!$mMDaeAs+aX<&C9DF8dXvK zOcWm}HKKM6cw~!zvGFCy+6J&FNgF_&#T=C9d?TGGo37-SH8zy?q5KAXI-4?xA{%1- z4rP?l`B6>8_!T9sa-`l3c@#V3NFOxhgUp4fdu3l@^DECVR&5eWR}Z2`4f$;MV3b3Q zMHqm>i2D%Zr~8N+@i2e8c0HcAYs@ceV<I^ zK8)t)rEnVAnE&ejI#8ZBv%Z?euxuZ7kKy&5qe0t%x2h(;oYa9CG&hEKXD%lCBZfC( zUx0oSK3J+nZ#Lnh8)2}7dRGIfa_IpJNXiNMSAb>t1JpT=KZgJFvQ8eDJff9>rLs{+do}Tkt^LmQ>7$AAnjeYP83Rc_@1_fUd>!!2u0G5jPV3o%d_K*oH?qzl$B3nfRZ9|E$+2sx7~!Y=61TyB+zr<3F+Y zU#2_l_*|{AWIk3(rrXKf-7#W-;LoGrZa;Ev&#kP7Lf^IL?|bc5ELVnz*R!4l=eS`3 z)+vR-B?=Acz^{f-f2fR{*t|m-RHkl1=_lfOh;8=b+Map+Y3xhf7dyfqzQpUAr&d9K zvp*etiH9g=tmGwewtw_g#F8o*yLa_tl38&r0^_uWDGfW zt(^Y!BQP~B7JC~gPjptH0z6U&>v-^A1-7C`onGXg~=C7WTBCo>;ylM zT{_@G65-T5mDlz56YEHzco{P1<0|Fono`1srQKW6+o^mZ+ioFq7karelwZ1_<-kT80WQ08k_77X(5=`XvUlWa;ECt5=~8|f7GFdA(p%kOtrqs7Z@a^RUF!YZT4g6? zy3ilp;W>M_kb4h4%zfy8G%}|L@5a9AL+5(%P#+OQ*foaJ5Rr+f(}3LCaBphZllL*t z!n5XdoOP%3ZXa6Glh>)rr};Uba(-E;q4Y=}y4VwZKJHBcy})Njdp@tbP{&@pv(%P8 z?ZtPwd1y_**bBdgn@n73WN+ReWyU-VGR#({NcR~m(~#DNGUQ+fBNXX!q+&y6DN?b! zAv}^l{)M7y3M0rtneOzai@kYd$cMlYJJ=r}6=tp+&m`%1=X+CBA0Fa(608d4%IQV@ z`e0MI2d(eJ>(od=^Y?KE#t~I#JxlvZs_v(4N42HfeYku5)&PqmGFee-V^O;$o)>x< zv^?xXWcf?*`^GjUG1RCp7l%WJ_2mg(8zf7=x6PKfzcyQzeqy%xd|_MP|AQ6m}h`{jsjM&ZV&aJc@rk7sr4a z)?q$0u0J0jwubui1~}vUv_J324)vsz0oVv1*o)>4-~j=xfINaFG#9f-3`2%vLg`k~ zAdKF-J?Y2*{-~N{n`ObZaBAUY-o)sEf(23TR4tu1Hv(D|Y-&aw(|I_}dzE|AtaRQ( z>PWw*^QOFZFZ>3?JFoJ0n1642^eXrDd)8Bza=Ba{;BY``&ob{ELuMM~%wQf=Jdm$u z=X+b{X7CA8bTfDD1(**Qo4{A& z!F(ex3a;0T{vOQ7NFLO82sX@D^`N(g@MJc>2kjlgQ`xj0WFE@rvr|3k%b|$#ztb4= zD0s6wJs8U0iuw}I<^C!oETNQP{6#qPMx>$igB}puUfrf=;I}ho_Mqj%@Sfqlp7dZC zJmot*$#*#K$Aas`U!r$o@>D)2|?AoYtL|6Y~lwO2a;$>@`RK=?;&Aqj(qTwq{%__AyH{pzBX9(B8@kiQ5xlumk)v4s z;9XNnqZq0)5+;v4F5$2HhXc zd+{P^Spsz#!~NB5_nF=~nCKjh^TxI*r3%X>@KZMzj{{P{u^&=O?1$dr+AT zzz_n)DT2~j2pm5Y>&PCjA#R%2jgG&@1Dwuxg&TV{wwZuZ$!k0&=;aS9g#WYFf_uSf zE%hi^1#C@cC}#?HqIbvfh8{ZrvzOiaZs20dI3DMlZ>znc3dZN%C}2DfQI`Po({7YJ zp08xHy3@7scwzTScN+UTY;SWq@H%hcR=-Ns2(8%1ze;fpP!jvf)bJ2yd&UIr#J=iE zV<#YL9MFxHOn^W7xGSBU0BiYs7kV&(r}_7qRng63=$6o)pS0AYU>S{{!W+k$p9moC}Un)NS(oOpi(uIUhASyn2o9AIEDMV-3N|slEF^9 zTRKydDZGx46=>yiY=EubOH%EIw*$}Xf<`gW&3vmp(FH`PWIxuQb)on-d5F_|V2a-$ zDs?xMQbJ$6xyXEzuVPbXQP^A97*%P{TYQB$0`WF~4F@Jqyv;vg*Sk``claZ=rYrTD z%4gtA+o`GiRd%~GB~QZ|B9Vqo<6UZOdrv=dCQQI|W+-hA7KIU(>DV;k9Vl@+e^v6f zu9?o;OKvr^zE}K+lqV@!SQR3jPXwY!xO&e$OkIb*5 zVKFY7;f$-nf{g7%Y47r6=Z(O7%V3BRo!`@mzI>O*2Q>gQ4Iz-HZ@0x}R~u}0CFPe4 zOw51u%7MHYsWy$V`o72SNZ3lK{sG=RM^U#A_+3rPvk(Rpcec)+#b-c&o`$EuK}stx>HIRJt&q_wjVc;p7sjoFAcO|>Xs4o~)29w;riASbO6 zwg`rA&2&6dP>kZkJ_)3g1-zGeY88z1K#Knwdi-4|o%2ybC^JZLm5x%k+1!uT1Sx^i z4YGX1n<|m0mqB|rb9XBK2$MPvEq}zLeuPdJqK;00fr}=Od%z^-oJJ}ti8iXpfWd~#egH(JzG>FZkdnq0?bsn#V4~|e!la3}UUbJ-{H?xrebbKDB#oHj9BcF}yAYMy6naA6*`gJHN z8zS_tLo-BLy$3ozFq}Cp=Xi;18~EEA`pFV2WOV@fs6GgGD+hjOL59 zXBh2WfPkn?7&$J)bJH+tA=0{GG)km_VYEb~F9*{Rk#-BFMwLBCQ`x zvqc&lOj{S>&ER9|MhG>t{Sc5K271#E3eJ<|6OdwS7d6TWzwA|h5cV!jUCi6CdVaKb zF^`v?lJqIW@DC*-VZYa+8J|K7$7<1Dk?yEPYzfjewJ1rX%K#VY$AF7;D&U_X9Rs*X zUk3a$D0!z^bWl9U)gpB%p6k}4l%)_@pPDpnDaxH|(axn9ga_om3{wPyuuKd>D6L!u z?ERs1c^Mzh3PLG$IZu(l_0_~$n|3efCiYY4!YCz(t}W-zLYp5gha9$rQsfGx>q4oY zNIwsy*&?M-+A7jHp>$28(?iKO2kC@RN)hQRq4btW`-f6N4){yO>=4gMq2!#4=O&?) zlq>K9=yj3$gTq{mUp3GJTzW?SD-r46q0TEcZOK~6yBJS|NDInjPpUguZO000P{8LH zl22>UTc7h}={D{8oVR4|!Sw8No+NjwAyF4!wKk1d#hWqD5L&qk;!#4Z7gzC75-SL% z)Gv`)ONpz*jC4}!QE?$R$p?ZllbS2Fsc;QMvL)CW{S_=Y8y`$*c{pT~;zQr&q1DDd zWX^{o%)z9sur+J&^xW1+SLs+jjO1gwosTgn^42X)Q$O9(9P_R`r`O_Hw={dbbxX6l z3dYCYx}|wgQ&^f>lzIsR^*DgiFCixI4;1~5r>^TbXT7}1cQv|OCy4s3=IP8Oh_>Qc zDx=cXyghUB#&xnh%y9%3NO`hfNkkCEKS5~t(HdTlc?VJYd7KY9y@osUYC&LXTpn*L z{Y{P5^8V7#B5|jjwLFH^vo)O>VAu2qUNr4DUWcZxgV?ecwO4#-<2r<_odW6LI?nQG8c|W7b7{@S1FcCrvxT!>mOca1Md(2q52$cyZj_ljd)PJ|=t8 z!HtkuO;39E3y-zNZQ@*Ft!q%yx0o-rYtW5TJdh55%UyVl8a9U5Iu8o5LKzl&&@?Ml z@D@p%bxzzU%t>_?A7^af{uHnor;Ad7g!U<8GtXqLJ?P?QG#l+fURy9gW$vQcKyo;v zcvIJHn1x5T@Hp1lM{hS`E80!;LA$%pA|UCym3P96++Zt4qHrs^vqjH4ZG$-6Y)ou} zKWVJzpC02i<=5OLdd*2~M^Avo8u?N5b{;P$pme&28ceIJs~(iMorlZa{3N>BR%vH$ z3jgt34))U+) zKvtsIX-_(dXOB_9uy^?#MGej64|Jo!`}rhuVik-KH+>?`@g(yB>=n=Uq4Wc2bhVG( zsC318;sBJKed9{z@Az_goU26h9FzcBxP>>RaoZFR@;k&=^JN}lNIz6O>B1pClLffa z@Waq2qbuz_jLr=7);p8st)s&H&W4}?Ytoy;B9^X2N8ey0Epi9T=cUtjE^Pvm(65+J*{3m|_UQTRr!k*u201Vh#F(FP8B7qFXU~b@Wg4Dq7DwC8=H% ze+lxL?W+5Z)vlCULy48H(1}ZMSdZxbCEgg3OT=aV2|Hw>otI%5mzjjqh+@1tMg0Y_ zfyux4WPaKST@mJ)jWbce74X^DL~mUIpX;GmKcp#<^v@OU!hUkm`E)gDqigMR75jN? zol&3CU^a(7`Wusdw2`8&gGx^$&A!fCI$_hO+?ubUJy&==SNF`cKkQ0>5T*X%M*L{3 zZ~i@OD~L6WSdCoSW_bE!pbu6OHE?dUCO%eDEhZzS{=*wYVtt(>vlF;4J2FT9G%l0v zZgo-1FOG9Hia_^FT*i#7xE%Sk^{an)7UvKDU=|9$!)sN`k!94w71nKJ>V1d%C+Elu zH3D9Ek(f6`5Y23Lp=oBT9C<<9g9(PxMb6TKyqUdAF5o42aT|tZMPT%Z!8n5CySvpD zkiCevTNzO_EkW^heIK}2UP&k&F&1zzMStGm^|+`>u6KE@=~v`B0mb+?4Rh!oxX>_u z2$p(zSS%YX2|F^b8FploYmD(&yp;7mE=t4!Q z!{$0zzrDv#%Jk=brG{G+q!gOjYQ$jt<`IqywAIut&~3)iIMJCAV^Lh!P};0IT`uAA zUgd(A2|>(4I5YBE!WIV$?fgm!bdLumj0HC8N^xkc)Vn$~wQ!E&X>?57;xNdtg~t7& zc!oIRVVGfy*87)gm?LJrmlh~FU=5}d9F^3TJ}DJFYfInR(#NG(BHj5)N%qhFE0+V$0=wF>_fp&APK%unn-O4jI4~;}=d(x4{fX zJJH(5u<^}ha(;sO){Am~#!T+|gm?032vmEQ<%Va|bFX}fEfniwB#B3zlzaukrMvOkj`clE7GZq zMu~JBqvd6o_H9u62PY*!8`@PWmK0HJvAQrF$w%tKxkxhAg*%ZaRu#ZV0N`BTWIq^nQ+pc*2&Pu94*(qK7jghHf0>jf zLo=*x8KwHFVPtYr{G?R6WKtSSiB!V@Nep#%P+BvGGCJ<0B;(_lU`M5aluq45l15pM zN_#kj9o3co@`+~#nzxq6Qtj)CiyWb9{-=8Ul0K&ysY>UcUAJt^`05D8B;F0>d$DWtMbTv^=akuBTp&Sh=}Qmo0201(jaFg zns(Jil#nR${DLgWz{WAVbzJT@$#oXwEr7d0?0XX&3B$`EOvwVN-(W)}CD#`-B^ zC55_$D;{*)PwB#NKq1K=n$e-my4+tmEn!1B(I0{4+(0Fr4S0mpo&dIcL@7Z^vb;>P ztzvfsDK2c6M8|`aSmkl4!G6a|uKvhCH$TF`Aj2a{4_4x(Uuapd(tyQ1qvOGt$qk>; zvtT9J;~?tU&&03rtj$DuTd9GX&gBuTu#}dED81a5R6%_k2(7>7wWU9)ekfeS>8BJB z1Sw7lMf7!^EI~?L+K4;@!&vV6k(#Iku(;CaYQQPHma>3_m(tE!%5gEiwV~^O(H@bU zru(&_BVU)$hA<_XEia+VVan?)tAzU1!Q|;tB6KBItiMcDTt^wlKf`d*N6VCPv_D*F z%f>t*#|U(E&=YDQ(wD@geoAr`*BLLFf7qY}dy$tv=dm`ISO%&HyiIY!Yzys&t zu+%H}D>KyLKKb67-=k?B&?l^RU8!xXl3@P!US+#O_h?b9@|O9ND&-UJ zQPeA#^$AU3Hi{{+iBivOti0R6&{&rmSaZgsE@gVFL9FXN3TTFbZF7&(nklE56R0$Y zBre>AVZ4k}l^sfGd20$I+q9MI`1xpw8TXH3sZ32 zUfvw%hW0dt6`b2Z@n!Aq(z%vO8tZsh7jqDZL(GlH^^U?RFHWf?zw=NRvzz&DWij8S z+O3q1*rOWXO6hIBbf+@(;2k04Kw4ACUC0!#)MB+BQdB%T6af=(S7}haTE*HBda*nn zCimSt^dK2Ft>9k0_ACqqaQsZOlhZM`cPZN~Zn4_l>l#cA~ zZ3?)pgy}nyu8*l#BGk78-G00r3*BE5VV|x)64Nh;)FfERV)9H<8puCCGA!JM$ZB+w zV&aD$2_Z&8J`0n8za5N;>G;`gx|4+I^X_d*ZG-7^mQJ(*PO6s@fJGqkO<9ZEl$OlMmq+3a|`vZ(&PMK=PVStHsh4Vkr+mb8P? zp1D;SY5OgDAgQqqBb@b(w_k+bHpT%*fL8Nd2IteoJ|M1kYv|V8ruzvwodKA z0FDeyYLCK(rPgoTD~=M@X?r?Ae!r9Sl5&^rx>+GV`D}?{VFQex*wW=inrbyv{ppPq z#YNgr@1-c;%NC&AR07;WY{7Dh9xT6CLNhul=UD5TG`JIF7JgG`W3rqHLn0KAt$d)_ z8`!irJ7d@`-_UfAZM#8gs*)=ELI<^ZU3jCi2rM^fZ7Q_nvm5%ney<9A_zmjU1%vY) z<#vH+j#6T0m^j;u6t}JlUZkLg-HQ}C?uN}RHMpUia^a6&y`%f3fp>JjbpM~q ztenKN?w79pqx&Vem8oOG)25mK|xIl8llvX{;|e)S9UVCvXXXggY5R>oSi= zQqR7Kvp&U>X1h*WKkci0AWQeG!7nQ{W!B*u#b=;eqiYl}9sa5)0}k=S+cdYX($J}5 zK7Ngv1dky9b=5%AkMP=5zO6QZ)xJxQ24P-(2@vA5CX_u`831?k&tPQ;n|YPI?v@*# z(N}5h5DdqDx{!e_@-f@E3qtfpLoruEt`hoFhb%)8It5>)(?c<=10a}TN|f+m!<5fh zlYi*iFeTaj`zw`2zxoP(J9Y=cnT+A^t81^&m&277*kishTxn^}u7W)NiZH#y55kPPZmu1NuWfpP3A6k$M38Qx_;}veHtL^+rxjhEIGsHhjs8<;DDw5 zVJ&!Dc_6X&e_2;fh23FaU8KF!z-0DCF__5+xpSvOVKS#HL9*jDTi4oOw4R)$}@8$`ru}JC9ww|R)ix3u>|D>IZKrsgCWTda1CG@JU zbr4~pz#8Lekm6@uyBMm*+MIb#_c43zyp=6eeq?O$X*#(Aee8IeqI006R z^8lQvBXo$FBBuow9Vw!JS< zbO9_mtnaV%=xb0| ze~#9+R9i?t(bUzjbuMT(gR;C;Y~ig|oLKO$bb2-9;PERtuR&`3mDa|o@o;5XYY;F( z`~j_0y!|{wsUod=hNiVrlRfsFG*pWAR^nM-8-II}-e0Rkvae54K)f2sa!%5@wFt~- zSE=#pNn2q4GmTlN)RB(RLL_YWY1+9C>y`s_dmWVjFG^eukD5}5febmRFP^dsm1ff4 z*29I$9}-*r3$5J%{TqCaZft42vO&j`|j<;67q&TZGg?0Iv zV0By2Evs@C9#^YdycsjOx}J~QqQpqUXwbKqeYe(fGcDhO@Ztke&{*1Uy|4vwCY$t= zh##>Fumx;kAAdWAZ-J>7ucTO$pJ?`W%;1k{{1&X?(!Ef9oyhBNH(=e`?Leq?mn=Kr zt`E_P9ZDCuj!*y`JaGH5@(3;eQMgHOvg}mqvb-O4Upc=D(u5y{udGRlyOg?kGdE@z zI6XzVyD$=u>BM$4?7tarzMB3>IOIK>HTaQk)WCcF&AXL2=KCW(*o~36c|wRKkb3Sx zc${>SzTKmw@CHIZ!~&TeI6=oZV|uJTL6KXOW}4~685j_6L;?E{euRrWBv#CQ*sv2K z{GTDWJz=v_uKShI=4K}(KUC&4;0Jo^sInFsqS1~!22C4wQfF`3F|hZ+ zNm_dhj%%;=>M^CI!sZ^Mu%BQeryrxiKY_cnW5PQ1`u1n#iOdR%=-IDWp{*<`7jCno zcs~K*1|OxY4O&%OPW(ntD{JWpeQ570}el@;;~@k8?B z-49+F_LonhGdEA+>Af?sF_@fZl&@Ha?Ymthj`UP|kOZ5xjedS@@k~$o>v!qXt z*;!J4`xxZ7`zzR+8h@bEmnh;7h1e^HY40ECbXO4g6P?b(1$Z{6?@|*lhXbF#PBAZP;ivIt|&*atF`A3sO-HfP+60n z?|Ky~mhpq#3U&rYRw%E$3%?XSM^UEAE0Dp+$7)-V=0)FC9-hhHQGu$=H;<`Op8B2G zPkU9{!jm@Ao~s!BuGitvPKtbE=KdXhd0m;t?j96c5KBR4@aBHvKT3kzwS$#g_?`~@ zqkLlCQ>A$2!SeCHC!u9QtasEd5mLHhP4ME~+Zx+c=D z2Pxo|@|IW_-cn}b4X^)g__hH@G-0!@P*dS!p>Ggv6l->b&fQk};azm|JJ_eqKR{dW zVEpGF5K(M04oJOx7o+S%!8f5Pk^f)|{qS9-n%w>X=GJdKV$nUUsX8B^$a@F|4998G zJ!LElI6$dSz=_)d^1ZJN7w+{wBBEx8g)&A-7peLKWe9gatSexE>%lm&*^)8iySQS! zWHBD5l@G8Dv}ix650!rM^!*0Se+rHRq8si#)iP%6iz}{^*{V0R zPefJjGxlpQWHM$Ph%5HaY}FC^CT3%RTV-Li2L8PB+>1^oBclY70#pz%HA(M<2QlvO0i`-9ul>YBU?P zhfd3&5W7bV#I)D=SIw-L%N4t~DoDDX+6zXh{Lf z`c8zIbxG{^%AaG1eh5;UDCc)oURmGXWm{SQxl3PJZ`q}^_^A)bs!M5<@F&bomgJ)+$WaTwdh(k9HQArk^@-1 zW#z6g^2po5n&4eD)=3@ALU-w5%@rp#gDJZxr8?w(dgt?vzBt|lb47pMKJt)Kjhvj- zw!Ee&(`3JXr`Qg%ZL}@fDT26W6y<`J?@%ijwIzC~HCpl3zst^wi6r;kX`s)ZA-d?a zlcHP^bbs_6rMp4}8t~W4KZa8x~a~* zg?QX9c4taA!dFD?CDp7Zb3YC14#LazJ7|en?Z=kvpa*~m=G@hmvIp##W@?^|4Js^M5= zH?OG_j_S=rLIiMK5+So$`)TvMH7PN)J8-i9|MP>XkW(ON$>h0TOn5p(#9y}HS{ zKx6#X)~wlnVQr#Vz5R5~ALyI5ijF1AUSc9>;T4PwbKIrvCz*4$R%Rk=tFSP!c+F5d zP_2V4=gxs@Z}ZqHSY5X2wq*m<<+*Li+bI-2oSYTKk*(Qd=OKRBV;f(mtzwrqT&)vu z0S5pmCsy^KRViv$`L8XuKo+~|ew3ghW;?Z|@*r>BA~w?_UB%G>Q9GrE{@R|xJE`N$ z1y!);Y|*#Y9XhMs=-Lp)k-7${JD|VL!K$D1hqZ1nIvH@=Fg}kNdZZX~=8K!)uHs0< zHS7615y6L+Tr2y-Iz2=!>EuwDQol{<94AAeHS;yq=vX7$bfJAIK5r_$QZsXl$su9> zEQ4XwEGI)Y<-DoZ^vgEo0*o&NHE{I`u&HNT>uZzMwoqeVj)j?@t2U~ZE%n6Rv^cpj@DN4L zQ=>zYk3Pc}tO3z^`vNu>dmFZho19DzhHPn!j+b(XrU|@8_IU1wEk^OR4*n0~`%Uqs zX~a?bah}?En62&Hnf@g?GhZ$dg6@C#8DZ!muhuba5j=AJfmV?q*zL zj*nI^LRB7sMv#JwqyftX?ML6y&TKWQ#qZzaU9eqSxTgn)P67(NtF$RDsIqU<+x*E(>gTIqBiu&HgpcRI2#NL67aRbu6==JC-4>EZ|{Ly_s9Hq>&tT7wEdQzv7V zhc8us0`{lSE1}p`v42U{u^TQ^C-Wjx?PPjw0j&I?WomC!4qC2yBWbo={lK9}OqN&C z0v%eeJ_hd8HuOWT>J>N!>Wl*{S3-40u3*k+jPz_*3N0(LK3SoD?dVW=^2g-T$zrY* z7N`@XmkLe(=zup4_&|jol;S&mW{5$(Let?kTKScZnOm-6JVr`}rdoNvt-N)m4j0ns z)p(UPX|HweYBfY+Zu@D&8nwApXuZBhttQndG_41J<&)Mnrv*K7U8jBqwAJg>jt){b zm26g5zyh4ovGe2=o9)D!Z7tlQ&SO%xHDSAIlz{h7l1^3hTG34bsA3xKfY`I?w;k$V zNOtd3y)h}bK&+Dyirm_%z6Kf@yVS0Zl<=FXST`M38%uaKs4Dc&5%nRiSj4=%^1V96 zC~~IeNi^pRjK{l2)jn+H7CLuSo$vG#AQ7#SN>h+p-#Mm!Qw?L(@RT-G9Zsq9a4pKz zByu^AbF)uQsnu!}nfBO?zD)!mkMTXNc62L>2yQEA6{RG$EA1$X-#M*XQEOqF(!7~9 zOY&we+gxr8wOXCds5JrZoP^`qHA}?!)xLpWlz|d!;LI~>TbB1N9Xz8RVVgG5{IlwC z_Sq(SbXN6c3pQE3epjO;cHK(J=hQ~vbyGW?*QMt)UO%+s)uz`P+1=;Vj_9Y;d9?u= zcY`vN>$822dYo6=W0EXAufFPlu@{r1CT^^nx%ByHf>EcyHN2Ax1??38X+J8;;b4*+>EDvtB*+|F#!2-zPZ`IkM(3GE4 ziV*>^zt!)X{LdyaFEv)mt^U)ix?|AUvEyU<2Ej)^cBqgJUIz=`6bcp!9A_2ktvhP1 z4`!X$Q}hjW6iX|lDe7r4q1n_o*IoG2RiW(+r+Exs<_RBs+S-ZxNuiJ zgYA`WPu1>h;W~ki?*r}wzKni4;JPc{V1YDJ;OGyp`G`@&CInr`NgHcpR+z>);M8*uBK_v)UD+DR83%Ctk!9dTcgwd^C@UgS*_7# zBW*SMX*C`&KO6F2t2N|>CSwr0`L&K){IyQ~#Me6Y0g^F}ee$(VJ$*IZkc{bUxDC0t z4Y`92Ia3C*Bamfd3j6hIa^%Lb>`Vc@#f{PIcmb{DDBo5<=S)avfr!xX zb}Gge>}?Ini(FM>3>#s?Y+}Paqyn?44Kv(^Ilu@^PaEb%q(n`jt*;fGa5d@)g!m#$@(+9-VeI zPLjT$TrZ+JJlbq*CUw=p0XjIy9pC^Roaqj5 zH64742GvCE7!QC?(S@2IzQDs6BYj71z97C(2e03Rc_V6?s82jFcw_(L5$v4*j$ zG)o8nRs)>Bp@ZA#;E#OKb{idh-4|kMtb-*Tyr3q)k`BIC6X4r4C=_k)qTCR)z0?oj zT@)OOwx9R`yiNyC)xoR$0iLRZc>us;bZ|=@ygC5jmO9ue5a7BxxRh>(gZRcka9%=* zVIb}k1n?Eg3Pao9>fqf$0B_R4wSocuLI+RK!AFBZe1Zl;1jn7gsDw1yhh2hN|hj6JX!uHkg54V=&H za7OAl_iBUANFAp~7;yU9;ndOFdJ=|?gy}dLbufT9hF9JeySS3h)iKUs7jkKExG`D! zfr1+uo6+xPqYGQMl5Uud(NrtK*oiI6rPm{XFvkv|uMHt45(s^BX+|Uv+S?&`+7Q~- z1%hWT&94gt*$&}EuHHnCdO$dlLo4e6VHYJv8$Ic`JFM8pxfEUBIE{UrLmTQF<1yNR zd5{uiY|J|5Qi~{9pU!|qVe+@gp=VK;><+n<)Bxqxa%gJ z+Rs+Dy_8U45{-*Du3|Au$*VPZ3|LBITO0SXe?Ft=1h|KDpXrspUMkp#rCSN`2x~sG zE@^9wmRQDTbiAE$Fh;ylvT+{uX=6-~+(~M0Y{|H-;)&1nihbIm;!jI#72jW?Rb*q9 z(2*qLT-u!sX!9ksqz&4PTte~fjj7TDI+1E@Nr&2l>O<<>#n=X?J1kv{=c(RHC|XYI zyBb?c^C&CT*hT8EBgdowGC)V}s3R}#h$2}-X7?7;jjk~KyFaD5?TsxcrxV)UvzSu5 zV7v;Eb}*hJo{GW|i*b1rnCWY)QQKC-sSAK%wi=$c8soa6@EB<|q@C2L4;Y$FS$)9$ zlx_gcA-#pS$oj0C7^7$#Zm5RKZj#QMiTqBgQ7xut?j}$okhW#zqozpKSI0)##|OTNABeXN@6@y)x07a?ZHOXzXAz z+>#!jsOumfu z8ERE)n;aS2GR$hOV_GS((L=1?hMSUbpl7J{QKach-XR?98umyQ3BPP4@@xyUh*Yl6 zEdfKHQC^#uHy^@&2^uUkZ33TxVspz-Dz<2}veKl|e88+%8km0JH3X%WHcD^u=ahaM zY&{ucI?Y-AfwZBysW#U3%7kEEce`2$`#DtFmq|wFSXOI zwSf^vS0%u^QYVw~wbRH9vy+4kqrYdEmy!2J&;_l`>E8A&8#F6EeiA(4aWr5y7*vSJ8*r<*y| zybw>e)UGMz^TzqOuMX^Pt}oZKYZcR5lfq7JdNV2PhBr*g`ayK#5ObuubCCI0qJw4i zae@8FSAzXEPzBg`k@cKjF9}L%ov@~6rp_Cp!b-zTN!i$&zBAMOjSjF1AIQ=G!sJST zNjSM>mibJOMqyR73n1R&2B5RwF#D^o&Ng4ga-bt4<}%IKV76|D-+6c0FENSAPtHBzIG%zH9!Tu;-;X!k>{Q zYyB&qzmlU4US{rUfYAXF)kA}@lkWl;gq@jmWmk32a+pJhSk=n~@oQiuL^vScH&<|B z8jVs^9K$6QK{`ZXu<~9PM4+-Sk-|7vnnil=L-TqacvW8)aCvYg@NhS<3gAwDvzc*T zvRM&t%E*r)3M&n7gevB0_*P<;MH*pW41A?(BU z|1NA^O?U`f#^7DT#?=&dRZRp4djSY^-)H7f_272%O-<&!`7W8aMCdaA6{*zI%XS-{zv?g#^l=2`8%Kbwvb8poU zxNDSho57-%pYVv9urTrk2CEzGsV7}RM{p9|8cqYO{0l=cJmErG92r>?9!CBlOErCA zKI-E`vb>z_@dnwsedd<~d0fP2af*O4Cy!G^l(~hRnpQhz#N_B9zD_)GCOPkr{V`4?}pID@uznqQCD(DD&2Ku3ZoZI3DlRXC$pdF6FU zI6dbyw;`#mX!sHH01~N{A=G}vJcIn6PAx~xiCB80ZI7B?Cl}M{{-fq;Bq2?0d(50e zNV{}(!ErOT;ap1vkA}U=^V4b3NpmVWm5SX{=4^5(Rn7jzj3m8fsygqK*^iK8&9S}7 zywdMp+9T@amH96IQf=2jE=o&-bAJ( z(|}v%N2GbO8gSdZr4CN$b4ID(625{Mo^SMseiXw;sF%F?sf6rLpu^1k%SK03?`Yb~ z!UxkbGygpeF*|_^#x3EKR7(?8-l_O0p~#?*j36$-r1TFMv-a2@UC<0Dd*$8mglL`Pa?F3nv;y@rjlwFR!;(54U|$ zfFA!&eHtCfKOo!cvu7FXG?&3qd^UM0hOUm{&y$uh>bz(^fg?BTtJ~`H7H^VLpYD(2 z$B<8>)P#7j^Endrh^{sedagbnptfnui^$y~>7EpRntCvizfZ`52o+Zk4CL)_b$1JX zo`Ksy3p4p3`e7O`($g*YA?m(#-lpB|h}&W9cu{?}4L`)deMhspxbIxZd!h`$;P$7q!K#Q?f6o3E!n+lBv=^Es4>PhouHLx<<^gGjevx;uw&@0S6{ zl8DUmQkd{IPxEQ?&;ER!x(;*KSY?9`TJ6{V$^w)*uf?kM2JpuXWTwCR`ykYf+2a3* z{uT!sz5DYo5PyHVr$3)c4?WFe{WJ&Yn|!<+x!!?FKFa*pVwEi@w~P-|A3x1^;>mhH zHG4Eai>nvo_lTA^c%*&L)BXAaINRfE$EfGV@Y}h@c9$^r_zz>1b$C=HHB>gD%z3#X z<6_VKrlGPKWqwqgy7zg$f-}d~enkI{fox?XC4cqTaeOP{^A>ta5T)%F!S|bw=RYQM zaPGhdd_7uz-bY+Efj34%(=sOd+bDBij$@*i<>$pK^H3H&j8~TBnd{P)6Zq}*LVO?5 z+w~!J2kuD4bmN8!1E**VR>jap6ZtIKS-X z=HjK~ ze|fsH5apJe>1yCCeyxvbjPQuI3a9(u;5U+Cf;wRyKY)-!yjnD$58+52ubzL4FDB$i zv$`#x-I-@rix=|a5wToVdy$mk6=znfS$6&tve!qwX6J*sx(-*pI&wd3qP)O(!=nQi z^YMgSHPQA<_@3mr31@imJ56&;kLbV<+H)zNfdTo@4|oj7m-2qCt4RFSMEC02Nz5XS zB1e)k9<{NhQ;_lwu8X@SD~nLx4o*?*D1FbTsDCWw`w;Jg-jC>Vn)eYO5bB86?dr$@ zH5kQ_TSbjde~({ImY8V3a(-j8(LiD`Z3@S$-{4&4O*#FUv}Gz}`?o0B3V?O6ajP*8fI1||5o79KQeuO%`^wdefUlvRtp zXh<`)(JH<+H#{4d^%&+H1MDE{m7w%^QW=v`S#=-N5`$_=Y@QYdutg1 z^dzO|CC(%Hxd;L(M}-aiZqu`Pp6;(6-hifo7wsR>JM^>9_2H+tp@c%YaOa?8+G<}zQRY^`4HT(D!c$;nD!oo zs64_T_|nZ^@y{{}P8T2N-0f``1?O5vTSmcIG{2pi^fkYb6JlKy9@L_V`}yFyP8J_> zAxiEbFQq$5#0UEHe!dAwd8kJ3WwGYk-?Z&MKAM#NO%EU7qv_mzd`!}&zbmM%7IQ7u zIC;1hVXk#_9Ju`hN%iDDz7J>W2CT^clk-!5s|)rs&UpWH9XPUARlzws>Bxf$x(<>4 zaR4fVX+y;vZWgaj!Q}a)?)h0GItg%p# z1q~=#mIIr0W41%&`Ckzq#+go*S77~(KKhmq4*e%Put4S9g5J2%nmTc1c+Fvm==9eK~7f%u>h`zJ0uDRzT*dRX%=ArhVJJd>f%4K`+m>&=jv^` zkD6rI9jdx?D5-TU2Y%qE)YT%kR!AZP@tYQ<%#e?nD( z+JYN?`d$V7Osvso9`HZ%JXo{DN3(Nnj@j9nvy{`_*o!b@yHdT_o&bc5bBC=+nM zxYUTrb1&y@)JF#=-^b+F?`{Px*@UR^38IFYS>F3DU3Y?y^~+}Wzr_8|_51Dbs%KB| ziDt9kpB417PxaRINy~FQF}?Xm1s&o;+m<42fBz3Ut(0HkHwE{!kc1@nJmT8KKWOZE zeyS-E_i@n9>ht_r(_g<=V2d!F_ZxqU?E0Nf_(q7P?_EH2f7L{bFYx^%wJ_fPJDb&j zz--hV%n{$fpDFApn&MA?y3701ffxBq(~F?h(L`5XoBUJ7bR6FT}r4GL$1bqY&D zbPA_I!KWA$)__99FcLodfZvhz2>u)J*$33C-4!V8x#)w?*=l_d8i;+%$QG{ttKk55^Sl)2{!o;r~;v|8F!>uJm>Nzli_6T>rlVOgAo0C%US&a-}ne?LC>> zu5@q#yo4`&wR8PXX{$bWl^-vf3vN}=m(e-W602Vnt@x7{>vuu8Va=oc>b&Y6gIR+( zy@_PT>&DOg3)S~B2;_i3_3Cp|AYav>a5Y}1FeO2!@B^b@1%-zHLSfXN|AWH7yP%K+ z3dVn-KniP6C{NI3C~3rG=$|G5xfC7xKPfP(CURk89eHyTU4e=B_)PQFn-z2qC{X)L zQY8K59{;?N-J)e9(j|FdcYsXLC1NV z(2S1wn{UhoKpY{E^QGmSP@f+9n~zM&VG#;dqW1(Ay%%j#OUXu66&Zb%9w@gQ_f-;6 z7PIX8AwQOwTHHX?^rG_~A>(gygEoE4U-SF@Is{090PP?E1i5v6N1|Zm$nxtn@o&B< z-OdS(N#1q(&fk0hnSNb;zzJ>1Q)4sHBSp1UJmlz9PnTmyJzb8U!(DPjDLt7S!Sz|B zEW6!5M(K^xH@kt-2W1M0RjeqjJ7d*FM&U<;Y0uRP`fdf?+C~VVubPGHp;~nA3Z3KM ziqm<19nW|;i)JLKvw5MAGkXK)6cP>UCuL7y~(TNj+ajXipk; zzr<)%^+g`|-y|sstiDhW-2#Lt&ivqF1^o#fC@nkU6GZp@<>O5|br$NWn*#+KAvqV- z#1LVC(a`)tg)4+vj-Ye1UNy|v26eO$26eO$hV;pif3+=B%Te@vJ7#dlmeO|2;ErO1 zFc{o%du<9cxYKv17c;msr6

?zCEn(gEc&2Z_=V<=poSN+*gE=TTifjN{TKVEd{ zCF*)9lCIZPiRtC=Jt{N394Xr@OfQGEX)UIg;~6vr=;fH}^i>+bUTa^CRoF&sY=%~E zHxh;#&HK-x63}xltBt9PvB|=9LcGqY1DXi|9NBY@PG~OlB!|zcdzuTQIAb3MoZMat zqM1JmKD66R(W3TA6&iBJdS~$@a<8C0sim$-69y9c(LT|i`eq0=pB8wGjm`AM=5h#a za!ABc9~r`Y5_5*mDiuQL#8#SzW3E;+#-N6}F%;~)hVZ%marE3zVjp^_wO}V}PSe3{ z1S`obQ(5ca$b;KjGf_{s6=rZ`>1}mzrqI?vZl6+DbPxuUw1GHIsd|=m1%uhE=ma!B zYEYZ8u;-4g&FpN?|DratGsc~MYNKpnxzQN&D-^TyVif&xt|-!p-$=Y#kt6iNeu-by zo;`$YLds66%X$fz`@3_3F77LQW^|YfV`%4o0>0LBQeDvx&BSp0cm-W_S`JsE1`5rH zF%y?`-(bOC9Y0tw8SC1aBgDg>;)Clb0(3@8p>GZowwTO6SI{$;X~uA2VW>9tZVagW z{&kclD7W0K!{VE>xVAt2ZMe{t+&V@RM+oae4j!w(yxi0GOP)hmdm3S_FUEfOTGyUq z>a7vNYMc#vOkMnpFq4~Y&j)AF!Z_Zd(+Ueyl0frzd6<%n`@Vjhl7j1$;&7!YO6#Qv zr6KNLewHZBa6S2Mq|zMalDkn#3zR!Ae;U6Us1HyJyU@C>kMIzVfLQy(KnzaKAvMb^6&tQ*f{F5gGu>E^0m`- z@^KjoJjb4&-ip<>eM@;Ookfc_I*YMwnfi9$!)=-R_LRZxnEH0>`F6Vc+r5;6IS3qv za2j~eRGZ$g3EPSCy}CM2I6=CpIJoZd9CRRam^if|juEGhqW+*Q#KKG{$2tHgKrBc8%ig*ZerBQv<_e#Y4-TtS-w@v5y1NbL%t5v)f@CgcOiUSs4$8^Mg6pDOf-Kk{LqzrU4B+Lv?pN8>)DN?%FQN ziVw=mK`E?N+9xN5!9By^o?-V_&rvg$2|WzmwV9Uo=k=Abd&iI8!M&Fs! z!drLEx+X^7k&Cg5=2F3}boycSb@~hIt7|?IvN*EufO@Gw*kdx?D8yvfadqP-0*-lk zf4}-*y)cX;&lIYIHwpqVmh3}+VQY<4dj4i%VBi&#o;pA|dwf@K<(dg85pt`0n+48b zI=L6KA;;*WPlZ%+W3QU(5CVx`ln)cpo-@`*xejPHcQSmNP@5xRd+DUl(aH0B>Hg1! zgd`8zEzEA(Od)&ja-Jz<&+j2Jh3s3tkkoqHg{#C|cTWYqdW3aq{e>8stO}XbStNLe zqy4wX)*kmLTN5}>vy#22pGhAu^j;*HsY4Z7n*R571$7)zZ>i9kJoU9UZdXHh3+uVS z3tu6^7}#8ie)=ZFbejER=;L37DD~l&2u5Vb*L2$+;i&QOPs~_3GG5`iBKM(9_6o`L zi+w^n^5vH_{5;Z)%tFCPPv^^$8dE5USo}3dY5jEq9lBpw5UEA2)k>ArS7Gk>(LZ~Dqsrjjoz=#C%t!9&@%!t>;}FVw+@1Z?hV z`2`a!gE|fi5lBP*@+)|tHAnAy!y)TIfnWfbx8 zi_5~HH1)Fzn*R;6eAT?=6&zj-F`uO1pQuwPOQfG(5pJ3$0J+0A>gub)Bto2cv4t7C z_YEP`=MZbMZhu{JL->jv=K0wlLSOac+rlo6%=%Ovb_Z##@#*PbQxR*iqM2V=I< zJ%0%UJP6R%cZDS$chviL(MmjS(L?tIcDkkLP27CvmJ2T!jLSFc)fcSF6+#*z#?88% zw#TT^>hSd7V_{R36Yp3eHZ~Y9Ze-XYa#*5)4fgZ}B4(iP&?1?M4@1)&nD~2?xiE1N zYc;xw|1vEB_SikD;4LC?<~Hh#^L@k!oz15{;;t%&YQ9-a=6u$(rjC60057IQfJ<5Y z5kH*^vUZINvi2WvKfkLVjo2sqt8s$p!?kv>>_dZZ5}?C>6QE0zAE@K?2-5M!2P;1U zf6E&oN-@gf9`)2*QS2j_$E>TMtJQADsSqt_}5<@)Zi>`-eA1^p}WGQmaM{_{ZM1OECXD7_pPcH+A%|1;=ZGv z%MiyBG6(zWnTT`S)C4}%Ms%_&)Vs5%YAF9#eZ2x44fG0dwiPqYwLhq!mp+9szL`P- z4PP#YlVhLiqw81OiGQ=6(jD2~%Yye*UG{75zP#ODT#DE4?mR>=>0!f=d2N7d&+^IeK*kn)Xji0vhLtuX0A;sdpy6p_#PM7<2_FY-2f+y2d$6Nr6_e^Pw^G3?YnhU|Li4pAtam9wpOuP zcSygox<$|!zuH%80V~GIHu&I%|Y@*Yqmp9eaGDP8%r_E@BlJL>ZHmk5SGwwp7-l zT>ETGT_CS?`u-?!tS8WtbRB3)h7R;+2Ce^$__A<&vA&3UU>#lkj2Io^q3ZZnx~dhe zbfo5O=x@)6oyg>6YQnSPC>%leuKLbs5h?M0ygx8TTxR-Hsi5Djr3;=D6G^>yHH~K1 zg5*r2U-8UiQ%DE?2>ZJ1)ybLLG|R%mnq^0~)h*hjonBK@yjVYA-?D>a{eZprC8GR< z@^%x0QU?4Z_@8p#pd3YMoz@Z~4&VE$I{5A?nA00&Z}qw7#bESmOVroLiH{8C7Iw@v zBd$|vyBulGdw}o4<71-KF+m)TmxFy@L|wF1G|AgFg~Uwqhl}8z)h1CntV~_;nYIna za#s3952G$U@2wl_D{uP#i{iz!9Y9{NhWU3@=7LF6KM&-wCLMXHNk@LxhpH3B9c1Mq zI^iWT+Vm2LWUryiUJ}=laf{TplSJ&|id{r|P8JuCbMMeolf~c3>UY%QDPjgO)_I4u zwrouM#k?Z+HizQ!5!9e%sZtYl!z<$Zgmhe}2aqAtL^~lX^3_{2#Eryw`)y$E`=8K2 z^qIMh?bH$R30eBXY%wTceLjqV#r};4hV3df2nnkV!|(quUwtrJoMa#m7SIWE#8l({ zmB8;kQi`YEoy0oy!W?lVxg+Ysf#>InFLUhb+#BNV%DZ39V*y~_TTcW4XFNa=0D{yx z^TjsAIA{S#`$kF~sbiYtr-r;O?&rwSx74%w;yRAZNmu8+16vrCHvwjEfvNTcMXX0; zliFDkbeyo$C7B5qV$Ik#CMSxkN8lm z!-d+Tevnx^wa;yAVNKA!cD{wxF}i7dxqPK)s|InUmJTt)SBFThtv32d9LI&YNw@({ z*VX~L`>CH6h@CiL;2eD?Mq|8jv`WNaHFgf|xkh}Qc+XLft`W02VbSY)Lw{zO8ogGW zMu^|*bmb@FE0whIMQlwxV;!CLt~xYny{HIl^K{a$Ev1LoiwO~VEcQU4xh(cPTUU95 z#h&eTm3b(Op7p17Hi&10K`x{wOX-6R;!yO-12>ATIZtFMKt~=Jpd+6SP(R-!{#65N zV4x0V4$`6Q!RohL#1y0O)NEa_M(F5ZmIbIIx5^|4K}PlXUG&KY9)U>FP{f zv@&3(A|FPV6p9V-y#^f|Gy4F?x?Md6 zj$PUHXavC+J!ZdngS42g`W+B+uxk05I_z7q8^>}fjf;-v$iaeu#>KTDpw|6P#DV38 z*C1T){o+{qRu`cTb)MtRIN4Ghj)Qe{0(O^}c9)oTcQU5_@Pp{fk>>gI?2qC&<9AHo zf_-9LbwsiF3|dqrzAk{>C4e0(5-L_C+8|YX8~eS*6{hE2si3XjrhC}`cKBcSZ943z z7)zdiRX6^SS9RmZzM}3qDq^jm;Z)i-M-HIQ6JlL+=2TbQv@JH(U3OB8A<0u|>`C!8 zBqQG8dQdxfQpC%TcK0=nIVGyH^BLdl@`L!Y^xU}4<#fbEsjm9)l!*Q8ho-$Eak=ysXt zBmKl-g;(ER)ORMGAV@Uf7DUtnQHmtS(a*EU!lpLrS|m1-evTH`lCF_Yo};^crC3t< z92IuR5p?+pIZbU@TPonl_2<-6e$qHXdOt_A{iRg0Vho+-FD;hdcn?^IqeCjw{P@Eh5Cjo0At zrqOglxHLxSr(q4hAO5U*He7nZnLc`^f=+owJsT+<#VpY%sO`+cZ0&lM?B^22ve#`rRXxXQBJtx!9eEa;+D3C$hF1+D^UQKv z^o0!RIRsb#Y?{;$i`KSdB2UW?0yVgm6w9&mnOaM8h_`+1T=w$i&*Bi894W=9UD`=u z903_^q&h!STJFA3J7!5Ue2l*ih78ChQ`En@NX^rhnho|jgr>Wk{(i{Fnh6VQWl|ax?SF({5For!1p! zJ*7irA(s~5POe~qhtC?6G-Ey)f0WCyByg%SS{`kwau*upkKlkJ6bYSh@&O*1T$^?loWG2%%mM0&L6TrLD*aq)?;ItK=2*UZV-j2GbdMh+7Uljc`nm zFg>)f7j65Jbl2RaR|O42Bc>ysm-|usBuOHpdefDYq(o@|II+<|BtU3pQ`t%rCQH}d zzC>G2k@_<=HC`88Vj_oX3~}?3Lwz|@>Z+DakqQX=F8tzGq^1Fmo}h>}eJvvM3pR*i zJ0*YXNl(2Z91Gp@<&hDYlEiHKs z4MsDW+tYt}P5R0^xkm-{rg=@!;*&EF{K^*b=4Gv<5PE5vaGI1%PJqXB(2ndu z$4p1u7G1QDcZa6EgW2r<45=SE+nr9BA?@_!(tW1X7oDQ6I2M34#qm0arnnP|t5CcR zSA{f7`rtp|HAC&RNeeX(L*+Z;;bE|smp#4^`oC=M8BWyHwEKLp&1=7}IH9 zXjWeLuIfoOy2s5*ES?q3;OV`$r5>h(KwdsXpOgG0Uz)*jnRJyR)u*q%Bc);fEli+` zta32@;T@?L`u!+DIWLA+rfM3=(SlCWA?P!GSZ>QS-RX=Srcdj1W9*u_84g=EK=Y<5>)g>?{P+9!sQlWL9VOoh8yZ&h!+XH6BbKEtRgB>fwLcAobQV z7TZjnspUPX1Mv=~eczKN34Aa!nj;?9KfNct$CBD$n!8+@C^^j4o?TwpRy*qL^3$u=+XuXBi zzazIzE!L_W`ES%xnxNd$$CqCIPT%&r^A^Z>hV)*0W5mvG*rxwH+fw_55hIn61}70__T zf76OiUM-E+x!h?-FRw-&Udg5bYfx|LGJR?du7Aj;^VYaU0noSXrX!o)bpfS)jO!)Y zbj-(Y(E#+x$4uUAdh}z60!oIpxE_^F6W8LplT3%R>u%X}0lV(6UHen#T4Y1bv+1R^ zQi87J(gqCDpEh16)vX-{pTV?T0yi`B-4dV7@}Ftx$4C=LyRhd2hM2PH%5@<5noNIM z2Nt(G(Fg0K0c2qZYW+lNmLdD;)yezm)fwieS7Q@DS2fCdHD>uKx4g022m2C|P_4I9 z>d?KPAdxY5q535&+vo)2e(6WO=K*Ja%8F7Ec*Vg5MzSsFwdcBCsd zNjao$M|x=!x^JN)wQQE~!Iv!BelxQB)b{k&W;}l?i)L(r6n!%*Xk0&P*(zE6wsdeg zBmy~e#t%EtNn54%4b=T>CQ>6vQurxM}n4ut5$h%dFm#H9v&{kA=tbHNBPi1v0! zjmi0Tbe2PE@5eOMz(9+ghnfW~9nvu?bU;JFYfdt=tUVVE1`WiXzrmvGh6a;}>*C-5 zW?B2~K>5K-?*OBHSu|iL7?oyG>rOCQnx*dFDYfE4e)UrX_(Bd=5jD;D z+PY>7Ytu~!5L1(Pp+jBOh92D|rPOuC%k>y|S%J*on>~)NDUr1f)h%cnve|^0D zU!QcPWxM|k@x?Et|3b8V^>2uezxq!^-#!0^xMWuqp|wiq>uxX#r_P2<)1MN)GE8I!K=`3{MP@kmSf zV&yP~CjWpe+!+swY(0j4^@G$5!vdYAHg*F|Z4w4F*(40x7TQMb@}rb&AZi-R?w?}f zFl6;lr(`tvnA>3&Gl%^Am~>>ecCo6h!dIL#^9HXpcHW8?0K5v?D!)UL5jZNg^4^HH z%2HpiCG0vAdA8S-4&@wRqi}x|rU}~bi&ee=j&=|D?4;rne205;I_|mYMjDiZxW@bW z`2IA`7C$Zp>k^G@OJ6)LH3)KZU&$x|i)CfGsVp z(oS-#g}U;jw3=gtaB{S!S_?YkS1GNfBfd05F~HoD@^j`%cF5C4XNgYY6kdjVb@9G^`eT#y!% zF4^ik7p1eD;OwM7DDI?Ay(~55Oq)`$@ZCw>dIh11EKE_iU6ru3-Z_OHz9!8h4N|D} zx-^TFCaXtL8ibRGdhBrL;~nVW+fo?)woH=g+}qM~7__#orx@WEbM5sMZtH>|3(J6${GZU&H9JKczgfY&^ULyDsRWzobAq>aOHRZY0yGccpm&(RkX7J^jssz23v_ zvy+CtNv3}Hq*2~RJQL`uZF~gzJDIMyCnd;b(1MKugYXO09?2J7w`AO^twWzmrs4Oc zaOnf|5{&2yl+>3OA9!qbM5X980@J}`|a199zn->NtHZQDVUiceQN%*=^Za~5stA5_{ z?;L5FKutdKS>lyIFZswvji1Crnu%}MZlIQ$pIV;6Ek)S3DGQ{~Sj`~T!`Z|t@ z)0QU7@)GiFoSxmEmgTx6skJ_}V7ADOIrDl@VH+7~W^FdLQ%hbFn}A4=v!!EsBb2%6 z*_D$w>kSe2uVeD&8f?812ip6}{W0y)qoJObVLk(`(8=aA&~rF3pP^!N(+-Z*jiaf4 z@@lDX9BUOr?}s&n9#~QeQ6KrqjW`xfVIFPz8s^cauc2Di^!35Ia!Zah&Y+L{<#v_O zx-qplsX@E9&#w=V*ApDqXbqIN8aE*>u{~TdG%iT~2)XN_Ah{(u9#2WI+}8L-EHh}K z;7`L&%1P?{V0npw>~Em?eay}Vy5HMk*r29rtuYSs(B|=-%i~efiD7amd8Yw=Crr*D zn;O!?VREW*JTPg&S8`-a2@H&IFVFTj?0z<**@4m2PdP9r*^V-L@t_OiJL!;cIf&RA z(y8HcDrpai!sTe86m(g*iHM=6!sRf@k%K@8-5t4KhpUDNxf4eg)yGGlto=9 z6XGkT_uKIB{mk;m9lZ6%Zy0ocd42kOq}(D-i;NOH$;1ggg#cuQih|83IegU^@e| zookCEU>RqPmANIO9gj=&jzM&COSyG5L4Iy2AM!bbM$F*Xq|5ySri0iO1UD9JOAY3Y z?B(yNVX7rVULla5Lg>bh@+|Uch?>wzo=uqRK~k+9!_ysXg715jl@ok*yU6{FN)y!n zK2-`@c3d3jYxcGsHJ}+i)1`g65v6*gi`<(d*}*E-Mev@?x*&XeRX!?dFs(ajF!X~S z@}EMBVBP;t-loO>6Nd?@3m?;oT$<)B{jL8CV#S<*{>j|8R#dfEkgI$bsLJhBb9 zN$T{4Nwf!=!KU)e!hg9oD?6UI5h$ z>=IV3KSKV{On$}p`Y?SY{OAXZpn_;^`rvtan(@`zteri_N2>3Ql@A(7zZiAccsZ3L z{e0=N3385@{41**irJHQL+nil*nL$O>6&p_5*gdy>(K^ASXZK^ z*?9hwL~~}#r~JICJ!k9iheS2iCO;zNRg0QBM@B~SrBFfb;p&9BGCtzzEzs=wGL9>F zQ+ASryow9L#mwQEM|mH4_%6#J>fnqFyf4SutQ+82@pnR$YuGG8BO~M>b?#fT69+{B zo@NGNhrz_R(an(e%<8;_at?<>0_o9rz9%O6WVE$b-paj$Zo&K68On2dtNiIWm!> zu^Z8EjN<69jd0eU9NoH6en4t*>c&l|SW@gow{Di(5`5k0)@FIE(cu-^k=9xxN2@cp z$ep>+7%yFv`>btN54AY)kCtqe3(S8#en=1FslGR0)u-|tf^*5(hAZ(;ATxRQJbtJS zcgRQZtxo_q+a`}U^ueDs+vMej1Uzf^xjdFLoWre8hl@?bWB9|+K790${vQycvVLs}@>^AX*;Q;x?LXWg*&oQ0ZU@qT0jRtNT?891b6r`&`Ky;JcJEk6fI zFLCvI!|or#y$@N)*w+^e#shcBHsK@OVmlNj*Vbd|{arHKin^tPwx_`G6=Y$;2@d>W z!cD876TXlqB+X}i2!wbGWxR}a9F%PI@ixlbH*oq7%KQd#$~=@sBjVY1-2gRexBMuDm+~(`1$g?h_O#m02ln*FS8^`{-a(-&pA$n2 zpF@64z)$dp3HZ`Ob@A8oGL9rYqzQZF;)W;xeuyfp+QRH1`O*ZpG#_q2NpkD3#7xvbW5we>2ojlbTn1?_VH6%uvi*jyE z6Xgw*YaNZ~mp{rwBRn2&EoX~Kv)i@GGLX~l9IPPl&$u7j0_A4GN5Pv~@vKi~!} z$QB~0?*}|yyl~3DkoE_CGxxJb^!gFG33>k>4LK^uk{u6d z`=j!H;(S0&$IxbfxJw5dljo6b57e{Ap&g z`rZ!~MA;S<7DU|}ai{zu4@dk9#y34l2e%!$eI}WGP$9|Yc8qrPkqvKweg#U}Y z+U~r3P0RW<{>bAs{)qk>e|H|gUUB8z?g*ikB=jWF?930vOjHdNuGy^ z@(sXo&I!NK2C!E zpzF$5+^U59DqV++$md*j^=DSdg~$mgs6Uh%CB?e^c}kFFZoX0Dk(zSD4m$Rug22%@5--{ z8Fy&FJvm!?bW>-3l!IOIhLJy=c~8EjBWen+Z=;Ldr7fL(U+ymzFa)%PDGY%fg|Mt# z?m|AfNps4PUF!TsF1E zME+O&5*@!(G}^2U?x?H(mK$&pRcuOJY%)2G4Oh!%{ke=L#`#7IIbc(O(MNh2ee}>0 zPLnI-I!{+&M)Dp4me#gecQ895IR2wRZuk){PJT$&0KYd0YdXM5O{6O;!fP@A2*@X9$~*dKF_m) zm3JL<_aix_nyCsr8Ab)!tli3}@K|oqq{=E@f`?V|LTuJlCKUz;5s_Z$ny0+*Snd~c z40^&&xp_FLw_pw&!<<>prht0grl%guQM}zt>QIi_{bH%n(!ZhGD>6OF7e?BwWoVF$ zyjNsq`ch}D$fX4q?=UyK%@aNgXF;F2y>!2&ez1*G&fR!O-9G1q>^VBdcJ!OTrH?Fu zv)%Y5ZhXDcvSMu3LhxIimRYW0mazL|Y2fxvVKGX4J$#LJ-j zJC43yP(zUD2DYO!Ajs_hY@d}H>4dUC=+zp8MuE^crcoob)kgo)EZlTP=ydWxXAI~d zF3>f^5?xu7ZaAAu@K~F*|807nSn8+LtgHeTDS&ihc5+wNK6amMoS8~f4VH#aQ1&uv zCdtCSwWQm0n!!>(rY7Y~9b_axBAAdE-!-Lq221D@bycE6<^i%6gKU*qKDPx-QQxb4 zHIB2>D&8f}Q;4LjC1lnNft4zIYl0Pm)>wN>op**M(orWS96$p|Bnt+3R)+b5TG^57ecgyvoS&b@KR`*(GvVbZFuRmkri*V z9%MqeYs1T=)yBgXG{f6c|B2cd!5$;-1MSmWbegv%?FkSs9}Ofb!Dd}?ixzuZT0H?` z(?Rk8GWQmZHCZBzs3eHv#w5Ko3$?tF;Yhx3AC(Rw5gA!;S+vf)2m<=K$2M%pi|SRyQ0^%Ac*+?5WPx4C!EoN zN*bMN{?rSRF#G={0!1~!s~6RYxmrbs7Bt*!Y1rV2Ca9}h3ben_aG3A?RY7lgTk1Ut zs<%Nd(Pq8q0==(;G7F7BQbW+hSZQ!I*C>DdlqGa4x~Z&}+Dxt9HL8 zEt}q4M}pRVM$5n{gHm+|IsNc4U46hyY2`*_9(O*`cJ!7%JZp_El-m;trk=0hK7;kL znUy*qRx$k$tyNSjilpD5>w+!yBML;#Yu#Dd!K<#U%u7-V@IeecE1M0G*%iy@SXTBM zu7#^~Wl^nqv`L7iZdie&wENsC=3DB zO(nCQ2bERWW7Oj&HPy59sst(U1S$2gS)1OZlj>DtTdL4D*mB3cJGB z-=HhPsxfkdxESRDWKj)91)fwmB#EQ@=2H31{sR0qy7>)1*8Hs!^9I1SSrD6O&S&49an!DEB;5LiqJEZ^@Zcx8SOQ)zZ zt|pL6vaDd6_0Dw+Uo%53@s-X|;>oxWIpn$PbWfzEL8CIS0+7Gra&k9SH-d|GRy~{b z`|J2_vIlE7klQE#+V%wN5fPqd3A0%XuG8J11lG1%%JQ15-3V^2fiU+vO^Ehj?FMpd z9d5JcKEZmQC+orpn|082dLmlWI@4DfT$8mM!L2oN;ZE0SY<&;bZXmbT0BZaM>&Qq? zt&t^%T&G9tYplI$EA?u!b|bi0vrnv;uG8okOQ-Ovx^@G(ShH{S+@ysemOyHcu=rQj zw#}1y9hVu2I`=1Q&CbF{;<-um&D_yMbKHO98a<8XV0TZ)w!5 zO2!gT<}9&$8(?hM7aZrciz!42dRl=W~vtQO)bD){w|6#zUggG_=Hjk?4AYWk98} zBRuhK@s^ zL&B`K2%~7DtTtxHR@Fx4CAy$-HQn84F7B&<_VX3GHPI4Hr6!iFN<|7>mfmDmd&~b5=3HAwVG>dwRWIM^;+}9i|S~z+FX)bs!9ISMcOm5n&dVY zn%izbdq$J|nM$F(8tM|cK(g?iqz*NN#!8@vt93@!@h?KZnN&^a5>GrX2ZK77&>uFa zGWW2H)GyhR6<$@9ZbY{sf%rQu`NwTF~HRus>9vVb-w^@(UusBOxrPWJZ z5MFv)S=9s65eSd}Wc6+-mVVWoDl^_g^-_G{>7&c|$_HXamAGyow+ZnPuX&mPl}0Y` zBvaVOW_|fG9n%zXsfvtOf(I|IpUpb>GCkVVgO?k~Z5jY&dGfM(k}2(v(aU8ztr_A{ z6|WLcps0a1Yh74`wS?6%RaNuM1^TF&XVth6UHtQac#kejur#hT_J~HFY7E9O;?h3{ zrZ1aY238YlpC@M45R3$X$%N`%O{m%zXm$$^q1=crp;iHLZ4IFsdk7UZ%w~P}UxYHG zdU!yIC+5fzHtS25=+sn?T5$up1Ska1Kw8*H?=7^59@)f0fUHqAYv)TeJk7%cMtB0{ zJ&UXZu_(=hmmA2%s}w+WJbCT&Br|dhhSZm6)0Q5*yb?VGTJ^lmdif$<*%HZ%6Ne8d zSI%qsgTobHokT})7+m>7)L5JK*hPA)Wo4MI0&zPBKz7qR$w*xan(C=$W_%;+4cytmG5*BBI|# zx;3L3A2*0wVu0j$@+t5n!o7ry{~{gGsv4gXPmrw1=$$Uo{jI9;af7({tOAI)C!fq@ zPhnrSS^vC1$F;7;$L0w#@)eu)*9-JSYkdf#sq6-E@hJqzz6xzp`vdJ=haCho%vsqhS&;vwKR8`b^vlQQ~t?UJ>xVViEw0ak4 zaXU-1Nx#LiC~gFIDi4G|e$z$Ct0qeOQu=x(GT^Fa zMCkU4ZFAzT*8ce1JmLzVUnu}bEkwB zWqAnWMs&Li5a0NX4r^YSXF5rVr!ZM>+N_g7yGEYL^rLgyBXU;Lw3&xZ^WL&q`}{`l zwnsF3638V%DS%qiKIsS<`&w9PSJux6Pg*12wpkngMpt$~NUNe%;0d&9q0K7&Mum_0xvz|Xsw{`U3HNq39P_bFRJx{|sdGK-rxp+k_wpq7& z^4jM~X4Sh`qc~5CI(hK&YT+SJDb5jm{XA`&?ZL|pdJ46m|#^1{KZ)x%*SMJIKh zp33&%Rp1H4t*}|!oTu5HJ$Si+T)ajCD8`eQSE>iE()ZCxou{`td+^Hi1d3W|v)(VI zgS%KdRjX7tkc(FyfX<$0~3Lq-J< z+=}K09iB4p$=wYmX8x!sjxIfxs_-KzlS@j2SI zx1~MZmuc~Kjfbn?+%@}^&3cI*>58b?JEtgF8q4`aZ$Y1?S=zRb;cK)Zp0GgX5}iF)wtE?(SQY zBiTc)3kt?=Y_ny_0jUJ&@d5`5Zwf48P)m){rM%=hADMkW!^;vz!t;+AP8O1}TpKMk; z7}V(G89c2uz|w=-J66`YlVob^FO{)1>Zr~7;#oRtfF;`#PG9h;gd6!Y;@(+$=?S=f zp7d6oz$D&T+Vd$FJ=Z`JqYche=wEEssDBaq`==~fv$a;28KC(852o|7S(}-#x)g{d zMvO1rTTd8F<%nlQ4F&~y)(2>@44!*{VPM%~?f(jt5t$J$Wnv-vAMpzU*wnty#;8?! z)@x_z;(?Zg=$e3;Y&p$KpPwiN+{rWa>_DvVx*HZ`(Lgc-wPk`Re9-3GGc&g#=ttvDO6v#T3_{UKN+CR#AS> zJ2NMHi{C%`NpteN&%E=_JNr9xE>0N*WmqEkNYGdQ5nq3C-KFAvH0a|W@xvGAD3z#8 zFbK%4AMt`2X8*eK;C(FU`)5WTmdwbJ2Tw;)&=KJMlm~>i>^sDF&oFz`MP2%M&^IZA zy7eVFs4Yny1AYWiV|RPoAwJ`hdd%}g&{zBs-*QQ=yel?9@;~B7E;0Mc-2>FwEQbqL z;GIk#;q4u!I|se1E-6{|WlyhxksvIWPy4av1OSpzqB?ylH99SBCxgC+5AnN7>q}05D(JiO5dQ*9mmE!wQqt>O44{?NrlMVRqh0m= zBHP7f_(W8fXcvWZXF9d3vrt!mI_SIl5Wjk6ed@*ly5talac1s}E2d|HzA1@a4P)>Bo06#jCiT>2l?U4%4l*0;)DE^+)SQAsS`kx4)TVx>vR87yw`1HiV43_CT#QD2~3DRW?@3e zmmK8lkx1S3zI0d6*A9g_J7>l{F3AK?ql3I)PQ6Ugpzr4ceD0i_Oi{%I&}RpD`J6=O zQKov@DtnMpiucLAbAbOcC((c=A%3^i2awnSKJNm^HR1@2daKJx%KuFR1TwqhxvQb7Lt zke_m8-3hs03;MqKkgv_fVks6t4t>b?)yMLB(D&MhyyI0lbiwYa&;^iZKjhP|sz;Z- zLEpbWfA&V&9|(02wbv7l~943Hro@>zfcWS5wgP;eiLpL9aA z{6j68D7&6xkjkKQYL*CRv0T2KVC=@o{%(+D4MmJUv1S@$AoKuRKIo zC-624%?^gY2k*ZSF~febUt4BGMgN|t={iEle%jCHFEpnVWJ1C+%^)Bjg17&*WDEMO^sQ;ULYHQX1zkX0zaJ3n1g7rkOP#4mtf z7w>U{*)vCK(Oxp|r(tpOJwE>ibEt9oyZpf$%p&8WcX3?S9N4u&ca;ESlz&_;!zt;^ zN%%R>4oxd6Xss0&?0JV5tT5>Wq^G2E^$N4G-YcnRG(GP@?1LAPo^%WV7UZs5%&EME zWjd)?gtZWbjL(F%+*2%{_8uQ;nVkx=ATsk_Kz@7|AwvsqG0)`-kD9pD*D@dIX2U({ zj1iyZdlYag#Uk#t%r*()1X2|OkekwpT`SE85~^D1#QHR>>%Gelu1rxi0g;SuKqjO! zF1*paKEW7IXRN_ac8hm;!<)>Kf?xJQ<;_?-*eur$+^Ce|I0nwuOsV3NZ!*s}-r2_= zyvZDF_)GYqn^2bcY<;u*oOrWYK;P%xY~GSc&Xt#DYuagEU0rG3VmkCmw)On!m>O*D zj)N!IQPQeyNS3&bM^FGY!uo8))>QKux0P9sjky-Mmfy zw^{xdFX6pciDz2x%F0z{8v{pMq&8KCWG{2LdJA^%JghHP@vqmIFXRAO5~O3J_JOL( zSMD%BHG0K+ht3=6-Hn0w5A z#^%>6=ig&4ZP3q!R!)OqpY5-0r2kcEVVfi`MBnWV{NNhPcjlWsf3vyw{4`u#;p}k+ z_HIn%-ga+$sVt|AvbGm8`kR$Q!)B4gSo0d6zSZ1o{NuIC;(wWihAN^8!%oQRBittz z!6NWpKJ!8IcyEMD+}Afl{{&n{%6hjVI$|%K;e61%owt3+98edrj(wV6Ugt9(GH3Tj z6oXe1S1H4kDLtxe!+8IV0HW7Hd~CbfzOwnlCTqy5G{hT(TkEyq*52B?U*;uGz~tRt z;?tin_q3p&7=B{j+6(Ygg}KuVor*7BftAN;q13~9gh?oB%P1?;?#6*v_yaHEOL&P-c-|~Au8;A>&tt@2L0nXFD*XzFtG`SiYyLGa@n;CUJ6d_)mt-+)56pfEnE{?M6S);(MHhN%Cr2x{zi6&@^bYqAeTJ|# zD3Z;g>V5Df#7ONyDGYc9#rwl<)6)yV4cks2Ma%!g_wea^%w^;aBBy>~=|mq!>-DYn z@E`Y>mnI<5bV%$i^kKXC)h{84z-Ga@8&cP9aw1qFKe(G$zhpjH{bNK zIW_^Y(jh^tZI|ulzrTz#ICetObVvlt+DmtH-z%xQG)mK@^q}RNxtni)#k|XS^F==4 zRdg;_#`xS<%~8dkfuRArP!a**RwL*Hh95@i;8FDP zfxzj&v6?2%j}k}1t!!CskdO^R_BhfZ{AJ%C=SLtb@L~Gh zC_f{bJQXq`Cs9-qML_f|h_--8;sy%>qjIHhFOR%!wjY$Kz8WW%)}W*yX*I`w&TyO; zkql+Je=z^@HM3g){|QgQPKL;MnIlTvI7D>>XRnm<>%UDXU#25MfRt~MqC9lU=E43y z@kGG09Xy25JVQeLzQKro0R|6f`wO*zJcXN+02}Q@;QkbwHlzpy2G}Kl|5HjJJMpNL z^+I-olKt(wluY=CicEYo67E56LE9HOm9Pki$s~w^AWGQJHH?qjo6~;&VM0Rx%<^4D zNu%F-XC5|NW+QkTeVItbMHr*}=@X_dxxC<-PF#?G4R#NYbA-;Gt!;dG3IAfR*;bA> zK%6W@ZMaY(__^gfBgQ+vfz~hENG=JA0W>_ur@vu#8J-RDOHd6!y+{SLX4hSZ?5y_G zKDI=(Vr3fMsr1AfX8RmT_(upmB41d(wlV%iZapjsiUHIh#*5!Hd-ciI!!uGam41o& z7)+2Ti1`ik(E{Rb>q6QKlrAla{`F=mj^ZvxswCdcSTaJLU(B*qh0@R84ZHQmr4`X`0;(_fE@myG8%)#s3@QO zw%H}C;3^z0Iv}l=d%wmQhiK7x!nrGSkIwnqrfX<+!P&E7NOVX_l<63pP{A1(=l;kC zR+;TpN0Y25N-_q?hEZNrh5eY!22nxuZ*Y1L6*j4k!LO+@i$=Z<0LZ?nR@S=sjF?GSet;`(nLK7xW+; zrak|~f&=M|HdC0f z-o+2TV-{vWDjZQt3N-0h#cwQ$`g2R~MU8&@YFXB;F1D(8nl|3%%F7F1=MWdvzufl|o(! zgPd;Mq?7d7a#0DHDXu%`fuFpPKoB zoQmVZ4DyQza7!qo6X6ee+JEZgjY@nB_<6vq4!S}|(NGdoD&s5Ew%O<2|*X zV_uhNAvAJLnfQbgB`yvFqp<~7?-%*n{kX^?v%vh#g?^=g6i{-bJhi7b)i#QuFlP5x z)NLe{KPexCyh-xoJhdZFPEpsBRJSA4EvaWfh8nDnv4HH47x?54bLi`lbL1Ex-+^yS zO3fv+v^WEe#S%@{X4K*^Rw_<9Q68d_Q~w`kok>oNh8uXkhg(bce_!UYI znkLtYk4t>;S1aJVngqz*>l1Lb6beOOnAvH(206h%J|qx*TH?xXly3A4|hh545K%p;%8#It{)L*GizP0{qW zqDoR`SgrW7Lo^R<7249(5!#9&e%z5)ej%n_5e)kYLnl)fJ(p}uau#2h5<>CSTE2YB z3=*1n8LrJ~EE|-ZGOpG_rW7)PCQ4}FoJ0*xrie?|19meO(fL{tkAn*bNXr}QX64?enB4N}XQDP4C5%fI|UH80?%|Qlg z)#i`us#U57F8#yug~%!(9Ns6z!pN1~WIu4iBBu5qGjwpRP+XtF8miAYBX_Z=Mmz$c zMI_V}qf!V7b7*aaNgI!ZNyll@*IaG+eTU70eEdd=t-3tLnep4(hs~j_JZ(b`v}?04 zo$U%s%(mL{cAuED3{P7g_{5x4l+(PH8e1GkNbvLgyHDh@HS|cfi}pwYkcKGr&&^J1 zWSNB6g9t!=dyWPKom97#0+D@t5Rk87QtI1>a%zd_$nqLMUU-h5USk$Df+fndcs^fHV|G+y z941>`39w@#yJ~O-U zvyYg4gc`cP9Tj9R{^$|2Lsk)}f{ZwVzVn}}w;*GHocUb61z7{gsQL?1&kOqc<|xSP zcKp49bVI&Nj)I(%Azx=fdO^@a7G##Qse&v8L_->3%vtwS7*TyKWw@QJ$B_96&P2BX zt#Y6WqG}%QrK+Y&R?Wxpom#uC;HA+!zyC9{eSM{PW_kgh`gz?2s5c7wDt6XefNnsx z?yR=}y@1@gv)-Cm3dpU6krWxChg=6zqD&_xIORxWv<#Q<4Q}LAO-?yh}sM60${To z$|JE6V5y~{dy@#StB&Gg9S(und$`cMgPbgvjvBRM_Uc7b1V&K43O%*AAs~WczbSOj z<{U&#+Jza0%xcm6QmG)ww4Hq9S7t#wL4bf+`fM1NpN+JRe8E@d1h1S)B#rEn!KHe0 zMCqZ{(XQG?7nHfw5jy7xmLqO-gr?#XidSi#9-)(V@ZY~O#|_jP3wlFivgh^4*$m2}Nwx->8agOwq&3$2VDoS@IpU--3{mNs_^`?_@T;HY=6B|jDK^9&jVQ{}wiqQ7 zCH#d3v00QhKB|lW{B+<`A{GXGZ$6Nqx6(BZw#Qld`si)EqK^RI*ru;UKtyw+)qPJL z;|;L;OgW`Hs`yiU?T=>h@U)yqRl0GhX2gYso=Rj3#Y>xNuRJ6FFU0Fmxbq|2qW}D{ z7LAM2D72Po6 zqcHgQKbc(yr;%flLEjx}0im=Q@5F}&QHThqrBPEeDeRyk#b!{Q#H=crX`1*dN0fOFOo%9Wv4;1r}VO_-#d(Z%EqNX zpNZ%D@SLz(yjkdpIBF^GN3*~0rSEi!Y}bUh&PuNVwgPJSO855NL}ia=ET?9H!?+c?GZe)oh(RuTd!)gXkUOE;wt$mF)SEUM_%O;hZ{ntlMt%%Q%{r8RUYE>yHURU#CeE-Vh~Xv``aiF zsja@ES$d*8XmaVJ23&>2h1T{CsIyh7(;TaZrt;1f{LrsvhkC7A+Q;%WQ5vnNL!+sG zQ=*Q<{1EQ0p|hl7qfa{+ zA_zzo5u*g?IYk|k|1hhapn=KYudmo;meYMH__tD$*13zaejANP$=R{g?{sLTv{> z>36ebNv57*=^yU?h+s+2Bwz5mS#V(;_)_3SseP&mqf@6x#@&J|3^#s^wgh(|+Dg;& z-FUth&*_;KH$yw1C_n0MgExHM$eJ0SJju;J%&r|>a-oGOckm;t%ZQgus?KR_94sa>?Y1N-lRJ#1xX{hk16if~t{AwGdU-voJ(6 z(H#r~ANso;Pi{ZPFT$0Zl%}4^<&uje?#7nG_w7@3MPo-EK88&l8|YUV@JJwCXn5!; zzVDb>+|(-+#+u_(bYXQ@%6r#85e{pM;#@^)-rc6q5 zqN|QzU}NC+?%QDCEg0-cTpPasPxFgOw!Et#P2P*~(*-1t611E6^lU3UE`y-ybt&*? zJ%u}^%_%M7Z9-e%P9%C-1)p`?oM6m)l7D^NEadMTH`^H(h%eXUazQ(Be|qAj`B*bX zt-0$q)=e&7*uZc)FxC#c%1_?8m-XtEB#WnG+#N9S2bmbO;GihC_P1<**Xyh~_xx!# z7-}=S3e)mWR~J4*QdF5cOB=ZD#WobrGM$}VcpH3$0IdOtJ6e|?g@OHswwmViZmlif zuQPYybs3;|2B@6@(3}iVRR(ApfiB1ZMKeGgAmfbx@SO(hXSA>2UmNVafl0eq={a;4 zAP^HdjKD)^=t~|__ynq8*>cuxa9Ua8m`JK`1q*S^Raw;bt%0Z-Qzo=-#}7MLm;T8_ zHCLKw4MvcSGep~O=OuaU^1x9I)9n92gFlz;7NOyPE_?RjKOI`=C%hUhyh|HFI%uA@ zq5lH&BpU3@+o{uZ#(@-}vn7{*ycpqCL&q>ic3L+xd(JtmMLDB$GNdv>nctiA$LnWFkmQWD;uwuOZXXJd zQvb*C|1kBx)q#K7fOVUdw6)Es=67_n;mu0>N1%OVEMj0zq>VZuSp(U{N;WdeQ`?OH z(17J%SZ7)^oSmicYgAg>|7KcV$WGhN4>x4)x)TTjG+rfel}cd4-%KC^+2Pyy^hT&d z**S>I*>DX&J-73F8?oZR{J%+Dih+1*rPNtainjiw6VfS2qx_;1@kHfm$r|wJ#Djr* z{-4J?i$$n5@NnS(T9?oa)cl`NM-!I_-&i60S&a@Tp|@83togX=XZ>#3&%O=~(9eqZ zLD2odeL-~YW3r!Z%OCrradY0H3G0+M9D@ApCg^)TP1x9GRXDK{qL%H$$M~uytYf42 z$=Et}9{748X?>>~W9_2h-7_|NLe117sikZaNAypXXj#^6W!7{(S6 zuvg`ijQyoIvigSf#(FJ}?s0bJ@pY{l@B=N`IOF@rDhpb%Jq{z@mw(!pO*cIKD#zwC zPlG8HN~a3LFLbJKg!>7dVxw?Z5wc9$XZrK4)>F3gMM*QfI7Nbt~uP zsSr;(#EoHF%X0op4>qjSX0g&C5nMif47Sf0nI#oW;0Mc8fj>%kWWTVdvExa6lI+-R zd~HwmF&(uS$QSft!x1PZlf*WtNV3e~k`y&q@p|B4{z@;D`?de(`6VnANP?pZta2H| z;O*jU{c_+Xc?9^WgvU4}Wu%#n_pAH>f7-*mxHr2vMPpkDRfa(f42vJ;TY9reDWG_| zrZpHDHhY+xeHgtg#m>8HEEQUrU1*U`xL)!hKBEu2BL##jO;SNMT@WSqP-WA;tcyOr zOv43V>;5hLw@ix<4*fu570mfX38>XTl1?OvKtaLgI!Tlm4U(>Th|llGIs~#o9tqOj zxQzxiOwBei+otD6`MKza!pF4{;p3hWH16=qx}MDwmpoqZoC6+GZa4ya?IYJx!8yX| z%M4pXZHUmY6hfyfA)0ud3_;cTB@|ivVA{YZTLHi13W94ea@(JEn4JxB$;jUbK;0?9 zty-vBc8oCd&`{|AXj*!WOzVgEcl}u>)m$X=rVLvONP|?vYQy;80jzj{?I5--JZfhW z_#e<(Wfnx7w;asctF|DSiZXi*q(0fkUmU>NU6Dzwwmj+D?P?Hc?hgl-H zCf}pTNz0yg=`cx}(x4 zqBI(7A{>zP%W55PGZ)#=4VeMkaGNgc5x}ikWd47i$YOCR8iZ&EBuB$VnS_+T>_qY^ zQaJ+oCZsNE;WJo`YAWoiogA9;ATK$Im7ID9h%#SC=4y;>B=tHn;45^$3~#o_tnIhj zJ-rqpta$N7;9W4;k~DA~25+6Qh1h8n{F0gr>XmLIC)4zm^f8$bPCwlfB zo?Q<`_2r%oLQrdgbto}EtI%9V=!;AlJgdR8D^q1$DKZFJJ|JXpA|sIy9=?Z%mn4Ni zt|b$S8lg8c6T-7s@ywT$DbqYD32Bbdu1py`+lgnVkxanOkv~Pq;|Oif6vDH|@N9T$ zLRN~56THDr5K|JNvRIOX2xSIG7@g z4Y(09hk2n1^7o|wMDs$Y;aL^_66TIdb1ycujY5I2j!atB0TjvMQ3xu{$4plIV9^g+ zt@@vj8qT@|E{nh$QENs0Tt2?`vShtU)Hjc+Cb~bPzNtX47)EhlAT*_uq?T zIIDPux~mcv^;kzej-HJ5A6E-mH{l2+)ErWmvGugtKoQ~L*Le7v4e~b(eUSj!i8Tz>;Mrd` z2GMFCXJYW|LplxF{SYlIh!WclO7caQv?tf0wiP-f6G>WCmqy-ZOTtNPKmj!V9< z9$I2^TRLAdk`;FWj_`(GG_7ThIE8Pc!@@$N|KEJ)NY*>xX%yOte2TSLsIvtHNB>h> zB-F5^8uyQ;=NK`oIYH?k$El)}Y509G{L{{Y7oI5or=(R&AA>of><55t1s0sFfpzf;p7vGV(!_V>8_9>Vu?BYfv5R@B<&>;Stc1^D-) zSeGf{2bUC}8c2QE&fUi)2(20qCPjb-9p(%&qLo!0{EV&U12@+3h=b`(w1L*wb`tPO|uIfuHsLa z*FxK-p7D7nv+jXZKmJK6@#)k#?H#JGol$PgSl-{oWCLN?cZXUz(>9cYSE1G1B#BC9^`928KRb-7Ky;BAjqLv8nxAE9$ z7v2y2Y5(HIV_A`LU4%~<%T70DMfm!$Y|2ngZe$*Dv@UrPP9rN@bGdmk%v1Z;J~`?P zqCytB9Pg{&c{>m5PHPg`XGR77UptPCEJ@>tr*i}+BG3pNB>(j${^K|} z@yn6Q{8L%6Zale(k2#HvZ1v$LIr$4CyI}+ccHY8QoyJZv)@|bZPGcV!9X9g^PiKSZ zoI}!MJ-ub7(EL%RA{SudM8kU|RDw!Q?w;HRQqIy4;pYz|1~FxtM-1z2YZpEfWu`K|(@&z>KEtE3NU&r5jgo=3CCdV(PjF_+MwR;-*7Tu;C@v zjwzdYzcZPy@qEaH$KryT_`|K*@(0djodakf;(4ejbgKwH?K3g4IhOApNKZu&DJ36A z@*dOyFDg@!fnaf%D~#6!)A}=2F#Gv+>N%}Z!&L`TKSsP-v_)tOHlj5gJm?M?7i6&W zwSy0zz}mFFbu)|wbkIh}TkuOJunw)4Xa3+f`D*;oeo^KR*u}pA{5<*>-bzh3C*@s< z%yQS$E!*-RCa`YQ5|ScDRAtn!4!JrhYdv?^o0MvF9hZbi1$%*W$PBX|VkD$kR1c^W(kx#_=k2;GDG>+fT z=br_){N;YW{w!8Jv%O*~?4vDmp*d+|e=pM)Q4`{{zrUm}a^ZV(`};=x4s9CS-<^=h z_dNT%r7a>)(!#vsBvhXtH*+6-ezuvf!l&Z{n6>wk{0{ueNvyNuHGJFkVJrEq=}vqT z-q;!Ujboko(an7BWH$1Y2khsmIY;c?7Sw{5;67>A)cQy_6Vm|1v*UFa=Y{zflUYHl zA<^LwYTu14I+cTHh!1DBI=vC~3v zfN<^|dY(2lg6}=0co&p#qq#?c+mITr$dfq+WMf&jJiBDdjIeArYr z#2B}U&!5UV25thYodP*530#_*0=9RXpy)Kz)>$y?0AL)LOh>lbtwn2*Yp-rq4HvbBf)zhNC}@o<%wt~ zs+ArZuTi-nJ|%)@*Fm{mI9@`(-vH&{FSYjJtSJ1O{@0wI9lxZQa+}I%uLlAtwhXrk zy^Vw^!9J9rY6kp?1Q9fkXBSa|6cdd9ucsW-|7b}`Igud#rv#0Z1XrsBTcl^HJxpo_R+#E1%CkhxH0X#c)v%^#Q;5p9Xts z{$SZHX*fT03zEzHoqUT7nrP<2wnNK<1n#?VxeL4ma#i*mr0@BHr;28}5$5>^-StG{ z67hf%b^<{9+CqunF^N%A-zrRfg_3ZU#LRd1c}l^s9{S(CXtl#tjoSp;;@(f8Hl7}Z zCB*-^vKVg{n(%kBsP$D{oXn#49=tJzdAL=AK5vr@DL4}e2MO+(MI^gK4Rr)_|HYy)5h2HV@FM;D`q z*4ifP^Ee{cZHe2ZL=~-=WlF3_NNh@xAioy+__HPE+Y*7bDH2!M5>~dvj1&t9R$wUS zbY0?~%cMmxi`ua?h3`B&mmcI25qEH)9d>>uNWOqrP7n_P0^yD{LQJ=3*@S-ad+npB z9#qD&P{WjW9@X%h@=o!;T_n_#r&SBT@|mbSo)LR=1OhDJGN5wN zNihX*McVGyIm&OyP()OS7ob%q7oJ=y(&zpWsVVEJa=^)&|Xo zOguxgw!G{DmZ#bji8x=W=S)>EoT487&oEq-YEP;R7dGwla4nZQ=0UF*kt0?a6$LX? zX({qby+GojQV(rQhY*dU(@Gg`^EocXmLz&83I)ag(KNRKmmYfho-~_OX~5+2ns)?W zfLc45t9B~)@4)Ypjanl2XvjosJAxYRxGeRAEP8aGfzk4MBrX(FoGAsFv=oImkfow1 z$YwM(+KD%bB5~0Q@&VIXUK7Eg>7fV@UCSc=0IR$!O-^}NQYng|Af+@JSLEJ>GZWA$H9a&c{LAUA;B>zj6jT|ujEcUB zK<0GFv_KU|l_Mi)s_CQEIZ6j^!zW(Ix{nk<7jhc#jDVse?C&VDdM)j`hnHW-o(uS) zFZc|9a~yltLg6W=?zj|<&N90ow4|+KcA-HB+l{p*G}*PPr`(M;qtK`gf9eb!gLmN^ zU2Wt>oHi$JOWGueP{XZVPpN&#=0+j+P7q;GPIrYNG)U$FKjuLZn#T%~ct_4IW^FrN z3~5^6vcU;}s}mm!z@<}d`V`f}cF%!l6nsRCy1!G1;$msR=tHP4ET?2NyPZzSYBZVs z%F2tGGp|#XW_1c}qnyL|(vdFr&B0`q1DY;2cRL=uc#ZZV+)Py z2kD?`oq7M6?4&@_k^IV$!kxv4v1UKs;{=0hs3C1>+uNas{-S&Cv7Sbu;vy%A6{Drv z2p!`>nEQbmd}6$1{}#qr>oHh`R8-@bjPy{A9WHsXdd-KpP>4zpLewc!D7YZ<7@QlP^M?a0;)7)QC0>Oyt;E(*eKK*6~>jk9%1cB7QAqx@U0 zqcktfE+0iw1Cqrc8KTUl!Cc}-{rVIT0h!qI_!!qu-pe=5!op~F0+w6kJOa=(Bw$aK z>#P`Bk-*1*pGbIGA!;ro1w=Vgg`{${{oj)K8sNv?+fo*rLHEZ~p=(|El-VqQhN~-L zj6JnCqSdOqIUwJL9O{DiFotiGIArcZ6Czw84vzj>t!KLBiw=7D>hLsehj^}a=X+)| z_rxnW$b06AOLRoynVNdK3v&Gv%hyzqUzZ^79-4+0QV_a|dH*@AXAYmUiUmUr7=BQa zI?#bR_4%_qZu#O0ZD4%4XAYu%rEV3RckIEk&&-g))%jXBxb4}|R`s0s`#FXsjY+1hR z3b{8Yl#?!k%=Hvzb04vMYwzL4TsF8@X8tV+(LcrQpVC$pn$|0H=x#n^E-N4?m-C_KBZI@V$DYxUao!BVjKW!Z_z43=xC_ zl|LK8k`4>ssbA=5`G(wsmlm*oP4A)37Ap$;ZoX+A8c1# zuJh6m>Nx&N=D~lSL45U<>;if=h<|w{yNsR<=2Nc1LIIu)=F6^PXCeBvY#4vzDmFkq zJAM@#O}LYAoj>a%pDmbgKYL=nEqiD_JC}Yvi4R_YGa21C^79w4NhCRhZ(G1Nxp6b* zMie2&?qc0UD?>~&>IzjZ4SRIKJNc}Iu<`y4eC>AELY275B z@3@8)8dq-Q2d_bl^~D=`{y!1DyKp##7hi5P*vJ=Oi_Njs>-menqnTX8ZM#wqjPgVv!*@ECiRMi7Kv;-vRqgEyUvO8I84bYmfnVd=%e&9m@|O2F-*4 zgfUzrLe2315NVt;4WVa^4T*n_|C#-pYgDKv z<+sE5zp?$BH7ay4<+uI#f8CE}cfN2fYuH&-p$a1|j8$frqCN^|-S6awuV;%2%Tzt9 zFc4`%iQAyklM#P`a(ftMy3ILP#oOGE=qT823`EmGLSNDn8v#oq|46 zeF-~=D@j!}IVa0bOJKv8#T=PvRbTx)_|jsd2a4`Bn^3hY`dOF;fsn#&MZ)2e`MMPt zU}j6W#)xji3yF&$VXGNM(ksuhswY#@t+5!5XvmZnEt@ASdy)uvCQ!=2tCU5*w;Z7v z;ZeLKz*?sGglz|)XCekJ3Y<{7b}z($Qy; zWONK~ZL#wMnbuYW-m~F(C?#6l->yPym7L%jx;|~Nm#qkG@S~?K15UROj7F!iLXQILprFkXxf+6$#2C_mv_XpY3F6p>3hstctRLgfC za6vY^E{OXaj9mm(0bjV1omm&I^js{`2wbOea8&9h#DakB*eHf0=UUal=kR>1>=J~- z9-Hv#nWhM-R#KC6+k$EJhM;nRK zA;+TA($m(d0h9{|;`yXM%y#*$z-o(8IP7A4e_*XRWPH~e#xVSeBBBLc23DZy)1k?G zw{RTU*K7kfZ(`@QlOW1VW2?F+bfy86e?4D%6V58pk9_k@%r!j86;@m>$yL)F^GGBd zDa3-nCHMHkTKH-g)|q7<8uMQvouY{??UB-@IQe5 zOWw-7DIkA3s0QQL_UrkYhx%m>OI~^!L5SXmA%5^SHny(|qA+*95)ERQ<3fuW z#+j0KsvFi_%><@J89)7YRyfepEYuz<6QlCOGQ&4Hp_75{Kf{=sko+CuiF%%e>5RA*O&b;A$?M#N8FIUjhAAyKRPs^t<7q z-yP)+I8pcjae8Wh-cO#d)m|VIY%UHuzJ@xNVyR?4?1aKHAv$z$73Bk-c!)gmMlJLX zlqD|OFWQS|+^S{rJ_P+J|HqB2TVb3cAd)krWp^lJd7LyuDia~^`9mQ}-|QLEz4#tm zLv_4>dv>wBhO_{`XDy$xn%$D8gCcQ2jUT<4HRuu-i>$~p=G4M8Ev0F2{LK;K{noHy zSrF{yi&h$t@5=bfHLS>S9#Vb#7DNI*zlJq8&MK4DU?Foli-f)GR4kQBSW?8AS-#iG zc*i?fr$j0?M5R&#$j&nEy92R7L)P-U?!W}6#~u8|JJ{faNHl{L7agoFJ&RLEy>+E}uK^LRe#(HCTTUro1G&?coK9YX%o}Jo z$bi^4(M@Jp>=m+0CX<+G;IgD9>KQ4{}!2CoLmkTQQjtHxBbRq6E;>wZ$h6 zy0_`f7yfAG@iXpb?bD4ASF*NiVA15eJNU}G*(r$@CyH1TI;}*Xc3rFKWBJ}EC87LL zKJ`A?hNU5GMqGaM>K(k`9z-}J>}%pZ?BYf-FctZG@h9$KBNAV}zlY7DHc5~~(~}Dh zK$x^j?hcXMkW8dXE&}9b3Q5~r_S8U43>&vlaE?~eJQ^!#&0633-`1{fE~1k z?|YxM;|K0zJrk-R)Rt7T&8%Z-sS%8KzwFe6wl+km;s&I44L|>WHa@{(DVC^oh~Q8( zq-*%jR2CZ&myie`)ob{V_p>PpmT0;z?%}voWDTG309%)UXuZ?aEgfn3)~w-8H?dCt zNLWrml)6DcR;{QEkg3n_=VkHnGwsT3azBop&1_vzZO<>ylqDx($i;#(u^c zZBZ}Gjih32MWQoRqU~1mO`BOk@dg{)USHJ2R?w4Gp5iC_CMWeQ;^n+3?Gd)fEVDGjgR!a(d%FAX*I+2_$ z6PK6N1R?W~l9>V-a&mzW)9=`hMWo?VaDIDq8_jd&AoI&xXlPyRPUs$Cy)Md5F|1m+ zQ!U?(NRcj56DfHpEDTd&N(mYyo?FT1kEcG5w&U}*2s@CKV?8P&^%*L^doWS| zJ2r|zW@@U&BHe&du3_k&I#9`JXiY{i)qupK624w7ibzA#??(CUx1T5jD&7dogZ+pn z0Q)_P4V!QeP1+G!Q2_mt6A^`F7=;%^orwrCt6)9ynjxutu1i;4jY^(^Wy(Gf#i7;gW!>cM@mOHA}&W&}-Usv%N|H47RY!7nDSO!|m{E8AlAGr=? zn9FB>u0!jD(jLhb0oVJ)^{Ezmna-AB0Vj&3@NifD`@ax2mO}{{-{2i@`F4{adWtLR zP-5Q+m5^Me;Ce!FwMlczT$Rm*eRr5U2%#;j`1XIZUMC&ZQz}u5)XI`li5jIoMvtZ$C2#cAsvY5{Z-sRai; z1T_-=lVU{AiHgoIcj05;aw{$!Jq{fq`cnGO-fgVcylnqbO1LLr(^?7sCrt_3ewWQ* z{)v=OTlHRW{dzl}@emu5BiCvRJ_67Y5K^wkBSGwPiJkS7MypEIjw(k~ZrjHo^S+W< zo>a0*_jD6VQpa9{{wdk=jz)}tESn^mpTLN(1KDmO!y4!l6p{h2cnqIVph|Of4;9|d zCqK+?De&G(k%N2Ej<1HtQ2-z=qP?9@FJ~pZb2%GroOBC)nbo-CEpSr|yt)5Rr;C48 z&OAdaZbCY=(SYiFF?IZCgCdurYEz(tdR?oCBg0~36NrcL+oiYg8IQ0TV^)(a#kD(( z&~TE)o$VA{FJ$9#Sy9N2_tbuNv*?_wG*90UVLIQ!e+S3N3m``kTto4RPG9a@<3RZY zeE)OV`zmkGi=(-SKpP=!fSA``ZszMB#S&+g9_}j>4EGnGjyS?jsn%oay8kwQ_)!#f zHpt&kfOO17cO#`sumVUSV$@K&HSLXf%}v!~@rtIiWGkF4AD8lO$Zv=ITnaa%?Uj_R z9ICDizlGbi!de{u5vp7LLrw92a_QO_a4X;Y7&iE;bbtB=|8p=e$>>o$hiT;U)nXKS z!cbVEK8Wx7O?>F%*q8qJmdaU=vq23Sh3W8VoK0|mSdVe%Vc77T%7==8X29#$fpF|4fF z5>X`)9ViMZ)(DH$H}aJ+96xG%Bi-EDiFXOHj#vSd{0^ociea}Vo1)P_XUAvIVy z8=>+`3(aBN2u+(CA|+grwO|iBXj+3pjVw{xlqWvzCDx_E3pfPQiNEyirDs^1DL=`LsxhGfh`7blPjl?#xf@tzym>NL-P1L9g7a{Me{{W@DMCm)^IoTrS zNXjMeE^=cDZUgbaZtv5QH5#MiL1{0|KQxqg6kn26>XdwZO&v_pZV>8BVmC-+3vmk6 zeb~D}krm4R2n~og;*rK~a4F@&;Ne?rKCw@I9}vqAmzo03F(JQmSO-^1o_g}*;-?b#hdPBL$LF2gR%AwJCr%1l94ukmQXRI4_dPEE~NqR^Pu)# z?CfNNJQAei(!XO)?Fk5XIJJY(sRGMmV}EvLvMkb6eSX)Y}^k=MM*I&oUv@0BJOPEW5CK~!NS z_Z6S|4%VA&^V&$20)<25v8gF}j4L`@4J=eHw)o6_Y-({*S653}P@1%9(2aK@ zs5G~vr)eW?Iv~$NxxdYd^Y-0<3Ku=rxDCJZ9yXd*wB#@vp0}FlMK!wMsKcX%Fm+2l#|{urQVhQHlitd7Rk6Rtd%Ig|R=Er!S1X zoATQ)_>I~>y1n zx$}M2C81kX(Ww-@Se1Mp{RVA!=B4XqBmL5Br9eKug0FlZn@CUGKqWsuVB1D(la}Gw zFvQIeDV%FB9Y{~v;7MydY&oS&4dni*lu4N;CM&*;k4lvq>R9TWvx49I0k#6hFXj6_ zV8i}l>*Pt-sRoD2PA6`R{^BE*oe>_*zu(W=8V8p0h99!7 zh#3rpw_$RCkiCc;6O|d-XgR!a;AZ@#d;(wwLJJps$co&a(V_5Wt#;QqeMd3&$iw61 z>wsKzlm+5Lm+|d@6@+OS&rdXn!EiWAu0^Rj2@g!M#IzC^D~Y-M23~vstLEdb=aUbx zk|OcDv__d>wF%L8yMu|0!BXH2{N4lXlyqEF;li@wd9j$e?gsu>7N3pNRAU9)@*DVs zgKT~vEnOEDs#4O`v1)h$@&0dYyRie;Bdp0^=FY8-2w3 zmI!4~0Mu}oAOQ+~4WENMfia^-B#XGkm=d3NJ)iLr>)HYv?gZU}1-5qA^R*wb!a!UL zeFw=XdRfDT^V(FTC=M#pnP*tlTONeEm~PUm1#M@yF+#@QR#qxY20I0@z_Je&Ui=nL z=i36lwZxZlL_0u>EIA1^#68pK7lb=Oxa$c`_#zS0U33x5y{BSjDm)R&O+0~eh+`5{ z)iW*MHgH9dneaFxRHRw_k&h7@Q1%6Dpqhy?!_E;V$3g)J-36iW6CxJ3Wf+Rk{}hwk z7xy@&D%9)$s1Pla1XSkusfRH?BTZC$pQQ<{mt47=uR6?%)2oB6vC1YbYfN9xtLwyB zGH33I=wg=hj-RlS^K%wKT;fWB8$uQs>!}@sCA&iP8sVHWegx>!ssLnqF6Z}xdwNcs z;*J5=7Tgpt{C_D*3W993oEOA#0jS-2*k*`I6-oj5eHqk7Nq-G`QBa<|P$@ho^nXlF zpM;??@k?wF*!Pz5uRmiwCe=|cF+lc!4ky7xuaRnxG;>&zvIh9d zrF_QctgtkTQbH)C^&wEwyU>Y3cTwYHl<$Yh>+GKsErQY<9DFH1{5flvWi%0}2OkDx zm2HS|5ME&Wwa zqB2Hs&ELt1CPQfS^D#vvUT`!o&S^9LSGIjq0=b#}*&!`Ri<}22Db`=ep($E^Bc&SkY`ejN4Lo)hZ zSBbn&Lxo2$lz2qm*rTdQHjhfR20Tw*k5^E#?&sGDa!*bF^;o&6G$ zHcAV?2`2P4mfy9WN zE(qjhZ)5o;{0+O_t3Pke8;cjWB$tux>~fe;Btm) z9D0d%UFmOh(`mRFV!Mvs@Gi;d;0pYg^()EbvLsgxxITg=G~U;7X`kEGjPL(1JFk%< z=HE1T4&;wEaCYX_w`@^DB}=Ikl{7)DEU&%}F9$``-G&TBk37`KR zdmqz7dWr{uECg?7MxhFhC<2orW~2^*qnq}p)XQ3UyCtEFyv33kMG;}ZVG zQFg>=zJ%}nft~43f;|~|Kmg@R(y4Vu`(x+9#^WLrY8oiuag|c`Kn*o$0?**|FqJi6{5aG3WrT=iET^Rctz?4-o2PV^DCQrK~hss2I)Y&$bd*u z;&>H#TvS)UwL3gaTD| z^^6V1ku_=p(sNa%d^(9&xvBv^c5UU*TK0zC+2)LeTdh&o{?4(A1x;V_` zPsaN3Er*$hJm~<7|C`HX$R+DuxMe(Lee2<9KCC()ylsVmhJb_~)JdoDsd^&MN1t z{gX&59jRlW9JvN6h)$=22*SZdJOU1dQ^3ECL|q&|?%wi&X;rZHLp9 zVk%o*OD07_re;X02Q4(A3y5IL_>cL#AP;#xYaySW=PWQzUC5W_ImdK55kK}TYmqGIL21qry9jSFxSAI=aQYIix~zdSdQsAz zo(u^;nlmI|VPYO0izUo!FvLRQ)V?a$N_MF<*u-ztV5o+IcsXzA^cs&Y;0GHzml}60 z;O94TE;d##;`{J9aw^K6hC6-(@1*IEcO^E5!SSi#a{_*&tp}R+)L{GJ@KwmM`fc0- zzM`?S*ch>ZKiJqgp-piHb|%nOImhT^^D1f{FjjaaktTM$MVfxu&AXT3*y2LIuZ44%8jDmI z*zrztCgju%X&^UxPmQlz&br@aIvXTtvD=+0<6eQLVg;Q+QWlRR^Le zek@Aml9tXl>9Air-oKTzbBhYygZM~{Jvso(2fWg@LvM;IK)G9}47=A_z5=>liT3vB zIe}3gv{856JazbLz{HkK8sNcO^Z6^S&}>y`{!XEbt~|z1CdsZnF?yPl+My>^)`m)z z!!q*H8^T?>q%!dN80e==MzUq1Ql=C#LzK)@LI!UQQPZMqAv^LCLOqpGTUwh;uD)c; zsGFxEkm&@Otx!&w0`YwGY4|Dl(NVqX{b@BMqw2? zxgPH`L(?ai!5AJqr}m5!$yzGJ5whPxRzvEV)`iyZcbrylqMC|pgy1I-OlGN2Wr==w zl%LMM9i5#|txtW$R0F10Q<)GsDU1`BO#S{glY0YVNK=_yE~OI%Jvz$s1ykT}=u`?O z4kq%Zd6;h6fr7H|#Dt>4NO+(OsSHA96=b%g6f*UF57X+)V0bds0TfSw%BKo0Uay%| z`RE&Q$~KLZjAE2;Oe2NC!1>&XIOWw!fpRZM{i&p|IFSZYNnw2=eegu2>MEunI47oZ z!uG^DHbzj}iLa zql2^GaM^_?1(mIW5Zs>3S5i)8>o`@ko`E`~^}F$!_heR}p3KUQ99fB@qe!VIb!Np2 z&YM#;0%s$U6;~l2)zR6nE@fg6yefw>YjP;_;)Bw&_Hq zveuTb^UI_p9 zO1`SIbG#bkC3CCvbl-3J-UWY(p8Su_&Vqkrx}DOe6!=(%J}px8sZX6CWVc_*ukPX; zH71L`yD(en1D5Z8n;sYoL!gy-HvT76(Eg(Nr`+;yx;O`PMvWmUEcErCQ~Tr3SUP0N z*j9HwtiXA7R^fzYDzQy?r(SBN70+@Em#FV9yiA67=FE(SlgzXV1dg*(IV`EmJeva- z{THi2M|J_xA!m^2n=x*^l20ylx=+G3WDk*>L1-%zZArX`Y)f1?p^2uB+ELYbA@@D` z)^)Al#S@u$e9s$#F6tb{~a>9vo|6ZFC zgX~erY7JIZhaKALbEzcZvl_H{?X{HLpsfjzdJq3E{UJTeqj4 z0|)1{pGM;zR0t4lBcfCSe~BcBmhd+~K;b*tl|d1Bw_&FO1PTAf8CNR&2T`-d^qgel zlslvREtE&SJzAV(u~iSwtCO6UmgzXpN(7-)Qonrm?1@MrvlE|M;_RPJian{+ z#3QXN->fV6mJ;WLbR4#1Q*rJ#79S*<4CDx;f~LIo#~)tTr0X z;Ya#9PxqzeC7NziuM2^Dly=H8PENeyF9m+#oXVyBoaMT4?QC8=z}e5ZVm3d2fODF1 zS~yp8nLkU~D~15yk7o0|1DqQY5Ns+_GPeH(`yeoXHeWi>In-#SSR2mfM+Q3Y)T=75 z8{}N1Cq%7uQTH$m<7V@QCpn)>K%(i8($Q#WXYs=)IVUy<4-dV4DepJL*(qQb2ex5_ zE^$@7IO_d0nH|O37wbsm64aZenZ=gTMu>Xph0H^cAq-s+Nl^&me+&O(F;x6d``EOJ zPHxj5E03=Yadt?koFE)22unQ(yqv}V8sbD8vuHJ7R;8z3LV|!;v-rrNPJ|+5K;jY- z0c61}z9JVyh4sb&nK6s+9_sAcGmAxr+3H>#1W^Vd#iKkp+=;mUj5L*6ZlK4`;$w#8 z&>YdP)QWil88C}49hO6LrB*2*g|qmJ!!QfTOeiW@B7iWMC|5#Cmlz-#OfCByWe~6eGsr4yelo$6i zS-<(V0@dQLQF^|@qNe{aUrOM-my+7aai!#|-HvtkWc)scCbW}V+&}~~n@GDsbYcvB z&`z#b3X$Qwf_W1*C_foPVeLy12PD&pD-}dL#!z}`M1?+Ibr7u`Lv!2TszCC7=o@2b zACO9^LRQwqb@gPtG{&sRi)|;F`nRk?KJ%r5cdEr(>!zl5nuQm%509a#$)%*-SD1E# zXyh2$nOsV;d{T=+)MpG`0?`dc8CEpKrNWUrl~u!*);5%&TNLH<<@i@H8Jo<2%TF z06DM%pLZHQxX457AjgfNtsP292c(;>wy7Xe#?W6KjYNK9I+P+OBnIo`4l(lxJKg(%&p#e3 z;(G-_ADb#CaBmZk2Dj&+=yPz^}0AX5?Pn%Qa z)SypE&HdPZ>=a9pz@+Mfqu0=(M{_kc_oNPr^EWE=u*r ztda>>DUHZ^r{!`x9lQfa(}|84Kj+?#2N#VR9SV55usm#pZysePc_B|tt<80A%;wz= z%VT22!L_=XiPiODE`#BaOAHdhcDzMVLGdyHasf~a0BjhCyIjt!QS@FXIkDqvC}1nZ zIMxKucZQbfr2=++E1BRmA8F!9?r==-%rmsVGLCij)`96=U+6exgmI;67ZW2q$APPn zmX$?cj{&3YBEvFMeFMjEGviX~8c!!q&KiaU&-bHfW14(59LfNw41nNaHj{Ecs-#)- zA&b`�#lWtcLK@PFWmgb!nWN zH_R-8=sl*?RM58?MMJux>$wrsBH9h2TBB%vS2UV85_wG|K5HE@iq3YGAM#T#Gf=&( z${6=?f^MdsO>aq_4*DOmSUsFuHd0W?zb{9M3!N4T--B3~MVGqqXfue!QjIen z!4@TOjFMY{lDf(Dd)lNa4Fa^;}m;ktI0`MBPVHcwc#vpL*Uv$+@lJ zXFrmb_LV#P5fudywe@6#kJLp!d9vh3-)_43=-8g&lr$KQM>dJ05u3tCl8Qce{cz}3 z$yx)eU^*UA!2@!c>K1HfAWtz4M!hP)e zz$}ovaV%-ta7rE`<8YcK#U?2-N%-W_Bdi&QCKUq*n>WIyn70w~iKTljp0T&%!4ZG1 zm2I-XG{|DAd^;u_i)SW2oz#6eg%6dZe3rHK#~E~^wu2-Yu>7YsPP&w$QSYI0WdGpw zW?CoHK%Zo(fxVE!z0A3z@$)o;KbX%EVaO>4pL;mHH&m{61GLv9VfRhd54!0cLdSv6 zHJlQM$vE^MluH(LDoFksMx%zwqi-;TZL7ZU>l)^7h|2WqFgdzoig{gO^w5Cu?Twj> z(b+ zGO_^ARe_6!ic;#uarN!QrBpGjm<6m}j0K(@uoz>$f!fQpcAB*cc4HP; zbut&s9sKR$Wl;RF0;7CiIX4alh`bg6^@SCgbl>{ZIe6P$bngdCagVe>$%jw#%QcpekJ-2``pXlF8KQs0U)X(Y7}ht$0h!%t90G z?%UZqGupsmx8rk`jX#A}J{&_+Tt<1vE z!dX4dAIM<>X}1Hi90cP4^sWU&{y0|VOSi+p);6}FvC0OZl@`#m{y$SvCkIG-8K9)LzzK-K(#tUC4f?G$py892qj>0#j{aRV|9HJ|@HSeea!dVj@fPc5oLk-FO*wu5s#tP^Yc%C`&j8}e>*%QS<_Gi0QkKH zSj-mpJ5XS)CzR3znaacs#To?j;y6G&l(6r-Ewv|c)HZTB6+HVao~&v9np-(r>2{hM zjy2fF0MKR&Xp29NWr3@MZc}tq63p5?9YD(%XpbYO0sAGwq-_CM(s|+N2s)zw-44*f z{yMm>eHeaT$aui%?vI1kf^ohq!Kuajd^egm(*()_&@)3QeXLw>aK40^#N4||xJzd) zFq!$x#TZKq+;3srL;EwF%~+trT{mYp%xoM<*wIO@oAv`xgIBLSe(ni|nmAD8zj`%s zfHjsVYMjHgrh7tt;M$zLel;K8Tl-r-R5W3l(6syHnl*5I2j5uOC~u9rt(yizuo*Xm zcHSr76&p-aWRmcmh+#;Z>B3Od7cLAorPl&;oA>$UV#Vv9!8BwX7E*#qaO8xuOA5uU zfP-oMI5}OU4CbSd(Ue&}vI4p9m&?b(3(HV5UlbY0*-o6*Fj_n~JM0)t>Gxw3`Sc)~ zalgC`x4YTIZeve4+i9s$j76@eV2Gfp@Qw6dOD7p_L4#@Tc+CB7B(fCG1<}C4bYi?b zKujJ)Egz6y^3xzQNP`GCf89z0o8Hy{D^OvE2GP{uLAjcr8aAb^1}Og=L}MS6lSPd| zwDLiDjvuktQlr4kISGqN+Xqpvhh)BM&bF3KWFf|ZXx$*1{gB)O_psSSMS)1U@I6?} zr51C-_i55Z>=6f3T5!8TId>4Raq-XbY@(EkT*pexh8>C)FmgZ32?h z18*VKrnjW>-#3mAWU0~g^F%DX*{R746rCH7yCeqEh)I~%1(R5!cY|d0Kw30Oez?C) z;tfP8PQZ~R)($JlYeF0WmxFQk`-+3jXF*F?(|c+l4S56}0m0Bkruq2ZyKw_)$s_Vm zpY)|p{Vd<8cXF)p5J52f1@SkY*xrlY`M-v`{Pem}ar68|Mem{VYKQ1TG zvB%)*XVYZ{YPlPWlOHl9>hW3EEpo`_vs5nzpKht*x0q9sqc**zdbosz%{3Oo)xNao zaX;N{THClFU2Nz+->0@WP;I^$?;%D*C%@oUYTJCa#lbg{`7mTERc)KzZCbp{bTITC zKRd{QQ#+C_nC^V#P=(Hpbc(YI3D=CiF0z8{(I zW@_8?w%Ss2{Hn1(9efIESL#c>Cd)NzX7U!8Sq!oT82H<1>7LaBi^ctE!DM*=WzLpE ztP-0o+_FhmV71d&g?*6~L2-E}=!($*e4Ed46FM1}envWO0^4U2dh2&1Wez z9ei4UI`_0Z!bq@HPht2#e7>CTcU0wPaOUV9P39 z%sq?V5+uPF!o~EMLrM7G3a;ckyc|{ZxeQA7K=#u(_~(%y_7%d+KylNtz+c#xE_r;N zJu0R}VwVq)e9)JgPKRHot+Y+zF;kn>8`t3UrSGT9qs0Basmlx;pHA*g7iM7RGML3{ zvhd3AU43c9Ou3nl#A^vIGW&VH)T&lrT0hfIH=D$2l;W^DTDh-&dZrwOeNJP(kS%N) z58vGlclZIQ7a0`&tZ%f1su-9=Ui?^*L3z*mNwP_BAljH)VijUh27UjmJafD)$gKrr zT`s1x6Ee&SxG?D6(ZDRU`0TO;zD$dcvpg5KRWdz(7q1_hExQG_svwes1a<@PEOc7w zpMEd=fbXI3IdZBWktdKS?mpanbPr9KW9*;VNCg&=$29iz`{9Xt4_%uhzcr{toI4^w zT=`9J1|6bL%~QBOuuA2Zwe zm&X2gIT;DJm9hC!OpE7&?=bk7#^Gp@6Nj2>|9WdjZxfG;g9P7_OjiVmye1LnS?Jvph#wEJDE1L$%~<>$%nnm2M4nOs@mdInr~(>wF!$htSuIqouR9_S|6DRkdOFU*sx`xR4L7t7dj zPrW%?FkS9Vy|U$6i8s+DZVIm3N3mK4%bD_9(QDaq%^T>g1ZIK$m_NO@ z75xbM=E3+DeJ=$T59YD>94(L z>dSJ}J;5XeY<~3UAo-rrx~5!g!-opbn?BT~Rx7vZLoH3kMP$9`^viOc8(^*4Ivpf? z85T9Xu&NB6MkUYn!0OTvdVv9_%dJjroB-iO24B;@3 zT*P_MZd(w~7*CNi2FLUQQeZ*7-h=WM$+eo?0A+Onfa+&Kjk2_HzzBLeU0YO24qImB zYh*ey8?s^vXT_~@*kRf^3p_1)(O8m4whY$BI+4Ox&qP|Vvv`A`J8lu}ZncM~L6=F6 z9umy!HH{+8!~s-`cL=N0_*R9^JQflMoL@sc07zaGpjXEK6p2PX%A$&%;H-#^emAW@7Vb$BLXW=abW=jBdT_VTFmO^bF ze8~m%gFR{P61Y#@NMsufL_>Sh!CMl=&Bh{QPf}mI6;c+6TKA*@wpMLaBi1L|%V3I*J2KhpC_$*2h20!KaQyUU!83%owgXCCuI$jz|kx7yZl8?GmOl~QHQp}?{yFs$GJB=!hq`)L82FY99X=Se5 z{RUm!=9wF5KCYMTPT|XNt|VApk4cgRlF8j^z%qD{1(M`Dt!gD@V|xuvHP_dr$i!Qe za}>7_WE7^3;2CD|yo$c`mOPmzPnlFO_3lpBmcg+zP?tidbqRhJNIF`$`8>G0d7VSP zTBmlv)57BM+>WQfdQD9Zct!0;IeuaEGuTzVbuP`*f^Gq~6=NJ$3e)TVO3p1t)V5W3Bfx*%JZXS|~ zyzjc*q8&u~oGGTF)ZRyFa8Zz^No3_DTlZUS&dorCytn|&pOU&gCGm8*N?qhSs zT8&#u7_C`(Lz`7%u2^8lyFf4r(yo>(vWEilNRCpAEyDr)>&z|sl9Pu zgHf@;QzxC4zAeX9@ipJwP(l2fZ~F3WIWefg$#+`Qhg8C^Mbar|m2Z+~8zJ9m4aBoR za_Mf$SXEk^WS#p4$=SQjHYt`>552`0!XDp)=Ue7MXLR&eXp9@oQ6#f@_{wIhx!7~K z{38e-T@oJ25gic`f(S0Zj+F8_jqj$g)$#;!rW;LJjg|ZKF0^d5+;>2Mv3!; znKxR4pJQiKFTdN%i;y)2j5jjpm2~r1RVZ$I#kDedOebY_y~x+ee9#5IY;;ECrGbCf ze6=dM>x73cS|f+jV|j7|v9ud4%adz{zXCX%%G!qO1-32dMu+pT#6Gzj%{_)){61^s zOfjSz#e6A8(SO&-_lY*$Xz3Sn4E0$ncN6Yzv}CQkQvB7GIk?4`ytLH~H8TtyPSy3qHVcL=!jte-nE#A zy|rANeOOj0<>Gf8X~Jgs_0;G>D>utc2gsn|)GtT_ZCl4h+t333O^nMw$>yii$Pk?G zYnyU$R#Q0Ybqvgu7?y>&&$~KazTBCTw%|hAZ#&bzyfYD`ZWD3|;Ob9_&oxb$O}yCzZn9m3xWCooUFskX_4?{Z=RN zV&rq%bYc*c))qHXo3f3wj_mW*gk>Y{$1aYS!#nHWzbm(qq+K*=gRD{G_v8lY8<03o zWD^#IzvMuW@1P_MnQa*~+hYiT59d-NHII)sCs5`DM=knwE{48g0$$JMk98}6C};FT+t3WONtCyLw&gKf58S|SJU*kHh2 z5`_DKVQ^eQ+u8B*o1JLsPI-j*I+d}I*q?pg69YDbJO`;G9`bA!uMk;P5n?F5Syb*yjBm8wV~&6Bb+<)QA3wtU;$fmaB*k$c~TYn(5b|2A3QUb3AF( zk!<@Gsub*7aNXmlukJmGx;GBf?)HW*1}#_e3NY_~iJ z7q}IweWCn-sNR9{3K3bh16?bW=ZaIwW|x)w8M>^!$rN@NksFfncTMyp^OB7&Y|#<) zE)$Yz)DgMq5L;CjQg2wwYg$UUtN2;Wm3L|}R%F@+ChZaAq>(hx)=5EsjDmzyG8qC# zxxZ^m=Z?q|XyT`GxsXbp!;9O}_|N5zRPd>+3=J~d=-05a5`>*(W23J>+2Mx1KHKi= zWmu7|xu8vnHEU3dqqs@#OnaJg6o&M+rM#msWI=m2+zjz%dp5&VF|9q@YN{BC?=R7l zq_(HXWAY;+zCDit28eKjz9zZ8lGCI=D6SA*99NIYW$D4M&XMi>&HjgN1MAwdg6D}$D`ifOIa{GTkGqJ1k$ z_!-Jzw|&UZ@()f|zVKAnJDr!CNa4@6G+Ue}n_Z#AmNcTX5=o1HLvOI5nSSCod6975 z3yNRMR*usb{~@<>xxQ$MDwv(8RHyU*$ipfP#3%Pjjx$dm>CyCxKEFa`O`-{xFa+4t zOb@>-ZyFo z-!JiKf@^T%vz-Ms%*0nqxi}^Q8-I#BT7h!>l_lCFF&UT8!~k}^5X zAh2p#wuCb;3??#TEznqiy7J<~agd-C;&u}TDBtPP|##F(tCz1kn z`EL_?qKs1SCW&#l0}?X}0M7>j;lo?A8lvV19 z+Kp&YStUXI*iheDRzY=J(NNzXsw4_Ar!oB%rkoJ>G^Q`gD?7#GNwlbf(x#c4dj^j? zho8boxifEOU7SE`Xrwxuv!AoHF095h4tE?mD=M|cxQ3KiQ5jJxz-TzJ9&Qi_a0yvz z18lFTbQVn;k_cA@lnT%(5l6;@0Ju!p0560qN5zCjG^&!)RAeF1m6Voci`qfGOhHE~ zDX;cM?)uut=19x$Xdla2^CbVchE|+!AmEg8is3-X1A)ByW_x<|>5r&GdgU1UN>+67 zNPRBM(fV3Naf!%f(9-Lyn3KB)1CLr2bK-Et#b-&hPg7df>Pd zcHbyMKi(mUVj`4|i7i3rlMnhx(EGlj&rg`bus)j;X>NqFUi{OL+EiB3U5_VnYfvoL zp!e%Xm812Qm93(EB8`ny2DJQ+WuL5&lRFc7K|j_j9K|OWVcb`I6^j0Zq>D`RGH^Hz zPc)zlkxEj`RLJMyZc#-X?!^VD+^2~Vp2OU)m9J09QOXl)7I;c@teBJ9fc8b9Qzps0Uimt*cLw z(MpUeG4CGmo-}!zG^8%kO3SbfOoy zt0@=>)}t=fl-;ecWE{gapip?@jHlTKxbpUP!ZloAcKh`=gOTG*>+r@=hw4hh^!fP0X`MCX~>y@YC0@U<~g{!-W??z^xnTTdOOlrSvzUJ_E)vAZAgw1;i|B z36grcz+|2R^N=9s8BoGVWHWV{{XP z2@y(jwo`7D!{HLbxmF3|zGG+J)p``^Mro|nfDXEq$RRmMDt9P1O^KJ!KcdY=0a;N2 z`$csEQ&NKq0^*J|K&i!u!{K$HMB`$E`Ud`p#~B}g&bTc;jtjU@s=o@tHwqf!bl~$s z0n3megLR5FWpo_GGPFC8fev{LWb6o%aVn9*YAQ8FcN4FF>wjSr?i1e#!uya*2W;}R zpH2GEJ8?=>kC=a9j#+@75d@vb&@e|PpsDcLN>!XafjI3et#ZffC?P%9Mzw>j}B zNy3veRM_EIi8aFUiRcrC_3+OjM|m?IPmVuUkHYFH%aTvl_G@imB?tIV z1cyP^SHWS9ayg&ZrnB{wQRTNIj$6P~JV!22V_HB)KHiPOT@;qH&VC1Wp8XEYx9xXe zt*A|TiAo#SD+nWZW2GI%*H;FKL-91Vz7kX6J_NIfU*Zwn=P$WBrPNnk6^`@WQYhX- zEUsAky}mM7{1~tIYQWZO5l^QZDyPNeT68c;iH!cUmZ_C--7wq&C1}Lf__Y>YOM2VLhcG=RB92m;DiQjbR*FYR-_S$Nm1^XDLaU%>w^f=6SGI7( z&`0f+7Gj`Vzt&zk?TV@qYk_gi$1zw2tAemb=am?0pP`l|cPHhlD2mf#(-aKJ=RpwD zcw(+lvp61-4{^PVcPi|w)g@1r2u1(1vl1$p<9b)-SmZW2p09C*+PW$EZg3RfeNm-y zmFcAjwSxZs-O6`DY^bg;?V+TL$m-QgRLaKDWfm7zUBA{#StdoUuT~P7Y(=iFMu?2j zKkuVV6wVM(K>OPIgMF2!B=JTxo$ja16O*I$C;BTVLgFg|o*}PSxk4L3%NrrNcj3MT z_zb641v=*2i#kQP$@`Zas(XhjW6HR*qD`K@QCFx8-r4lI;MR3idzzkqxHPe%1q>LoZjeOHUmSm*mjYau~eZ6V_}BJ@D4Lnr5a<@W|W<)#ZXdD zEs}cNr@Sa$tg0WsPZ=&@LIjYu_cKUW=*%FkD_^0Xqs$3W_IM>tOsY(n5XIX%)3r?Gq-TP1#vKYxnfsDYJO`s8BS4hD-H~P8A`?IJitHaDv7qJM%EarLz zlk&H6S7-&^ZOV0^Y-dq^OiDZ9EJkeGiCPP4w?ygT8V6*`?ju*B6-$&^t`z=sKdLp> zhrOnJBE>8&Z^F(E#ZRp8Zo_uL$>yV>h5}Snh;)y8Lm5`7HG~`UUHoJ<3Gcl>Q~Fcg zrOG#z{s(>|=8vgIPT-wm^l@)0FG{XY@ww==N^Yu>t1Ohx)7o5x=s}#k-Nf2iGXW zBH#6kk&t{`-T%Ux5IV62bGolXXy;mGpKCQ}s3@$Qn^vt;J{RRfXzF?lI4-$p*?LSH zgiFuZpiB|s?Xq<69W)sooHSyiGD5xV#E_hq5$^RIc0c2I?N=uq+^CFq^(YHGxxNxX zeKsjiiBp2fqv_NpWt=FBYYjIm31KMshV^toQ#S*AvCuDVRaB;*P!d{tbb z4V^0|((bLw=%`|R1yg)(Qq-d{x^gP=bqN$`h8*sa3CJF3@vahGzA-2{+qQxxcCs3+ zzwxeeS#lOa>~}|$s`T!5r5B0qNdG#gp0HgJlJh|`t{RO9uUwwqs2g6MhV4))ij+F^ zzz%d8Nlsd}LrF?kUFP`vWmYiOaj~dO$udZhlXo#{p$o+5*TYYYT2W(WmBE&i11edx zJZE;hDEfU&zMpl_yu|RBvbkj(g>fwGeWj{%H;A8mUx~wgxL0V+`%0GcIlNTbiIAyy z+3+#y=-oRN%~=g!BX=r|)3B0k$`yuOXWsHqxU~hz+-Bqluav~+OhD(!=Cju$6M%GN zr*gN5a#GALrDpmQAm)k2KZv-~gvN)#F(XLmEGNy~r3?{22s+KUX%_B2#>KGTHVV&( zN;M!4`^)3FMG$U=lQIgF+0IqShz@&{xb(6X@Eiulc>lJ*sHSNci~n-{azM^hc2bw! z$_VG<7Vte>?${Co{tYlj&hG^Qf6qk*LKjod-AV)M{DD&6+0oWM*Ai0e-w44N`nez> z8w8#B0NPiwfhSnN=V8A)Hj50`*&yI&1m*3)Kq|X6eYZz>E2<&mb(ObyyY?|QA5!rf zUpHjU|5~lry|N{gm?$>%_IVN8?P5F@3ol;_%!^v$ieBkMWx6EBUe_1wQ!Y5m7C5mO zRTQtkupfhhO24y~sOdjkxlD`kKC-h?nTifzAW-A#Wx8G=D%z~eo-&mq^vq9`L6S29 zIvLBR-+Zc^5w5SmX)c?dDpZDr55cG1@btc-_xcQNp_q1+P8?A>bVh?cv{II`p55hgjXYlOzb`1ZPTqzdM@!{f-AiYYdVx3P%j&^(79 zy-e3WS9*2eFkY17?Il(~N~vc&1+MoroCZR0uQtTlbleb?fyoVJ@qd>Wjw*x0ZD2O* z7XUu2MpEb(O1!f>IIs6oYD5I6i0J}KfDX6}L#c_P`(^#w7fKn)*%`TDEV#xW zQ)Fjre67ikY?9spFI=V8Uxu~KM!-;<8v#S{f<)u#G!!@I{_$u8)F9>CT&0c2l=fJ? zaMWjpLg6u=CL^|G!1VV;q_7OK$y%a^IcxZ-Tg8e%uScQu_FD z;~G)MwPkbT@?H@4_sDufwzoc2JFZL?_g0HXtqcRS zr=giFN0JHcPC`by@?6NsAwkeHY-mRkz4o;-Tpas{4qnt^%NPZ!4#j?>40intCh``B zR;loECrYjGUDElhL@I5!Hcj?E96_PN{ zoOn{HBI^EQ3W@!P)}K^{Q}3fn1wJol>MPt>K7*srNp$3m{th(WKp4r?w-I$crSx>Y z^B2TSJf>AAd7KtP+fFG_p`1e%(BhEyUDV)nr<8Ef;SyatrNoH4F6l8pC~?wFL@r0a zvJ8lJ9&j_UpGzB8n#@M})2Ee&*h#xcd1sVmg8tHb{ZC1iTIE}%HD44p;?kP$bnxXt zuDlhIIN)Q1^wC-6Q}OCQwCE?y3y=T77VA{GDpmYh>FXNHpA(-_ zs_UMgm0=<(7T?AK06NlnD8k%IMI($GCSCqjsV<2Fzw1fol|;$u`Ta6Ak}%#YnG1S< z!$d9xX=A>oi2nh4*%P@~;Qa?-#zampxS;F}sj(Z_OuOl~%f!0agZpWqy+*&CQ)2ak ze-xKg;ad>!+R4{=@`_7!`uU;~FJ@n$5fjy3lzB<%SLG_x@L>AqXO8f=7YpbI&NIDd zOyzhwe@SsUheMyQJbD(2ID&je9v(k|IT~>NH&z(n~#{=*8FDq}0 z;`930D+;z$>tCRqS5dnT{7&btDxbB_mK@DEOR|N>d^!vGEHoMt^z<`$y5b3e*xV=7tcftf#d`!ha4*xUHq*E*e@;BOQnrg3;%(nl55|Ft(%woM8hqCm@(6iE0x9NpNu}xbpc?Ml8(Xqo{@u*;Zf^eSl!)eGk+0Rs}+T9XlS^K7n?FHanL4YIu03&R` zZg&Vc2K6;22(XJE;AOfePK`-B&ppEJlyf!mWP}7^H7voRU)^eTij7q(U`Tco!><6u zFFytvzOo-g?>N=n<&Km|Ym7sRK}c6nBJ3=D$4J<014)}q1?gS(rE!_)2Ae;O^#{G*_?FH5&L0C)tuzE9Al^#*p*}v1m)XbAH zI0$jNA7aZpNusMc{xB2-a=#x)%)dzD3SiX@!s_FP6;h(m%`0&l+^gjvkXC*mzx?Fi z7__}<0XPMme@+LMZMPrJ(VytV*@#;D-L=)xl6dYctxr&=G#$qj7~%5IX707$vAH(N ze#bW8Nc$a|YQxUbkUHwvX=hmy^A(lzc^dv;hv8s`z1mlVu!eqvO9$|JBh2S0!5EO2 z9vlXJItPb2%H^b(Vbr0n+CQuwK6s?M;Rjk;SG^ytz1)_{*Hgb0o*(qH_0+9SQRXx) zYp5nQjRvU~r;nE7q!IroX&DB`pPjl4ClEf&rsb`-;tLVx1#0i?`Ptx&5>Uh!ql-{MWdR7u;PEpgQ>Qr(1ByDVpUhs>P z`h}+IMoH8-O)HzLH8ZN8^fSeBk#hyetj^N!t;q+Z{B4E3YKKAM82GICObE$gz+t}Z z?+-)n-{zqZ*Cx8kHex1E|UiO){z zU$j@Zu*+jnh(1469V~^{g(=xw(cfLBPmAfVj_N39AH09}n_O9+*h!ULuD`y;IH9P1 zM0Kn^sy)Ql-_p6R>O3*JSfAQWUEmb&eMeLGs!g3AeuJss{>tr1&eD3(&T(p_ex`?7 zSBOg|3<44I4JAFGcGREmtzMDDwmU!X#GGt7Hrf%$Y6@wq^FDwXwQ6a&xWH?S#(q%f_cpsYS^u)0t9nBAcU zh|SE)vNeO4(_vkM*&V7sJxo<4A9H3P^IpvS3y%d#{s+b|m@`9Z&v5mukJlT>>#7R( z$ROT)o7WqvpB$n7BAn-7frpzb4Y!U`E0httzSP6Vsb__795b`I{81g*yi|w-Uvds# zh-vzznVs>UU#2g=u(A{NY9cK9@aOu83F=fy{Qfyl+LuL+2a&xPZ0}PI|D4wIHdV?b zwYyZfb(%Isq7j>vFp?itYn4Yo(DkCDn&9 z7B(o99Jt^XPl4NTjl~}96m>dc*vp{fx!D8Il4%^c4A*@O4jR0GfSQeYQftF$mwy0; z-6LD_nj;kRn7`yVj?jR|)Xu$cDR~ddNckYi&HN;v`4ZPi+fu4{4nK8-&OWA2zBOnk ztX+L|I50VqAL!N~&@M-4+*7R(EAM)AS~2`kczKQrHs{dm)` zqxD!2@9Q?Nr=s5MX?33@`Y3ey8Fjo5#2X00jmh!CKm~*i;;pE^_8)bTep|gvC^<|ko7TlrcQY(?19(~x@Y{#=Yco_y(8wujcw1lA z;M!n6^TyZmWSl=3s8JPLqs;J}Pmf@{IdP`yrg6`zW73a6C)TY$>~W{Mx#B$;+k!+C ze@2nB)f_`LpRqiFs;vOu>>$4NToSm{c*5zY*=l|u0Lrp|+R_p{8FvQ(OtJyI;re&a zsnK?>XY(boV9vJ7Y+8M|e12*eCfhEvHB9DgM^PneG)G-#X`U?{ascmM%;@ zz9if3OZFsVr6>qvp^Z^gfd`v+btyUMud$1NzSS>RidW3Pii^ zQEP~Q4$$}!qoSMI;ZWgjd zS$02#zpg&OB{9=jpHs|H4SMV-@MijrKRcjgG7UyG^!Dp&PuHs-13YL8t0{==Ev&c@ z%!KNELL=V5vU%($`qVenMpCdO-np6!Ab&|4k!6-7{p+RbOTzWcM-b&3w(Hrs>VqQk z%YD`aYP6K|5q?9)1BAo-NL_)+&PV$wd4<|beDo2`TcHle2Hwvr)W=#Kha}$j=W)gF zI9kpJOphY07!``yaVGPfOzffZvGYd(ZyY~o8@kIyR;8ZN70c^8-cr{Jaeg0-U!}G# zd*0zza|ZpF@>Z!A#DR}!>1wrQ*!$3y(MEo#pIEIfmqI*hPTYU>*=x{fmY?yVIYNC3 z&+pbKRrS4V)n5#f{vYdG*Q>*Y>wFwaP1HMT3!(2dHzn8a<$U~IuByNEjyl_!W(>D@ zoeyRzl+Z!(Q>5UQRy>`Vno<9F6Yr-F4AUC)Tz@qrifJ79gWSL^YAeV>`CYh0ttVdF zLp!&qHC+q#*s`u}Q4dJs#SiuUx>{2boj#;<@2a&#W@FN}shx#qH%-~nUBXXD6Vp0Us?gut)Yh)4(AAuC^>|MW zbv@3Xyv?modQV*|wY8!7b^xOrHlb&g!xj5M(EV&^(3ZojZ&B@t%KAe))FZ-qy1<-$ z=o5FT6+*o0zLghtTMznfXf+q;r+|>78s40B&Hs(Vd~L- zCt>Q5Onn{=ub`j*NX1PCAMd0Q=e0-Zng6PfMJDYu^VtFSK6dfrox`}D#!N(SykGsV zt5Q)_*aqDd?!3&}g|zk=p;jUHA+?onE0rDEJU8WeE1xp!*K1lM>Fr+&Hn6$SWAq8OOHDR*ki#a+WNF)Wd2UXDGl77ncBK zu_owW0q8bhs)s_yjj z(11r6kHALk?P4d3yGvG8a>p1?r;#k=Aza?}!nfgz_X3l4?R{EyR83B|`F;6z(4wLI?PI5Z>MrJbmF8YEQ|z6Cn@3C`Z!O z0}*8x9a9I1#_yZPXuJjm?3rU~b#Y}IEjb3Smnb9V331O3YWbBqHvKzTh%J?ceBgma ziq&JVrBcvaNN%_BbY{BE(vE>eJPv+*xa~68v|Rdr*+HkjQoC?wB^^iIE4z&*99L_m zFSGFD86Vy&HqTA*;l08Q-}6EE`8(+Naa8oLw^R7n*gu;L{l8XQinrgR316ds8oh(& zeXS;@53=MPht=*>o~t^3&lx0d><$v&s7W>301st3FHF$cACAHPoX$Zu`fdawn9&pgywnp7xwk@1Ir{C4lGBbGDdsX=HPuJ(qS^ zaWhJZy9i+Bd%Bdk3s&4?rNsSY#XV%kP0RBac*=?#TMFa1R@}%^;=Zur29*+b$cnqC zl(>(#PBT-HUP|O{i?LHFaqn4i?MjK;WW}{8C2p-1mt@CH^E3BbR%9JJ(l2hQ73VG` zj;y$n*g)aS!fx?h2RPz^g zO5}2Y@U;W%9?sK89)vF4LK}bKZMn^K;um#@DA-JG&S6m6db7C&M%V(YK#R|*`J&Yp zO8-?&?OP~061boi3Xl188U+@9eKp{N0zNJh_7v$UZlQR#2HJ+(u#td4gCkSPS@@#$ zjzy?}ko_yxl)7!E=<^sj{jr&b@blDWx;8_rNjuJ~57V??)e2Z)w?!8Oik^jE(*3Y0 zP;^CGG-y9~7vefeIgMcg-lpZ7^7!z7CTKYPAi|A<|4>zeH$Bf?1ZFidlHjR+)6utQxhX!L|EV z4MOc}7j^@WX*MH_JbC#0$(pS+;er~Iu?E!0p+pV2W%y%ul5*w(iF2(1;*2mz%*DIU zXA@H1z_)KdxR#Xjs)>^qyNOO*P;14w>lnvkcU5-yep2UfI{I-YNjM7>`@0$~GV4%V zJj;7b+C0!2%EgXFvUn`$#Y_Ry!EHPijDvy(x2F!h`MWw;bla+5`W*|6qRdu$ucnqj zb^lb|;tv#`Kh^QhuaJhJ3f3YD|5QH~-YvA`FEvBFu!YY3rFN_k4sDHX--&%%Q^9%} zN4@^We0I1Ioj{-bje&d*>qGtrQ=@GKA627_6lpd&ekJ1}%>s9MJY6wmzC~ru0j&)4I*9 zbppM3NsUPQBHwQ}9K|{sLj8BcxzR9^hB$3A9lV6aooSmX<}#8kHd=A+d(33(p37J< z5SKSm(p3mVu{v=T8>Vk;qLtUwWnr0IE=O0)8L^o%uB*?w@+Eg2`ue*1iYo>&R5wg( z{K^WgMt84Sl!vM%nH?t_{g%zFXrxyvFys6B$75^H7hhz?cSk%G7Dd#cdXn~_Kt_|K zwHKdlq%S0Gyx6*trk2r~(qlr4EuU|UGH}~e`FvU`w0n9R*5lbUTUatXxqQ2mt97?0 z$~|nwT=b-iV#ob2t%$P5zrJXZxPQ`&EW{b0A(*3rDOTArA= zj@pE3BWtIaO5A%hB_8!0o@pp?f7@)UAY|JGVR;6Y`qmkV%(goZ&6JtV1>xh3rp$zO zG^!kAUS3P#VcH!0h}P^9092PtShn38%^CuC(ICJrusYK?Ksz3QxJ6Ipgb?Vws1vWO zqtjtpV!3%pJol7QbWeFr6VI)ur1Dy{@T{kFJd-9{(Y|ID5EB96`v%m5_~xei!dhBT zUYj7g16T`|OVP0pooU-rG`U={!u546a{jQ4I7Lnc^1&0gBr>xQ*Cl@%w z9#&J8Z8cR^GSO7+>2z_-Xxs|3Hqds1H&9Di%Sey6@K!S3t~7_G59BM5MI*_ zbXe9}ig(vgn4%?jwe{llAU3Hl8}Q3#|7>vGi#ux91nL&Tm4mavU6=E~YLk%C#A)y>SSRo!4|vYxs`YB6D3m<3_9mL^1Mv&Ecs zW=~N!N~<2uMab?fPUKNW6uhQ>7Fwm08ybgN6R?>JD7(;cUpxuu<~72UI`m^zElxDfqp)agKo=tr zeH}mTCT{d&Sjq&L+iy#1FO0`D+{8^@k0x$;C$n2}R?9iMidIIWg!av&6L^|}(DzoW zrqvUVufT}_=lgYmQx{*mLPnZ+dmuy z-T?zeS@SG5l07GnhVI<6$fd+-R-An;oIhU$E6%4A%7?Q=W~Dq%$o03)KIhrDsY{&J zMXk?TKv5S{kRdX>$y8e687gi07?NV=95ELUuVguY$f1@jgMI%Lg6zWf^ai zS`#&3T^Q$mxQuUt0^X4Yt!^8rmH0|V>9Vi!LYgbW_`Y4eapI5 zb9@r>fks|UbK|v|qFNrUkJpYj;tVrwVDb;+lDk~w?C0=KQqF3=@@36idP1fu@7J}rsaD5^S&(5EdQchWf`SQgna(+ab ztJ?9f!S%QN;$e&L5U<$rNb}ck(};RnWY<4|!-dd?HB-v@*`F7BobmsLKBw@_HXn~C z-`I2Y=|YMfgc-s4hPV{wd_A;2dsk6dqBcV;U!~7W)G+_cT1ClCwT}9+`dVGg2F))@ zYpA7&AKs?@O_BDs4YkL_&bN6Im`FX6v_ayHw{bZIVm?XIK6Yjy1vtFjkapD9s_R9K zv|&Q%D;agJczLA`h?SCp{&H3^BJa6ndU6XbLvk*It`ECo8x;awXUQfo9Af#n}NCShAaQN0V*$q0K0#a5G(wq_`n$}j!zd84c zk8nkK5O;4s?)%zl&2P?~_A##H4dQNI!mS@^r#&zH*gb*fOe@57BHloA&O*U5%;~91 z3p;4TMf!5O&_PQMO8_n}C&jOzHYwV`s#cpf)bCHrMOfgezMS$>v=c3Ve$#Ao&f>{+ z+jk`-AbvoYuReCdou4L6-hFTCJ5#le&g9uhld<&T1n~$IIXtsQUN;;}c?GHEQm)kI zo$ybC_IqQ6FCvc}`PVF^kVGE$c9bZT0kK!!%s@G3PZiiBB)S zOi6e*F8p|YxRxe1E!GbX*Um}e&=T4?68Oi7y)dFF=#dn52x{x60Y|ft^MH=`J|_h(?&SO;>CL216sIz7NZd%y|c4 z>^DGvJfwXd+t{M4iO{2qN+{P}yG{>Tl)CF-t+^!nk=|yawq6ov7U^dvX-izr-LDu% zsmgcP4RbEXSMOCyYw^cIYV)Kv*Hv{PEXr3#(Wxi3cvmQY=C8t?5tkQG@>ANB@Mji4 zAj%+nicDHSxWHt9UVXB*SE_O$$BOYgef|T&==|Suyy*K1#XPOecK(uWoG5Qkr=Hf_ zRaVw2($N2KM;^Fzjy|!}_K_ zrfY3Wj#Z;19Sy=GE~2H$g54M2?5|+t487nKp7k1EQH){!NgI0+G_n;n-#nQWqPkr~$n&OY84i zIu90e^O=B!lDm<$lxijEWALRK3V0D7(2T7#P)r8Eq%CHt}uk=TP}LJ-m-8wsvv-JjF`CtBywwHGQ!mf^8_(;UipUK^WUg^4gf zSpsu;`#LTnQNE=cBnV44hM;US`!PA{3zr*ss9t-?Fn~eJMIa%E#2l?@`bCs&#(SFa z@Q=CM;`PRrl5kA+zuV&BPbDjW_d*cfrffPmSDTvtsD<|@jL#RM-xjYe(pwn^L4)w7XVan=w5A#T zEW9rmuh|{oHG_V@YZHVw3OHWGRarnMvMWbY;}^Bi$d6yNx?A+!qxYDun|ofQUN35k z#Ne0c^o!a6@%Ma6eo331eiR1cj2!qc5;iLuCxIcuHUbxnlk+Kjo|c}TZ{aol7YU26 z=E+zTgtv1(Et{wP2bXJ@4OF(k1v*?(?FMQV+=3nmVp_<;jm5hpxN~bg{J3%JjX(Da zaHj`xKVoy^)|;>AYwgohth9Upqx05`onBs1D7DgHYi1TU8WVzmd(Ed&*;;bC(N@9M zUdDqX%5CxBh_V-Wt{}Vy^XY81HbSg=fzordbTR1#T9l*Br9LyYN`6TWGT4|nPsZCX z1m@ZyJslki@h#;%Y0>tbfi1juEtoG9a?Vj`}IRL4=2(9nbYOb32;d~JA zv-9weY;CN#K9|ld)Y6?F&&8OcJ#Iwk^Rm`T44OxCU&f+GKZNpzu`$cR0hu22=)IS< zE+Xkg60c|jf)j*Gg#3%a7@WlT3J7*ia7mWz1i2g0o3Chd#KgJ(r|ilDW4gZodvC@T zB$0XVg@j}h5yTz@L5#h|9&4>ZEY;T5R$EGj1Z}mNXunRYEo1AFDyg=HE}E9AuPSNO zQf-N)s#A>RoQF ztdE{XbZd!YYWZu==_^#q_!CDsUnIvWo9#5h_{5$s<8?iwK= z_X@{JNy>XppQ#nBRb=Un`M%Su9XNroLeGmEecp1cjdkFQr@Lk5U#CsaLi)yx>?O>| z`XKDcR5g|w{^d}8xoNmOnD-rB+-DZ($}pLs@x(J;)X)~H z+=NObENn~g92|aa&SXqGFz$3mzmBQLUeGbqa;02fKGp?3GdP&;(Im}ktl zFtiRh{JdA@b6ASJu0I#z#d_-51$1p4Y@f3h=u7FHKZS?U*!7O?SwjrUKSQG2<(tLx zivm~wXeILEmqmeYJrhH)%R+eqQ$}12Q^q2QEmV@^DL#bomH75fc5Pk}pOyrXDf>FHABMDmB0g|T zik`vww%YRA!^sl2@IAfqINn4>6$q}@^!f*m8tMzk5Q+@mY@2?f9^8!2!M&-Dcy%`7 zyxBtDQDle{n)4~mtG~>nvKt(AOa1H_O>{QbE7q(3+B7j>A__Oh)c`TY#oDk7#nL$N zHmApcB=yUtWgD;y)+3uf+2BZ%o}EwEHb5sU=TORrj_Im{xrh}vdt=+{54)hI2F|Ci zK6Es{0~bzQsspY}E>_oth1$Z!5R(gM3bpo9dCh1pwxE*RFgWme0ZayiPUc{E!*fw4C%() zKqCjuqum=Fajnk93Ca4}28}RQ5L;<}h`5)QuUnXF^AvOWwXodMuqp`C4q?!vpGK4` zx1tO#ToRJ0x6k3qy1ihXErP1Zj%zM@SXh4CWEpAeETUY=iCCoX81u*gxhoMag zg6nC#bUAgDNTHk1gPfg1$(tN0_L4b9uj%JeTjC#^t1a=RALr8cO&EacCt5)f5J;z`L{09(hP(5tK)tN&>HaiA3JcjV)Wre9nV}$;(PTM|yvVgaD{^fL- zW%HxJ=8I~3a_I18M^aWLj>`uA)>8bfjF0bkwS2CtGGBaf9Cv8)_Za<+5I&UCgu5by zFE=onprykb_k3Mer);E$ttAKIfGAqUJ|aRCdU$Q56YawHNMp-;W-dMdi6gN~6auC4 z!uKm+{pHN3&@0CQpg(sX_~!5@m=Jym46Z~N)Tu!9pdNLfrp3*(>GCIzhFNWqXGP6Y z9A<=vh889k;s!GoerIrDYwFByMLaWm31Qk<@N&zeObdS@+6AXu=DAMIxsJaOHkaXE z3t_Jz>=ff6%=?9_qSmNHly+zit^3pwA3X$sTr;DvO~5s?a*V;e(47AG)KMK?F5VVY z@iRyBs7b*3oUxu1pY}f4{%PjpC}=m%p&_544G;CuqR*gD=^onfnPY#}pGeR0IgMYo zywwIznz3w^nD<}s$s_v1h||J4f~=k{f1DY%Rm}UsNH@w1JB}R`goT?}ka;oUO09ZQ z-fn!uSXR%!#j;Zm(7(rsdE4>LjBUd&GvW47@)k@xcg~^3TO1u?9%aFQQ3e9*tjS9g zFuHnFz|{?N=)x99a*8Hs3`&v<);zB4LcOwE0CPol*}UfX)vSRWSE9!?_Rx?o95Kl~ zSP53Cc|6FmG9Bbf13rf_jZXZHzgZBR=7(&`|H2WKQkla8X$mbh1q(B1Rt}`;)Z@zQ zG_w+z=GIc01tv{|G0o~4wwjk_&|Hg(W}kk)Cmi_UviYr$;A0iiu>3Y>8I=gEhL$u- z^)$Bpf-G8E==c?e#Ed4C{iUO)x`lPgCgy#{zvvK-;yWGmEVf`_8EVNZI5 zhdOM7+K9~a9n_|ahgNQLBxn7X(*#zbORuJH!5gd1fAQ;A8{DGB{l_*V%yb(NJGnM< zcm%2}P>m+B+Gdxk(IKXVYWo-YndZc~*Rv=d4M&hL-@yQS9+whhFiqmfRR&`M^qCoX zJCG5N&dAC;Fmeur19hv1$%vs_n>1`S@6hbQIwuc+bE|Ug1-M_@V5l9^uyPGRxYk1e zY^Nnnijk(rY)abhc$6A#a8$xBgFfLZki1|U&Ci_bWDdfaQ6OOGFEIC%Hh@)5BY0cV zPum@tRtO-gg$pX3ad>Y^S4p*IZF(%Z%kp9{tx=h+npDVn+Wm(xQyHW*I+) z_&KeBv{U9{u7JslAcW<;Ig7UML_2}>uI+Rr+1i7vk+ak|@`k7te0{%lMB<5$Su}B% zV{GGG(V3)-J~bSh5QSo33_RZj()Z%IN4b!E9DAbGzD6 z)_0E1?tN%)0$Xsv7au<{%Vex8az#%dDApBd|JwlksRj6W7KQG1%nn)4?DFK`8CtU2 z(KkSdg@HggPKU$APg_7%aN}noBJIFAh7jNBxOvbs)Nqd@-aXA=_HPj3(!$GPW0UM#nA%nFY4+>;fYeM?}Y)6C!sd3iSV+KaWuuxIG`y;%AEK8rT)h2Ks$ z10So*%{<4<$8JZb**GNWaMP5Xj#R5}376zr8O2zHe|b(X?C#p`F% zx*r@-S(|2{Bu7B)h`z{MQC{dDW^lpxS7+dmRmFhs68Kh^Gr!@MoPlqf`Td4C74-Vw zf^=9)vDL+?8Th_#ey>J6MwTn)cVi)PY6b!>ngJPtc478kvuMOVSY(eG;h9`x58sEl zA4bjNDA^7a%B&h*`<`qB?OmX)!6@}yzo za-MKZk)-75x{YhoNk^egaz3S-wq8ArO~`sr_|~1q9a7S!>6G**HkZ3TW$gI9I^CE5 zC;H)-dH~}gug2rosc1Ti1wr!0Bku}Nc)ax7IN{v5mrnfUcuKnXIG-IqsXmA-+S<<8 zzT<~hdOWUQV3l*;v49WkCsWu3hm!OzsAxj~MtTS`olPt~I6Dsup3<mSocZ=U~W@Y)06;{Z^4@tJ)%e-@ULYs7sav@#ca8=n9X^IV7VeD-tG z>GB0E_O>$vm}9N#XfE~~`LjTW7nozTd^q>YbHOoU-lv?_hQ%KK=8g70SXB7?K~9J8 zRnxB11^#=F@U(Xi*1EjQm0e$-;UW*)O6bLw`1;zUqO;z2xk^XCY3T*o+bL_9KiRjnKZ4|E!V!Pd$JBv}t^fB!&tuIVwr(AEzys z9RJnsBzs4s#{W1f;#w(Z8@-airDkGqVc}@(x@zD2(uA?=%HO_6{&8f8(wM3IbU?8* zdK#^~hQ7WZ2wiiGNpaco3SlLZ3iV%G2`ponUgTiSK4z-cLj6;yh2Wjj3WYY`lh+-J zUAj1#7Tv-^@bqNbz`sW))BanIrBc#kA5W8uMfb-j6?eTYfW!k7ny!Y%O_z~Gr~a!` zMc;q{imx7ceR446tE0{`$fF~tS^2L{vlSS#*M`>Vrd9Lbx)KDR)OzYM9e%R}e z(%JIzXeoXQw|${I1}UN7!Z#EBGCfz5g^Tgvq%?uIN>0P?q*17CwzZ)lRaXkJ;U|*ukowDCGkpk zxqf+R{&0TQr#c<(Cl8b!8cq!d$uV>=T^{Bu=r1=GrJKV7;*SpF_|ejiz`*y6z{P=q zPiTQoN@^}U=tYksy3HqOgj`8;*zX0sm^N&h-!5F$YxKxkd?CJ#9+|%>cd-17+XmLT z51Ka=MM2-_379u|vHlRfW%KygR#H}k-7vz&&7*Y5&Y)o&+#(1J4u{4iYsFXb&CDmTWd96Z*ucc@&b{pF)!a&ytW7u*UE z%77tAjmhLaxkgJpfw|sh*c;5WJefQ?l++P&vilK-NMyWcVJk{ItkE5;5di$xZ^jYE82jmF64 z?q&dfi-NGb%sp!cyP^s3Bxqy-95jT|GUe11O{dXR_*cT6wft){EPVO1NB~d4t`%s3dOTz z{UXa(TnRLdx+{dT#>%70X&)IO^xIf@tp4E%p?>4!_Az4t$a9xie)$W(OmH>8`0tei zX~Q@xrYcO>j zmTZ@hR|R#(rbdk~uYP~u&jXAwq!nNl7QqRx&dMU~id7IJ^0LKxK37jRn;Oe%=`Lva zW%Fckt<8avZVvKj+Ys483oTItB;q+Y#??|gD*(zNli%`(jE^BBkG;|>*u||k=(WZpCp4(Yw1mCH z%>!u!XC)f{usllYKiIePVL8NRkLz#J_n_= zXf#F6KpI0)N}Wb1wU{Eeb=O6JfHwCYm|>4CGck8IoKWOjIQ^iQ?Lr;xm}iGsfLjcr zEmP!PZkvHOkMXe4e^0!2=nR4Pd%s{ts|=!nQ{}Iu!h!5CRh_Qw#%)}=SHkVSKGS5M zXf7`bo{%dxITu$F?H|lWVVH>%;{1b|_U*y9F_`f;{rQAE*xotakZKDpjfsKvVi1P; zZDN?;8S%9I0i_l>AC@DUlkdW>3jp`-;9Om}@+qLq7ME zoEdT+RVAQ`AL~aWo|Yr)mT1sLI+MC>!wv_>1IPtN{VS(i{b||LaxdxI{&e6TNyQHi~|035(-!(TIrzk+6J5AR12Ng`cukGxmU=@N7(T$|GE#<_yllG-sfJ zb`Yd*D>*AXOAhdDEby8AD8z$l&gDMZG)Mf69(_{IOexWslQQH0Ch`0kROm|YUdve)&}n9jEnvKd-B;EyPlX}#aVE>v8o~NRzJ+EKP|O{ zLrWIr$ZB#er03y;SO1#r1cJ0fHavX1)yrHQOL@_Hy8IQrXn&5J7~h-u3aA9`Lbwvn z7~xHgO1RpWQs%)z@JnB=gkJ9d0-NREozvZ?{J9CN2QQ`!xQjZ_m(u1#{_h%i^%(Cy z<$nTrFIn(>eQC>l$bVs9Iy)copKag@jC-H*-v%$?ObhM{z+w4!u*iR0UtRtaklrf) zuAs^C|Gj6a{72~N@=x@noeSg`sYhRSB8#U=&&nC@dIq!aqmr~Mt^>?L+;sk*Qa9Dj zK~*fww(3h8pOuFsyBP--k(D*sJ}BqU0R9SmGgD`9N{CG{94{b08|jYqrVh`^9iq;F zVgEb?;olibGr1=%drlr9ebYyuM1O_?vJ#{*9eB^8VslN?Huxmt;0e4E z_-0yGf}MS6+VgV5p=})kQ=%i z88kj%8v119?ldqNSq&PBg+|*xzPErUO8@CeH%BPR(z8A3@JyvTB`!ku`(AIFv`9{t zmi313v^?GIK}op=B&K?wHIM^$yKy~&YhY1t8vT+y!adNyJIE5&7u|O+MNLQww+Obe z;AQrvkX$tD6a#M)<3ZcZS~t4s|F0ofMQj6Jbqijn-t>GfnswFQ^hvIKSo*gIEzOgA zW$i+_x%|BtUtcBNonKxh!98z7_u%p$V)-F1w-0KTP1nm|=H4pg4H$k)TN-HE?2+{m z7<(?Gksq%K(fGx3bN6zCi8yBBKGo|4n3!i_;{9H9azHN?(Ce^X{a+ET@Jf zA~9Q;b`PZ)i{*Itc!TKgkQ5(RxTj=WV-8Z!lit%p^od@y{bhN+6xPev>lJyaWP1mt z(43X4k~~GUf7A{03EbXXojl(vPRi(4rIPQ5SLHV(`?UuUgB!VJDtxC(d0+19@*{TX z3%7P3ux)2o?KPTK)VNH=C>k*ycaLoH%Fjqobn~UGkdKMBr`*P&FZeY(ssAeZg_zSI z#ZCR^E?7R|Z=M?Qt`FZ9T)V69<|=uym@*m>+5iVxjKtqrlJG|yJF_A2OW;WJ6i3_( z_*+Yd@B!Uu`x<$K{c8ZT1EN!Us;mA+>8o$a{j2|lVAFtSzIk#CVVY4bqkolZ^yr6G z!l?1vuqbwP(}=gxZ(r$5v)`6i^g74=9Xo_VLvlrzs{KlZ`marhgvMYS9sWFZ0GJVA zmg)oEIgfy}Wx7M_FxP*V^4iKW&8jbl`EuWpdz5kSff!l8`!b7-aF1?)b9Dyho9K52bwENuyR|uJ?ZFN{Q=W?x{_KT?{`-; z@Lps*n0fAr2W{zuS9s2M43=NDuD+BHqC+W%dG<&l=C?x~8 zc4M5DO7vfwlW(Yoy$|)jrM-q&VAjY<=9s6$B~^VDKarmhZI@l8R+CDU+Xk2Ezj;9} zM+KkCUUxE*3s8iQI`{>xL2*aQFk%L7^~SGGQeP(I;80ps3t3ku-_pmd3(G0j z!z^8B0PyA60RRaAsB8gft^*VZB{8&Thdc~UWqR%cNr>g#1t$3ftocs0)dZ4jDtWk> zTZr|I`LFz}*tRsgGdMdxHSv@syO;HaebSJ2KnJ)z;1sq@Kkt;o?u>H+I2jh4X9IBB zGEPQuSXJ_VD~AOX$HGqz8bVhK&g4=Y`t4h}fpn=Ysk`Jv>41yUc41I%hy(%}MggSA zt8FNUCJUos6o@XTAu}hc46PIc)oL7Tku8MUxF~-YraJ{LI>h*I8TdD#5{#eqKj5>y z<#?Omda3B5N#DsSwhw^QyN43z{=onq$iRAwzB}V+wY>cO!~%S*9YySxyQIj#^R|QI za632-+l3}8$_V}6Gibyn2vePKBYNBXZYfOl!i`{6J6g0GW55z4yejkZx^!9+Zm5_HFrrV=1`AYDu;wuQE+tBPiX!-Ti zbSJjn1`pq(V(z;lF-|tO@G!g`B^F^wm04(nbZX2faQAeHF9HdnmX zka@aL&H~g33~5aPX-~K?UBE!aJ}X~U_7uO-hOQN1kNKn4++jTCs9U9?>uNYSk1Y_- zABSYmr_sRgQMzMkwD@~SWLX-0^}ReI^(2U}9l8aK2Bs_QXSl)~l1buq)+8=HekB;m znYid>2BrKdt!YTH+#;(`|I7eg&3+ESLOZXDm3YY}id8q5#W-JR^3}Co>TkLwuQPQrqbPZ`E8nC8}vE_L?+B75ogKenG z4|0+^I~7cE9&83M2FKTGNArJ>Ti5W`)XMw=*x}$VV8g*~I@z|oL2c;p53-ta3F7u1 zm(crriodZ7uV~X#q-_mYRz{xt?$AW8r`duuuGW;aPfpG{4!o7CYnVTZr;E+j5MX9l=3{tYkcE| zCxGnNLGp*C(&>G2-zo)huGGMxx`2A@m#c=p241!8A{^FSl19_^%kfDsB8;D*(8`QS zn}E30f%G^Gn+wZRY0G{znCghrhI1LicPSlxxGtdT2QZd#D;ilK3JH2E^60;|LcT>6 zm(-(67y%Ts59R@SJ|v{IBBX8IPM>rOuF$**NT)ef{vKeoaxaRHNlQKyede=S=6qpbM_ zYh33_u0$=j$vsbMH(PQaSMvSH$HJoIwZ0 za04NC!jp0@TYx`pL+cL7vqKi3=GDrG7ZCHu32#uhVAy)AFH8(inTIkoPlOH8`)kB^CcHCw3?gaq<}mK@if- zvk>gDDj9O|eyaQBvSKv{-cwv2<^|tz!2G8*rT!w%?r@OP-v*}`yt910zEYerzhFv40=%n>=t;nCCNm&LDsL)I=j(i3N? zGmglO9>_IX3A8g%CGb8Xj4i#9#Z(<`B~OAKRvQ6n>$la%8sVvqn;RgVHd}bWD8o*c z17-_m<~!;gW(%u9sG)_>z}D2E1lv5d&_|cZF=YopUZ1s~{1Q3JuAolzecL}v|D;)@$VpJqlMLdo@JRxr0hoU*ltPOHs;gMH7$1T6PT0mwz)_(Y52SacoSX zxhLe#^wW=WrK~%O#EyfJH&cQ|k_c&=BKfJc(Q!Z|ti^m?(MqI;d3iHT#JZN36Z&6; zbXa@XFS`U5ic10C8B#M0%Vq%I7Y(&NV}8RiI|JXpo8NHEE)opsO%AHwp$ zqWhlW$D%tS8B0)0p-uwFi?}yXAOX{W9y}zX0PQiah{r$fJvDi^(+gD+sU5YW>t9r< z?Ectbq6IT?pE{6$chg_DFtN22Ejo!g$zv({%xjT>8_u|xLf^A+=xgja7y7sb_l;JR z^qaiIcCxv#s(z#iTz~%lO@1U%GMWx|Q-2^EyD*qH(l^34cYz-__su^gC*i^AmW1ny zs?+Y@$dP3Kw8F6rFEqa3>=6_<;!7;J_0G@*8aP*W^WBft`;5xn)N z-am3r`=%yF&6X2+iys7*|06$W--UddZ+E3%V3Ons!&VL{*{#O-(yqdHA5x-e#J^}m*~!{TfbJ_8U2i+LNB1UalT}`RW&>0oby1XMDiijzuStP)P2)q;!k>?(>ol&NYLBbW6Qx2;e65!TM+M7u~| z*6lSfCWi)9TZc&#(Cd2q(hNP4E3+3WQ4H9cpMyGm$p<>21-}!lNzPm zlsYGo8jW4aZFR{Vt+eIikik@JXqx>jRA#bnY7@%FzXQ zYQp-IYie{RZ16SwDx)LW!Idv&2M(Gv+;|Yeb<1pXSI>AN$iWQ5Q@id{= zW0ZpdxeJ4H^J{MdExBi#xeJ@nd$CFl>4kc0CfVEiD#q$p|b~f)nGU1+kxr zC?wM$r!x2sNVo(i5UCT8>=vZ@CQ?Q+U34ma`rU!2ra?$KKsr)8SVrYcBwWGsS$zz3 zjj(9KakFamXi1!scLx@o7GRule9Hp7o0Xb{?`%pB$14-=faDEEIsv4a7Nk`s68inf zno9j{w=XPi+zAvL-$FIgg0#RyLfSScEH0Kt8!D)&MBa(JU`#&vl4ijiXJUGrQN;wM zd?+4<*mB{ov4rA#{x7v0O-AX%5dq`L>>fFn=(50#Qbaa_t_0R z=`}3?-Aw?f!jtutCgDAxZeGmb(-AQp>maIB8@?t#)K|QBWzOEnlfEw@SWGuqbB$82 zZvah=y&H1?$hQC#n*d;LXhWq|$bQr$FHnE3?R&nVGR|&$3jvyMg0rdeY+0#)g63=> zjg0dhZl$EzC0|X7NmDMw#MIPhYT?f7v^5?eF#513!Dvj|hdO-?+bN6f(zJM9*`?4w z9hFS!Vl0j5q!dfjos`^J8K-uNMJ`N%wbzILp1qfkk+z8CgJe(mZq0VQE7Gp6O2uZ_ z&1>hkfNE=n44ic_&bDaZCHOWrE4A;!GW6FIxVXH|1B%nWtp?^`+GPffdn;ud8c}n>~ZYU1~F9`-`chM~t@RJZcGa!@z+^u|PcXCNhKj9df z^nR6cG%Gx;64mOibd(-(vY&4h<#bp2yZa!ofHhQc3|E10)#QWMNQ@~uTLu(P-$dgD zXo`i05l)Klq4aVm8F*_M50;91;=x*#gEd#U1+S%(KIx&%7vaLZ{0XKNbTM`Nt&K}-yjaTCM*HZjbCtnQD3?2p#{2fm4>&;iPj|KEbVX-2`?83n_28|)v1g6#wS zz=GXi?bGV59jzar{DX33Bm|esQ#ZI=LQ-(K4h~cvv6l%hmx*DP!^AMZO$@VKuMSc= zNseebJV;5E?9sYk#I^^NDk)xp%TOfY+5-Ny;g~g-Wi`qoTguW#FH4c&6zRjk%GXhi zQH%Us#>z30c5pod3B34wcQh@2P}wQ@s?mrcO2dXPAsw%{n^ZHLxw56a`ZI5p?ou%Z z;y6v6YQ9f~C@V#&QFR(IOi4|i0515{ynZ@f&VLmxV+FoB@h*U9Z+GB31^|3&UWlfh z!<79|C#wc*gCTr7a5&F|s`SZlrGtdpMFYAib+4v7Xr@)u9W;B5REAde;L*j7IIIMl zaPw%|I8y0Y*{cV!GhbXZmCaB_xEr8c0=kg(OuDsjRWO!h{w}Ui6Ka7jRCIBzVe`O} z$N|>Ow5nX!Wd~#JZ%zb6faj4v=J=V=E4P%?Eb-C6mZhYm$ho}PdJMs zDSeWX9`dGv7pu~`NlIj0YjzACIT-k|E!p3T^qrlg;6|LRNV+*$No$5)FgMOwx>c)v z^TefeqLLej8)^c2#R8f#MVVmtI*eX17(?$Ja<$11W0>D2hW=eZ^`|OM$tUZQd`D(U zCeXU6N<(Rn%5s||l~btKG$jgd0$BWes?+3YN^|#{kRQu278T_ke;YY^%W$8QYbz@;PPd$NId9)iMMssF!Ttau~gg$%(Cu;9&7>8;0hxFG^li24?Q{$PaD2;Q>P?{Sng!QkvI=4|MFa5faX9k4-#Sb&pN zDt=r!B>qGnJfcL>wkMPy++IjefE42y`*zxBEj6@pwTydkBZ8&4PN8Gdm16gU2HsDg z&9-Y((tho>;$h~_+t}?ac;gk{%_o(7+zJz+cc6|4A3WSwiXkU~%=@5)BAspJh@n1@ zhuVE>XDQWf_SIoQikQJ0$Z)_g70**nS7!5DD6cEC@lDm|D1omc@M;NXU&2Ojtr-DbCm%U_P7$(+~7wZ1QrB>P_aRwI4X5N6lp*e#oC3A82BkN;4~=W1wu?l)whbz%ZFC=< zaM-(og;JAn+W!K^XS;znpYd=C%ap<$@dlye1>WgO!4iuIr}P(<-R>={1>n!ccsPA^ zPrTmHM%W`)Tkv*;(ZogIZ@GaN$9UcE1Ft*E3%q$2y!XTCpLX3H z57VwpoaU)u!D|vm`*W2;R@& zjXcJl3#CJOirf9Uf!B`lunlddxufb}8?O^gimNPm--h}oEmq>iCD~YG_#0_(V_6L= zUw2Es$C$p>NGsEUmz9s*H4TQ=Ksee{3`UE-BSWx)vGJ~g1-MBl?SDlX=e~l1vA~{Y zJbn1Pd*xvG+XlQ}LV^WWCY0v?M@f+uhR~M(DAOc&2rnyQeSMcGHSb<(_@$&9JNaLP+wQ=XElSEd=S zDe-C~0=4rtt8||*cIpeQOdDQP+|pkmbn`U@M=+EO z#mTC)oz<9^yoHs03zsVKHh<=l;LO|FKo83YXFkW(#+geh)A2Wz%Xi9~(9V-S%aV6Z zK;E$B%J0&_a=vTJ6&!}Df|Q!UaobAeglJz|7K4aqByI-%Znd&pnpxI2X^oO~V<)`f5bry+R%s*JJ}#$0RU_9rWo>M2d~tKEX1`9mfNEMOm%>7s ziLla#99-*_aM6AlVcJ6u^hkm7nVNx5zj+cH$ynBW+s{sEA1E7b586r}aOj6us4_zQ zW`m=4_)>acqcJA_+P4typZN1Py|Mx3kOY9}$0@WlCI;qHK^W$@iD7(G^$%eVX=&HZ zA$9FM@lU0~50#pwb7xdmuILJ9t;m%M^W*iD7=57-l&K zZ^XP(W6_umV&^Nb3+VG-ffRU9L*;3u;W31Xik?8?m|tN~%)W6qA#@}Yo_&$2ZwFu)! z2YuytD-%R}!yDJ&kM(wy1bTIk@a|S*c5p7b&Z17RBX8<~avvY#Jp9 z;m#e-g@O>fA3{T`?Rr(16`YZI69s)A z9uC90x1zx|%ZgA+_SUF|{F*0YKpaZ|ac%M=ZWH;Ok+I@!;^rE0cEo*AO@SxzUZr;& zyy2qseirkkFEM(@;XIhu&l=xUv{!k@w&@x&wUDckr&dJy1TCGJ4_2$7e8x8w{-D(9 zYL=e6Q%y>RRdp%3aFh~~uxZlL&naF44KqDUtA;5pS2b$1PpNfhFdUW)1UrGc)GMA5AS z%5ze}4SN2daysO9=m&RZ595Z|AC<_qs9%(#K(8V6g|OWwpx@YY^%@lh%<`@v8@JN; zZ{9?9Pda$_ONZZV8L#85a1J zthHc6$cUoopOoPt6AU&_U(?vEdmA=+@!iXUGyPxs>L=x8KWR@e>20uf$5^s-F-d!( zXyMOFw~#6Z>6fq3;h%YV8HfQ1VL8axjbHgESVFPrIet;Pgq(qfv4AIEqe;KqCVLC4 z{*ZmICHwX3wC)$ICU+az`=CO3HEC9YF?bb-R(7zOTn)UBEORBOuxl7J($eocX;6iebWSAu1rma_frGOW~rghNG>7i{DO^1{!>O|>AsW+Hj3Q@i8J8}!Ey z0fi~F0AOv}$^tOT1SqUdu_qK&a@L?0C*VBR;~ysnJ5=RWZEw71uHxzi~RT}-970^>7s45cRBGSnM_=pMUso}f$ zn=(Lj|Ba$?5vN1uJVk?+7x6G_XnC%o<+=WD2~#wF`s&anO=MbH9z3M0wD@IW+YvfNYS&oA=N|!5Oyoo%mjPU2hh{)mQSjER4mRRy`G4mGIp!ZHI+x>Y< zg7bE24$ovuUT$p~-I5yg_8-ble_p{EL^rdgCq2@Vx1E_+aMIgvGb405(3&0KNt5(cHFmoO)U5KY|&MP$reg|ah5wi@uG{qa# zp{S!(Fwt>FQHal5i7=iKwn3hc5YA^Qz2$GwCEgl=dTWzayQeteZ%VzOq=tL|CK%`C zOEmj}64zVPX=9oRQEAgmEV1=zW_Cxs{bJ#IgUL0fndASt$-}iyi zDdb7GM9(|~=qxMr_ZI>bU(hIyx;rsj7f<@d3&9Ez9YCzbCG0qRpm>**3{5e*>0=1` z3UCn6-t7-~(hDs>r%=b5Vj%6CR{}&l;o0H_7fHRW^t?NFV*vV^1@uc3)EP<3FDq-@ zPauFh!z-*2xGv_Nona%aFWs0#T7a`J(V{C#`+!&ZST)V!>O*E}_cjpsKUn}WP0o+n0C?52`8IKl zjkpcBiK}bGy?2|qcq48#;x78W`$vftrJ?72XRo3yS8Re(X|B+NJ5ulSN>ZmLTN zkQfBK8o-hTILQPS66yNCN@wZjIqGmjNs?xsqe(ZEiNSyw!GJk1(|mR=n9~ywfzD|n zIc_R(>MT&?Re0<$n|>>=H#+aLbL75>_Au!@O}mNx{L$xW#4NQYeSK5uTJB4fC(fJ5 z`+O?Zy``)V=D}Gzs89)5eYLUhkZJPZto3sO1x#b#Tg9?;>ABI=+eR z`uYDHR&loFA|;DzL)+!Qu2FBBs?bxST3`D0FM3N<->+Dpb)0#g;^=cULQ;p*@(W66 zLsuOQRnqFtmOloYiP^{=Sa?ZVcha7SKT0SWnxRcqJ_bxCW9Gu z>406`QMzv$tWEWTkP@)$*#Qm%i+YZ=i;F7Md;549RlEZd4%KlgQ{mZ{=t&FGaudm0 z&sV#g+7oV#=Y7-5tHZ^XMWSA|BFR;saf(bFK8vvBjK)!}*>Fy>YVhjVRi7$`sEq@1 zmjvft%{zyd+`G)&CG~xeg{a#CiR*2_PkbA8qiR{Q_cXI-B+}$c>VuN!4DGC>j%r*a z>UvY;*BdMxPX8IqdW4x9dNZ`LT0?UFNi!;|9|RO3qd|}WGHb&)XF)0A%4Pv%H1LfH zRmX}_4=@p?x?{eB$o&U&@wN-BTKxqqsVk$mP5p}|J*P%VP5+`^;cAqMO3r2dXEke% zQgX-X`-5hOt7%!2LD7$c+gj!TCjwM?D8Vp-fAGZtz7wxaRYEwMOgRj@4x7sx>0&>_ zp=G=-WjDXQ`s-4H`MnA8I0gMLcxK$#ZTjm{|D3%Rs|UQIpL+h=OpvRedOmlShE!3L z-N%jav0$FvS-3#vM4!bY3Jn89iPbgSSrRaN{_h{bm2&(&JRZh*%)u=>9~?!!WSpg?4mGLHKIDNMwMSb;zEc5dM1HUp#olekJuXhA zl0RX(6J<406#%!QCgzjq%j1|u{N3>nYACBQX&3R$&XF7^a~%Fo0gM5wJw17fs~zw- z@V@vrPGb}EhQq9~_6$7_3|n>JPreWl)eYg*kr%3#6b@C??)<1J=0)mZ`EMeRe)ox( z7h#0GYK9?iWh3n6(-f+x@pcK{l>1;rwQ{(3y<*sRrU9#wOOV{L~LPrD>$B=Q=ComRJdoF;R3dy zl)=Kg9OnpcPPZb}HByDM^j1~qVK_?83cMIxc`t&BVcX&bC$ytL#8DLfwc$91=Hzz~ zb1c|)FaM780d}yMGZbG<9VmtWK{KkUDOt%V7&kKGlzl(`TfjV)T~kE~S5_i^CH~fE zcy#O+fvMfRV}t*bU4IO-B^t9asVESQblHLF%IoPG2B(YGn0-1hAqvR_*zqU1qtvLF z8i-rbkzWjOnG%v^V@OYFyV!UUn3g+lv3X-RdpgFD>7Tg-Uq zqwa}^)?|l`^zx}-j${6$_!??2Y2EKMt%mwZ=vI!03op4vstpNSO0{Sm1RFfA#KVVSq zkv)>pdsNeV4}=Bv9L{Ju5~udp#Dd$tOtIihB}3``11w9hB(JiN`_?3fw4T5+l=Bpa zpYlB)k6FM-tyCqp$o&2gDmTjgCyjp9C^5(NG~)IkPIJ}p$2s!5ATDSonl0w7zkXB0 z+Io_DC8*u3RhkjZdk#*>hFEy#eoPZpMpNHU32GnFis1>ySPciJHQ>%{D{PGW4(&@9 zcT<|2s1CD26b3`&!2CPQ0gl;;*|vBZNnkJGCE$7 zISp-~r^e zn+FM@6LP0oa*sB1JDXE24BU#Rw0p7j04gQap4 zHLVp3HTzx@wTdXwN!pUE-mqf1f=k9;NbN0H51Cl5W^}8mivNPy$p|jq2|(1eKy)`D zGMdwq&D2?91-emJjr3J&uI>`0gyVE51xr^8u8mb93`QRw zqh&4CmD1>AbhZr|+2B@cr!HQs5JmLZ{Oj+rVaEFIsK!}=*|aWk1@oE{oooI{t;a6V zdTfWMIQ1AUYOBU9NmV;Fy&c|G;H|RYeOro0Po}C*x7ISEk!p;1TWY^%Bkct9*K`ZO zG7|uAVb^P|HjomI(va5b{9vHMU?8@mrCNYSn?QvvDY}h1B+6MWFN!Cc#!yjhf;P#_ zjl?ALr8eqt>B*xkzah63UB_Oy4yYtpbRi}Ii0+GDgGJZ-D2s0N?ZpPHO%|*YRz$rT zsAihlS5h=)RC*!p4wYH6k0;$@L3yVXC2x2jN0FZ5GbLJOQnPkyC-?1Ya}@vwS^#GU z05%2SUszFKtk5;2qNn()68fs0+Lzk3RV&<9ZZ-SDh-?8J5C9rt;c{sSjdrOIYJj&D z-YNjvEP(Y&0qKfMjj!curME7;Df=T@BG2ZJ;u2Ip=TkhzV@fEky*l>JgvO*}`FbR{ z#?N!JHfrfedo{7Sx0KK_gU}qT(=`=)rlYoQFXa2tO_70cf<`!rGCQcThE?oQPjMJ( zr-M4+&g^XMhu6R@?5qf2C$^&+AC=qoc9Wq3N4SlKc2uWiY4yglmEn*e8zGJy_RmcG zajXLzckniGy^Xl^<>#Pj(pIUAN%9e3W{1#gcoRfp?0P4_A`i z6A!LPtAW?Ug7^4Q+Syf&jq#@FI*NTY!C6IH>hnFdx=f;|+ym-h`n0K9!KF#p95{s3 z04ZaoIRdw{>hzKE(oL)1Qz^Hn;k|guZEmTb*}jlulzj>0>P@FP5VCCU;lci?%3)d~q#rmaHXLn7!xvVor^}|M{>6gJN^s75ot>ZoEfBhWHZ6vyto@%w~xk^c$ zQURCRQgR*PHR!RP>SuxMH)Wyvg^>A>C;e>;>>jRlO$beCd@qc~m4Bfny2C)nX zn+2kt34sajl|Jf2RtS9#;^!jaQ9OzEQ?M{^v1)OtF$a0Oui8Y)`H2qoRVTW+8{*n( z!L@v!wRHjnUbhg~dYBfatC5n>fZk45J4?|&(b;shgT`vxJ8EgdWW0NALDKX_*U~&! z3AEnX8&a!PUk#&ze(DR>!dvt{X9|38Er<`8g%?tN+5OcfqV(f0v~hqMD?y+K2B_1S z>)r#^QEt`&mPU21f!6n-yRBitnT~18pp^9x-Ys1DK2p*oyVG<1-9)yjBAuGi?tYTX)wkOIl0)Yo74_T&f+v-pd{CVu z?EqH~!pd17l%!JaA!^;Gi9MS8m0(X7g%I*+bL@ zAuAEci9h?9J{h7$rNrS|8|jennCQRgIo}JQ#fbA;?T{xQ1bE1nf25G1YCp+UnMMv( zb7Kqm${DS2cypb9ZQ4Z?Vt)H9>{0zfp~KX^0TR$FzElDpPkJ;c1xlbJS0l5H4v&VZ zP24g9xPF&#xnZF*6B~U~fzdY^py-=mq00gAwS&RH@jp|?PuV$lOy7!y$5}VGgL(^gWEl7<w8UlW&7HFsLwOh>(?Y~y~P%P39L3&oG ze-VCUQbZhuUknp*3C3p9-^diYE;PQNXw??Il2Ed_T>eq9)t&_glt&}V)6Y}X{hPGFYHJN{v|E`+ zAQP)z$q&e^t6ovSFrF(Gw&g~eYZKD+7Qm{9nW6fPV*$23*MiUi3czCtxe(LUAz1QTr+R z33Z(9BNO-lSZ7f@_&)&Wz&!oA1^Cx}RCccscD zfNw7}Cx0L9{zr|W-05o7tT)WaW=L!o`oC&^<1Gv?c1>R~zcag)BZW;cVnFykNKT}ctNoBe`X&gJ&CFGWFz7{>gIlxgirVmut;Xs zK6>j(wL@2K3xSdmvGnX}66eB!xsK*H3d53WXMTfOmK1C7OS|PJ;~E+f1^)wceEwCo zFxLh+yis{!|4pi95<@jHF-5PIvix_YeRTRM^`x|AAKg5w#?!Mi)k?!WSX_(Fc6t0O zdG%i#F1Fx9Tzmw7!}pr<`Bznkpktg?K-!l;(2K=~P|#j;?D4YO6#7E8vt4P56IdP* zhgCc?)Jm;QGMq$m2^u+*4149gWFez9KBN_Jj^>*gn6EAToV%Mc+{cN_Y^WqO_a8LPsy{? zBp;QE=rx#G0syN1|I<>I4Vo54sOU z3b^25aMK=|;eoYi;Y_tcu<)F=Al6S{pYQsfVECFQywgUJbJVMqzk()n#}&Iv#ES^+ zzYLdsP3Efc(rw@^l1Yd~hiifF2sDj*T&O`gYNlc9!S34BJydp{I-tF##k{-5$wZ4l zYC1jXKkW|Y*k(d{rMyjhG1qUrK&>iO+0A|}QB*WfU3eQ-1$&Sr>^M^Yng#buh*M)# zu+#GSu!Ju7o^H-p-O}3ceC`G6SE6)%H-$c@c8HmcD)Kw4z^XP14OzfQ&Q33X6zNVc zCyI2Z7mQT7W`&&uMXs<3-?7t6H0^s%t*JT@=m#@AU$z!e=<}-D^K%f=JYDMPo-Uj5 zt<{aut$l2MPeGrIZtVl}TkmuGzi)o8*6Q+LmD=fEBPbpfW%Rze<`C_HDvBOWQbl@u z(JeWvv5_m3y4sMcE>v5?m&IxHT1Wvj0|k}}xVw+AAj}5> zQ)IN(#YUr<&~bAcq|?UcK?bWovV`*ac)(zWJxl4^OU9QFQ{?S*6%3hMY#8^`;Ml)2=9O@MZS$Msxw5}Zsh!{0nT7$ zyrfoXD3sGlXwbI&GERLecOU&hk4RRSwNpNK~d1Gm({k^Cr7Q~FCPx&Gexr!_=u^?0x-b@$S6;?SJY8* zAU8{pm=}-K_!TvQ-grfwa9hS!;i&1koxyUeYT|;ij{h+jYi(+WH<+;#0N7&zxWd|^ zRblzOwR^Y+dPS|{`};pCE>2ARmKKwm7+lzrV9eF%hud2)A2KmZ%F``Uhj-<|a>L{k zcuY(*8FW?%l3Whn{HkgJbD3by3bg7~b+jS%B1tbCnx(E)c1$=g{P!AV1Xuu~^t?ra zx4f_QYpNu6)(IC$xSj}%_%ok?lfr6C=3T7pn(?7R-kjZN(`?_wt<8sb(cGo#Pkuf; z!BBR*$UMvfm19DAD$vWXt6ltg3xo6WYtC&gdB>W03oB6A8>-u%R|p9zLJsoQu;lG* z=EZ$RFTJ65vt>fKS_^l*>~G;kk|sgiI$s?|$Q{8Fj5HCTUtQl++lR=|RWA(8QM+jI zo9abBH@MOuP@wF}u-Jn23AYJNpds|>GPQxN1nl~`X{z@(er{@F1b*0p@Un^EEtmJe zcTiT(Yk0+R%5t?*2%%&=SA6qZ-~8q32(eseq`fh78!i97d^}ZN0Xs|D4jR2eZ9-qX ztcLpeE)3>70Uo2@eiJN%i>#5%cVUR{zzQ^sDn)TZ1KlSMtIAPW>`~4tHOKzLb~Y#+ zbX1o)%%27mC@oE!)oLsg4{Kggla*Ac|JsB~TIZdE)nhdaZLMi(v@6o`)o`}D2pZam z5(=(({LF=nctkPvo|lo#t(Z|suMrI$gC9l|_N4zC0A^YquBz{(q%~?6Y27z8Z4Ksi ztG=OSYv8I9$f!3E3MULPq26eLIgGm0gygM6_1;n+2+Cg)oPRa)zii3>shJ-)JNe#H zw*}?52x>JJt$i)|pEmOsR-`Z9hN}ScpK1u&Svf!yIOvK2sHr9YP%}T$hJOpy%Kag{ zDwX7^s##kZ!5|3$sb&FbZ-Qi0_AP%0z7Mu_sLw{vN5qAEk80xT>h}#DepijGtJh9} zUiYY-rkH+U-0*#^)lL!jmRvhWc2G>d+QIe~C}}ur44m5E(4zd?;9x5}6W#nm3(ki- zXm>u=^gRuJ+*1sk3jpR#C8&f()KDKx%(XfzWe{zCTNUglTYzWppq1~b*(okf)CH1P zlai4QlO?PIk}O%$K^m%3fJdij=vsA_^v@1Dv{tPdS6EqF+8wjmk{&@CzEeF0>|tn3 zViQ*Mc8YmlO$|ARGO#G8ZNH-kwqYRIzb#mlH@~5k@2g44uOmD6U}wOVF(JjXh2p|F zU@5KyPnij>r{VAVwC3B3bdlTW=KHW$_57Mr)~So6|9nH+*QrS{#mLWoy?l^j1!j-O zU~PI1G})>)c{_!!R~x2%!D+zys%+i*b__G->6`}N!&vf&duuD~U;OtT;c4$4*VEeG zHfG@yzM&cG)zq?ih=1k(h`S%SCd>Wt|Jy)CBSppC(@>{kl98g4qLQtoMv% zDLF+-MMcSRv&g781|906qMAyIMn**qjS`iNii%^@p`xOqTsUC-Nzusb`?|Ja%I}== z^ZS0kkMHB*?epHf`+i^l@7=q0Z|oI2U*VqM1oF;3!Q+=Es342=1(zYyT+>JP-x$1H zUvLh=)YR7}9O#*oCb2NK`S=_qx1B<~+la?2z#9YNeZ5bd`I>P? z+^fELb5uNj)3QI!|Jr?5FfNEE2E^O7Pdxt`jeF5v@%d|<1?TJ)6JF;w&}nmk%rEIq!<~s$4Mf|eTOgED~9j<4~Jh#-{7{%mj)dEX^psSCu8QC-D2HN zvf$h+j=pW2;cuhJ-rq5Ee`E|W+`C&`_Kxv9|9n5bQ~vln#;Jy<_lh^);k@?nUUBRl z5lJ<3~Dn<}b)o1QoK3u?sDUEF+l^IkD*52wCseR*vnjZ>{IH79Brkk>Tw zy308Css+AyRVp5{|9@KjRI8fdG!KXutGXG_9jiGertTH%s*TeODbvL()l75w(UW%@ z7a6+uh|6}ep*6g9|Py6DXq2h7N&7YQ?cQP%+vkr*2MfDq=yPmS=kk`H5 zveVJ6PvRQ~)-Okn@!QJL z>cdcfJ1fEx$Dd5y{jTvVf3=ga?=yyb*Xs8fQ@v|Z?-|4WX0h|GH~0uOY?oNnV7%we zTH_@BeEZ0P6lM$fWn+(iHh!awj}3B$+m;@D+f&i`{nyE(saUnIj(uzQIEH_2H0njh z2gZ2AC2u?4`M`L!-oTw7TAlHt6*K8is%>9=hr0Bh20UTZrGpBguhzWD=}gB@1M27I z#tcaEJmRR+K=i2U&`6P80>_?mnIw-Ts#~msk-gChp z=Yw-WDCdIDh(`Z8Ui9B~iOnBzE_jms{eCX+&+|OY9x+~w{g@Ae6ZqYwkGZh1nZ$=5 z8^1GLw@YmQgcAaV^wcpwtfcfyQHAD~17_BSR|`YE@d>XBkvA~*QTnH z=QdRz6Cb=Iy8cDGSBv#u@PU2G{{8_$(>%N1SjTTCr*K30mD*XN@KZj~ZrOQM-0;Mx z@%|Sufh1g?(r*6Lw5M18`j&%UxlS*F-e=m+=BqMYf0gl@RK9Nc4ng`euU@EsqClQ* zsT=D!?Q_0nqMzV+`vYzf5FbnkCR5)T{e`{Jcv>*sV!mfaVFNP?ypWWSuJ_}fGUJ7T zzU}H`m`}yOzB7(C?Aa++hG~=ic97Tz!2qlNLCu1E!8c+#h~dA@U^a+_Um8~`U;5H` zjo)9`RgFqN3oDlwjWUW0zA{D`QWmHRxX7?=r&!-&oE7a>!%2O9L7tgF81K=bn?U*e zwmrz?!MQt*3d;!-Y}c#4sHP_@6U59W<5<6%%A>;iUhsr5>YTtGKAtZQl675(<;V?H zVoj5AoL>t;Jk|Qu4#zu9#@YI~4`@f#pW?}#Iz9F$;p&52Pn<+lcq(hDv5MZ9_psIe@*HtAhyGC0hV!tznYFriMPckn&vB~pC zM@&^sK3>?rGn&C zs`KRBK3V+QLdzDs>1|o@TcdHrVAY=CJ4M`&wCAfFs@hXu>Ug`!I6^Oqe&RMrK`W~^ z9ZR17W1E_%c-z#IiQn7w@1)b;UaC!B+#v=ZpiS@f#XCZ3|FKO6#`Cr5^#kHPw8OFP zfNIl^-|)7nt=TwYVYxoVlbv!yvsXV)w!E#{^oA!(_5Ck4{$z!^Dc7;@j-B3C4Q}Q9 z_`{oym955MdPCKl;{Joi^CHUi+z6z0HSq0tPgQe4vt&THRn(9-+?nFQL1UZYFO}kR zmvJliPNhuq9^LHK&l81LKrRhFtvESTzfv#WDARTP#Owj7UfZ9ltIrna|H8M%K6=CP z(=W!~^aEoJsGS^s+G5^-ST`^pe6=H{^)es0wL)y}rCLV6q3-#aY#8>2=;}4z7@P0w zYTV%wu5!p5UGJavR=3oA^QtF@<^6+nus3QxKXg&>)|rsC#Y+v zHg)|)n|luSy-4KiZ6_we35x44_3M0Z4@l_83NiSo@lKjh-LTaE*zWz=hur?h z{0u}h>E!f3=4T+Nm_%FuV}1pq*>l5Eg_!=Ux?#!pglbRqk@=q%T74|eeAZtF6#DNK zj?KSvf#G*Wx%aY3L>}V=xZ+i@{usY8u#DYB#^zC>qVbq9#Xo?ZM9`K|!6HHOU8NhT zaaHp_u-AXg1iwAuXCe*v&C4}kEuzG1&^}6^*s&{*@JUKyIGi8Me$6V*8 zP2LIFja*7i;E+v=^`3Bg`-~@dX;X)dVVnAuo5Qa@*{+>AuizEmG%34eyFQaF6|b_10ysm}bys8S2W#wFYgfCoJE+><`P=27a#;!txQd9*8<{~opM%wG^wd|yTz_qg!4@ID_1CVNU+w)}g+(KO|1B|U!Sfpo3se|C-|YF7 zgki3#b35CX>kIx}E>;fGCL6wgRXm~mZo7DMkanlhUmdfTV}2lM-!X4(7mEgK(`Q$x zW7+-``)Evbs~G~%{j>ZXv^G!n49wIUjvrUDT|C2a#^*d~8Val&ccr?6b&9^AXuJ4w zur}B5z^h`^5N*13InSw9AH=?%3H9arf@N%*&_AK>r!TmN=f?Fveo$YKUv)xH+N&>E z$@9m1(hp4BbNulB{rwCDIVbMV-(kDy_x&ew7rCL}LJl|{V2ZxrT6R#GYJORKIYi?w z@;PE=fMyKP@eR?_EJyAa`k`8IfZ6-#E}9MS)K)TQNhMQ-5ig)`S-}Y(!+xZTvYRD?z_DTKQ?cVKg`nI3ZzrEVKz1+8bO#k-g*?g;j zK-+vzjOc$t$CriJUgFz6w12yKj&Pi&9T}&(;6{3y>SfSR=uB-{j4?IVwp8U3pRAW zB-W46)=m7{cl0MO9Tg9-Zs+W+ZrFa7i_dXH;J43>;$T^3Ts zfyYM_DRm$9{!N!fDxmr^vU7Yfet#FsCzM-xR$Z8W&)%xntB>na__$7OTSh+BJ0btS zsv=hp;RT{?ls3($eZO~2y|j*#`kBYIjUekKhv&0V^x1W(Q`ak^y=eWm60vm#ARc&86*5itc7bH z^}NA0UpzKOTWP4CFMb`PT@&}}%ic?bIqc-SMDUbaU7UFW^6eL;w|0D&2wVe;0h!wM zvUuL8jT;uPN==47ep&1>YF7@mEGQ@=3G2&Zf~GA#U1g8=iz<6dUKT4gZI1drfB&X= zFN^J(Hf<4XXj)ucv@ehEs2<_Hmip5?mhgG_TV(jMOk6fw8z<_5KQ7inr<%;;mv1k2{X$4~TbTnJ|WEbFHf7RsP;k@%Y5}PxE&hr!wM=9T4vV)q{BM z@XK^bzAW?3&SRb*bfWigi)Zxlf%su5`|-RQ7s+oO6CZ|Xv*L#MGVzGY1Rpd1X(m=s zDBdHq5v+e-b)`C{Ok6ykLLH!KRiXZ-;w?Xgc*`ji@je<5?-$iYcMr|~^0?{})Emx>D~YKxZL;>(be?qR?B6f$%*h31BV_yHNpR2kyA>HUS~CE>xB z#5WVQ8F7n!X}qh_xbhUz;2O4sG|n23#uYD#tIXPj$v2)@IMTVsTe#z8`)rGN%B(Gl z8|h2;pDJBGfc?|TzMQg|`K5f~_wTEE>BN`Bgh|BfpwUz>y+g(01K9q3{%Z%hgmMt? zvjOpb+a@+o;zHn|E#h+(cegL@VilKM&K)v0(x^nV_2$OWFiNf$97UeY$PAXM8DV2du8Psl)V$5?H&Fvn|= zB4VmGerU>h1rylbxmBz`lk1=Scr8$5P1PoiIN^-9gK87i+quoHda5>bsAW-sWXpcv zA%T~2NDqe?EYV`&rCR7|^*Y`81>dvF8@^qV&(zKu%J+2Y*|y2EZINNgX7TZv+V;2= zY*T&cXEJV=r%-W{7qheZM$P7v`{dnQ#lC6UHF~!&hiPX+e3)i7bZqu~1Y-DUvsgbz zn+y73fdNDVO(zCSjr<)DOU(vVwwma2!%kSHt z_iYcGu8ka;Vkr25W_q(!z1*KE(xz*nahuqniZxXgi`RU*aJ{-3`+aEmsq2z@KZ~E| zl|@Zmv~cD2$cvt0dG=L9?bTB8`E>eMjxXL|6_3~aKaIzEPThHU>wtJql!~QiYxfVE zMzyO~v4={jTjIjiL9us>)7}7ZQfJ5zIj-IeXp)y zkP3^-yGwi*@!W~Wu2jdek86uqFhd(RZ-+0I19`hOeHa(y{T1{Y+m63YA-(P1eYQp7t_%3P zzF*%J93VcLr41RxR9~VH|C-9FpnirHq+jn{PnoR+h`t$GxS{?<@o_LyOP9~ohF@wK zhHj zrFmP#gjw2LeW$o!I%Usas0|Xg&(c=w>%1HKW>Fb?z3b-LTDbmo?>ZH83E$!_o2{9L zuOM%pTl{&U&E6uuKyHbVYBJwYQi@~FTOc#WQaJHIDD|k&lwRQ zaw4@$hSlr%PRV)f6QnX4EZQQqg>ik73CZ>aCwqyF}?_dQVw=Zfz)p4_Oz zHj6vY)n*U<+86HzG4gE9be3+w(VS^oIC}4ZqYu6)+RxSQ@q3x0zrBMW!_A(nP4lnU z+lPuRbG3|V^?JV4(EncV8g^1|km*Be=BQrRJhY&MZTG$?7R}Sn<0Xar@1J19%`b{| z^R!FZU_Y%On+=!0D88Aejhm3KYLs5T$&Wd|dCU{?c6JF_Qgesrln7&#Hj9I7fdw~k z(Cin*(kM@ql+z3T!iJC+#kMG-T(6=q-Zn8!;fX@0306^fd~}oeK1!Q2l+R~RF4#|M{6qsb?ROp{k9D>_hPX-no(^zPm3OU zfO=8&^EWZ;T+I|eur_$LRTrWk*-x&GUsP@K+)FQdUlZj=7f?TM@c{d(bBMnf zKTA79q(3<_Xt4Urt38{V_dmJi1>bLk`F4JRoz<&T|3u#zcCqGsZE4(66@g= zokC}PjB4b^L!$;1CWWfBFhwxK7q48!d-xRMJD4}B1dkdwe2(CS$PzTxP@e7$Ec*>Uvlgh-sr;v$zDHK21pFJQGB`OmKk-i-9Y;5a*HpX@eDUH{Jn!7qAIDoxIfz$2AYS7JvEX86 z1yY_Dw_Z%#Vqe?|Dz0}r>W|~zKt9jn?^+FryKRH$x|ji!?TdGe`twaa{c*hO$S3h` z8W8VM;;5-7%O>wxVF(lKs-D#uUSI7UKpPoA!5r6rR(O$pwk*+R-ICzT#D0|t?{w22 zXX0uKHQly!?tn}zQ<>noV3mn8EJs%IxW9v)%e1uWU^9Gam8-P8(@uY!7Sm2Gq@^-` zVnau75Zhw8Si1B%-#{Y0i-~<==i2j}_&!!!bnP)3OLZ=rO4B>#lz+l?O1|$pCI9$! z%H@=gxA!f?CQZ-2>N+J*m5=B4Y@~de$O)^jCZtnWZw~owNGmj4a{S z#BlB?ACQr^?P7DBwsP27Up&7T#Dq&U&3D!Pdp$AVQ^Hp^Rtz}&al2S{iMC~E^XP&M zA}qFx;qlt?q1C|!f8}AA{rEJ`IU`PZ!E%%7<1;)%PRrNX#}v$E|DnG9nd3Rfz@MIG zdgsiMDaL}ap3K=s*(Vxyw7wwjyi}Vvls{rNgw0>RAYQwa4-<^fiLOhT-+7+Ussor+ z@AuB{{BgZVCNAc3p-QEn*a6C35UrPK*BR{5V#(#&MRCi0aet%&d~b42j>}&XWCZ5> z+0R(4O&E1r^0tXlZfpQcbG5mZ$`ojp(le z-@H-2eqgbR?4Hxb!wbKnLi@f&(KT@pj2cB_lf6Bg(0rU0tah}RI zSk&LQ@ZLBYJRpbasJsDKkKm8%h_c zzBIyeB$M5ATw|U1(du53@!T}L^I3J%@Nm6IxQh9>t<`@wx%gAMB6L_n^cL z+V#`FW(PHmu$FGcJ?T68e^zg`@csm!x@Sz!i}_(8CZuRf4c`cHXNtDWuuq8nDcXVy zAEbSczn|h{pyOw#=5nm(-M#Pe{p_P&L+rc+s0qStJl~(rUC)TiZsb;`?aw&wyir@J zH{A5B`2HsC4RKqtHuU7;HJ@C(8a~sEBhraI~|CWiN`wNITK z#!a{Jg%Lm8tTl?qt{<400ez)~x2kIgMA_OOg}x$h(Z-B>pWJR@vc=OS_%op!sdsg@ zIQ+Dju|k_Ldo=-6TU<|@oH)^WH``B~A^EGXM;v}qtXZM02;px%s^0|s&d-0kAM@9{ z7V3`dI-g~+?#L>kPtzvq?-!HOw9)!(ac-J+zCPV?cbYcG;3&UU%hMa$3LT5mwXQ)! z6AF)td_Uu38REvfw230=PA$xk{7><~o!WlGkV3~*cWFcQObVuCYFFy(9Tk~cqF%q* zG4vj7iowuX;Fys`5JO^tn7l^2)^L5kW6c_Eg5K~;zIfiMooP5N-?7iCJ*79i__$cM zR=dUU*yE0UYc;<4Q7*zC)RybZ9r+Jx7K0&oy<`7F+Mz*))_*uYc#O$QLsg!`@DFXa z-mof9%w4ZNGd}DeN5zd#U2^2s&3xdXJL9pNpE~Wxc~WX>nA|Sf)@v^rjCqb{9@i!q z4C@~gI}7Nr_dMnp_k{MS-Z1(x$L4=(Kj{rmKk8Wjq)O=5N5r~kwJ!}Vx#Ff`?I**d zkBGSEv~`BuT(SQ-3V&s;*!;Y9zacW$G5H1UsNV3#!;T3Xw2SqI%^L^%njYJ&T(j~wp2fQ*t(-4^LgElv^Q-#Hu&k>)0-DLu6s!<@Efv)N6zL& zqIsanHtR&i{X z_E#z{v0BSE)LO;znQ#_0_mYaDZHRHnA95m&vd-D!AqjribQ z?T{gUjbqO~ZJD1T^Y3Ev2iy^H<=@5T4``G5e;30)B&|b#cRcfcfle9@7IChLymOxGQ0@f);lpIg3hfagT&zqAPd zLu#$)Us|T&zSUy*er>v8=m{!)(iu6qXB*SU5h^`9hneAHI8P!M3D3 zDu?;&B71gEas2S5#`g}^o+diJ(qRtj zz2G9-`~s&fs$jZ)zT@BlEpI5FtYvj-YYm3e9KUvI2EOKfcELvdc@DpBt--)>X#7Q+ z2?2++g%EQ{yN|!qDs~;xHlEA4toFO%bMqM6e&rrNUHt`|X3aX?C5uflM^YM7dOgo) z8_w8q*HL<}e%rHmJDxhM%^YIbJwm*9jC-n%L- zxZadvFfmm;!jsN&?v?#*^{%bI`RNK$ElV6j{7oT-k>x|LS#o4(sP4$O43HYG^&F9d zO#%9#q10Xof1_(Gj$;w=Lrjx~?H*AufBD#gYyHML?j2&@&vg3)5j2-9xE_qRE24KfY&3vh4p+7ck2!N|K`|cGI62s@ZZGe zV@C`PL|~c-Y)MxgEO*i>5M&Ng`8}P2=E;7(Z;B7;6gFm$EhCG&jv$$}&=>x<3o5k?6P0t%f-YmACZ93C1mQWguD+bDvyHmS zc7DNUyB9hf^G)-IPWhRwuadp9H)sW?nRG|E2H25wOlm)|eIwhyGMl!HUThi>;NHrk zX*QEMW2x!p;USKnWqsw(GJ++y(y@N2Y5UN)-miX^(M>+Ogk&b_?Hof3y4ZQE5bgn)qdsuYY2W23O zi6xXJf+d83&SE{~z$s)Poh9r4Xhy96*GhK0U^!$spQV_kl%;~Dnx&4V(aL`< zEN+%QmVmz>l))@!me_j_N*hZaOA$*6OF2swOD#(SOEZg$rI*D&>!1u`31JCiiDa>` z#Iq!^q_SkNWV7V56tYc7Uf%4818qPqH6T3Cu$RQ36jd$s<5a&Zw))leWq zwuV}8-cK)9)fLVL6CEdoC5EMtC6uL{CGa0?%m1G(r+kd{e;D|Gnvp---+JN>|1HQ}as!mt&fKytq$J~2!NIUbV?_NJn58u*oQ%{>vT=RDPu9} zX^zJtEXJB=oU#T}pLNP+OfGiHfC_5pd8Z7=m<>*uY-J^Me5=gGNGwL(gjQLJb=ZKh z6I*2uR$=fPl+fHNqp%4RF?CX_%tSlpW76bSS%uBmgt=2%Wx$&>QE00S!+4CwWV9x* zlFmvhW@8o>VyIW}P(_MsCar?yIe2Ymp;F!{_@8IR4=T4e?XpVcb!Fdxe>dOF8r zO?a#9#lXd_Tx@dul2)rsVWl#*Rc2#(T&pa_l1q8K6EAC(CD?EUHGw_XwaUo1sF`FE zs-kb)z;^b}NTGx~NchH98IG|Si)qVSWjaRROwC{xmSN8=9EX{=T3e-#z}dG_wU~op zXvb(QOK+8Fn0tGx3?yMECSqzvtIWY7w5tqZmGX{O*@yvm(qtHeL1eT7!!i7xR+)^= zXvYle{jIW|m9o{XvJd;RTV?3mROuQL!q~MWglP}7$_mVSkT%84hse-7G{wX81uV{` zq^Nt8l48)UE?JE|x4C2!_NBXIFIKE{$>3c~N3U|p2(;#AxMVyl4R^R?8fM+;k~tW9 zw@ccw7OOD(9+zyy+$@*u!6pou$Q*n z;*z1*u+=3kXy4|N$yiwCl3CdFvP%|X$aa@3$C6iEvJNv|bx9}oR!~DV)X1CE5N1_U zLm0J_8p3L{Sy@S~qKeRkm6-kxRfPW4lnf(wQ?hp%w|glWw$xBEOy5Vzu=+hphEeZR zGR*mal40G46butTqF|W!2?g87{`C|Ld;aB;RtqZ`pHec+ZlGjX@&zTs@UJKt>b|CA zn1N1A_?AHL(Tkf2gqhz_LumVvI2imBaj+B%G0;gIEc%%^=zownnB;PCQBX_C+g#F& zmJXMU#?UU8Ou~R)2!z##2!!#y1j5E61VY!Z1j3+WF6sY1O{r^>W=t})$!N6sx5*?d z8Qdl_u{NMh=A&y^n=HeyKx><``qp5i3Wx z$qWn{(1ei2 zY?HaHgqho930fw#$!d(9+$NhaVM?3q#iYd34}!t(wQ(UhrWa{>*!0^fV%x$ zc;wQTu^( zScM7LYo{||$R_#{25qG;p=BF=35#B$FQMsW`V!`Dr!O@ynqFy>)(BRdti)sFt8^x8 zdX3J6sTFi4_4o}s6J|K*OjuJ%XTs{8bf(Y9NEMw4%ip0dVa{&)61w)#moTx0zJyWx z=u4RY9(@U&wQW}EW+m+dI@9O)A)N{9o9Il~@;#jiT`hDb3~r?}VOeOqti+sY?Xm$I z(TyR~+hyRtX@VK;G7Q6Kx62r`%x#w`m_EN&Rkf|W2!yR65m3)`g& zbusNSppj7!+b%<~C9YjsFf_hhCS%a$?J^6a653@URxfRr$OvjK%+hs1A z^4etyW*4=~YD{>#T{bl_{zIQ>m%VHVc&=Rre@&Ix+hv4uW4nyUvXXY0hWRhH%N)#b zv`ae%>};1+n2e2>`%b&;!JI2PWY9O%)Y1+aixF3LNE_O)8q*RxWFJ;y5zq3gmoBsZ-?~%k_Px;)xEKjlEBH$Rdn= zszcVR=h219qQlB0GHv-Z31M|HJG7F(3mr1^AXR1OF(z#!LulGW+qx(zhNFEmRf!>` z9kLcvwz9pAK2t`9+Ud;Oc^+e4p(u^r>zXFEoINYkLbjskWO=OZ$N zA)k<8EVtIv_T6-j{T(tH>prE8)#C=L97{gykj)tIZ`!PfD*dTL#$XPnU?bWw^Z=a@ zGce&7s@6#jV)f5dJ(jfcJQf}#9=gzUl<^1e|;Y`olUl`dBNmr_-X+Z0T|(nP8f!>%R}CSwKWVLdjW z3v-g(GJx@1el48|-Pe%-7A2EG48GniBN(1(H_&vLa+6yYVr42dfwr5iR0S)wx6t;C z)4tniBaFD49kB30`Ud0F_Aph8MURnl^j}W~Fsgur8J;!8Zdr}_cDM9r7?y6L<}h-z zTQ;g;i9HzjDmBLNYsN^-x4!O{eQG?S=@2Id2b~G+n1r>Mi8+;SnU9TFhKW1q<(RP3 zEnBb;b%)95JM;w%+~t_Bs7Vtfmo-O5VHkF*h%I>`~{{!E6j@E|3^%r=?`t57Ftl6EqL z#T}FgtKF0c!#WxF7}?G7n2psK+(Usd6(e+dUB)2_fZ4r_|14H&SSiH%qns$PsgDCN z^f$Nc#Uc#W>vhc-fr-aB^L9Yw)@05|4 zan>~7GmV2PFaqY zDV?$b>#!Far*_JaL3*9}%uX4Fg_wv-`b ztux2~D^(be5i>hw8fIY*y3mf15mYIbVx!uQJs2^IDjh-~497~0#hBUD2-aghCeP`V z73jo9>^Zkn_MtU;Zl~nV5?wh)q8k%1b{+vRaXtYs3(K$xYcYHQO@bKpVDw)o5SC*u_F~CtR(fe1orDeMOXwt+ z8c!Qz83uE^lKE0HglQO$O_+wEmysbXLOV8N6((Lz6=N~>U{C^0bUM8q!?6xyG5Cs3 zUjJFiWyOXrEXKU0R1wx=1BP8m4Pgcba;epVVHlR!DPz#`S2BdzTv|mr#WA6=}vK|vtI%U8}IxEIv z>~cC4HlYhGsXRYQudBsS%(|shTCfv7l^sXZ#w*zYgI3Wt z*n2mRgY~+QdpH1duo_G5C804i&3$BmjHRIq%P^FT^xjWfV@Ngyz_2wG03#Ug)ufk% zI^w6UWhImq`&!xpbq~FZMlpB%zKpQ$xy&!JdX*O zicYj)WF7^;6s$x$HmK*VthiZ8{s(Pqq+}R|ruDQfCSwX_K2F zZHy()(8d~_dJ}Do6_|u!B@9Ch*-Bg!!*CmM(Hinnr_5%>QbsT3wle1{3>!4P%7JL! z!KmO?Gt*A0>{Dlh74jJrj2L( z*S$*(OeDZQYQRh{#$s|>_8wJ*eb|6$wd{w57)XX|FbrMqlOV=^K#gE7Hlh=IFshCM zQjiQR!jg~K4|}k2EaN}=6Lw@n1qM;l-Tfw!01ouOc>R`i34p|qMpZUO!|z+ zl)MzH(Tz))J5uoly-tOPaEwit~uR814+VfGii_+ZJG)ByT_ zMGas&22LPB3`74Wj>9xe!7|LodMv^otiYgeC^4pD50;@dh^jY#ONlWDW3dKPF}#^J z#WXBd+p!V@zav9v!!Vkx1!FMmdoqCWn2i}&gsDGJSBYsWCG@m z?2_SU)2lHS(?@m5q;q)L{I z6KId@k|o%O)tGl~mu$l9x$KX+dDM(*N{qlt%)y%Z)Wlgz5a@y90nOKkc zm>k_DD=_RlnhHy>2VEFM+eam+ zQbU-08#RRX^e*XC&!hh=hUe{F(u}byyJR%hVv>5iiYCVJI~e~(teEbkjjjB5bjeh7qD?)%m(Gf%Sc%nHbXv^4k4}g&_fw!bWC)|syqW@G zp_P>kR!Xud5tgrESYSLEYrrfU0k9f_Bk4qIX(Ft|MASXN@o0XKVTCR%$H<&6S%;!=Yd!DzGw=Ta4{6k$H*JVM)G#-r2(7NQGnk1@XIGAb|>EqRP@tj1*Z z_#X^gv|%CY){_xzd7Oe^MggZ}bYajuwm(5r%wzng{gd9yhRi29HDVPOVc1htC01Y) zRu|DXqA0=BR3&C(6q=u*CeV%0XuMLR~lXQgdfDSDq% zE7p9-j$|aTj+~z1j+pi}=WMM0h9?P zjbN{n^9Gt+oXBDsURa8S?bIyRbx_d1(CNBJ52Jq}!*S~RpOx4+&UA-(wZf=g0-+u2 zu@7CCbc8m>o;{3_VJfV-6;x3$xJwS2Bo^SdQgbhjz(}5e4bPd{sbQw=9dX@?zlM zEnRFV!2n9uf}xl;s9RdF2b0zI!QHYFvxjuc2CPLlngY6I;KlUrq1`eJD=`N9Fa@2b zb;}$y2X)I*EW;Y~AK5LNt*o>JcT0b&E@(`*jK)k%!eY!vH`ZdAv0Jua59+AW46R#+ zV6>@QMqwT%VmW4D1J+>3SmIOViQ~FuJeFV@y3m@#O5_>c(vJ3!ZdrwHY{b~{-7<)( zcVj9#Cv;0ERhc%Cfbq1gxm%jC38S%S5*bJT$=xy&-I$LFQ>bbT4y7QNi7rf@+RgR< zrF5RD-7*rx!U%xDXLrkN^baRv7;z36!_t{l8HPr5%RbCU(`D>8i{mj16VQd}7%-<> z=3-!Ew=BV4tj4-?yJZvR&b4;SURJ{Ab<5z(Igwxlnxd#GESpbNVZuTJVI!8Hdl4nU z)bnW)tU_G^8MV+PScXw(yMQJ^(_)$gQ!x*luoPphF|-jY6&F!5tiPC&VZ#zib_K&P zmXcxNUnm(S#8EQr!CZ7+LWZz1o|2*erIZXKuooLJcquh@83n_1jK>O0Lu>No^iEcC z(T*;x!iWU=048D&W?|5kbjmBp5c)4ALukQtwHYZz|me=WlelhKX!82DELT*q+3*kpzqMqbZw!+>S< z9n8ccticKlyrEmxV$M|nx zrSTCui+bWwI?J`3NFJltq7ySPWqr4-!_>zqF{b6S-*sf@33@q?tFaJ^{z+gAE@V5; zH(?@%K1m!jJw*mE0ZXy>DaL;dD|SKe$Cx5|KZZU-O(YWlBeA}in!vE%6(n2DKn6b!BAk0?1S<=BU&kLf(ixm2pB^I$LLVDaY!NF~Srrgz`W zi%KJ%3Y)PJE50CM^%#S0q4Rx7!kCAFE2x>T7?#v*^Vh_u29v&_lP_cZ+gV9sLkm`5 zcr!JisthgEfc?8}X+v`h2~jd9R*=!2pJ+=m7V$Hk2@_j6lVS-rqYL{m@*sVQjQ3z9 zwzy~_%xdF=m1?E;vQol^$aYSlScFa3h`ng(ptn=9Y>dE0%t5o8PK1S6g}oR{i7lPH zT4Dv-(A3o}i!li+u^Jn&58YN)GP*gFQAPeeR5@lIqGXtVgoH5SS4xOE#~6lKjZW-E z|1@4?bUiW*BkYG{GNxfB=3)`ru@N&i9FhTlBb|+hWH@G_HG!2rRx;IwO&oxAScNWZ z#=w$8(*IUUieVV=;vpH2cFe%2&4*+m)?y_lY&j&Gun~2)F$_x&$xw7+ET(TgB-7Eo z^^jHOvy!>(kgUKGY{ay(L$VKBUOptv>2#*@Lox=-F%6qB5A$9>B+IeL!EsoLed>8M z-%b-%avYXp8d`R69HwA7=I*c_k_~DHHuPdWhO8uKXu;r}hh!=?V=e~0bx4+B6xL%B z_Mi<-tEdr-#?&ej#OxYs6yx7LBx|t`-Pp44kPObCNv!W3l2NQA)Y5j?fHo|9|Bx)f zun#y8(>^>TT^LnI2JhgEhB27-5eZ=n=BdXYQ!@1!8!+h;3WjwUawmPHo`PW!rlPfu zm0VW*|3yNWiY~0!PY&;*zpTG$Ye0e92uF#;oFC3Fc(d3 zN{r!HgEn-c9d+4^Zwy5jMx(Bi44@gaFbRt>8>=xN8?hSuu(^}*Z~i+~)kSZ{JWR(j z%t!xjIv0jwGsd9*8mtvjR-p@1Z5)4yHpj$XGJv*T#((fy z5_Y<9hRnb^iCszKBJ8^0%0Q7Q-U;f zVlnFIwDoAh$gziIG=_{j%!kSJcFe`#GY)feDJ8~wOvPTz!4OJbf{|#gU?rXvC+4Dm z2nV7WYbZ%1Hemwl9weg}irJG6%LELVd{|~;EEZuJR$(1Fu?LGOv1J-Hi8c(Oz{O~J zi1FXdN-7(o!Vb%POu<-cA{#TX7VX%Bl^Apu8NzVXJxszFhJ~1f<(Q3iXvaRRMbmU@ z8Y3|%mm0w+RaLpHB(tFcGqDNtP$T^GxjKyTMVJ;TVIc$}7R_fVMi@oT=z{tbW|8d6sxs()RF&?up z0}HVb%drysuo;8q(nJ`AA^D6RVh z5vE}e=3!veVOfG zsv4W456g7y!5sWwWZe&Z?CE?c{&9Bpm|ekO5D}zq=-5s*+F(jB2!gQ&gIGb3G8o%b zQ=(1Hw4L6Y+op_~?gT-Q5)}loJ9cN+EZN<$#%?er2o1u?IzxkC&e=KU_nx!YZD03y zUN3!rzR&mje4pp}Jbz}kyE$2SoW;luHo3<(haRuPB@J+#OU!VMdDgkc4(qHX)Z;$G z|6>0i3!;MQC+achIm6JCjF@q5GQ%b}*kOy2E2QwrI?OoJOmm*IT;VqBjE(=gd&DV5 z$~ww;x%d5FkW$d(96Ma*@KaS}f-SBvylk5?%Dt!Ac5HKj=?N)jmKEl?!x9g<$G&&^ zC!(ionAvB@)I06}l3+C>872^!Q%L^H2IB9CQ%GKWWvwq!eaF_?2W$4`& z*`>ekjxg|SnPH3zOmUS9+|CJ>1beJ7uwq1vawH`)9A}1;%yX8@EV9ZqHrZl_;pbQr z@6iw^ILB!&a-J(Ja+A4r!SZwMTkf#K;PbrTy%rb8ImrwcxWr{{a*Is{(&{n7$orfR zjB}P#TwJ-+o`UI5@~Tj8x$}J|@;4<5+bMXB# z$OOk;sNV_nBo$5Sm7aeK9aMjUTf|Zj56|X8e)ty9A|+Ut}xFk*Vts0 z2W+y#79+1Sl^-=?j&P0>tT4+43+&4pP)?A2y`HeZLzXVLiZ^U8jOdHX-SDTVV!%IKSIH)a>4n#)|{ z%wNk8XWycupH$9aZgGO!oaPY=4BFN!jI+ix54gn8r(}jPHgbZLV2>Gw@)ijPxyCr_ zoaa85*ybh&Kdm0e*=C0EztM3fxy)Hsxxxe1*kO~AEk||kZ>3r=%4sgLz*VlW!Yww~ zVC3(7iDaDppOG1kago!kvcP?=Gg45GQ66xXeOH=Njxbjfqy-0@XaC=8m`T<+_&+U5 zPO|SRbI4KdaFT5WHn_ke zRvG%NRQ-cFW0d1eaEdd`bCGM@VuMFKX5=4b>S`V12-lfrjoGX1|6M^rL5J%cTJi!W zdCUd&U!#NnWU+CKS*BTFhAUj)78~4Un;nMUYObq3&Kc(pGd$u_P7r#Vp7$PLoh2T# z%KmFD7LKsR2?mSin!_wG%@x*JXPf(szukFooyE&27n$G&XIN)$QLrmmW$>SUsIZ@V zjPjUC_J7V<&k^RC<_70kWs&>bV&6MtfO!UL2E=|=IK~Fk%$Dr`f}mKEdakj?HV@eU zFH*=9hpso*jB|t2+~Fb*xXSny2Ea+~vB<#Z4UkcGm}Io<zVulqiaj$OwZwLZkRFT6BzTYZm zKc_jt0<&Cao;7arfK7&O_Ib`Bj(x!Sz$s3##5~uz%-{zd$?RwI=A1bbv=vNq@JlK% z!F5iu%31ES#K4*nFv>knG0`fmCmg|yvdDE-S?4|v8T^_>y{UstFv)4oa+xJodS3)8g77Cb z$S6BZFw&Gd#+c(2hq zI3SqjB)6|LcU-&5+;O&In{w>4wkbnbtM?77pCjzM#+qT2S&lHz@#_qb)2wSS&pp>G z4DQqG0q}&f+gPTDis|ce%x5?lQJ*YMA2Cw{0_yGkt>*v&bT=Txa-3i;tr`W{UlL zGQklpF}-L1uL`mX4q0N~O;W}<_c+DCcQn9ZZgGO!oaP}5?5k^-L#%O*2Q0C}28X^Y zGmJC%MF&()&@Y(d1eaN2jaxim-_26>A2PsECOOFh7r4R_H@U&^myDc69&?T1eY=E< zOn=z`dCc6Npd&cq&@EQ|_behtIl&}nILieta+MoAxYg9K#TJu08v4ElILrzsSmP8Y zzG6`_k)U$Os_f;|PZy^b*SgF6L=zGkFc;S_7k^MGrdYFf=)`?{2S;T{_de8WIE z#FqOB1`iBq*PJuYG}k!K(QoFQ$%5)PrJQr$l5%b^^h5iXF;>4V|RpZ_#j@^X&hD zOmLBPuCv7^rx`gg6^9z;DASze0vEW#RpuIkir|R*?EjI9w@D30S>zdB9C}SpTv8ANjF{6^t@?S|&KiEE6nnk|oY^gNxke zD#NGEJ)=D6m9wv9KpbJXWf5|OS!P*ck(E}?91C_74FAM-;TZdVV#FL~hGSgfG&fn` z9yb{JsrroampbKk`~K77IWhvqndT(tndb_( zSYw^LJYt98pE+obWR&BaW`-p$@ravD{=B#U1r0&?XXb_p4*x>Rxz7bgkEM)Dztqv* z{a-s7dDwO`{@ndDj#g$k!gUrI?|7d5=RD7?-+2BP4xX;eFn*_Yt~((}-KpK3W}fq` zvB+JnGjpQdZE%mr3|`Rg_8mJBIm{HtIL9=XnPrs)?sJ8~V7t4;lE2J*mqVdkyW0`O zL+x(lmlhl2TxE(CX4v8qCogJuH`!)X2Kp~HZQsTx0*QWR@e0-o^8r zW|oDVpeR`3I;*U)$z9g`)#M!>bLiJzaQAk1oM~pb%p!NV#b8)H#@OK`huWru|<{A@haEeEqXXH0Jz&JyXYImnN z%sk^*@JI{Qy}@Cg z!eV2V6&AV2H6HVj{TF!tNjl1DPIC6iGRq>@xW+0EpKSm8wO4_OrQ!O4A zndJtHtaFP8+~vsA{1r48o(QBl%y~|5gIVsd$PTwSG9j~^p-^FEap+a+g!=u)v|P)N`DN%rg37 zQ=1bc1?!w(l^rflSzPxp$4qjYGmO8)3pmAfuCu`k54gh)4;i_qj=j|4WSWzl zV{TTkC|G3hW$o@p?*Z;`fyXSe?_M&*5stjv3pl}9PQJpv<~*xh<~}#sW}V^4iNHRi zY%{^gEA9UoLHd>EkQtV^#0odL$2|t`ZF|jl0mqr-JZHGdMecBwfj=>YjPa0T4BW>Q za+twanL_rzDrYVPQ3VA~aGhB;xXdF~7`g9>z%JtqyxOkeDD#})GN-u7Je%BLoBJH> z*O82ov%m~ja)P{|$`V`LVE=23fNAbA&tvYe|9%$RYdt?;>Mr*j$7gkvM~vKGiWz0# z&#ZQam|~1`9OWW&V}cdII5*j3lQVD7a~2pL)Kf;e%_IYV?nNBq3Y&8lFH3LI5f0Dm z$OEMM%`(Qxzmzeym}lm%teFSc{|AD)f~mJSQrR>m;Riao{?>`c43iu!SZqwQ#5^}R z{r46t5B{e)evpj(FLTTa$2ho18A~wDS^pCS&qHkV&e>}9QtRO>yHeR9Q=&!!8lt?GdyB#FwSMB*yKEqxx&bmI?QqIa*iD?bLbJi zCvcnx%rJ13Z%#SEpkR~pY_iB!?}3V*{-FbjV@z?Hb1bmJb?&jo=x5C>gS3N{rqxWgmHu9v#FMaD6fnC2E|S@^tF&do1qnAy5>gwr=$D}O8# zU(#WQIKddR9A%zKE;E}GR0WIN=Rw0)t;a|yhnW1b)HBUVR=B_#iyXYgs^=tk*)N_$XEHe0bQ^I~$ImT_K*x=0L?f<4=UO|gRh7OI0!5_;A6fn%BECigl0OZ5^OK5?eI#@YTe-NF;S?|x_e2(|-n=u9{Gq@2Yy ze5MHOx5k;+neGt_4?oi#e6og^;4Wua_=7XuB@T|9>25O4 zIbKU#t$qz zc>efIcbZuixXE=Mv%&adWR44rOc*)i3_kXZUri;LcXPgO8UHbKK8KW|(Jz2V7={dmJ+NM~rjg2{}C%%sfHLxWtZzD~vqd zgN!qh&=5zMXOe4NV1vs%;ua&%kQt6K@I>$DAPY=#oeOO6ASXB$wAuGei||Qjx}%)p zBp0~A4VGBr20LtW_{r7=(+nq#m{D#q$z9H}!$ro%)#o_3nac_e1$hRZWesqcfu|S& zM>x$i3!LW)*I8qo2RvfvQfuU?b`wXK;w0y|!ev%iWt01t+W#X@vn`%&E;z^;CYa|8 z_qfPot};AfTXBkQE;5|bAx2qcg3+g|&t(=l^$Z2r;kF-D(lq)aixc`k94n>=8X9k#fXvPPa~Y8cN64h1O&p5q1V zXPz_M;3jui;~{q$Nb3OmIriK$-EmGb!#OUo#w|A4V24K>d7chDUk1{>{VxbT-|A+P z`Q8n#v+o5`#=#d_q#R}63#<{2vcpLZPFiFf;Ued_(JOzEk#m$Sj$dZ`z0g!J&c(}m z`(H5pVvCCvZg7{|Z1a%8ml)}!)ypwXa+)nJvhStpvHxXfx_eA8@FE{V9A<+Pj7;k& zM_A(QbWTM! zQ^Pzr*~|%c1#NaXJR?O@QpPx^IK>W^IQSj18u^&kVyEYlCsFaf3VD;~@uMV{N=lhdIIm)2wrz`z-Q^ z>x{fs2VQ3XCj>_dQVdN?6=PgwidD|B!6ml2$-dXg0Mk6;JR>jn>Bu*YBolOX&G+l8Y%PI%S!Ij+?3=adIL^U8(NT`Fz)4oPz+J8~ z_-7V7wFK7~?dPEU>_JuCT^U?lSyF4ZlWe8R0ZzT;e$EoZ>O(IQ}L_ zIg3ob*8O=?!h<*4|Eq%5n~jXeth2*C4*jKuUgwNwgd>bH&N1$CnxO@Yvv;4HZ2Yy6 za{liu>Z~VT7S|d6QyE~C zEhZR!hx#1n5~sPzDw}Mw#WsVp_J6fxwa%IgPBQv077tTg~oZ&VX7y3*6@_1Mkyu4)c%|hTrHuM;TeQ|0e~bf(1@;mGj)@CifV6zt4Y;vj0tv zPL6SbY3_2KkqNBySK94_UJ9FaW&I>Mm!tUTUhyK!<;W#Hhlaq46_Eo+IaF5#z zRg9cNJZ6%8e`RVo%mt2di_>gyp8HqpIMdgv&#{^jYj}!*1=rVGv>g1r%yBp;$OtC5 z#1vP#%55I-kkuQc{;zeEF&^D$)w6Vysbk_xPD<|IB2yf?Ri>C?=q;Y(23wWr?4vw(HNsfNYNSWp;3#@RBd)#K=Z_PdXIs9!? z#0gGwmIbbIg}bc%t)3kV4itp)R*O+0QCAPTrqu%HL|F*akMA>4JkyBF636?m;4d%JSH6C+^{r}*6I5ct& zbDDV;xW^41ahu`Wd}HD)ga4=lx8*b}*j12Zr6pxN;0in3V&o_0j8Psi!4A`mELk&* zvA}UIbDkA0@sMkb{M5%bQ*3e}Cuj*84F8ik`A@5y$464m?VlMj8$4i>ZSJw}t&J}L`#+-4VEk*)o zyVE*6!BHKV=VY&A>@P|+$2f7Pv)viaaFJDRa+ghxoH*+zuI>M%VCe1UloO0xaJHLe zlm(`_&J1fT@qp{>u*so+HlpC!?l{MoVU|nW;U)tYYM3KzbDD$iu>ZFO+gaInAMv2ASt(?>=|gX5e4E=OXnu%@HneA}3fDWVz2} zCN4hPt@a+^0W0jg!W!T(hwh?bW;o3P3%&c?WUS9fd-vJl8i&i?!!h>V^=voID05lC zxS+@-R@vfy?}59W?S_`kAxAjR2{t&*L(X&I?q|DeEV9bM@L4}{E!7OXQzjVW4#zol zkF(ubF5Tm7uDjTKK*1`TtZ?j}QqDAwnPuO*jFiJ%;{^NeC375Nfs0({3Tq5TWRT%| zpY2B8?dWBk(@b&y-Z>Qo8}~We-C~UmChu#Ju*ks`FSwruIm0a1S!9b_3=NoTF5dra zH~1dglTi*0YKVykob4{Kz*VktyLUhLptId0!5ky+HAjrI!zs@Hj_tz+HyD1fx#cX| z+~CmrjP!r#AQPPB5|=qNtRZIDVu$^!w&z36b`#9)39^FzhpNC?*0{k#27mW#H~fAt z<`_$y;T{(`8MWwGVUx$~aO`2G>I3GSDF!aFyO?E(ZPq?u|Hpq%LkiOD`=AkXge9iA z%`BTNFcH%r8{A{x?@Rfb#mXp?Ofth+7Fps3E8OD_TRdFL8NtJ){$HK>OmO%Q^ppuM zafX{LvChDVMad-&eMm<*!9!-*_Xul)BY&hpCb`Ev10R+t4zqt$y__H|nB^8rJYtoR zN7{xQVQ}4ZjB=JqmN?5zme}M5_aALBvcn?|J;t1W#2Vum>zw8ubMu0ZV1<2;wVFA| z24{K10z?01+cCy1j&qk89x~6dG3NkNta6t7%(KlV2S4h0jxzK(`+ri<|2QMz441jd z8k^#y^N5=aeasr-5SxtikSVsGoHGJJ-?$Ml z#Wl{b$~iW<$QG9w{J1$}l;NjXq|7kSEv_^0REvxe9&(!DPgsPEv&Izt{jX=cbAtHO zjDSTpxWOaV7~1q8W9*+$ktxn`mdmVjn?p}mj|oOTsl!b0h*<`oVHa_j>F8iEp! zc+AMB?9*rJDf3Kmm2=$XGQ&w3;xL;WXPXNg{IpCk!N{|m7hK{ZTioExr84ws`+r+- ztYGZfR_T@oQWh6m&(UKZGtUl73_e%S8D)bb+-ID}Ofd8ri|ctZ#u27C$vGCe%m%BU zvHxq&_W}h?w%Ipn1XoJ+Wk$d>Gpw=1z?6N>1s-tsCFb@jpK8;dXYA!V&Mg*M zEN58cBA2cd)bLI`!0uTROM;M(`pBXmU;Kb)l z%^P)?b8pfR7r4m+x4Fb!Zsr6XL51O(Dc~^cjB|co2Dr+6ubgWPyxClGm@RhxN(QgD zsNSNZ9PAxz9ATc@c^%;N-&!+VVd(Sr|6sug1Ie43jH@d+XJ4`WLltKi;XcZa+zCPXM;5!aF?B&VE7$YZQYBR;4U)^mMk*HxXCHjxxjrE z*=Cc2Uoa}A?0>(-#Ucw_=L-8isG|(5*_Mnmykqrql+)|JxNwfMT*-YziUfWCrl*W@pW_UE z#lgZTcbMW4=eYM#4RUZpM>)*{E;960i;*!Na-8vxnNp^h=RVh&3xC|I6eM`W0{g#a zL>yt26Wrqz`#zxqjB|-|T;nRMJmNmbHVvR@O>uVb-Gj^5z&j}Ve!!0gymq!eI-I}O4aM)pzW1p2`=2_x8E39*e`#k)*{XcuP zIr@fGevJ!VBm|kEz>t^kQuJC#vO*gtihhQ zsP`RH#1w1%scV@nBF|oKSrQH0sMa=2% zdj3C@GtNWKaP&W9l9Sxv)_>%rQn0Hau&-wv=IFjuGR-UtEO3qMJYa*N@A(Yi2>ZS# z#T@1gCs^Se1K&3=rnud^&pj^X1cC4CIs4h<2$z3g5wgYt54q0a0}XS5N8DoM2ev2U z4E)eGK!wGnA6a&jZi_Fb=KJ80mHZ1 zCT$Hd#VO8njzuo9%1wsP$Ph=_W{QJ9_MyWBE6lLLJde4S6GYEyn62AYWVoZ@)8?8{ zrkUh2=eWyd=Fgea-Zfk7`;B@n@8c+^ImrSSSm7!cyV~P6b1lJx99L@CIF7T%EcaPt{N(N3Dkr(mc?N%O4RDZajI+r(PK9pouCl~!9)xf29y5NA+q?b0 z(2+sy@GvLH2(}(_d$+{W@7~_6u*sAPN8EAU7xe;;aqw72m|&KZtTNBQ!*1`cG0rNd zxz7TFztmAixy>YV$ATHb@Fh~s32tzPJFM}TyX^awlyQWi-!sQdG0VZ&?cHT2xXCJ; z+-HlS-@m;Z{m|&=FB#d$Y56m&!%rf){ z^%!M^bKK+J9~$`?9p@lpe-`kOy>mYN8R2n@Q52MJX-2ljBB`K-!jSu6KrvY;Xjr! zj&XxYZZpe6F0t>NhB(4QrWt;WUBLu%#ohygDv!C((Z_1|H`W3NImJ=tImrz!aG$Ge zv%>J05i`m|&a{22k5iwcoMrlP_J2W8P_V*HZn4D%`ycOsVTPf=1%WNbIQs-I z;$*_A=QK;qaJ_e*RhGEV6&`bqp*vmR*Yg+{r=Dp4Cj@~fSwxJmz$jOkda?t9&2b&+ z-G7P~oVdV$4XY!paFX$-$_UrF%1v(d?z7Gs_jtg-1s4QbjPN)ohzdF!#ltg*nM7pTZ6s~q7D(>&%BLl<8VnBgFYUu5LWUuFup#(oV}IMVCL zi)~xw6WquNvVxu7gFNOT2k&Bzro4z5&alV@ZgG{ztTXfyBWIk!z6$~ijIqiTXI?7x zEU?IBt}`}$dpFk*%nOcL<=|Z}2(+1C|I0PZJc}%Gom*_M$s-0{VKv{)h#2P{rLz$yosoY4{HU!^0ga*=^oTg4n=vv-{_mtp&! z!<=WFc_z8YX>PEh*f6a zU<%k^@SZZme(o{Gz@Mwn5N8Ta+G~ndAyX5o?Nr+~5dznC31s%eu+3fWv%?OD?yCdK zwk1={a*;*WxWz;6GW1UM7-ytk!;EvDDK2x4buP2TYQOy-c$c0l7-NT%9J=2HfjN$I zhZ!C+&%SqiL9d*3mR6jgta5O```%;GGRheyxyWg*a-G|pd#~M-6VwEe`+Ff{Jmfe7 z?~@`XxyTu=_R3c^%otmoVsOx+c9hx za81gXWQNnsv%ocOvcWwbvBSs%9a#UWKBFAxBs0t~&mz}2@*x>#;zRa-OE9A#{2&i- zl$)GnlMC!{l_MXPI;MEYIra^i0*;Z$vrRL<}r8Kr{ZwMw(($s%ba4BOFZBvLl0GtLkxV@c4d@VPO!*%u5*^b#Fql#|z+bIx;)MJ_S+c~jTB&s{F^ zh#L&$eow=K7ze+g1B`Qy^IYN**SN_#_jtt6wh_cU&p0QT;w zEOX)C*HghLtDNK>7Z|+J;$xiKoZ=y88F;vD$6?ku!DD6_xyhV!mRsEB9(Q@nHp745 z{>}D(La_QJ6+BmbqFe0(9x~0~S8QJvxWc2as?WgJq@E+} zaOU4F)<<~%H|+m$!OAy`oZ)X8Ir~{;n_CQgOA0x|7PAcep@!JcEsk;gyHd|(F0=3Z z7A@01kb1^`XtDm0j{L})VLT@o6EsfwhQj0jbVf6E1EU&XKlhnno0AOx z+&@yWbZq2Y{-q9cm3!P~;E~#4gu!1~Gt8|B)&%j}Z7U{t$Z*#jJxV4x%yGXsH^q5o zxWPPE@6_q8ah(-LPIUYTwz*~C(cW`GryJ$kojZQtw<)`*?@_GaPM7fJo&l{3aX(_G~|kGaawW!3$}$csDOp@e_-<2a{Z z+{tw_f`Wo2E_01dHh9D%_D|`+6OEj4ZZO3fGYq{%ea2qe=~lVSL)IC1k`8c~Lobs_ zj&qiom*qO$MZuAREe5AG%n2TG{pFo*|C2Su5hh>R>1LT_fs0&c<5g12y;pbqjJNk> zOa(`o;0$Ma<*%_Q8Q})Ua)KQ}nujc~?=`pmF;woxxl`s znxfaM$Gywdwz!|yFh~AYyHB_Or~Xc=p6<+Nf_nui=GZ@J zkegT772GaskfCJ_KEs-LmpSDmvmAN1=UH0mbZcB;lQp(kXWuhT#d~FloewxKo|!Wz zAG8=0)LG&V*E#&JQq0*8YcT10!|G>)DK(6w$NzQUMCpfyQ(_P{G)#iqwYit)zu;zs+HhIK0!&L{57e+bCIFn3qhO=DYI#=1? zHV?ShE5Ft@e724=7Z;3OCly>|o*P_an^mrV&e6#ohEfii&&v>F+nw$%+YCI%V!Ocz z8Mx6l<0!M7Ws$`%>Iio@(tFPr?f(fu=w^$JL!9S0i=5)23P+4QS4Y2OadMi|+~7Q? z8b-_^q8ajdd!jU zNj2Bm;1Lhl_kA6Hp%?tXNEtY=-x+6?Q!H}mhYq%0IUAhhA(u|c=%oEWbeoh4qD(Q# zIi|VDC2nx&$9mqo&*R>GhF)a5o^~YjfJx4^WQq$cu=*4Gp8Y?Sa@N`5$dPS-nf*Wg zGZioMA@Xw-8To~Z9OnvWxy21OxXS}Zk9FY18srkke(A%9o7`iQfhkk-E8CW-Uz-BX zw!McNJf5=uQ)irfFVVBJwhsecbIc)b@aV+3Zp;fq7o6*kbBI$M4htt<#6y^ zcTBxm?y$f^));=NU2viMTxU8bsGL04UF77Q&vh$Y;vQ=Zyv#|(VJ?I;#Knuwbqj2A zoozOH-t}Dfn1kVS-TrBdlVfain$!1CkAwF-*InV}z`1U&E{HrxLob&J4ztJ!ZZXU0 zp>ux8v=i*X=lqgsM==}Re8{khucffbb@Hke`QVd`=8l5^cEm$=VO24Cs= z_s;q6e*}ZSf3BP4G-r6sMJ_x-gN*;-x$bVSoE=6UsiQMe_^5M!DYZ;I@mzO-@ux~P zN1k@huWXh%j&W#02AE}mOHY?+&#gT@XO09F1)IGGpCR>}X5dxkj>9}+n#a#P=XW~$ zmYh7-UE>VvtZ|>MXB*k8?S|AjztY)J{hV{%1m`))WzI7BTm$5GPOu?3;x_xArvr@h zm?`#U?1uEY?g%rSVCea#hC?hc_yPmqFzf70p6ecQ?nN^3n%-A6ie@joa(@XCP) zo`{c>AAjY*AK&*Ltze+{XYl@g4+dHM1i1|D3lUNz8npP6e;bw_)z@u&BKkblEjxTgHws|Fr= zB33P*tPDK-cc!mB)ou13NcBA+{N5Aq3BDtA{@Df3CO&t{FBg2y_CSC6^_79UT$rhy z>h_(#4zEN4Ln<{qmAw8`ce4C9R}b8`T&)a*PUNpI-&h%V)QR*B<=<%G#LA83hkw@f z>=(+8e&tm6sC)m+ zUwin;8wVogZ(gnEoqs>o-7MeZrh)rjag8@De!YD0HQsQvTYmU8TA2UlDL=Z?yM1xg z8V^-Gt6ZXGd_cH&jY*1NCS?9Z_y5mOiUwJ%P3jIsp`8s_k z1AYwgRClI#-=E%lhLrVx|5P_}zQo@$#8vM(Q0DLQ4}`9|Np1t>`&I`Yc5><9RCnr5 z<;UMN@W6|E6B$&w`or?&)q#heJpSRSZtVQM{=P_{-`%vk?H`q|s}2mDSU6SwR`03g zp{7ohFTG~qKIQyP1HtmpwFAKm#(sRN{Os+4hm@1o4unqbw@mjPZ<@NJTfL5M+&K^^ zWp3;C;@+QL3o&IyWesuYch7gUckBGU3HK7O`TyVRC93V-(QC@LTx+Q(Ut9iZ&(+tK z?{?k5gC98ay4$+(-b?=5LhRL<4+R4G*Of25&a;QFD_?${QH8SQf4FYok_$`O+q#S8 zpIvKZG_EtRooxB*z4H0j-`3qaUw&Dy+sTUpfxgTCYY4rvX=S1Rr)*AH@c$`WR2KMe zWxe6ADC@kw{MOG6+~;KF{QX`$a3Xm5`Lc5Da|6K>p*t=f+;{OEjSs09nD{@NOxU|F zsT{q${F~1WJov858Yw9Yz3zq+f$}4+F{VVV_ntp3KecA9W@gK;ty!!2KfA5FaDKIy zS84;H3-?@a+;LrXeIoOQ@{P5DOHORhm49Bd?VA5kzT|q_ZTfBH%dXeS(PH_H*V}f1 zf4}xyHit&Fg+*deSzQ<1n z?sZYtwrIOtzvG#y&+E+bM{esj%P;Aj1?q%OtbMfn51-fR?T_Bp?eFc!`^|Igl)7z!f%BGa%dneKZ%5S}9 z;N-xPvawIy*6od@_oug6`jid5qx{A%IQ81^D8Kg$lF`1Re9IRkXYNzwliSKGtL2Ap zTVP9{Dqp(YJDax3Z`qctqx0UUytzFP{GHHeG}e3Te_Nrw4t4J42ykz#{5Q^^ll^zs z=9T52_Ugy3EMI&B^H-K1dc(lO?^plqe~mS!YRR+d)!Vw`<>%Zu@Vh5RT*j|1zssX1 zmai?}e1myhzpnhN8+38!bL9u#s623e`O==%FO=WXb7Q;w@f+>%(hawDJ9oO{^zYm# z_tQ6(Pu^srkL$N}Grbe#E;p6$UNHkNtqzy~}U8Y2e}$nJ<<9 z;iiFyUpVp6)7^ve6K}Q#cN`WMhCgQc1svh}I*TY9w?KJ(k+@@B7A@XFKnZtt;+Iv!hb z*;oFX-ev#2EY8YlKYjVL+Xf;bSKF@cxLF?hqPkmGpYCSvcsT2J;M(6_o?LX9{9O5^ zU)19A^}j7H7kjl1zHqubbw{l|j}71W+sl(}moxS9ExlT6H~+Tyiko|t8o#}~DCw{q zzV)<^%Im*va2c1Kua+Nwvr6e^ulVg>k;qxKE?E5c)8)5)W#HZyRXx=H`e}>zd_s0z zPJN^Nadl2Cf1`Z!%>xg-aN`@j+r3G+;!7F~f3r98^La_$+ezZ`;Eu`}mp-l@|0NAp zzTL~-`I(zl>qP21y}7y1MODuPzWaZx?7FOfxBT&5m8t#Two~5kHB|fF>2COrX^Y(_ z5ZL;DZ&rH~aB{-s>OuK|4ZU3Y(fJpbQw>$dPMz)^-%(}7Gm+a)cPH++thh}4_;fc> ze)}u$9|^gdakY3y4{Pc^aOd>tZlm|XnEbD^@%*;EuXFz=#^wZ|Givv+4yCzg_r-_8gUi>Rd0Qr&q%RXxAyDa-Sc_eb34}l?dVUo zT^7%jZ~3yM^xb~C8#`a?id$3~?40fn-myfIw*264PWvs(y?36>xLod*AAgHV!8^4~ z(H+U})fzj|>dv3PzNp%J?1I++*$;Q#by*L#%AdGp;C>e#U)cI>M)rHvrtjSH%bm|J z`Plsee$u(+$nCxL&J!+67q`j}x>dD}yR>`|oNq04t7?6BZP^UH>x))A*Krvw|LjNl zSaBJ;SNW~C>f>Cb<%B+8tJbR(yHBe-TmGb459=F{ahJWXAOCg6`5NO=e*-c16a6he z?A)tC`-{mKvA`Ty8DAGoTk^N;iIUhhrN>!JkjMXyOkg@#3o8X7LzsL*h;Vugl{ z8Z|U5Dpq8;sHlLHb|BV#xdrY0z~M~Up<3Mwwa12*U$r_HS=gC6oj|?9M?x^_$_BP%$($~<8W&q+ z$?Za`?iW51g^D>F5Uc#91?}y?k|nZ9wTiE_$kK^cD9g_W)22E-GYGk>EtWk6n3^q< z-bW+hR~A{)-lv}EYc$r3dMXf$xYmO9df@Q2vRbuzbAnops@1X7!p>2|nwMFPx5s$d z4^diDU@1wVYNf64k(i80 z--1}$N*{^INN(N076WcOOeO@S+~ONcl9}BEN3ZH;-s&UADRw5F!uoT&#kOYv3yWoX zH?iAtx0WYMRyQh+dv%6ttUGIv$zEeYdo!^9K3R*3ZRCE7EUl`QQEp*pw!xpqB z0Q)QCsA{D=su8cYCFvuy^4D3|S)y8hvY@>h*uGv?enj(9tL5R3SS@=u`}mm#O`6iG z+VRh5qB1-Y$#T*U3?%RbVEJ>(4IRWWpiz*?l%$W*9c>8emcTCDVzKSj3SW?wAJg8x z7c8>Ws#f2&pq3A@?7v!Ur{h#$lXCZeMvb5jP@qQFC+K$kEvTCVyW(Y?r^cFF49tI3 z7JWjEnXmcABFubQs#?h{WH+;q9f*wro6J2(Kd`D*cBs~pHXoZJ-I|DBwQB$28|yK( zQcq(W-R>JJGuX~-VEaEcL(cttTC^RM*Wr_k-eG%~+kZ2 zzHI8DzTyv*Y^*Sys@3$Nk3EnPqMp-PNj}mAN1;6hSn#n-+KX27C%&;7!TC*%Xm>;rPqr>yNIkpm2hQCA^q zr{qr>7^?~mIc|+>L8<7(f#4d~1NJQ(7^^k64VdKTz%EvWuaWt^^r3s%0ExngphDH^Up~O?iqZ2H#F~GtHjTY+ zw`$!eTU9G7pEes+Nv~?P->hPWR^nOQ1N?SC(;rpaGk`s}$n^ba)!aJ3X3^+*)_$~F zZ_~Pr%}@SM+el=8?x;7}#Cs@n<<==xx%ueG4vF^37TR`z{H<8vP!2%NFR)u&w!VrLFwm6aCT zSqw~Ar*Ls9`*%>QfsEFcs&4il2bh_PogJ|IzJvY1!apf@rybq1$xxtXv!{O5t*)}L zGZl7x{Q$q5W4JmS*k3PmKBu(}&uXOTU`p=is`dN;`w?Ss8xX75qNAx}Z*K<{ydaxY ztLe1?X0g%EPSq-Cv9Qy_^+5b~9WOOvPXYQ~mr4IdEBVa<=BH6t+P~3?c}v65sH+08 z)PJa!(b;-nM7v>RGQ9(}f24zK=r*cudXEOBAv_AZ1XyC$7&Dh<_sXEwSa93mSf^~B zg$<}_ryQ`33fL5742bSC}bNZ>FA2PF3lU;5< zeevEg$mBKp(tud=83#z>25bi=!flkzUlEg_R#3F5+o`%;2nTdM=jxmt9LqIzQ-Hld zBLzk~Kv~6uBtA7PY5zgD9^C>{xI%Sdw;Rx256t+Tto{$JZAHrTv^1(#%w54MMiI*a znpxH!lg#3Kmkg>_9a`n4=b@(DJ*YE@o2|*+=(GZpY`FCCI=RlLE8v$H?kEiksih@r z2FD^MBJ^ZHs8)rND+bj$YAG9`BC1J^KYUq(^Cr&9xtrm8g#?AyaW_aG^Lu@$tfU0RP+7W9y@4#53ik(RkLUUhoT zXFgUMPBZ2su((nt4Y0lIu9PzesG#b?14R7dZ>B}t;I>~VH!HPh-5?`q+$=z?NVq^H%-#yKMMCoFx>1`|v^F#E~_djE1d`3=+y3RGCAx(x`o zo4PG3yd|jH4NSZ0faWkgzkmv1nui{84kYECbv6uC}@;l?Son$+r6F>_IK#J2(QY1E!g~r+LI3sNSe?!`G-T`IQBo z&BzvBb3pHmzNP_Pz{qQ5{?}CKyY_&-T+#q5L~CY!4s(O8oa6b;45Rs93`GkSq%F0A z&)yAeUMgEL5!Sy=-uaq7G%l4vN?Y}Hq!eT9?QMv4TqkpeAvY~QpvyWTVUL*4n)afs zRC2=gR;sagLr%J0whm)7@+Emk**Sk3w8Qwoaf4i@W#VsSC8e$WCZl$Z(e5fsJ6hJPkiq}rc>f!6!U)*+rp%#?3VDmf zt@{5B>KBfnAN_Z^L*=~xkUwh~(k?qxzPCLff1Q;9HhhEl@Y`bl2C<$3SsCu0ZZE!= zXns!?eWO*bl$({;wo2A2PJ2(DGh}a*-HOYL6y>zdYhous!u$o@^cy!t{X&j~7qxJIYC@+v&_ABv}u(Ad@3Nx(tUo!0o zQQ9{&s0S3yf{Ryu%5I`c1=Wj@kD(iqL@ZnYLzXUU}`tDOe|`PW_z%-ks}$28wT zHrEiTRjv3ptR1G)hgcbK)NHQfGHwmtlznK04ZkVhj?tba|5!iWeaZk7qM z*)9zzV*{20yA_yWY+-E}^X!&Ip>FQAcOT%)Z)A~DRVoIPc!^492TIkz90S_>f!XiM z4!e7*gY2IFuGLoYt6~$_9PugjNOpBHW<;qY+z4O#AW32Fh_KW>^5Zb~DYp3cg6f6P zL$hQqhMg@~u7_p1*WL~6eNVQAxp^htCGVgaR@fzjYN3OGOE;UAy^x99C3C_N>mHKJ z!V!ynUz5Zsw&4$~itOEpd3gtgm=UglKZNkP63+jvG)V> z`!qhdA%k3EG*kSlGZ$abFetFD1(T@(uv;bNyDs*MD_Py<#7NCDW{UO1A}ADkwp9#wdQK! zb-Ep4iNkWH6N}M@Wf7%q^uI>$bWX?rk{LWAYnAQ#Rx6$^olbf@@;}Q1PR|k!4x?5h zoGHK(py8ir2dF;Cl(ZAj4LPFQIb;4-s4lR}g!RB4V1}&G<2=Z5)G{oMs+$WAjM6CV ziXht_b0rh(s0^Nfk9=ct!bJBe;a#DAIeVfzHasNEFPBer&kXMm_scC%Y|#;ZD-+dD z#BeD%VAzMHh9G-_<0`HIY<~Gv4R!GFKQ+`j!7no+-7_afJN@RFOdb!MQ6n)odP2}# z1NsRQt=gRJz*3-@=hS#ZkSU$2+aKxIt(@jJ&((}vl%FlN0aJjLKpHy0-7vZ#ll*d4 zlzV1aS&S@-(jc4W=Nw>cz?+dy_sH5PJW}G3=U|8BO_$x26Fa5{T77Y#)vig@+~f_m zIwza71~ezUvly5%Q@O?!6etfANadxf+hTCdtPH!~WNQ#D0hXO2J0?+YL42Uz=QkNA z*bS34)K3%pWZIsZU{x<^&~5qPK>ZcJVs!|z?e#!kf~=m*1V}$4sMV-ih2VhJC}QnE zGXpwfuHov?fX25ApqMk2Y2;2&nt^mjFr^#Ke4vqFpWH}-H8u*lE}GkUrrhYlmnmn- z!&=s!C0i*cIuZkYo3+V|1V7S5;FM@qjnr$&DRY7?%LWz!)6AR#ss^zXQn}<#p_Z;W za^n=7(vsv4+)+p^bXyzPJoh<$s7228>n#+)Vt3@wg}JhCihG)Lp5%@Z*N>2|Iwx3Z z4gx-4l2MJl5B0)xWzmmld-i#Owolj?IQ6P-+WD4iojvFl08P(M7y-7O@0WM|Ty!nP zttN}sZ#a?0XQYVzL^c9RvN*;)Rnnl@axS#AofT;KfTU#&kZ7RiC$buinPoqLOk6u| zs~LAN>qn*=9xqY!9&;IaBh??+28dtnr-RLXfHM_#%si{@_H1DKJedJKs{?IbFXUJ$Ij0(Jq=%t7{gVD$o7eG*Of2g%Z?TArTIDoQ!PfOj*Ov&aEa(lPHsspk@zKa~*g{F!CTS&vlw&;4u}jTHdo1DTDK zMl~6eVVJ~*Gaq)!fL?lSIgKbY)=ob%VVN0nSPds%7Sv6OK{pp1XimxXoa}>ado{4{ zGFcfzu8bUzhhv!6MFX;xGO9-}S{P+ai% zV;U~%Q15hi#LVp5aj?4PE9im$VkisnS2H|oCIb6_xn{+n+&hd+sfH>sWUB<55$5cH zT?;fP=7bSo+Z};TpSjXT#Ds{^Z#mx>}^@COd5&K`t(Ky&6eM}Xc&Yv}Byz`{oP zQY$Kj%=(72oSDDnIvQASKzly0vr^{IM5=9_U+=v&Yzt@7-0DBd9W$8{>D#O|L>i&n z%D|>?oujDN1I=Nw#}v>a4*ysSOZbzVa0;Dm*dTK#CpL?J%;CT#X9r@f@Dyw{{neOY z>bC@xJAp<(z8Mf|RH5FcU?)crihjwe&>6FW)!l$bZU@zX=$m%JJBv;v@O|qnI#Jwg zc}8-f+uFgSrb`-7tAE9^X>SL1y&{`t(Fw<^@+xIi>L&l#h=%FcI)jaa`%3N;ANL1d zr-&<_d7cL**a&8oGTxCORS&g9hV&qlg;bbhvs@LAW12V1U0OC!S3K_T4K_hKk+Vg< zYBkB}xrLk#42*ONu)yL*J3!SSb3`TWRCMECvxFy9z|MZn41XKX{F%k-Q#D~cEq^|h z>I=#!HF-eg+Fq0A zC~fU6I-?3^aEq_IzOTcA0-Vo(S1tEqzj`S_$BI zQ>z8BBoi{k_Hh$^;tI1~%L5?13Gz(;6lF2ry}<>`tHyT~AqQWWyOKB|aU@PMNo{ zte_OAKOa~Pb9Gh?oLU7-3jc|arpHHE0Z>=SnV5@r=6pS`G5gW z#}qLRZ)&TJNdl?{m6|(z&?u?6IZTMe!@zfMcMgOoR7MZPlwSO<(Z zry{7qKt?OG5@}`Ah+LIO=(K%f4Ubepw{?NdAvi^i^Z+x}<+6URYR0k~SN|OTbNL;8no(0nIqD*8@ksmDRI#Dt61CXJcywcHk3* zVkYkY{Jf4gmK?v@${G!xh*M$b14j+EJsVhgMCQ!FR__tHYz_l3d{kC~ZKFr6u1W12 ztVE1idC}=ZZ3&Q`>)a{=7LCb1v~3|FL)Pk=@jEu71~d{JC>az8*sQZLSq2Vdsv6kM zLH2}ZU~9;bJbE^_2JJjNe>S%U-q0a=7fM)sk9>JHZSCxlNlB!f=)G(jG!mb$vO+y8 zi3(bYhSsX~e2!6x@0RJTvJYI;jQArF`lPMt~IR5V5mjkT!q z3jt-;2G2ChM3Or^0)PT$kkw@vF`B&;5bAovE-JfF*|R zglu5<%;YNyC z%?b)iFjEXD``^~Nc1kxU%7Ilnp&m2_md;3SvU>DKa$_>4I--XH=P0R#ZW|6_rw?ld zCs_e!cic;RPm+Dfgm&V|7Fk^9p_LrO&K$&2ft99*ih+&5RP*8n)CtNpm{O{`(Nis3 z&JNg~?_fXB6%+JsDaRF%X;}QKTLCsw0N=5|ZUCC5?b$$ojLi8ltsOCJ7}GiT$7qGb z25W3U%mECvwjEdk3|x+Z>Oq0lb{e|VteA0n)({jxlkH3amI1j`Xy;uus0kD}ilv=T zy=~w$(=8RSW86c$_}5!odo-~96j^;ft@Y0eYBj1>R{T&PWSpaj<((R+frG*N+fS9#QV5;Yv*fZALPxK2z_y+rTk2AaoGtQvt2U<(a~@!ziH`f& z@By>TO&F*sC@ZcD(Cz+CI0tq|ie=ha3>*a}nxhViyudOnrK+0^E;D`60lO90Z6?Dd zz{(3{#|5;u@h8?u*%QjR5ahG^3+QZP>QG=2lcWnV7BO!qa71vHAeIj#E8+`#1h9h- z@Grzz#YMrf>V}+?rY$hmI#3%Z#@ssgVlt|A!O)m5gy8t(Q4*pt)$V7i{gmuvPBl=` z#lh@b0IUb*m|ZFdjsi=~y$vWg-SV?k{)8sCfdh{2f!z-bG&v90cZux&32C|fXG3Fb z!`TUHD~t$srK0Wqc`zn&9$=FJBukUX?8U&gpUa|D+~mm^(wl9KiBhz}T$joNsl>#{ zW%8Vsg_p~2N?UPeP(9^A@^_|8nn%ctX3ClK5X)I8ixihHl$*h}vPBxV#s@b@CtqPH zOY1zEmJ7}`y%1T>k^~Igt|tJSvQ*l*s{r+aOj${queyta!X>aHS(F0Zss>j7LRQYF zTOq%+Vnu4vis}R#Lp6CVPBI2mrI%QtBfV<77VIr|7yA>B-BVS(Ro*ve9jhv7M zJuye-P)3zqOW+xU`iM2Cg=y5{U#h+_&ZsR9GZmK&aUrW`RA&Y-A6OwP7FZWeov4I$ zE|U*1X=~064uWd|rux8vLCE<7`FQzIV8yZ*1KXC%q6IWC;d;4w0S)WCLDnj6xn7=A zoR%lMDQzh?S}wGwRFDjAlu19u|3yKvr2Ul2O2DSKoE3=m2HDPfU_UU+yiEgneq))G zM%9f62Xseamj~I-m`6whz$|m}f!YkFahC|{02P|!Spf9rTZZlBz=V8Rb}?noh`5nZ`Kvtn6KTylAC2~x_er9#C>c`^g5~+oha9Rfv~>r4^{?xloq2} zX=Wgh>$l{GfD?c%s8pD+9GGr!jY}|4W|_s5%1dZdFZ99VF_ zrM2N_C^dhllv&BOE0DCM?#u@!6lhv9oB%2ZnIj~Hs@oI9&KB57D=fCN8(3&mWXxVr zevm1>s@nn%Ou1mI>>0q`6*B$jG}gP)l9H^Sqm})D)p%zOV(CG)vl&=sKqHTV z+Ja1JRo#eNEL+aVKcX9i_5@(@19Fra!}4#DX&FqF{99Gp=sDazvtCWSg&9oKid*Fl zmCAb1NE}LURC>{a@;B&VjStDk%5VNdFgyMUDS zn+=zv>b*;4^}sN>8Cf4({pAVAMGwmBM|r=4M*8}o^$K7?5Zdd3_3LHz<&1wj7EKT~RG_7SffB*VNg@+MT*FX-7tdZF8vydDhS#A>~iv6d`n2C&(H#;FqIZMCL} zWG!+>gjcqbhuZlA`*b!JMyuL zb?=g+iv62pS{4rL*cBYyl0S1Duv=5Cp2}>Xh+0{xLJ?5SIU}`M+=-`e9vbt8Ge$3$ z5pd>zF%&*@yvUll&F=UMGitZ&QxiVO<_S(*i|JhEyTOfY4q~IgKt?PECUt77jCaYr9)XU&6a8D94_2&8n)$zP_v^u3510}!)HE`#52E5>5cxCU&vR|@0>PN<-{r(Fw zfk6KyfnK&no`!F0-(m%}^g_2ewp!SkxQS^DtTAIP1K1Aa&mHv}dQcB2kWsUipzD2M zNMB>=@>K)702m|dUI#V<^MOg`J{MF1N;Q4citfA~aFhD_i~GifPBF40_$}oJ9F_1m z#||9CUr*{^9fAtFtl^NPD``30G0J@XI%p6Wc##r=bb={4(fo) z2gv)G#gyEu(Jcmh%=?!H*u{NAfxmRLw*zxOmrYk|g#Ft(BuJ-f^@Cf?LG(ONsS1(3x6CQx024AbU2j z?7uSS8njYJEC)*NHE8vK>r96>AeQ${Fw?gKQ@_=1n{o37@`Ex>hjyy2_kY2YlIJPX zA27`{l>%%A8p$!*0rG*&K1tfO=*Em%*jWKP9awKHDK=2&sI0!0#`Z!@Fe_|SrGz8F zjln2lSwM6C*khh%k90%^(F)5wA}8b!@wrE3P7YQYjs_=lZVpyDz&YjwQnko2noS%y zX54F?&}vnzEaYIIa;Fcm4q&?3JI6C*F<`to?x0Zv84I;*Dbpz;^q~1(>*dwhG%}J( zK{YdwWFckC2s>z9Xw|^Z2QqyKxC!yV&ai{>=u)mAyCV(;_U;o#peNW4%DYRs(af_M z^188FhP9R;v}M+_Cd!^%eKq#Zv8K*qw>tGc=1dP8?sHEbWySU6_g6UOW^{?lbP<5?PY!aPgtqiW@z zbkNFIqlo36e2{#lZy)Vtz{aUEn9G7TGWFnC2~BbQL6$9P$Z^`py%Gh9R zRRf!WY36nw)B_5HNv-N8ObdpI4|WES@MYNT4%XMUX|iuQQSWlgx68SJh=`ME*AxBz zIGIm5vFnV3WBuBqbMH3ued+bA4%KJM11gntmOQ6rMxyMdv~{0t#F{3(I*fND$)sOH zPEN7fYcJlyOrI-@eodW)bLD2(Veu)l7HsQ9jIcplT7OL~73a#|m0yr7Uuv0oo=nQa zTo-bUrZ~;9Wh^rTH9xDQ&aP0&J8rDFwF`Odo@xGX|nPLdK0lgXN(c&wKrg_ z3mmxJ@*!6H(}UzjUEXY^`6>MvO9L7+@&%Lv|9L4RP|a8 zmCSe>sAQ46^BWo&^UH&LENc8oMm6N5D-Vt}Xk&g7Y@|2e9bs?2>fl&&h)geVPjeRi zmCJ~$)l)_%a^XkSg7c~0@k`Y+PO(V!L2VDX8!205ww2zTKG-?IKG_{F(&cQ~mye$- zua$4}@ncMmOuvaHs@SMmSJqAVxn!wab(8Yf$X!}CER#)?QA@51wBf5_Yohid&mUS@ zNq9;%)${;8IL+}-LrllPdox|^T7HoIlB~ViJ}Jd-|5{c;vvvIXATK0W z{WfrcXHRdU2RF!8WNc}_KWN?K#JofmH)@T>$rR-MP0&}~-_rh~-^gjd#c=O$t&pSAZaz51jSBG-91_2pX}DS2H%(jxe3RwBS*8_WD`bVt zXNHiy>tOsNVVz!nCtf&%y0j}x~VrS~hLSsAY(G3RdY$cR_aXIBNw& z2^`pTc$&GW0OlKPdkQfAVVSg&rl&t_5JEa-f zG`PkI^z1u>c_4-!#v_`s#1|w*|W-hc4)4I-s+we)|n!^?;?@v-`#oTQb?htvOA$!XewV zD9~btO zEz)GU7MXIt7G3h}?e5dj+XD(~x=eQ8L92Qq7z&BK!w{IK1zK7($j}|sSYRV=WS2fx z^4Oq{vqBq{Y020}RpxS;^GED??JB?YPPp95Q-tMYnl)9xA*_q}^RUiabx6TEGN6(M zc~)qSoLB5VD|A?v7c&e!vQCQ<*;(v9JuKoX`LYZuTnHh*l1;xuC0ll?N|Aj2JM2ZvNq6CfN||>T#1UDpMV8!85!RR^ zD=}xQbP|6ubQhg&;xStvXNA_wNq1B9%LQ5_%2F*-WzF60(_`BU51GFlxnPnjJrHqa zC+H~dRH;Jw94Q7fs>D4N*PdDeaabHR^YuvK(G57RP{=ENQr2LN} zRfCjY7T!zM(fHw5+ga4%l1J{vNVIIbmlk+`K&lQYkL*{eM6s39!PZr>yN1E_OlDuW ziorcGZl*0A&@XFB-Lt|YZapNIpA;A8^wO6~=w-4CdT5mlQRub!{AZY+qi||(4MeAl zXIZ)isYY3|#(jEt_HBn`a-Ap6Rtc+6cCBH2$|UqY_bgi{ltzjAy&*jJ_q4m^w(-4- zr{ef2I)Rq|o*3=9O{Txfh!jHVk}YV2b=)S4+TGLR8kF<{+HKG~wYt+oN42UMHrJ0h zI?2NOQ1%qbj@8)9gcL7J%itCok6UOSL9vG-EV)S5_TZ%+I7vl^vxKESD2iR|<-5yBBFj8-q-RtmME6*u%Yz`#l81~C~&`^Zu{)MpIO<2ZEWeXy2t3;j* z!HR`7<_(zp8RoP$KT`QJ`ypymcAz$|RhySZw^WusgnfSVi$Y2tVmwpm;2_6c3dOhpyT zlPzme?3B;p;*=?m(s`FGcvRP`C*~Z}4qps<2`DNfgLiVr6%T3@k8A3Wd`-wwxQ8Xdwhn5#q<*+wXF*<}P zGVd-yCdZ(y`IGxZTM>`BvJEyvV^A8Q)X9KSI6?dgy>|3wT#sHotX}!mpIACVo*X}m zs5K<#6itTMavO=D6qqjCkq#?+Qio`|y#rF+ld`&raY;g>1l%gKs|eNtSzd)J`Sq46 zM!mdF)>e}g^!ETu<)bRR#%F}xsj%I+?Vc^GOl2p<1@7a7~?& zTjE-jRCmby8EEFrW!A)o&cxn8UmI0phTU^2iOS4S1s$+d6#KBCVmA3%f_A2*K7b^Mn!YlPeYZWeq6IXEt|2*=YzrWsZ#W ziaTOj#8cy~>4eQRq~xf$=U{GjH3o*ClC4GfDDiaovh&XbNEVMH@<=uP@yoVqUE-e} zZ_A5p6H+c2QYrRVkKsXw%zF&y^XZ~mSwizYvhFd1|B~|Au{=fxl2yqqu0Io!DW+`5 z8Jdy}wRj%c^!!<~9<}PxLH%KEuySGNnv!Kavd=@3S&qVtxDF`gKcLj7beZ`VBM@2Me!v^{G&xDryQ>{7)Z8LAJYA~8)FMw3q zVC=YTl{{C-F4(d4Xs4l}eqR(=7dl~gO4Q>Trm(*srd}jnb2Lm>JAn~lbQClg`jk3LtG*tiMq4gJe;wH2x3H6JT zJ#j{^?SsJ2COySm?Uv-KQZ}3A`&u*bsUo~V&#`rjf_=>Jk-cGy#}dcW6gt9jqHL=uuR#;wCjRm zJWh?R+c93ji`j@YWiQx9XxIJ#I}LWNvS--xc&w4l+we&Zk}i~Wrt67I+gAmKH>h39<}!=wE3V1N&Dx*@o1y!J4!{H-RhuN+(<7eie4fHbpLZ8x$MUI=%<0--%9) zM7?MP@$whxa>!4WGVetk8ZA(!hDEoUv78IXB^x2dx-fNYA1YxxWS6oX$JC^K$TZkT zUZf!ju)p7UFYJhm^&qvN30J2706PtKn%o1MC2?~T9;n(mzBjB#AxTJ8$^Ityxv_)}yv%A^`PLzMG?f(O{h7LT z>C47I-Tt!s+%VtYWveb&m2ie-*UL=B{C}{<_nTRJE83ZDH!|D&u<2|HJt3@hR_U>Rzb9Nia z-{ynFi|!rRa4pgiTKGCPxE9r-NKNs}X0PjS4D6O2TWC%lQi-x3c3Aqm=Az(-R4B7s z(cqqgBCP0Lna`ROmvaSE^4;;>)P@u(UADCn!@aPNO$SY|IU}g0;djl;#8F72$B3$> z=q%lgEZ#|%vO3Kh3?=76CKi-j)@d#?4Uo!Y%9{jI8;@N1zJZ&1I>)!pXv$)(e%>1l zLQki;M(Php@vK`on-A?C+4u&wdm-szxe@lT3}BE%LKU1~_L$@C`h~7N3n9g3?ipW| zmv*KZ?9FfDWv(drHx4YU$AY)sB!;qN;7!ajMs2L@9kQT}R<|ExN?V=wOWkbV(?(5g zu#fd=A?#M!f;RWqd(_AdJeRvf!)2pV zIEB7NzN?l2MKv!PDqa8J z`#K*uUZ%Wl`PX%|VwCkjxvCw-?{fGCTr z__6GFP)zMIZI%8?GvRh66=CZWt`z<6aGg-DN;9PKV?wD9nR=P|PbN`4YI>=jc#UyU z(}6d#b|8{v;71VQT)mAVww2as3#@~Pm&Zn=I%Ghl_%fpddtF_!n_mUAd9T%%AWJ(q zmxR1OKDagfvS5e2FKav8C&!LrxE!d4bJ_QJc`SubFR(}s-rvDO*Z6+mFz1KGW@i^& z50Q1d8G@u7O`I!sAv`MUcG2_U_hr&s^vVNgM0V}M`}uN21$Ya&n`Y*HV63F}#HG~p zfy~)Olb7(^tQM!TnL>)}c0Zn|gxn;%Acr@6VBR9dbwF$UVEpLlXct0nkeTmNpGOwI zOMNl2|6THY&N4Ffhq_j>k>=Se+m)N7TrH5DVfVpE~3R<*-PN$cAE~Z<+)Jy zs#LRte!#vo<)iTp_0mw+4SF-a@B^f1+y_K_z7{j2^!Eg28Qcol2{*Rl2b5c3m&*}V zu9BG_lKX3ZKq~r1O}>jiq_?#n1^ku+t?>tBi=cBOglt&TM@By;v_NV@Z$=^8!va8$ z#C3CPlOT(`jSPBIH}z-BBU%*8HZ3aUeMDk=J|4dj*ADmnM$fS`KSF9)F8PS1AYN8| z#Ll==t)! z%yoYczbnTN6Y*^8glj&EcQ4mq@q3StnUDg_F6;L4jzD8Q9>_L(FTQn?K3cqw7|L2eHmV^Oa-dbpWBZ8NO4*4f zJI0Up(XDK;eF||{W`By+VOgw2n%qtiHrgvYK4oA^SL*S3yK*vRzbQvShJ;b`nd}>2 zRm&>#@Ne|pqRDMxuY2lAO`m=DDl(a#r^2e2-}UlJioZPW#a4~H-)pqzNG}PxL1yoV z*dU83!W#c=u3Nc8CCJ^F-2Iyf6N`K{+OaRAE!UvGV-7CFXnWm&x0N*n~`O6HTMhpWNbtm4HE->RFouBKBsXBUz!)G zt|DX6Qc~iV<`E?e61UhvJ!@LXSI0+3)}46mD_Ps`J~?dkOXH2b zwDueCa^68s^tO3o40q)D*@WjP-njrX^UIqG~jmXR|scqP2e5DbW_&c`uzVUrh z(R8KD8bs;&Q(wBzni?@UzP5TKMyT!HAH~JRb^wx(5$J`MAaP$|f^TlVa-SHUGf1Ys z+!HH>UvYkH9W-Wi6t#tDmHI;_!+dc_>m0+TFB%{@hR6FN0nseze0$?F67XyvgP7tE z9Lw$|(9LICu0G2~9}Qr^q=-%Y`gmKJNF~b=Y=!y1mSqo-h+HMcnP31#79xtU%3=MQ zZMv-l&ak|q9AZuj{pW>@;?zM}lOu~kvF(S)do)_xe2<3LBZI_gt2{Nx>>8C_pjg+) z_(tg*Y(+Rmjvy7=4O_=w_sRNAf>)ncYyamRpklK80gTjqb9{|UkgAb&u*0gpF^=E1 zN=WQ#A#s)S`2iy_Mfowq6|SGk3Pyu3y1e?LOP$?{4*L*4-7AodD%>nPDZ-lmXYO$H zCq+j87s!PAEVGA@BFSsPsm@OhsT^Xd9sb|=cg5P(kWx)I+lFY1Lp~bfRb{CJmrA_`JMJ*+ zS$xQ0Is1?9xCx&7=>lMKqdU&lfk3?6bC~r4eYxc&XcY)>a`~_2ltwToYmCGuQisO4 zwpTx8$WBtEE0z3XE2{9@M27ff=@B9=p|+zE58M4JI2$2s+;}wR@?(3ekSqqoO`Tc|wm; zFnV1XT@5K$_PlRk`_AboqT!!8@9Afp~ri;4-33F{8pzX z>@@0B=jfdB@)-S)o{1KJORmTXJ3N*VVCzSM%FcpaA&5 z7L2;5UfLgZc-$8rT50kh_`gZxYg2kA^aSWJJZp!ouN3l>E}OCHsDfPtS8D(6_ShO> z^vVGBO!LFgxvF~B7n{9W&t#c?gd2m%$%n^XMQDAl3Qd#?kI?z}A7H1!<`z`hsmHLr zXcxlHkS#~(Ym@Aui1nO!eA_#b@<`NCq|#;XQEX-WfK>b=YHK-C;n^o1mQUZ;U^&Xm z#aht2SH{H}FO)qkWk6dBpfwdat3&yC& z$IrP>{=GXcPJb)|FwX1hojj$>W;Hc@4BHF43ihzIV=}F!vraW5xss3jQI6?JhQ?RV7$H>Mh}c6i4BF5BlAK%`s(in zEqdh4xN7(WQRtVaXcutTN%FUE@T9jxp z!>+$J(O?Lf-$%BBJLO0ibw$dl;S}5vgnLK}f7B0Tc$^hh=9abmo5}VPNUi3xt(NCe z*$W$m&|et~U5>brft#JdY@suXuP&k#z`$6~~$8Y9KY4&$d>c{mPzU>*Fy= zX4){x8zCE%#46(oMjx|y^eJ@~tI0Ns@Vpts$tHK4u_4lVpd!5buzSv8voYK5IUD~h zwR=vFEk1wzP;0vNAzUmQVTTu-Pp*2*9mj0mY4`96?|R)oM@^tAw$T*fbx6#3mB2~e zz!m{((OA$R)8wtsOQ2WFx(S}CY&PdQFj57DFA-I{H=u3PpI+!zDK^?XcB!OpYmnl8 zSIA|u*}-ETk1_fE^yLKhuq}!@HOUz z;~VCsVTILtu-M`>e7XlIPCZAQG}9|5od9B|d4gwZSl&-$tCMj{drS`p_rQrwOdX#+ z)LI$r6xn$K)-vRC)#vXvCQ`J^yonI`=3^obEuD8*9&O-n8jJpHT!p}jZJ2j_;~HVt z%YbU~K~$vY^jRSnjUTBbDy>CI>G}i05&!&L4qV6GMQNlbBDM#rHcLms`lvPcFM5x$ zG14Q~%x&KhVTX@~Xim&!fd6-0Vmp(zp?g&R^NHp+7@PFV;F_xv;v37N7y zia{)_(Y@9d9>XJGUGxBbYJtYRjmr}_=k*#mZW5hfo1;aF$t|7aafGL!c162pfQ@=c z-7<+jkLzkkZ`q{7*4A0x*5@qP z?5JRKv$IVLE^np~!YwdZ4tXS#?SWy7s5P#9rXbT3aL^ROxCjC=X8F|G!& zyo--t*qWdh$f^juTSQlM6bGje)zakPja1(!K#z6m777xRpYV}XxZ`#DqJz`S61z% zftcrjc(TX(;|# zQ=xT0yJ(lbq<>mh&ZSckkCrvC!V)i&`O##YQaHSUQcjBO*CJU~#du~+(7$F+yv*Ee z+g#7+-dX9kWF9$X#;~4vE|X>1p6PKVkd|CF-alUaQ>Ap-gD9P)m@%OTN)AR3yvxXh z)N7uf7fUCLppE@qcLvZZF{SR+K)1dn%Y)7bD6veFYS`b;|3*!)t7K0s{%pn+pZT3? z>w}gpGp8|ivM(RsxCD$h80@9fNVT=Fzh9wR%zIW-=VsOJg8lt@sg>8l?vTCHXivuv z7|$`-QEty!{06;;^VW0f|HW>^M-e}^`RTAnWR08VXJs;sZ47q>v=V@3DqACWIgKJ zOoP&AP-e!V(1?OAw>EEsE)Ywh#da<_zS&u@+3&|$skq3(dJK3!ju>Zy6UXTH%gpIG z(vOW~oX5a^_g4;EG{rB49qN)b(}~Q4D*}-TCt0>DCsp>tAu{KBJ?;&wxlt{EnIdsB zSbghd;S88egXwfEZL0>#Ju}d%mdzC5)mH>kcmu3j1RHRLd>HzPw>mqIVI zz2S=Sz10C*@`5^JofikyVZ}IjRYI$iU8>HX-cf|NXayfLextC40iS-%q7~oBK1G(# z^h`Y|IxCRIF{x&=V0q;cSg|Rv5+P~e>(z;}OJQfqc4ZeH!}h{%gk2^BGid-Hu%CjH zyH_3`%&u*ks20NJe7H)BTv>k#Ig@`D{uG9(P5z_ANQs&SF+nbv1(81~R8%UD%)-kp zvRzT8{AZSD)=6Dg9uD5rxoAe;Uyb8qyywKJE#G5l3nO2ol~*#o^_DNm1mkqmq1DM6 z)vZ28w*Xd!>S`jd1n`zLo`&*AHSsv4;HvS{TC3|rijSO5Whe@-BJLk2`z1B0lUAHc zr>bQ=EPDFNsUAKezeWbn@=SB8Vkbfli8>7~mrE4k!#T_}{x(qxPh%&Mx0HdsmB`6` zNq3eTRWMq1YLPFWYtbUk(+%S6(}~Auxdas6azkM9W&KUx+dcxz(Q(7!v0kc_r29S5 z(t0{ePr1B(I$rLPZ`4GN#3j(bqWr_gKkB0Mk??(0iKByYUQOfJ!gj} z7UFk39dyY4Gp+T}kC;bhpT*LV0sq}Qm~g4DGE)Gb4(K2Oa%JOL*x@sev+#gd1{77u zltf%xv1)uy*YqFpnuf`OM3(c`TgUfDXJR_+E?I*%!}M4pwmM}yD7^F5z*)2fiC(}J zKj&-iUI4EdXA^WjxnwrtX>!wS`s%wa;Ea+MjzNIO{q9)fEm$oC{={N7?Mo^e-##6v zPS^<&H3w5a0@bK-&3oqHO=e2bR$41_9d}k_Q^I^Mc$HR`nyk;G}{?Pcy zgdHzOw2o4leKt~+NU0Z8$~tv$EmS?v;x})ukKfL>eay>mHp??6qiJu zOAiuD=;tQZ0`D7o@v`(>;wW8ihsEY-BSma+$?-0(MYu@zA{<_b0plpr0}WZd*)T6@ zLf%wA%}b`1I_TFugf}yxbpv$T*$NfNmSlRLDtnM)(fr0lap$2my4uXK6B66F#k`j! zKuC)Bia5Tofx@2>orkJdwo!z8OU)xyTnns(((%EgA=0IEnet;@%S+{G61z;-Te^xZ z{PF)&cQ$ZYS7+nDc?&EoOial8rrV^VqQXUGg@r{$g#|@L4GW8k3KteFY#6vvQNx8r zUbJE1qGb&WH(Ipe!bTev7H({#jT$yuY~h9*B^KuYd;QM&Dfg{Dx##J5{?Fs*Q`ddH zotNue=Q^*y1F6)=VnA3OseE)k3yyMFDa$_DnTICMm6B@%T^;li*+eQ~Rm-UCKW4-` zI}Lu#0ba38IgRAH<&@JLBQHFSinM>zt?@54NUv21?y~~oo9^4wx;;oW%H%oZ(QqH0 z_Y}5@{*?|#7tX;*qq2AoE2rLXp()G0=8KiJbG%a-12;gHjyYcM%F~J6X)@__q}gjb zorKa!=#cfab845)eixrk5qQ4+bfy+9NXKVUjucbZUEiP8AzCP#5DhCq-GoYLifC+$ z@Vu^WF!v17DwTx_inS0&98e6S@IGf69#PA0?thN*ppK?O%d zdf#BYu=zx!DHOyS4^+R(e z#A(o?s?E&wfC3QKa!<_l9u}We9oVv3>00=VdAb$IhdXmAfl5sbb1F58RFcd-3-?HY zoeD|ETK5awl#S}Ou-Qf9XRfR`ivnd)hC^PXkX~rnvhgf}WQXj4#S8$6sSzVExchZB znYT)gf_7PVHV#mGHV)9Xmx7eOrIQ0>Sdx;w)8_3CZFM?&DZNC)0dO|D(Ezcf=;=bAB#($}hS7(V&PyYDKnO|mFiF~jfreA_#PsMGG=H9V z27Z0ZJQ5j_auCAvZ7_vc_iYO zznMNjaar$ddDkINh@3e7tT@o;}}t{M?3TcUM=N zqxrY^e-Nz$TGa%aX44C;Or~7moi(>?0!x#K{v81}h~|e@FoC8`nF@^dVT zjgu@}o)-`hyz&mIW1JldYGr07AV$v1#8k}kGPPs<-kGN;BTe4P#Myf?sbQD?RtxUP z^qv{tz9Z046UjQZPaQ1hLhmtBu)yn`lm=~>#Q4PHLhsoj_44k8l&WqALkHWnzJA18 z_ma#g^cI&Y$^46*(l1t! zDF8zK#Z)3!UcMOdV)^UEq*U;cIdg~{{{w?8i1X2(|BpJ9EyyCF5xFmmNK`od$xbho zQ7<@;!O+joDx~-%05%Rcb3QSq14^kZn@?UbXR#n21TR;Xx}-y{{1zv_epx!7NwfZr z$mrLQ2~V5i>G@6@Y=s-q3WM9~Fhads!=CS2@FoHOi{X@Xg%IynZIU8+P&X zH|vSV??7OLU4A^F4xG4%qx$wEvwzP1^SR|xtxwN z2;G^sj6mZSLoQ_-mmEO+7&S;iS{+iqm{-m0KWjrS&qXtOo7Jp^#+pJk8FOL9r)>+= z^rJb5RIbdtg0d8-rk)2T4`N|twO?y4I*V4>4Cs8^RGI4{0l5m&tnA%=b56 z!PKQ}8-M?>)CxdY?q_D6JgEUz`DYWwV<<$(SCMHSXDDDR+86yde0@Cd zFhO%nggzh(k!1`691&RzWe7Em)e*HIe2Vu~Y!*fMy-rt6J?sZ1vI~N6EbmF zdjz<)`+WLUrTeXk-67W;-;Nu_Ip6u z7N#XTE8 zHC)EuH6koSDy#!d=L5W2Xz8*M724>7>%1q&d&9Qv(N{*1^2+Q2G!w(N$=ffHXZk&RAcf+)o(#%m-u29p8elm)&)Hj@y@Ttq zL;C@H+MyD5o2*yOHrcG2NEyu$SWLceK(l`@n*M*PQ!Kav%|2On1DZ(b84zv%#1_GPN#>qCC0?Djrqya;U*I3R$&e#q5=)30VCsMjdsgmV*8g-z&cat|Eau`zL zfyN^uVz%iFe0~w-XYN!)`7;mP(@cd(rORrh!qU-nOxg@>Z?c_^Y{)HE)*RoCIkLt@ zQb34mw@~;wZeqnsBV#p|4ngj2v@J*As4~z=bl~fSlW4q;1zJ znIlu+{9L8X64{`jR2-RZ7*$4Q#Q6#Hh=|xvb!LWub7)aSFsi+cv8Z0{!B!L8dRccH zrm3fdakhl+DA?q%H>+}!Q5b+?eo9I)=k!f`(Te#@Wze!ygjDbrSzOFe+mCqgNL&JY zNY=upZ)^gD4PrTGN3I{%fEt1W`R54&JaY{`cM+~e^wsL6LE#w!t(WtyQh|f7LL#h} zR9;~v>uZ1(e$bvls13b{sV8Ai1Ox2hD<1g{U44J1>2VBVH$K zZzpgMs1_f^8PSLVL}SHQLNStMUJ22+EP78b%HFB2vAhH?;#6uewWx(sFB?m+L1Q#= zqo0wb8(IU%pFW&%l%y;sZgzn=hreD=h^Nyc5$PZuvUD+d_G)TeA>B)!bx83p(PHm0 z)1oF@!{R#X;61PyweCPO8CJ6ODEG|C6B2?&<|?}|i0wx-1$G&aYLa~uk80vEy@}iQ zm?738MKmRm(D0+=k_Wtpue_7pkGi9_Ie)%P``FcXnm33jM}&8hV49qFC$WP_aHsc} zW77`V7I0Kl5*p%338Ga&qrd^;LJ#J9z1)Og#Y#SM2W66=)eN{FtxP^|N^0lZ486RTB?Ri3rhXTSfJz|Bk}InDMP7*+)bO5%nEE1t(@lo&3rCwb}AO$?VT=zcax*@ zvS)$ATcx}@O;Z60@g@_D+MvX=CWFxVJhKcBZkk26(ml__$PmV53OY;c;*Tr_UjtKL z{fVdr8IX-A#1D|(#1Nw%m<4-Sc9c3cZPx7wYSU0+=EY&8B$?uNKt2OAsyoThAtXEVQD=`Dv2`l8`wSh=)fSRrt%*c!dB^mZ=jxj zw3+-w=0ht6afbRzkRn;H0)^0=^Zj;cRU~F_O~sURzTYl0%ki9cIlUaGtLG6?%v8%G zq!8O=#Zug<>YxzjKO24GSQz|h);&Fk!Ql(-J31R6vA2xk=v4RqLtdd~fj<5=- z%eY%|O$c|&W~9QBkKZPr#rb?E3_~kBJ}_E&xG`58M2m%1AUVs3R=LMJ(dvXONV!2` z1<*2sXr<87WF4v@De~Gfa!)d5c*oY^lYV_YLp^#zeWFK&HF9yY4I_016@g7 zz4FiyHU`#zi{?n&3%dn&qHIz2oV~CIU~{db3U7n0C5hKB=r}bA64t)ifpC^AuA*Vyt$Mh4-<4)f&XghqdOsZSs$qgsV!B zURjSE2SJxd0L1k zDJL)zYvAjI&b0dhoIW2}y~-RBa~S?2^B*9?aajxq&A&{Z_`UbAh*CJr0F}eV_XnJO zLaOoQ*30%XdQT@ynOltw6R&n=SKMHzrld8pq?&NxmDQ*+w7jNRsccbDDAOJU@RG=b z=+)%8dJm$PBukW6C#xSMt~WlYH)54uC4W^qC+ZKOQ;m)@2E@jzpX5A59xbx&A^K_U zL$qLXUZ54UDM}ITR2k>sY5yn`_9YiJx)$lUs+^n4(1tL*qpHJLH|su3|(Cf4?eC<}atF1QY znsX}jMp^tYId>!LJV06wjjvlC=8&?HpWzGSy@$O=(kVk~$#iBp#& z9LKFy$6bIk>4!aCs3yviTKtU9F<=2Utk4M$!aO*+0s{}|XXc&Yb0lO1$|2Xr;i zQf2N6x^5GXsiNGd5^VnXwLh&|L2J}&8oHZ1^AWC=J%U@aQCf@4ATkX~S=( zOr=eEluVr?xoq%eS^fx_u0h5*lB52$))gu#}FBM43%&9%%-Z1YCUODnG+Ff+1$?|)(Z0QDHve{Bw9{bN$uk#M?sz3wGty_$m*3WABJz(9r?95jYknLf@rPKdS&ZM z2IQ_A%z!)$sVhj#b2RN0M2m&SOhg!vo8(3z`$ldt6F;g)|nhWaDr}IDtJXTNf2W5j|!}5V*tup0tux2^sae6_&Vr)Vjqs3kZB`ka~ z=Fq#v-lPx@-)Jf=*`*ah<23TSXy(ei?>c#`{w_K4!S;8Vy*g({g~#e_3o>g_6t8O| zu|{b8(LO|F64T__AXoY+7m-OTsnA?o#{fJ zQh$Q<2OyP+uaWYV-nDIKE@^5nyWDo8n3L2^=fe(dwF&p3(JT)(l5m%sa06oD60+Jg zN+)=n;>W}%e|^tVho@+;p0}Dz3t@XrrjAi`)J%n4B#T#LjUHKrRA~3t<*e^}kB(@9 zlgx{(RF_%G_gVG&zt6E-wUT(gZ?+CfkhK>q`#zKmD7*vreKLwI3k+(0GAe}~E9<^b z%*zX6t8rUk^B1#KJD9E70}k8w6m3WMP{8)gQ{M$?nxt6u4I@GtA5B zP~+s?rx;sCWpWdm(K5RUnJBriiM3g-ENy}}B5NUr4&S4dH}`Q`Pu6McR#hpMX-`vA zK9hZ#W*;e+gP+mer&Q)GOKI;u`e6x3imZi?xi+bEx$IDk2Yh}&N9nqEn^b(wH&cp# zz$Ml83Zr&F{wcV0g>j>3elwB%0Y@WA%jEN?-3zaf^JMZfq*W%f71YZW&yc|oFR6mX z$bIGzChcQ$T~P-MKxx0h-`;d z2IAbv9RR5jUkgUo%i^|JrC~+OwLUTb;D+)!XK8ut@AQA%hn%b z+vFeNh73kOX0yvXkM;SAz;NeBEfspcEdCMqA@X1c?;@4RiXY(*B|m0z)bS(2S*A&@ z8MU&#B-aU@eYzhz9c$r_HSnFI0duZWig>q_O0e%ki6RPM)bea86s}JG2ucGKwyadE zm7kR=H!HqnFWHR1=BkD&#h$C6-W#PzX_5m7owHJ|eU3KI&roY@c#$qq`#ZWs6*v!ly+|5-8T%6o)(M5l_D^ut zhLwBTYZNvgYAU;SFYLtgoEpLot6J$qG;=|^0J_OQT7KdUKdf;ty0z!Y=P!B>lK}+c z>w*NdDLY7{M(e}=lRjoN=wvqYCAv+k0A@+aOE|>9g!&bpuVdrpm#A+Cy!a#u^bmEd zCS(#-<`^2^5gmAupg0P-SZ23jclL;1b~8=6Kai%t4G}%?6J_#G2^87TICYpQ`9Gz4<@JHpQ>&$4sFRGPKgAh1<5EzqfXjt28c;v` zUG{2tMutCq2Bl9X{|uRAnf)^wG3jx8R+Ms)GYk9~4w=i(IkG~fvQ&zVa44CwQ7IX` zZwkm$a74s746cE+^V5H^y77W`m`n-)p>w_~*R~TmYv9y;cVanOpmfO=mG#P$^_YQ6 z((Ap)%q?3LxGqS`BK;s*Hnf5XG_^q?v|L%eo(pri6IdDy8enAx(ORITO`vHKozPMw zV_(y(|)u0>bth0?Zv&D2S350r7oL?%61<2(x%msUey63W@eSJrx>$Q1syV}gE>m9oZdmOZ+ljr;Pm92tV`LtcrMUF z1<+!GXr<7?C(yKd)zJ8(2zm;0LbLNbFr5x)!_NlNdZBSYc>_CZz0WekKZXZ)(l^ip zbLGMfl(|6`DPV%I3vfvgfv~b4I+dLn(V4AXI^3ZsL@xjT%SO5%maO#T&B>L)>`mJ>F~ zJXdOPn)@q+`FaKrmir>XsYcKDV3mNpat)vF)PmH=#$OQ})4H)~DFJf;TBi8A&}9!9%!3kl9`p1{(|cf)E7q76W+n?TbfMxpU& z>g!Y_w#^2Vv^?fh7KtbT@yaR$nB#0P;DgsGJCpG@08KLY4S3D6@D0W&o}zn$kPt1; z0>a8V+zxiN)4|>(m!S>Y)1Fet&twff+$<|8Yt0pFt zLn;gstA&;~f#wXR(6VInn@s1!Uy}p7nXGZepquQIyJ#(YQL>xy*f|d!Mw~i!Gl5Km zuTOqNHh-1z1;jaD>jB|gg^f5xR#%`?Xm*}_ZP>XR(Jw*et5KXKWk9?Z*AlSMndrs(I}v)LEL7PBWcBbfq5xWlta=-dEqsG^ z(-lMuv?AH^HYF&MDLt68@(t$>PK5tD-O60h1E)cj^*H{pwg>z4z7beN&8`vQUU?Tb zOW==Hc$BAF$$XTIoa<|e1)9;qO|($So3`-9&`RIjGw4)7uaOPt$JfE0ST{eJwZg8I ztt1uE0-I^DeKaCE!n06=+T34Ljv=|?*WQz*@z;D^T?m;k9w5i}Zrn4$I@nx<_%&rq zdJALe*VX;dazPv`d9K%$@aEqVR}=Y}D+_V|++RiCN12jdP z{pu`5WXErCgHmYD*=O_(x@dBePvIw5Cwj4ZxvT)hSCfnOcipjZAAP7riW>ncRV7<{ zoh^o$zr}r`-VUstn$BOyF#NV$`&;i}Oo=p?$b3j+ws;YhipYA@!#r;rcV78BrkLXh zIGftT2zYpUmD&-?J4mE~|de-t`zf=g)v7-=w*``+MfTiBE9x6gZ6C~##T@gQB+t6X%i9sRnI@q^r+sXN0U zC33<$7?|6-0WPNfJ-J9%%D243SjEg3sj$p<(A2QfAnU**I*{Pcy6`h(j?DZ68I>X7 zeAt~PZ>P7Y6qMPo8YkU zj~Ka&1f09Bg|K)8Us-7iIO6yt)0xaa(qeiSwikY(OzFqpOa2&GJ9VY-+jPn?ub(l$ z40eiUHeuI21$M10Qtc+#!DD^_>@HaaJFK4!^(Zv50a{c)F7A%`SrAfWM?W4?EXTf! z9S0@nT`;dKRWKsYDv>{S@-CG~l8+ViOZN?LGk?w+M4&R#go6r5DVg1JR5{REb}LHhh*KKsM*N-fl&|r9evxqGdqy%CZ55w3tCVq(O=a603z49z<(`HYS@< z4I3s~{hm=`Hq)&6gSI1jO0+x8-ApYCWuXFgpWfFAp^Bw{fc@9cFf)5UqP(oJ8B^EG z4i#nT`aXW#iqxf;7Zh}<0sb#RJIAW?*2#iLmLFS z?rugQ&z&0Z=MIv4k}OoPM(!JAelhenJKygaq_jmJ*;BI) zGqXBb@B#aI?OOu9UR$@YRIeVb{(#mUlGl+!_hSVEGV?E718Ca1yLtV{`|r{-zy*IH zlX_Y97n-GJt8w=O%3-x_m7m|oR!1_w`*^O^d(yP@(cLNNMp+50RGIl9dGJO4hlJ^V zS*lo{Jo_P^AhpR~KP2@GnLGr@mf1t_%4NY2lJ&BDh*7Lbo(2o+*=fg;_PZIXED|xG zi1_}BGS4;x;s6;+EfpuphUI*t+zhJ<#Cf8v2ZRq=hLLNK*?_PHSkB}k z{Tu3xOO+KXtB1*io9ut5!j&(u-Ova(RTgf+6Fd2tCLvoeRR(WM2G1-!<<7lE*ddv! zKv6=+%rkPuunIt&*c!m92+8-7{!dX|0l0%!kJjzHhIAzQP!EPi*L7WNx z2naU&7&CYdHAa_`kC|L4rr!!g=2y|KAg`=t+^zy?lMRT+_Z&JFaP3w*R0r%q+3_*C zvQ;p~Zglj0XiwdD|SE7ilMSywUCY39KrF)16^usEgD%T$7J6h7m z*l}&#OWytmoKQQ4KA{#6UyoF9@2o_sPS&ebr)(bMu0hFmn%n&SYIpLeSa}|F?xTE4m&uAX z^^MGemI>lq(Qf&arY;3@^c!H6fH(`z4v=Em@hNsLhIYs|z0)E_q4CAQXVA(|A@1lK zDDBYrTbZBXVy)AhNND~rbM!+x3tRsg9?UMzXVi#4oit7#FO<3CU|bAVj8hZEIF}q( zUr42tdJ`b++Zs)_j8k%@IZr2!D=jt9?CN!~H9F|$>_9dZ+3Tk3QW9FOtlB}ErO=#Z zLIboiS@t<$w!`^3^K*B|83ZpCaBdxw!^8=v_GABY-J)0koAH|jW`)&}sCJ;p8dx=& ztKJW80qK-2pOb4RG^fzBwTjrY{GW^)% zzT?B9PbDS2R@@9D_0&MCYWX^$v(Fpin-!4_d-oe%(GfAV8awBQkXRLOjrvZGFPJm7 z$0gHJqMIM-D3u#9Y#ROy{!m4Dg~JD~v@NPun&w8kJ>C$u^VIS}1ybYJ-;{!|T(1C0ZH$H&*C2O8X|@Z%bbmLBN1 z$YTdm4yK{kTLe~>Rc%n$bVue?V^#C})(G3Ov!s`Xs? zG|rcBLOvu2kSVKSWI+FSrnhcHK$M*C*a$sUjP9Ut17A>TQe5;nt$J})qr4rrbrS}(Lw znKGFY4w14`!srG{9aK9%wEiGkDzqM1th$}(I?LO}$-bzt)bs2BQj5eK**FX+pQqmnA?4)#qwHtGDpYBa23CNzPjZrK8j(NDEv zWXd6Eg-?*siP1O`V-qT`S}{*(l$?JET7|M$0r!^<@f{Ia4x{*dGcSs01mQgMjT@U)q!S+XR~Clnt$%M_bV<=h0TQN+w8X`5KTYoIq2p7HHgL zQY~KFoUr; ze1{@2AoC8TBlOGFim^yjP$H`j^-Y~#n6pIvKlg z8WtMljaJMstXfke3SkV%>S>fU?{X5ppV!EoOAakC%4G{0Vf8Tdulz=gLu--MhY>lP zy9EBH^+0FAVML#y%LAj28nF=epo**Q0i2#g=_fU3Po>9UPo54tN@fE>%W_SON&5l) zKX-SFsFP$vYYUGZipn(K5RtvPcAX+E1Y6*#>0n24t9Jz;IA!o$- zj?@+ew=kuT5s zQ@TL{ikJ&6R#u=pEhG6I|LpNyz{f&Xu>-?e4VnTd0OyvZYraKI)^hR6km}UnFXqZH3MY0gx zY576AS+KI@K_6v`leG%EWs{F$_<08wtciDE0bV&T!FMuSmP-POQ#8_arv)GTs92}t-ddESqwN697x; zk{d@9GYJ^%Zu{x@&exMEEy`V_+$326h)*I74M@7};eJeBixjVt&7>F2S!R|%lx-{G z5uSC`v5@}Tu1q*8@0cW4C3JK1b6RG{2sz3{>B|2bd%MMLH5B9{m`C*U1E|e3FqO`S= z1BkCdYN82MD!Wyq)N++tBkPXx@%MM{3oNTHKhu#KkgZ4gP7Z6o-!3JiU!+UlKeoqb zCyCJc`zuFNlRjjfW4vMX`*`D(hU$mrJR#7G+#rZKPzK?a!7&(PKy|sm_Y+NK?lBZ> zNEX5f8_?ABJCtG7lvT&zp}DeAb+RNUiRj;rPSyh^{fH5eTsa|$1hSRQZVW74dq?KK z1PjDjfmDJN%6gS6kj*Mrph*yKB8Oq+gE*r}OqzKXl{Kc7BMRDeV_=o; zM2yP@1$FWPAS~(;9Lafb9|=C7I?2a#-zTyx30H=Gcb&3c8+65qgd^uuw_I?pd7elb z_44A0WY#F}D#nuSB#P7EDu(}Dhl+V8kxMHy=PR!)r9BeZf3;x>p>vM`+4yeQ6TePV zb|Y+_M2Aglhoq2VFDW{oK}El!_Xl4!%J znOQULfE~_reJKR+Bwm4~{kvrTY1Ptg;Sk>Gn@^2Zjc5%GRR@&%Ywq zEVI8taB8Xxteh4haf3SLLf8yqOTNPVt`n)?;8clJhi1m8z#qtnXaeWGh_4W(;#LMG zs!^&0cAU&SnJu7E*jg7IE%ZBMO*!RNXOsM7+G~8J4Y4KAcqX0Iqn4wQ}+mMQrB4sW!^uXfpYo7vZ zOlF@#*+yVFVXht4s4O}K!}Dy-sTjfeV`NpGdaStt(fES;z`QiyR@iKhX-c{EwoOK$ z5eiQwlYC8ysW>cW8#4bj6`yw+!&@ak`RmInRV-G=n z91)rIOD6G1Ip5utfVA>RtPUbUB~#~af!!}#PGdnmAd}`$EnY^SgLfs%jS2>3#T+J3 zeXDi{3O{P)zrwj!*$GsmK>{L4E3^*TiY`;2h|{TE%#+ma3T~anbUC|A&{*UxR@Ok{ zn0$030k7qB9~Y0mzvu2%9Xd=!R3}+JR*)v~XD}Pj{6S#BVqe!2f*fVlJQK*uf>kLG zDl2VGAgc-%gF37eN+z(h>DplxLJN)ry-Me)S&C93r=00KjsCbuu`yYpAX8pcP%Q5# zU~UMQ=J|18zGH8wH=UA(M4?=r#(Xi4r)0ruWnCI=!CmV#Tq<#WVE#I*=zUYCSySc` z_Uct?YD8?eooq!*SQY5(b04przP3zh1(28XH*;s&G z+jPv8Avx(tbZ(-e`t5pcI@9BBc|6^Bysxo$Z08(O(%_Rt@X>!dIyb$oQDSpC!&?_3 z8nRTx{d}_rHglkPbiDB2vL4r)BGEkzZ%1r5pM0c%6v(1^7_LB8AZGw?R5*+cP~v0# z+XDh$DtV;Cu9mIyaGU};_8i~w(^L8b>zura7VfugmTiz-ZKhQjA&EFyeU9(UX|Wy!hJg6nk(Vr0X)?8JqC zB)>b?cO0Q5B!j+OD$_E27cePakby>xJeYyc@;qS%8m+P!5b8NV4mi(uwyUQ=F*{8fQRHebM`!G8ghhVjFS(^Dlt!=M7h)VAhQ70b_x)Btk=Mv(biz8km`6`01`zBP-^B=G z;fpa(w|9HMszse7;}5!0SavZ9q{`ZhNg&0y-8|sZ3@h8W-QHkandOTKsg@~OSg=}- z&GMZY-*-fy?`!eW|ER98G>csOWOWveJu0tf;YpnKD6y9}Udd#5)^_>FFR)!R@?)}K zzEh9o$|^|QZZ2!o^b>{?x9<_2o0Kk_=hFd7kkv&+(qWKYeM1F$p>cOLo0Q7s6hK()iQ9FBW8R)l{}T)E6L+WS ztddcQkrmn4q(?Sn(^Wf9lFx7V9WEo;^z-_Z-QwDWJtR>hlXF-LubGYQ^wVVrep>xif%3_J)@t5@#I)qR-7M`|g|PgxI+to@$?Lg} zFKs6cy5mt-AYWRrTVAvF4{Dn%fE6-_w^MzyjxD=sw}jTB9Er-W?WU<#EwobEs9Gbk z6%ap+#Kg&i4tOI-ai`)+y6@m#*!~aHJPTllp=~~V$cN^+9W%2=I-t@)VAC9*}V zYh`u5Z@LUzMf?gccA_&k_wtyHX$Ac@dG~RkQPSW(eja|>NBPv5BGW#cP`&~Oktgze zhlQrzE^l4$OOSywy~hNjUEW2L_6)h2cvHV*PxFKi=}czc)tIMoFYHvyT)=|1$j<}wwXXQ0?_&#~?8iGNm ztXB~x+}B{HUYYz=wP2YszR&wNELgUEXO^)_N)AR>2TO&XEQ?jPb;))!ldpuv8=hY! zCr^cG$(8wxPq84{9Fv9-C@kO3*|%O0mh^lYpt0O(0BrgZ)&kl6K2d>EWL3V?NjK(G zR<43AaC&F_0{XU>be-l%9%kPf#92~jDuf|C@Bu+vK33lzz?Ae<=|5BfwTSy|x)@(Ho z-7nVPDX`mQ5p2fW`wD3U4h%^vtov~rvNDnAmhG@2lE1rsC)b;uKVEaAFP6n>&W$K0 z$}Klyz%}ytjo78(dw8Gj7`2S*qGrpDlrKf5+(eoKKVag+X_xc7K{M=pS#T4Yg|hr6 z(kYgwk&3VXL0~b}1)DzBbNJ0S(Yx1>NX3EtfzT8_K#b1{sM`B`f{Eh06~T0w zXTXgLy5vCxowD{;v`6H%ThVTjtq?=QJLRz3=yc;U_cmns!}hm1MS1Wx>|F9I=2H51 zcp5&X`++$9u0s*oVZ>(^W6rMEx9`lrD%$GqUrhFYrYqkCu(AEJVsh-@>Ycy8d`=(rx-W}K+ zgdIxrO{PWb#0EN8kaai0^jVl+EJXF+=eOCh|oT ze6B9C>UN4>CmU|Zn0@k&Vgs^6L95Ixq1;`6B{O4=lswxBVt49NE=Sq^zir>yYS{kU zVEg%<0h@z}5{w!1(VpG35_Y1jSM5~Ts-d=a_t;usr^y!Bj201#NhEqWaFVYY;hs>6 zFi+WauqRGg)Uw?qQpbC&Ea9`Z1m>aLqYCX@*{~RkhmTB%%stR~fa4B|Ry?vj;Et?j z>In(uym{^&Sf^1IA_Z8YSc9xm&>4`CmU@@cwLOH3$cbrV#%te@cUh&O(Y1$ur z|2kWGIugpi?EgJF5W>grXFL!t(T69*PAy?qOaJ9fpW?u#t`PYwK7qdsc6dTeMNO-r zX1{2lBcjsh9O3*-|Ba!yTNvJJ@Nx^QW(4Y$SiQ_XLvOS&_Z@@x4_IjM3Qxv+hR|sR zOEw$aEl8W2;6aBvq)H1j4>R~03!|nRyx77X3sd6^z0Sfh3-jZZUcug*^MiBr!;N62 zg@YDm%rNvd7Djmu?iO$;!&qw08bhzOu+_q}XAQl_!s_P?Uh+dA`SX&7A-D;8&NB(N zy7aY%pJ-vWg+&%tTG(Y_^7Db|Roe72Y7M>ILe0;~zt#%0KWqd>Ep!XiX!)s@UL3@4 zv;4*uqhGo%umD9DnhN!uJ=IAvCfz_ce^2#%BhWS9C`Mmm6ZqLKK}WIC$~C`W=z|uP zy%;DraEVE;_OFKCYhmATpj^SV6-Kc0=cZeSzhYq2s|FTX*kz$>ku}#Dy^envxwH`j z%eNYs`A-9fJ~42Y-V&qNcIaUasl8&F`H|)`uzse2*_RnOWcj0BgGU{0V9ikmrk-Qq z$WHTbjm@Cd>J3=fFvH5*d|Hk(c!kF%m~pNlxFxMGHzjRsHT2>a4UBumz%C0%EF5kR z)X!XM^s_px-fISSziD83w*xCYP3DKE@D0Oo3(#j1NbE86LJRYI4PO2GK=~0XU;7(F z@3(MY@^SZS0V{Znz0W8ly<_3K2IdYJ=oTo&QQ&;G-_X}sn6wZ1yk*7$*%wTAlJI64 zm~LU`h2Z4xsj-A+B~18NViQQe$j~b-9LO?wbatS8wUv*x`~nO2CExSlbkqOC8J45? zujf{iV7MoOUF)a`_yG)e{t0+E{1{Kk5+fhQZ{<(KD?ODHa6gzQ#N{g%%32HjW~aV> zPzW)ufNO+;-^4pVODyafHF%}PYb|WFu*H?Lu+POu<&2pLC(i4bX__RtBGgH@dzpcm zw)eQum5cqR;pbcEk(`+c(=V#E$>dq}f_)_8%2iu_gN1JOdTy0-sA>aa zEbOo_>)VE2W8e(Wh$S@F7=~Mb%GoRV4kJB1uQUl^sWLHJsc`2Pd^Y_;Ym+4wrRW9WL08SOKjQPVCl*YTYh1!k*~Dw z;6hh!(DDmc7&*79p5lpZ7rv|Uj_k0u2}4p<+(vZOD`&~Ai3vwnxb$F$atq)>S8iVp zm2L~tGRqjiE#QDPNXnzOf)?7g$o065(PtTHj~T&zHAc4OyN$8N;;yrJSB5^iDP&qj ztu2u23>DLVcFWRVpLI)OQMFUH#$E%54?3p%rsg3mvpY|+ z_<06Cboxojr#*fCQ!$4d+~o(QU*T~x2x9D_?<=A2o;c~4-$mw3>FF^Ul>f!RXKrl% z@#*8g_%M0)b}e;Y%Bv2&d(@=w7VPfU-$mU} z@tc2~>OatwDEUSM!_Qf8Pyuw;#BL1_J}<|i`yVhFxEY0C{?0)Qk#`H?R^;Hz-gW3> z_m~0>)EMZwVv|Exi&1~JU$&V9m)~%~fnU>%Z5!6lH}r?E|EfdpzuDkLcN;i%W41$g zakpRxmb`Z0?WEItt&wx}qV9ahp}Q5ODV+R0=ic$2!*EOJn)VG(#^hp6XwaC>HR1BG z3mm#zKsTdFVOKkJ*QZ>)efvtq-ks&1^{M$+M{j#P&{;g5XGT~4^!*PWUhbOM^_6Eo ze$Jr>`^rnT_rE-Zyjvl+iB4Hj<T&VXL+!%d_FM! zji;ao`^vzF$2)YlNnBs~eCwlcd>?tYAQf&+21dkT1Ut*$w*AndyFTI;;FJyCH`kJo z+bdkXzjsV`=x%p(^_n{lbLc_7mEpN_)2cU{NhrAOkL#&*=%%0Y2W|#T?|8arr9*ey z7E5U$leS|Mk}A@UBDV7{!@?{Jb1fXQFyb5ZRKhWtnj2RG>SzQeo=v9t~c@xNd^WND9-YGEOZOxSz!uPdAuozq04*6B^-Eb zZeXJLbdO&0#Ul?XPh+tTf~no6XsG=+~@ zDL+l7@WsWZ@Ff=3S?CtNJ_s*aX$tQ@AtCCP2Fq-+u+7453xf+kZt4H7n}%~kF=2Y> zfGvB+N_pc1W~4!0`ENUAumc3!&UMPv+pS|*qcj?4tnhr<9vEBz*8>NG3J`OW_J&mc zzD|iLS+<3x7P_rh7KF!$X}y$_aJ_QNtg^7p!eI-GZICFn@IM`778}>A6ytgYB7Zmu z*K4)uwprM3p$smZR=!afV#vX2Mh*&K+lMv?5<7~XT2QI4{()55H;8+vfJ*;RJS|02K5w{n$V zH-_)9g>S5vPiN~&?mwIVevU3~{vEa)u2DL^;so)NJy~U@qR~qX?6uGpthvX~T|DJ+ zW4(c|Bt(5BuiP-3EF81Y6^>gPs9b53L!VgUBx0en);+NDWHYQZ?v%x!CmeQo_OoWV zskd}D&6YpP_fJkZ@xZ*V9^{bLd{w4Y(VQbECqx|>S73-m1rD*ICDkNaf0LoNTbOvW z!QDiAtlYq@hTiox15<7flpC>fabGv|Gz&ZL4wUo1?-YJFG5vj0O}ElWL6s zKD;3npKf_yK7}0GTPBB}l8|swk7Z|`V#@E9)AQ%RNkOgU_pC5k6$Qx`{@G;f|FeAe z6xNhcZyLFVcMQyWZg&wikAhQ8e(5h8`kJ2_81u70xk@WH^s1rP{=&eHH=GlFPtr36 z4!MhFBR|!XZw1FJjQN?71X%p6mpw6JK$hSA{$CQUZ5=wJg~12>*#TUh+M|?+D_jSbo|n!ygFZcl=X6)$B(MtcdxSF-E4_ESS}6Bw}t89l(O7AK#b zk#Nf8{;|MT9N89#*V=*%CK&zHL<8$AEI-QNaYq}Nk~CQt0%6%?@Vzq=e4*X9%TLct zNC>Nh@W(R~jyk^i+eUKS!piR$yy{^Ct7{FUMx>Mwx;;)VPD?ndqW*`5K4@X-T7xJ5 z$iS>-16>OgoNY`P{S!k^eaXPiHUm@E7+7d=SFh6Q)&0!y+YGGm6t)|J=jR6cUEFFm zT19_{;b&MFy}{sahRv4lX4ql%;yR67k%e=9HBqmEYlD{ID*DedHSBub2&IyhAhCDJa;ndKiZ^#?-5>}oYQ*Mk>Zx5?oqa;~+br3z<(p|Z- z@_1U+7uIsG!f6#{=Ne{S>Z8A5t0Ceq$A8I@V+UYl5B3leP$Qfi^wMsC6VRxZoJa4T1AVV{Mj z!Yn=p9*|ehPq?I_=|pqL@78dSK4SU*@x_om`^cEpvwdV=U8KU3mSPIf`4t1RPByUB z!m?D0TR382)+vVWHesGkr^doY3%f0xGuy})T3GME<9U?D5(;bq+yn=#VzlMA$coH_ zBP1^~!GCCmEnKsOajEi9X2Q{jH`~GuS(sr9nRKeWk(qEwXyrq4_=O2qPOX0^$p0QP zk*wrm^`E3J-mm1h#t+0YazbZp; zn<=T>;Mo?stu$s6+@qDoP4sas8EfUTEo=fiZWYrl+;`I( zeb=qBYvi7bS#cITW#~f|{tq>=+rqoU{+HFn1(%uIJBdxEVr4%tFw4T^Ji{NoLLp5( z=Ndyuy4=8Q3tKEKvv8kHZ0|P>SPOb>#=Dx>^7|}5*7BVeCV$WF-fK#_tBI{*k5!De ziu>Edp5>-@_g!Xsv)l9|-!XK(n01ItR2cKH)BUAmKJ$V64W=|1uNvsi2TClyM}*$5 zt9yG!=nk7+P=vl=*L=Wr40je2{tHu}7TXgV?Y*%yn^2L3{jV9heO(9h*UEF3B%Br2 zSnJe!<)u_QcB|1DxA6abZQ=yD)2Bwc2IP|H3y`LLc=+N;-H{j*{%P_oF(G7S> zR&igwp)cDw+o-i*iY=LpztG^_mOjVgb8b*NJ-gBp z+ASQk(CyjLH<|?Y*|T#^&mOcE^xKSfHMZsVTYjA7f8jXSXBB&`VvJSX-^NaV)HHUC zy|JuAnf~j!(iGTxQ>@mXp@$#(?|-=MbtH50_qapZe{~u=W-HQBWGXati-E-!c3N0( zVf3vPMj-Q614}G)+rHl7`)YgFl&v=75ewb6clphhK4jspS?txjRw!mzapyR$Vv|)E zuyB9dzUNW-!DnO{Blcgv+xUJxvN-e6Q$87vB-DX_*byKkByA2HJPvq}$O}uLp^S^h4CSZR?^Y{F_8#F_wP2V({Kvx25kZmS$dSEZc1@7-i+% zrg!$DQSWMg8}TNrF#- z8W);$YtJ?jwl>|sFS$2V>^jcb&#mf!NT`+hcLQO!t%&Ijczf!3re>Mv7&w|?V9B`# zmRi2w@>4BzXBOr2jNHC@gKNoZn{lUwPH(7SpVSqow2XEOzbF#AdSzC=)x!Pl4V6#C zd!%_`LSjYU`L+rce#wpeMQ!}$hdl2Erb7GL_ZhVOHV5Ja|J8k;#v4p`>9ZD$wHde} z&*k@6ezaRa9px6_#{1g$aTU9)Vz^b@-$wR4DbL-&3SmvAu}Ip52L7LK;xb#2eT{0> z7nzFYJCG)BwuER4gGaSgOW#*NuD{VVajMO@#6q`;U4F8q7g_j)qnfLjXcY=9+}|dy zd~)xjTJ6oI!1WhTGaCTOS^r$G0D6$oC+rDzXsaURsd!9B{*md`81H-ML8^e<= zzOS}-O_^vjF0jyTdzbHZ3ufW25T3V>*{rJ=YZbCB+~2n6>&|Nvrc2AsEDHy&FjmOE z(m;34^8bBV*m#X8&=)NWt8BqDt~T<)%fg{sjYDTzxpE7?a9QXordx$l3-@VH z*(gicS5I0$oc zcz9&|dQ;n~8w?C+|Ns8x|MKTaQTLdNjDEww{+kT!uoY~ycyXc9Y2l1oBal^L;HZUe zAnjgi==*H`MW&U?Z3b;_M)ow*WBH|)-eRHC{QuEB$yF@23TrIf-{wzWEe9^rozy!_ z1;#D>UlT-oOHIMPD2S%qY2=FDHZVAd=9QQh7_}8lvhrUTL|w&UtLV3i`x`_{Y{vc~ zQ?NA_26Q4^?EhX6bP1O$3}3s>0N%i<&RnDH2r^c=IkoA zT7?k{_qXYXo-$4ETriN@JD8BhJZD?kg?2Wy#y)@b-#lCT@>_erR>Ykxr8b)icK^`A zfLo5VwmV%i*Bp5m*9yABWs}AC)zOPeO=~yUjQcFy)!LR{XX!l_I;~Cq``lJ=6Rxoe zT^8kJ{=LbvVbv>5un+TJx~fz7zVLbvT*ex9Y*S-306@9WUnRm`>uH5Tq~+ZQ}7 zw|<>q-tnfXKW|JO{FVt!)^^hHyps2(G?uc?xILey+4IAEcfD&_C{7}8a2vI>0` z?(bA7>REaJ?u08VT1QO*J3bDy@UX@A2%!JTQ;5V*O!`5m5PJqt_n^1kDinNX6uUj< zeKGe`!f&5+YqJF%v@p-gr|h&93kiI$tmB6!tPr_)d`M1Rl5kIG`U~=-B?+g7<-K4o zD&E7$QhA5bD=#(Bb-gtf|FR4-VAI=g!!+Dw3e;m^*WCtp4Ks3&iI1f=;YJI)tbB)+ z?Dq(Bh`Zyn_5=dH);Sv){}6d(MY91?36pq3JKm z_sbJbJudG>Q^O(qh~KV6EZxQ1UX;+K2}e&2dX!J! z6TWx2;0ezS!= zE`I#p)2%$g(9Kth557B(1h36>o&;$~wb8OfGFpevvo;xfZc>K%~ zDdFF4&d=fkQrj5!WpZ;HUts*hOtxwN%=>fy58Ji{oNr(W|MvQN2jl9O%6`qKel_0v z2Jg_^Tu}L5_6-mFLp5xTt;$#X`=i-!+QGI_{S@Do%N09+t;$vBzdnugvFpbZYO^?F z;cU)W_z|}>{4#^^OB;qJalXL6@#~%R3@)f=65C6MM^|)NzTyQ`KZ*ArTfqCTN3j1| zDr_X0F+V7Ne+a*M=~D$CPvneQ>$vO7zs7mcH{^n{jepMtp8DUsf6&d>&e8W6 zuYH;EwtrD}0^^l?*&eNy)~^-gFND!&>9Z=s8a^N}neFw7j2EjjPOW78_%X%{R0DK1 z1mWMq7tiDdpPtV7`(I$+`5Yg|zasbJ0he!ZhV>t?t)9rXU?aZ}B{TxX>HlZGt7dQE{X=v->eoK3F;p98$V$it|0ug^~=vNej$-7YEu_oPd4L+Ut)YHmhJrY(RBV8`>!!j zq{gsRXW#W6AGm%7H(=>*_J`Vd|G|^0U{zrMQB|)m}drP%7AF zb#TT@pRykp%XToH@kZ4{-M##JNyEkXxvPBpI@OsEUF72qKg{-my4`bi_Rm$YJ?d92 z$?E2U!mpLMF~DOzkjojDrt|*3=h@y+^FX1hxLCbAq(|8c<2YZz*Z5cVMe2=g#p~CQ2S4-vA>X?_{jBuzIN7))WiRxKipYKje<72gX^nCsU!aRY9swV?V@?x9|Fn=N0)L$LOn zT+YG2#-_D{UO{Euvp#RAY&Uits zf&uj=5#ugCFxTMy=PvU5V1}aDFa8z#jq2LCtll2cGsHcR{Uts=`5fCK)uXxUt|=Xh za`;B&w)Crus8LN&^VP+stGnUy7_NA|dTZ;4YQ~%YF;`HahPMAFJR>%#<-S{8tl<~t zoOyurA47v>{oSfXeTtTZ-;{IiBv)8i!1F|3HBa5eJ}w~qs-%9^V?(Nkc3)z~8GaYb z#aB81fLg}&*<4<6oSLXUyn;V9fsaqEW_{|SSt% zhuf?&TuSB_^hQPI*k2}8I&l|>XdCZD`9*}irpJ2RC4aHG4FBH$^0t*lG{sJ{5 z=hR(MuFmXaE$?4n$JRB8&$w1yGnejDJ>q|tGYqPWC{fTZ*j`YJSMfpiFRK$sE@Qv?6}D|zY!9ji7FBY2H~)dGsJapK;6>ZXe*6V-`ME>Z zuic@FRlS%9?q~y0{~c`r)qf`&AnU(_4dD9kTm$@f_V&}hxc~3m*wfH|asS`h3FwRa z|ISW8|G%&QbN*Y)FQO5XI|p8vfRuscL&`*&h%^Z)3yJnmL7Iw`jg*5l4QV=3E>a%S z45WOd0;HKpvyi@oG#hCS(p;o_kP4CJA>E5~AJTlJ1xWWJEkr6pT7a&#(!)qAkxGzOA+1JQgR~ZD9nvF6k0Px{dJO4tqzy==NM%S* zAZj;&QWH`$QVUWm zQXA4vq;{lTNV}2tAnir+BL$H5A?-&xfOIf4@WP>`e;c}--r1id`hOWL36-wv$eQi% zj?%Pg81ZZ*qUYHxrLn~rQFANS3*T+S2H?jiZ2gxt?K?P#j-#RiC3qzTcG5jfmcGNN z-GKl21zRrsmWfRF~uCL8JEJRxP%q!g`Z}_;A-i& zz$V-R%dlaxexD7bF3r3JHqnOBFipAzmZdQ2O&WKy^b*e|j60Q07}+UAHV&$bfk669 zMG9l&S0ZKGFzV`@TVQk{TaTqmrrR(YUK&2mr~01?%o_%=fe&Szfn+U^&LrQ4!Ii^j z%}3ZwBs(_Cj?uV%$qvGwEiv)Lo{mXk?0&-|TS33<|ls?vxDh@x5t=BGhriz}Ag4iM~_ZYBqCxH#o5wE>O`3?YE zeg#<8VQk%$*jKTY^)mK457J(2Jx>QT5j0-_I!;@I{{rkRZKVZ)U8SwmNx+g%V(YpI zY(8yWU4gAi+B$O-TZd^Yt^-@S{}0vrYCCjsk+8HQz?`pO>*x!#m$pvPX{@EKn_bx2 zOJ6tp>{53+y~<4$ z)!#7Ah{JE0OGWBcOBihS}09`mP$e?tt#rysnaE0r8uw#!URZ-;`@cm1CRO zbInK@v#nbfE8j75LjBi_pGTy`cvs=rYJ5AtS}R$GKjh|JL%#U_kdZO28Sq-b9^9$x zw1UN}kZBccv$!^7jB~VwqJL-PMJ(E-N8+k0Sr(zi$d*uP8>Fv$%Vg;rv<-m+6)~Fb zi_wObQL#^8|1RCBZ4B(MXco=?Zsef2&)ziGIlYy7JXV|%oDgP+ewVLOMBXqaiM}_C zWXEdp?ieTF5tzLgb+5`Hd z(zfgCrLEK-lXkoQxU^gJ4btw>OQmhm%cQN-pOALHzERqpdbzYtUxjvlnOk%Eo`hW^ z;{Rk!ig9a=i&txto#pBS0`2JOqZ z=t}h`ajzFFF4G&);pDGDN0Pq{{Yd^=^dtG(wXaBjowi*1JG2$je?)s&`b`)@%KxZV zBK>A`H2Le%(R6%^MmJL_ZV|ef%KUn(oCHd7uh898rnhNyHK2vREm3t z?xr%m9kT%WWg6X0W%@4s#FzXhaQBnHTdR=%Mvd;OGJTKsr1Z;igOI-$uYxOB?9u{G z&HQnH=;Gg)`^Q)(J6D9slU<^m>=s0rG}$#om{pP6XbKejt{F*=ZJ`zKnC>x{=~ky|ru{q1k%h`l+ zk1opfZN~iQk`tlZ>qd2(5gc}D`zyeKa-B{+-nshhnb%Le4jgE>Yv1hV5GtuSMQE~uNu20`CAfzEPWLq|85ld-ClO)-Cn-6>PebeK6)%|$S+ zQ_a>zE^n+X+l{G=rt^4jy!7L=xWK^*Omn_itOhhx9yDy5?$O-9<1hinx(YFCw~730 z^V-Z^I29+lBMR1C6z3y9rf80DC2VZbI$sTz6RLpTwHi;pSdn9{^6WxTu4Gv>dd%fI zRK82Ro?|`+Fk1FOv=%MFYZ<|Dj$I;unwjoyKzGyL2J!R`Gey)+Ge24i) zamE#6Y*Ll3Yw^esjU^}=cU&BL{>TjT5LRNUs00ffhD1A9Q5l+?Z?1IUZ=tr+>F zH6^CBjyz-1n%0a<;g7drz3@qETJyn`TGNh^*0f_8HcZy%o+fw5AoKGs(AMaOLn>^ASc`(~gnW9EF9o<|q)EX3LDX)0)ZX zEGKf%XAB!iR`E=-F;z_Ngff*{Gp-v_N@~rEB*UcEoPV6QNNe7ty;5tYk?50JQwl+; zHP7w`Cbi}z5`9u@ezqOLjkKm%OVUw_&9fx+q}aSf5>txJ(igEM#pcx>Y)P?sl60yR zn@!JRONvb?ET!12r8=b8Jog;7q}Z$^-7CfBZc@ckY@Q_rEXC$w61h@rO7$$o=4&Kb zrP$m}rAV=PosN}a^D5O#Vl$#YPCW5VsPee40g+O3?K9XqBZVkhY>|~xWsb;7>QRfV zq()d|CDmn-l~PBJ$V&9QcMQgj)hzYVu&PWJblT2DwO5JE>vMy;V~d#clJS!WuUEKU zHYPY4#nhLLIqvOPx0A74ZWmQA8#6sy^s#Wiw#bGQI}NEgIB{7WFk))OBrWDrvdZT1#l< z{2<6#>#*vKm28O0V{+#45;-FcXC-Gu6NsF(Vwop$RwLfJKbYfaVR9C=FgSyxX98A0 ztMq*O4a4;B*NG9wYJMdvo0Y7rQ?l})l9jt`vT~b}m7A5U+^b||laiISN>(0Fva=tXRObBf z7NfG_VICDy{?v;k`Ds+v$x(Uh3^-;2-@yp${Zsp^X_5F94{}D9ZZ>bFlBCG%Dhi}0v;`{-yKYKZ$&}zV02r= zfda1118-%ib=N$$)sDEN!KeTT`%%{!7HGrDVf2^ znN&QDQ9Z1cL=#Tc*Gm$eRy|Cj6C{1DMwc>)*1h6%X7CYji{j5!ia*ygf3A}JIWvIc zQ!oThkf>yEWG6_{U9j~eT{N>iAl7|sT*0|5ylmt<>P5q4W9+yp+($8i1LgEBOKjj! zc_gZgggB{ZW?jY1nwrAhA8uNhS?iKnlZ;A4)lv8|K{D%ro@is%EyS$z#L=u^v7=J_ zEGwAes0{t|im`AstB(IZvFbi%)$>k=S+!%P_)%MMi2$cw6g3L=_PmO3_Fc5QzzY z2qUgx#d_h>HE+cR;L~A*6?|FKzKMhAIAY$elFu{m>yKjxe@2+M1srDHc8r*}9V2#S z$B21bF(SLfyzQ7|-d2!WO^nNmwZSLmZN-SX5%acU#NLQ`Td_j;RJj!+pP0AA?9AJm zaVatp^R{BW@QHa_F}RX>+c9F^c8r*}6&q&WR*`jb2l|vX=$-Luk!Mwv5@(eR?D@I*S%-fDlvtd*TF>h4w?2 z=-<(qBI1ZqmmHxW21R+69s-|~%zNR1V5BH{sUw!@_u!8~p(XuJ`#Q2n`pw}V3hPu- zEJf1q&psFz`8*vZDYzucl7h?FiKO6XiOwb;#5&nGx6{KEd?^umNx_#>m}w{vO_@(+ zN(#PlF6x#PT!y101($?B_Yg{X--K+C6x>7kBn9t#1}7vbxQrx83O=7`xuoEwBp@UO zmk}pP!INn(Q*e?9l7f3GJ0e97os8t+1udOUaatI09Ql!<87F#_c`-HD89D6AI8M~C zOAT^H54$onGZG<^WPKz;M8jdB@-mz>LglIdEmU5T^>Bnp5%Ah&;V2KYT#UMk^3-Fk zrzlT7M|tWv%G1tKo_0ie@{5O~JZ>4~*$S@3QJ#1i<=M(no)$&<>`|T;j`GxfF3RJU zREkRDC{MhM@@xgkwMKcUSZkE0g`+%mq0b7jH_mGf&bxbYJSaE9LyMon7wb>O9$UN_ zU!ZS>tw9IYVE<|em({SmIFI$w3hdCv`e-7IfQ=Q`mIkM)Xp;6tH0g_I(qD`womgy+ zM3X9P(WEDB(WEuDXwq6+G-;hJn)HY*n)IkGnzSC*I)XbR(WJ+0(WJ+1(WDKwXcAOC z6@X|GMTsc7L{X)YXi_-36pki^qf54E(wQX`O|nd?GMYq_Dn*l^MJSq7$I+yAnrb$!rf8B|euqJGAV-tp<#!lc`8$jjjwZEmG^y@$(WH?Hl)tcumtReV`PPUenb?Hebx?~Y;Z8!0F3EmHd?Z9!n#i6|1$ z{g|RSpG&I~`Ss=s3Ov-CIUc`7?H;P|liHmmF4UU|Q)6YUs2<02tjH-PuLo0ElGa#6 z%ZCTHUc@&bu+=W|8W0LX4^o(@J@i)%=Ch7P+~4(RSuAuCEoO0$u~a0*7Z3sW(E|eQ z*iRv$c7%jnz+*9c#vmjVqt%5rZ!;qu-o5A>DuF0a98O|yXwP;t+JUb>IEJ&GVmMbE z)uOctweJ-tnh+-0E56@k=0CUxwNWsIW>L4M2Vm4EN(#B;AxNlG;|^P_SZc@JR<+v0V711FaZcHKYTrSRs6>+=`J;I#6PE z9caxM)`3>67YC9Kv|@0j4zy#W1ML{;Kr1$^1Fax+X{IeBVWb1C`3m5Z4zy#W0|}$v z1YMSvbl_oNR1RTer4BrP3mq87kY`v2S~2Qs(t&o2bf6WZO6cOYVqqP~m`w-TGm;Lp zVsu8N1FaZbdBNH-(t&o2bl@l~tOG}Z$V58uIP1WXr~SsB07~aH7Cktk0ez$ak0(P$ zjYMB$B!ik}xU#4wBrG((e?B zERufD?+7bD8IY06?L2Xr1o1%&;Lp7mqt=oYCowFrS{8jM(L#ep8L$@ z7Jc(NqgndNV2pg;FPT)SeBSRmouCZDWYLp(##zD@zdO zB0Ad=gpsQ6c0m{!&Iv!-mn`V?hJ!H4f_l1ut^z#R|>|!E_o5Z#MkX@W{!_vhebTP=GN6KsJ8w#a3&^PO- zZ-fk`>=i%zvzan}FNA0~z(t`H3UF~KWoO89lb$}Z_H~)+YvO~{*X7a&wMAc-p|8tS zUstHUep2@Jo=>T-1^RkisQ***5`|JcDwOhiJVGfgq4(p16>;D&t0s~Uk6*jm-aIHjDUNJg8G6rsf9IV{3H!M&Bs+YCFZs z+~8#FZq5z<5WDm95I8{uF%N;08gV2qcw|w$44l+rEcl!IMEMX>tqhzT0JG$WknmiP zWSqOuKQt;M4i|BmBO!kYhmyAUoP*_|g zk?2O3aj?8yR9!;gtzE`UB5`if5`6y>p4(~{A73)k-Ho`j=;@9Dsa;H zmjfq_qXH+?o^aeM0mDoWO7SB}+`fIofs;lKob3Bt;AE!?oXq~qfs;R+1RaieGa~fN ztHEhw9Qnk9kA`x-OQDi694Z<2*P}uup~Hp7ENAF0Z`a2$!jaas@WHcHM9wtrJ!O~t zk^KjieOuvO%KxgeCzSoRvM%xL{*DxP(G5PlQ2gjV{E>qGIh}ZOUp8^Sk&mJLZe=6X zu4BsYxlR6FTmC-fpSI!s${%3s$Ja*u3GXuHf00K8p?Jndra9LWqXzFQ}(p7{mKp~d!B8q zc0mDyvqIm?=xTBM&mZF!T~KyV+3=}#pW*!hWgC?(QMO3g^~x42Tdr)ivWBv4VgD^z z?h>s>0mqc>Q?^&xeq~Q9JD_ZldLz}~2jX9Ix+dH^^d2{q8lHqi5|}>y|G;>o+V8+s zIsu6kD1FZVA+&f}SClgXuX%fDM%Rp(@ay2TV`Be|uDOZ!Uu-ufi3uk=?h=DDx>A!G z2l%27+v|b5M8?UEbkS3Y@I-EYS6ou#gFJVHZQlR<7p*#%vCZ1_D#ZQ~}0cm6Xt zR+P7PxI}qDSE@Js>Lg{{=dublv~} delta 522943 zcmaH!4VY8K^~P`RE)rmc0IM68uPiJ!Ag*ymiMnd|Y(!e)7Hd@0@X;C-H7d4Iu?f1Z zQBf1K?Tr>|RNAH#+o)KAMH{Hqw9*EC1Ng9Ji0ozGPAKhsXG@qEwE*Cvp6b=PYWSU;utr6d9)f_bBnl z+Aei#`$Qv-pFOr~jMw2&*Ca<*%4Oe|H zJ^h&Ng9#Defi^?fD`jQZ(TXxkX;H>C+YPdc_^o3UWs>05E1C@wmAzK}JY2@xDPF3I zvV`i%b;)|%R8MlWqI4)nE5(%tk0{+F{OMTPfc-wzAT7kbRFP}F>}Y}bPsZyNwJMHD za-5vRe{VF9wmOUXivX@!o9NoR)a?r<>6zbQ2m}1vQ*%GF}`{M7j?)=+%CA@ zutE*X>r<3DIuh|OJSgi)Q+$LjVEG^!*+L_?N#_w!V6jUIomAkg5pqa-4mM8B$u!iV zX)=BbRrD?5TWAV0RL?QgaQI_c&mQ8VXoNhS6BTj&isB~WBryg0-1y|&C^Lv#MSJ>{ z1*7#trzrm?u2>%lo2W>C@DyA-O2)6fLuNyeI+~;rEk`6jV3F-Bl7T8FFmnu@8 zkladFuuiCq<=jsv{tive+_a4MQAh8k27)xAoV-_2JyFWJ$YQGKK*!;G z`W3q3oj;HbET#tT6Jw}%w0H^4CDqeSK4GI(Lo=zoMXRi{ad}6S9_ne8jA8{fuxzYs zz(YyL$@MHmUBvYtB}XnUrbK_-VDLzblA`45lw6rY4cPuD zD;h@~YNLu)(UkF!en2DVoz^(VKce`>GzBeG{}WVyNbiuo{&?=QMIzuzo|BF<>PstUKQ>`pDobG5P zeWPsP1Zwy$s;Cv_cpRohl}gimtT~wU^z8#5)Iw-Kglbo z691bq)OH1jdJXLztznsN0gB&CN$RE?;wfvR5iS2bA{+2ffj%0EjX#&1lj|H|nflOG zuWW2!8g(>8b1cV6tR#_Shggw}m=%kdg}xo6GBkSL+pdAz9v~1}fisy4(Hyl!$}QM@@1@6dxV8 zoWLCpQK5LafcH_nAGp^u(TEQKU-X=;Cn$MD;fC$cOCbye{Ig|6QQ+2{GCl^pk9ZvT zcH*f9K3P%bz9lP4HwcQduv7AEa^&T0ksPSDT~f^h4-zi`AGce^7lE&PSMm~aiZ4q( zFitK1lm#kKU=1}~1@3-N#w%mxIP!SsXk4wpZLPv)#KYFW#RBt^U~dpa;6z!#0X#(9 z3A{+$1$>4>*5d}A(z$3~@qloE3V4Ap?vNGvfai((fp<=l@d4m{#DjwC?VG8(hlCIm z@J^N$g@JD%9tGagDdS_nL&W0)T=!J^mQuzwCTxMY75HA_HsJPO z$$IR-UBn&0y^=>1CkSyW-~zsnxCeN2p6s|6c*}#bLq6bhi3bcWGL4sLoGJ=JfxeWi zC#)e{4LK$G>v>-i#)OEajVbiE*Wjw;Fk4{nwfWr6oRD|tS-T1;#K)U;O| z2gIWYyhOYVJoXhit`*?%ugg}dz;_U@Nj_kqh2P4Ct>YUrEKLpAfUnHScsuY7#2vsr z&&zmM0~Zrp{;F)y-5@B6|07wz1AHxUFYxq#WxOAF;4)c%0Qj1h#Nk-9uLMEZt_$K3 z0$%)s;@^CE$G%BrgMRK2Guq@W3?5tHAA-NM4hCAP2M5fHFaj z5U=?yQ)B@v@M4$bHsFhh+kqcgAmg14T+Bh{X4#;tK~R)c)FC(U3~>+e<(;wtFYp6& z0Y2d2lSRCq1AY(+bOiz6EemA>A>gT1@&dxZgU`wMDDWB2OCA$kZ{N(p@=H>PLxFff z@)YnK@ig#_zmxG<;NIJ0M{@(*XkTglqb!gg5cGa2W#R?k{X1lQ5%}EKB`*PALA(rn z`fGz_foihjs@HbR0C<&n5cxl3dgCW_B);1zb?T zNe#GxbHg6s+^`RL`T<#gpq`8N#VsExgzAMl9z6n&1NYo6>q#GhXAi^m_Lcl$1f3U; zz{^MARp73j;s&L7)PQ@4D;*P!_RYnSIw%WRJ0=Wn7gbj3SCk~t|N&(+T@oC^a zt7ZLp;QUEWqyPfnzAFOfTf-ILTu~J`e|}K|&iAaWazqBsI(*~PNkheR&v)J2!1*H~ zKky>mr3(P(j)oezKL3;DoP`?%MF~gb&_#jAX-H$hHxiEnUw6B#Cx!eD!S(jjAjJA) zfei2i#IwLF^kG^KIDg2N2cEuD)?X0(0zJ=psQHtYA{1CbcTh{f`Oaz?_?qO0H;O%< zJ}|P<_;M>Y;x^zFs>N{x?gY*sF1mozE&Yh%27x~&@c`#r>t5je>8KAlf2`sM&L3U| z3@&Dtub3w&2nBe8LcsY$gD`NOpD1v?*B`6rdS>wi#p?yZ`F?K(c#%F_%mPo{CNm}n z+(-9~i@^1I^!Ak!2-~SZ8Tj1$Wdk+f+#!WJ#v}Ry#an^TjmvuMov^bMDe0V0K%u1b z0_RUV{lFa*9|X=H%f?M^T)$#|WS%kweO$!nz--vS*=KXWx#2u;_SpjPRS{~S1cL1* z`N2sUxc&*X{-^>EO_96?-1dMRYK3&3ngH>L6$D;>HsHMc?7(wWkpuX+e%Y`SI4?h! zZaq#WAJ@ZIYy)mwvFNB{fE(>A+^};%Fs_KNzzuxIv-cRf2Y9q7xevJi zRoPKL@V&buQV4>;LmdLn4M%}{#>;wQzKSIrqRh+ugv~(Y(NU8T)|qG7dN+jaR_SBM1d}9fyJQ>WBj8WgG|2Bb{PS z-}_Sd$}%j_XZXC1v%tBddElIk1>oG#67UEoOBn?A@G5X#$2H)bjMk}*Bg)Iw2Ar0w zSpOg_UqpTYoEvrn=Unjs=Z1a2*(dx47x~B8%gZka1^CKBzu8XL%a&SpLh-UTH?yI#u;)=lJ#4G`zISbqS!!q zfeP4x7i9s(0laXHY`_V8`(nx6z_Sm^v#;0S$!l+)6e&`uA3{sS1He~ZDyt3x&k_#- z=P?cgr!kHwQ4n~LW59Wkp_Z{;i1(K^M6R!bZw?tN_9N(BkW#U%gJg_$4=D^xP;DL1j=Ye$s=j?R>r|ebS zz-vq81$YczH?Urs2`>~-mdOG>;11$J;ME6{w|uutO+TDmFP^FoC*S<;{K&d*%1Vk5 zoFQHUzMXglc#(Jwc>G6l$=IehPD@t4PCoLzk&zu#)&Vg)i93PsA?^acm$(}^PqhcQ zIn`bec&dHCd8+-ud8z}zd8&iJc@2dOUN_aehQd&QjVcPfnZDtl0OT{UFTcZ-4^lX$%7AX$%49X$%ABX^a~DFw+==0z8dz;0vjv8Q|GRk{93IrN$pg z-hKCcbE~OB6mK;(;Jno+U5(SlTa6VskFO25Ilgufc$qkW^Y}V}^Z2@e^Z2@f^Z0rU z-t+mb#tQ{_tMLI}b#-#+nl5uo34vUsEhP+`x0EPw-cn+~c>v?U%>hh-zyp{D&I6bM z&I6bQ&I6bO&I6b?_+bXH00nqUDFUCqB6-8TU6KA3(nzWxr-;{pZy|0yu`vVl#O=V# zkI2o!1-vLV%*?|ahVhpV3$b)-%eMS1MW*FZ@<4wb)}O}-9LZn0g6&wjdP}4E9c${ zypy;cxRbaOcr=~7INlYRPO=Z=8N~g-L&O8XHxLg3SFV%Y4FR`F9#O&|@H9q&^EAeQ z^EAeR^E9S_^E9Rnewb;@Kmne{EO0wrSpj%8oqRLVr54l4p%2WDghTTBZ6`HOV}ZCG zxZ`>m?*u-VxEr|RQMpuoz^n3g@|6chM!Zxu05Lw|LEtSn(3}D9CmsgQej5dD`fUsZ zp5r+1wbVcgIL~n!IL~ngIL~p`;D?#x928hb4d;Ouh?juJA5C`mcMS>A;48`1{cXu; zztbFQM|b0N^H4j1^H95h^H95i^H6($n?vmdfrr`$oR^ayI1hCII1hCYI1hEm;D_1T z!cc&RIttu+V{-TR#n!e`=3W})MK?*F0Y2_qlIMW$AYK5jJSNvm8My6aW5Sa6|6pV! zO+SgMLd;&`HQ=6`Wgo1v4)cCdfVdsFkNV&Oe(mi>-$pCm&k4zHt*d=`ZHRs|Rf&P@ zcq(~|)}==GB-d;6+s7>$W<-@BYQ>`D&{S9ZPQR3u8I2h_{i0-Vs;hhP#6+@BL)^L-W$&ViDYM-%J z)|NV@ap3Mc}r_lTZDy>$K*lq+A7g#nY14fbSq~O(xd1 zC0%Q63pV^(M%qtp?AM|#k~@I+{Z{-?O+1{y_loy7YrD>OP%$saTZsFBbBBV!m8u-B zP;&LdZAr(&HnsfkWcS1KRaZ56%fs{AJAXqL2;~CRuIx`<{K)(TF{-}|a@H!_tpJ}sMDiMN$NuDdk94WN{mJ%pmm1oiT#){j+V4$n z6R+a?lOLt$tNRuvPk&S#I6qBZ_2_(c%aY_%kBU9*Q`tRF^7=>H9(c^DuDBsN?XfO3 z`)Tsx$L6bj$>d|=X-0qYJ@KUcAld!6sPD7nQt_1kEct+VDu0&T_IOuBIUp+voZdKp z6Awuq1nwpt0)9U6Fz~Mvj{$d{VYHXLZr#YphN>K#6vT}CQ1UeJKH?eRW#U=jJs-(> za==THCl9TgdT!1xS6c~U9AhLe1J8ay6AHYjj7i@3;}gbK#c$*Fheuwgx!dH0{_7u~ z5XtC2x)zTB=(TZ@2Z8&?OCAF5nIL%>_)g+c;QJg#e5;ZI!C@Jby!9vZ)Oawt?I&GL zKJoHDKbaQ^^~w6JJ&pO1CvF2i_f8pa2kwnY?f|~M8-F9=1^v6p{3FS2-@ zEEonoLp%!H{Sz4<176jCpe!D7;IVrsvXJO@1Xq~v+v z`_hsZfIBI^1UyQ8nE11i5&uS6wgNG$h*yC-pONu3;4l12a^=j%iQYr?*np?055E+B z*priG9S~#PEV&bSk+=&ukAoX{h~mA#^VEm4*N=?s+#=iZL(KH&Bo6>T@Egg4z_|}0 z;Qdrj6u9FonGdh5AGu)7Hd$vJV#d){o&wHWd>Xje;-~$*YeDmivbsFT{lp8v4-hW` z-}(FGV?Xb@a)$ozHi$Z*1z%Qg?b9*QihEKmX+ks`vKfo4=eN>3Ku`zB~+Jdx%GYyWW)XG2r}j z@i=h)xp)dV{aievq(Lx#FD^1K1Dt;@o(0Z77taCbpNr>#^UuW#29FHf`sUw@7ohAatMd0R)mO$VcEd$?ihwNwtxUWz0D)8;ZYryB;DdUy7dg|59 z=$4oitcEZ!(`-#P;A~BH;A~9};5?(wdai#>iLJ?1F9=@jOg_7*tD{0Q;RCtz7TMoG za_c5>pCD&zFH>X)BFEj5T#)N(FOeJvx%HOh1Gz3WcW-i=cq-qU{73{_?~?}Mn%B5O zUH2tV-~6ow9+Fca2Z(2YM~UZw+wV_)y16UjeNA3V8RRPQ3h>MuGQJ9&v#)scaR6suaRO&waT&ZW3)xrPP=K@01Dvza3!Jmi2fX<&a^(E= z{2L~R3+UC9ZYvPW?NPf`7D;FLTO#RCFoj~6&+ zj}JI!j~_TEPXIV?NT>CWqc0!D#7*kl{^SJDo_C4dX}uH1l&OvPzJt;cm;Tnc=gK@ zjrPrhL_Y~ND4?7!8&^0STl6ekU}(-b7nP={Q=cM$g^ zm*m@$fxNT3g$6$gkt>PEfR}rc&*r-ptmL@?IZHebyoIKq0K9ruvU{tzRhvvM-TJNe zU{Y>a(Q_KdE0#=tw6!aeT}=rD@}Aoz&jM$U$N^`M$OC7OC;&Him?8*l5+&fg!<2!u zM^u2bM^u5cN7M{1at=?f%7Vs$Vw11}XOFM}XOFN0XOD2ybJ4ze&T-ZYg0o4ufU`%q zfwM<=fU`$V3Y6z*G)oy1c0+g1c9?hgn&ElkoANYz?u)NkwO#-c>5)f z0pIvN$>YG+B_vM)_ungd+T_OdD+-%O#uSVTRjPfmKo+?DyOQUCvv=fy=jn{rgs51y$iVMUBFH60`9z|)v$)}Lh!D=lyp%j;Q6IY z(ireo;&I^n03 zU6Wq!YR}MsR6*XeA$iryT}#s>+rHA6vO9^}ft%h1-1IKs!n;0wxhs;Q>bxNDAnpTh zdKYlhyMUYC1$@A}Kq!7c`RsP_;kK51Pdt^iWcwexBAtJbNm7L1mX{?j0k_fJqcU(e z#aDo{lU0G6PF4ef-{&h|ZJZr;GAnR)G8=GqGCOc~GKaxMCZm%%p#VFX3wVsK*bSVW z%mbXA%v;av?;rZ=1+kLY$^5|i{$T+4_Lq~RUg?T7Q@^4hyNJhtultjn={RuyR})jf z`Cm=U0I#Ox`}yCzGD{6Tm{g16TT%OE)wc5*=kkS5CAS0TZPEdpw@D{(PA(U4Gr8O# z@HXiI&dKEk&dKEi&dKEm&dC)p_+gSO2n9H~Lcn>O3xH`H zN&)9>G7X%!$qaDbCbPiJZ88S}Z^EO!o&f8=Oxbm6It@3%WO}5a#wO@e( z)a) zdoPyU4&1ac;HHfMH*E~~fQ^A*+8A)t#(Ge~z{Wr@Z49_+W57)t18&+Fa6avq z&j%ahMO}dc89Jp`fp4TkbPYJ4_Lbhoq~_DU)#Up4>km5Z+e|@XKJD9q^J(7!oKO2s z;C$M50Uxk25C&{)^blDGV|Yw1ps!ywz~{Yn(LX=A`m8v`zE zZ0MU^ksZ`b7GxVWlLKzr7;w|ZfSWc3e89#)aQ`s*hd1X(TCXA-`SZzOI9ZrT`d z)5d_CHU@ma#y~J_47h1yz)c$iZrT`d)5Z)g()e>W1_ewT18&+FaMQ+sn>JR@^<`w* zSiK;)X=A`m8v}0I7;w|ZfDhOh2&RnzH*E~KX=A`m8v|aY+$w+VNHzuqI*wk*T-Kxyi~wu3X=B`w*%im+yUG?jRD_5@h;#4HU`3gjeYp{ zwq*YAw)PD)Xnu&ST$Oz9?_EpRksJoOOgswQv@zhOjR6-ncFWsck+oD^7UUA~9B|Xd zfSWc3+_W*^12zVNZEf=O^8Co2YiVXLXq@rB>m;`UXB)EvXB%?>XB%?@H*L%X0^67y zINO*9INO*PINO*HINO-t;3AFD#sW})Z7c|!Z7c+wZ7d9&Z7f>P^<~617ONKoXB&$H zXB$faXB$fcXB*1^H*G8n0^3*)INMkrINMkOINMkec%E{rbOG2{?0T7WWhjunLGlXl z8N{o=*ATA(4-i+r&dIKizj*8*!D58nN>M|f_h-ZPb zjpcx|jpc!}jTL~KHdX>5y*9c2AM+!Nz9lD0xsYd8PT-<%OKt_uHf96PHf9ITHs%0s z+L#jrwlNoQwlOzwwlNQIwlObowlSZH;F&{Oc_#0Qjp0F%n1zsa=1I{*P2kxPG2XNEI zoFK4`xs$KH+m=kfYinOfgXV?E*te5^c(-fmT#|zzM~R1kvyFv;vyDZ83md!my{PorHdve|MssbkqYHn1>(k0y;b1+{|T!B=TE$piyL#< z{%_fy4Y+f$5tod7Ffvl6J~$wzmHOZWUfU(>bOA5Z*tvl(r1jwezDiC`a>T!1kP)*RL|?zV!2+ZTZ zkp%*#AbDW5z{~V);HuGL{y(sqP;oAJ{iPVtql5Y!sr_5|06AV~Yc4V@m;NV@m@!jV%KL z8(S7Q8(R)I8(SVY8(RT58(Y!fhcUJi6kua317~Ba0B2*X0%v2Z)$@8|Q!Z^Z9zJAP zfwQsMfU~jLfwQqWfSbnV1c8ms1)Pn|4V;b51DuV`3%o?R<-2sEG!{PR@p~md6j(%G zs0{$;-x&mfZ+THBbqM+IBoCWhwy%__K-3hZv8|v2G2r|=gE(-0uapAbPxYjMn_suf zfUx7Vx71fye^!DsVQo8gMo?<+8?PWMi`d_sZAF z%lD6r^if+5h{+Ro0%xmp0cWdo181xA05`492ZBAFR6iA8%S$J_Kb;?`y&-2m1yOtd zB6%7(zn{tgx0hsm7C2j74!CJ`c@X&hQ~@|!T@g52T?sf_T^TrAUB%!c)p?!u(RU51 zP=Kwj20TbttX$rh6l`@?;B0ladS3s1JbS$$mKs}~1315*asuB_O3pqY{uN`IIWNdI z>aP#@+`q}0^8@F1CjsF6eY_Cx>|^r#c>g{yOAW3|b|0J{@q6iw6NLKDk-Q9?_t6S) z-bbszIk{@U&E!%7jdR2Ms1-OTmkl^4mmN4KmjgH_m($>fNiG)@;N)@x=Y7-zoRiB7 zoRiB}&qe#@n{|J^P?uZ*;Jl9pf%85Z0?zwr7`VBQMnT|xGzOga(KvA4M^nIgA58=A zr`*Z}jK!$Yjg`x1B3_9{3iDF93Hhl<`HA>*FsTJzteV$rL27ERehm`~dL^ zaNb9&z~@qY4Y;|FDoYwy!H(0kp%zP5hmVHJ0s0!^E^Va6(x!zh7Tc9xVjhU?Bkl#x zTd5B?Z>4_Vyp;xxHh-X6Y!MGt9fr_V#G}A@=Zpd8oih%ccg_@WbLY%};QOiem};3H zahyjJ3VMck8MtX{z)f2NZrU2~0b5(zIH9Jk0XJ<8xM^#^OaNaWmz)f2NZrU1f)7F3w*cu3?tpPV}4Y+A*z)f2N zzK3!vvlMKNzh<0;0{k`O9B}@caUS>vpG@ik@F?-3$@TFU5B{2Q$rL2#uNjwt^Vf_k zz)f2N&R;XG0UxlnWsR#q*xD^e30q6kP&q)~N!+EaK1$eH`6yv)DPkUo-9g+7+_W{| zrmX=Vur;I2&|u+fajH8EvD=A9ft$Vt-1Ifzrmq1X@HG&MKh;KAg|CIqmnl#Ly}6hC z4mkT-894h|1vvX!6}ahZH4xa>l;w>x&Aw&@&c0>?&c0>`&c5a_xX5etH768cUvmLx zUvmRzU-JNGU-Q;;eOORRElC zdz68*uT_8_pn9snO<${lAbjn;VZzrA(DJl@qj5F3sY0jr;V|KAz82wY`zY28u`Y`B z0B2wG0%u?I0cT$e$TrKO&B$JAGX$|tYBLO+eJu){eJuu@eJu{$^tChyzKnMJ(ZbgP zi)d>DeIM~6aQ3wlaQ3w_aQ3wdaMRbSAh561fU~bD-)x*=_BAVT_B9)D_BFe~MP8$? zIiLXhniDwtnhQAlnj1L#nx~%Y>xzBNTQ3OCzUBkYzUBwcz7_z^z7_;-`dSDC_O&o@ z_O&Q*_O%#r_O&>0*99`?Qr|p+uce`Y_v^Ai2KYGQS>XM2`!@%i|J9hh$@TFU4?eFI zOhIz~XJd-Mx6>7rfU~caf$yXE3UJfcsvrnoyLhDVwY{_qZC5mAy^|_*XiG*4U(1ga zzP5*AT@dS_ST}I?H4kw1H7{`XHNR}rH%j>0PHHm>44i!}3Y>i{2HfglR^aSwHiL`2Mqjf-0roWqaQ-fg6FB>t3po3lyPoUoiha#fF9^=Q<^|68ZhgRm z%jA^#f%A7^0>I7h!URF!@4|$D^LJsw$SGH%z+0Be4#j};cVSY&iQ3c0Sf(tsQ3V+Y zoJ%|loWBf{1J1Xb^T6%@)=odx(iO2%ePz&lh*yB~7hbBs`3o;K;QWOb<;uofq%XW^ z|2)<*HL~bJIVuhaQv8xTf%8ei1)NV3Zs5G)JiyJ9gck%pN%(;Cit_{K6&C=`D=r9} zS6s;8hgor9D8MT&3Yao#EHsYqxYQt&$!CeL4+y95|mOQo#8nkp^Dw(QX+le5*q3=h!?Jwv*W(HF}f&Z>}et3>}g@(>}gTp>}fHBi=4(&L>vmRr=@_ir=@|jr)7Y%r)BH8 zzNYvTk*gO3=Tk%;ID1+FID1+VID1+NxanzS5ZKcyz}eHPz}eGkz}eH36^*%7yj|v& zbp?3ZmOd%ipuoE8B)0>PQIa}<2PxhOe8x4h9+%1W@fVMl2c_UP1<6}ul6!z}A?^jv zp5_DI|20zE{$44gf!0-Qaq3Yotw}WLvMj*&)1a(XBMSpua%e z4V>Q*d4TgfA}?_EG9PgB9g!aden%7l&R!M-&R!M*&R!M<&R!NZxX5MnvKSO#FN*`` zcSI@R>}6@->}8pHuCFEbvTVH|ID1(RIKLyx17CZaoXP@len(UUZoVTbfxz#G%E0*@ zQ3ZI7a-|B~RgxX50q1u_)@vtfKkT$jiEND|ig>$J3CSUgLr~~?$y31j zXpsiaM~e(_UXEGd=FuVt0v|2%zA-bxv~b-llP(Aa_Jt)60pCDL8U~)F_$ctcn`AvPlk4Lz9{khkxG6}^ zKb=ki=buief%DNK1HAJV*>D!PdE+$)g1GT|_f&D?HAq)j0(~9vik6rvjvm#i;wET- zSPf#=5?7@8nEMYOEv&%#Xki1+H(njUL-Ms2nI=rlPmQ@CsGqnSIG;N_!1>(a1Kr58O1o0tjq) zMc{0BCE#p$W#DXh72s@mRf8YK@M=(i4Ntkg(ZJa7tiajuY{1#@?Df3f@ErAmSa5v) zZ~|w;a{*_=a|36?^8hyu&kF(@o)0)1o*y_HUH~{7UJy9HmkM1EhR5%v!cd@=l1Ul` z?!TK140zuUB##5{Oh}$GIT;?mmr9$0G(3JUl>yH0rLw@;@N&TUy;L5!X?O(?gyBs) zQ5fDDT80(S3&d;MNhb=!i=QYAuaDoN-T;Y8+y(baQ(q466n zN4-#Qbihrc18y1}aMS334;UQ?rqKa6jSjeJbihrc1D>JW3f%}s$6pl+LxBSuWim#A z_Y;pHr;pU*!1*Kfl*#q+7Z1J>o;C%^`6KlV@VV4*7Px72z*kUw9{7OKfgp_Tp&7#H zmeWvGKu;5|X^+mZwEf@|;d6@#SywjZX^OZFxao7iO`ij9`W*0}e68JoitxEb)R+f? z;>5kcO`ij9`W$f6=YS9R90=|wwC+=d&$a%F_Bha8o5=rw^MNh{oP90}oP90_-1NCT z2<&qO;Ouin;OuiH;Oui{;Oui1gNr;zpQ}Ov_PH8xKF}#QHRcujoE13xoUNYg>x_NQ zUM~pF2Ra9E_BkhT_Bj`D_Bl6j)8{-Ou+Mpcv(Nc}v(Nc~v(E*9ub|ut-gE??3qgVD zd6|r1;2VEU{s-Jj@iE|`=Vg4{`1+Gv%IpC(x zD~6LK+eD{wYC8*nx{J8(8SC-8uL ztsOdD7@eIOb3@P~;vV2^bY9?WbUxs0bbjEb(FH+p{X%=}3}JM!9W?i#uX;oB6mT1T zmnaRK@0@3Vv(aUNn|IE0An={@Ja9I;0&q6EB5*dk5^y%UvcW~7qtR8M02^HuINv$1 z0cWFAzTKE_Y;@Lot}iq;I$OOUI2)ZEINv#U05APbPMH%p-#K>yH}9OgLEt;*9^icE z+zY%&cgTIf`Odi?INv!BetV*}>@4wJqLq|vVF=6+j{@gA=P}@X=R6Kve3$6Gv&83D zE2zFK=xO3P;CypD51em~7l8B4@gi`#IX+q`gHU=>TYt9YTai@<<N!j;f$$h}LJR`XuxIZg-0671%2SMNqe`>@pRYD-_{kg0t3_Sa5$)mtq zs6#Q}i^@Q3hIkhE9_mXDcy@!VI}f~-+AILyDEoN4QUqZ- z6(|D_ZP6BZEthqdUy==ZRyEE}ydb$3c&?zm=@lQW*q+yho@1Fm#QD6mqq4Tks~_mk z5#NRh5mRn!tTXn!_Ru+&t_A%&WZf>%=e{nv8~6(1KH$;cXrmTb=BugSXcsRKeX9IM zyIX%QZ?;TuaxG8tESG!v*3RqUTzik(E{1mjINp zeI$7hIUT!0zkI@Mc{0urFt&fH;>)rdO>hLc2|J2l~#dU|0AcY2E2#35@}3}?fb-rzwRqy z!?)6u~UbRCx{E)dFNWJPY^ z-ge17!1)4wz-_ab>qyYh+BcLoFVJ60p|;}12-?w0fP5bS&YudUUSa6oSG3#pXM0h5N`H10wcX-5vgeJ##u5qlHC|xPUnP$M5C5O! zG2ro-$Y>wv4v{ zUuc!_cHkSAOYQ)^aGAm9C{7SIQUfmFeTuBe4cxs#yXpeV{Px1%WXA%ak2^;D!v*3( z4@{SO6!Zgsmjf3A-u%=sV?g7;cU~)b3V5_r4qzI%=lC^xJ#&-{2s_&31!aLRA18SZ zc;>s>vtJiqEe^Fvy#)H=Q{@Ggf#*JxyaGHlQr1%iuH2z5xKP{y3CWHtj_);QMqrq% z&k4Np6}e_yz&jt8@owM?Cra)CZa=|jPdnQ$zPC6dFFWanpzwBCH~>5|%4W=35V(Jv ztS1EAwN};>2Hx|E!6Ql(1)8-OaObyW199N~C6cFrI|~-0qiNvQyJdXF;E{oa?p!E) znuP*$CrF+Ho*OGG$^&nq^eO<~xmeaytmorJ9|H+lQK?=KeBaBOda>~2OqUrssX1Kt{t7v=}PCnql~VDQd?DO=Pn8wf%H=WW_kmx%2MGF9OZ~o0l`mOW)1kxcV$INtTC^OBV@x?;I-W{-UfW-k7T^v;FAZY%l(=x;D7=p zZR@3$wlRw@m&We`xvG75spZ7Ts&%ro7vwE}klYWv`9;ba;2Z9g@j>8ghskb-fcHpy zk0@afmUqaCqQHGWloiE*Z)}!44qQ23){_EmP0IMR!L*1H;$sz&E98}R8v zWrys*9dXGWz$@R8^*aq-XXlwuWC0fxC^kv%2EOhnS&;|0GG2Dv3q15wRd++hSI@s8 zz(P9M`RfJ2H_{EaPf%|E{N&&CL zWcz908>+Iu8Q@#C8tW>eWI~|cQ>Y=y6A8fxj3xOrE)>gSJ9y~1U$DyPEr{73v{@Q0zdF$ z?IFFL9jj%z6zJ=0lBa>&_aCLN4kZJ82EEJ30-yVwHtidh`?_~rMiUD9mg{9ZHQ>{I z+I!y+tHE}*Ob**UFwu|5a(3X}-^g|xz^&{jz|;51ql62%Pj2<%Py|AL+!|v5Jiwjw ze$fkj)hgLhA8>^-F95uFvy2ZKJTkD$x-wD-VSy*@Mu)<{1GmWdC~)r$a)e^Q%P-3K zcs&>GE1mzALaJU6+<%nhY2dYjh?u z%ZiG?owO&FfIDdOtN?e8mi1TfnK(jk-~3)haFX^|P$cET5waocn#QE8MrA=8@c8TU z1Y`%k@sO;?0lejJGTsS1@y)6f~1U%}|W?wBnb6G?un=0rYa_ky#<$$bDxwkPH;ty-j ziu$^1%Z;~JiXHTpF*NzW*Dcf9SBQRWq@;0!KKEbpR=5Xv&MwczUf}7p_P`3UWws2G z?FB(!`_XVC$wR>R(Doh%zVdQ8p)ugiw2b4x*KDJ6MGA!2bF!i|aN9MMF~IlI8=@@m z7fz8EmIJ zmg_48JbuuK7q^r_STRXflmVX0%TdV!kJDK%2fVXg)>8oPdr;O>G`KjP@Yn8UjMF|1 zi5oiW25Zx<7b|!TIc*Ipc;Pg;ttj_5rbi#0`K-VzbF{}qed^pb+MmU9WG5{g7sRc2 zPj=W1+)mT(0p9;r8Se#Nr8^it;QQp8)X_=+g!IYU12>2Zu4uBtDCqm>U1tpWqcT1Y zeBry=&>O`Cx7?#d@;vaK@sbySdu84#Mc~bs${8&I&;Qoo5yeA? zKA!3RYvq~C3;aRiKH#Gd$#_5TF~kGF@1uHx29FG+*dbYoNai1Y`wNNhz?mI~qC;|5qF9Qz{uL2JeuK^DUuD7pP$IIgmPXRYz10JS| z9KfT*oxo$n-N56-J>%CH?VGDSMS|}L1^mF%6dwehAszyrB_1`oY+vC5F;mdTMNx88 zAO)O9C=EPM@mb&;p95ZqP=NvnMdC%^CE{h^9A5!mruZ6gj*lo48t1-31#G~%fE{?1 z;+?=b-UYly@gB(|=G^lTd7*&PEmwgbIL8No+bBK+oa4g{T+F|n3d9-&@g9tN8VByA z_%v{i&j5E(d=9t~ujgML1P>J`0_O%wz`Yb-0nYJNqEsLT zJVrbYJWf0XJViVWJWV_k0U<*|7I>Dpb86$%q#vaz1D+x72A(DEB_8294*X75SH8f?@(C>(^c`mTkRWM0@R&A7b)bSR=BBLp+xwcu?u-;iK0ABAZQC&khdS|%>Tsnv@_F%kciro4;XAH?g~b+7*xgLZO#!ws5U>9(Uhl4Zy<5Ci z+Xg!Df8zC|y4UZC*R$(he;{5jt$Y2Eczt`_>yO3j$LRHF{fa*oVB0{zrq->NWrI7b zN^48vV3U%l9z3LZhbdL-yq1KR@(-<+=tEQIDMjb`gR~zOEaOLXh!=_oP}Ajoo&(MTI!*Z%6u6_Rv%kh_+;jv?l@TK36_B!?OSKRy49m+;=q4C+a z?nL@=_0@OgG$(d7OzaVi`a7>*6{t6o20MW=rCeuiF!I#ozzYq)h8uVb|{ei)G%hz!^>bI_xXhwYUFb znbM|T`5f^_hx*koTVzl4O&_C;Em_7NUR*myJ5PvbAGYM)F^Q-e?Y(_%wD$~$(w}a+ zsHR`o(*1|D^f=`dy>G)t-q-udH(RuymnD5UVrpyig-R|{X3ye|0`KWSt9!IiupJCuIRJ2@#w^|ox>BmhK=n$|Fc8d zk@O|w#H@XR-Z4JfJL_<|G9t08$Cj`-qrInnb|~`s2J`^YfmtU-drvx21wvmf^r?r_ z<6`jlwj`E_wCXsL9y~g+OXy=hiyY<(OUEXb+3bncBGE=3t^!@xJNScW?~pIhEn2kK z@&)=YAsZx#CQ z52uHw>La9GvD0$%Fg>~cIZW9+yE0mPf2ZY4_372xw6`o1EK{^|-m;9H`MImF+7ipG zqZ6~nM0-~qu5w*pIa>SSTb2`+>4lY^_Jp%j>DT`*)>2h(PzkjsI&wo2vqeTfeqOXU zI;E*UeMfsuteuTloZi&`ag(y%D7$WK;-rs-Av7u7k1EmL-NG?veR4?C*W`c1dhhTI z-E{olEghCoI?>m)ZY4`EiuOL!sa^KAVNkOJ-P&Ku;)Z2?F*Ce6HlYlP_D=d*wD%uP)@jE~Q2H-8bg0cC zE^dG|-g5YW#IjU- zVyhUz8;+!lmC$j1wD+nn&{qpxcdmb*@vCe8b+YA}_m5Yvd3SQtH3zQK{==OWwZp*ml>TIP&yKc9|9;xbaimk)g8`K-3 zy)!%YskYUW3zdy$p4QY~Ur+hl%6_x1l^uq~PFfl5{rPyM|1V>az4DI5<)|9U99?O?=cu>u>ivD!tb-pn+1Hob zl!NIXDBTbML%MI#dCG8jQS#F=OVX=sPM}76T*Q))G zKECp2fv<-5s~_I>+B;(4{ZDCMec$qcdfH{$?)NSGdyGEJE-m@$?48T5ol^>ZXZIbR zgLuD<{>^^Pjgk|olCU`6&-S4UEqiwR*_Ag6E^Gnu$5XArt%hXzy)eb#h`i=w319V!CfSlD>0zB(XXi z?Y-v60f~;AqrKlal5U-pSR(XGkEE}elvpkF3y!4kv<%l~eqgykz3)=(z7H&ORBNa9 z+6R`!J=Mw?`uw-tGkpIYz52E3spb_~(=DDWGj;9gdq({6d%cyD^}i3lXUOzf2dBAa z9rTF&xcc9gi<;DrCTTBzWLYw(D2Ak{P5+N&{7~I%D&ovxouYm1KbA$2qOb}>Hmtza zX^iNj%cH$}_ZcI4Sbdk!_k4jq>l@MDonN3^z8US^Vd%#whigDPW1r=GH!SusZW>)vMBFZMauZwA`nMI`+eXy_f|Z6VS^FpR_gkAh zn+w9Pw0ODArz`qBy7^EEMOZ&6RxRZ93zLOq2R*`VRF~{Q!H@TiWbTElbtK zZ)rdIR2bCNZ)qQWYI#xJ^Q89dXO?bt(bu&PJ`*W2$f9)}u#AT+4u8qmk1S$%ek=S# zAHIex*Y$p9Vu{dyeI&i&Ol%dp?mveuFZMG_TxGC8Y{?`Qh ze)##g@I>vOP3ra$MoImMv+XO<-o<0JZO!UA5j~ZSB8HQA$0wFGPfS?89PLetl_SRR z@cP_n?>$G-$BFXuqrG<=Nf-4mIV;+GtD#?T_y(5DiT2+31r>C7qP+AvySZ$>bBw0-fv$#c4Ig(yz z(XJS(o~k}MPkUsjdW-tZJZlm(nMP2?gZNdokwNu5!d@}sBgucRzn*noAGbU#D z4t-*dUH^`F-+j?2rT_c4jJWxqlRY=jd%U z_0BWPKNZZ3>(b61rG8a?Zr-N*N2wE&LyLy~@*-_8UJ2>n2^ESOQPW`|#e91`(i+L$0X)jMu7Z?G*o40A~MD={jU@d}UEsFQ{do|(A#w`V4r#UZP2-YAp7xH29VKS^ znQb!GnCaYETH7R{zdBEwGfACvaqHQ}dxzcc$tC%Y*fsMr{_Z-r^kZ zsDGWOeKJK|Z#YwPXQD6Asr~#o_1-qUD&1(en0IaI$vZm&6QY0$)0HM=6@d26j4SMf11P}W4-Ho>5Rl` zp+9*f-Pe=YCG?+>E}X=;MCnQ5UeJaSiAU!~dmpXS_4*@bfY^{NOQXFHLO{L#XkWB9 zaik7x=}D~qN3{2@Bk8NoOf31oXzyyF>$lKuYu4YWPSkFlsy;c{$Uy5zV`Yze=aBYs z)428d`v&D4->JIV!<<`v~N#S$A8&`ua8bFxOa47;t=I} zkL9k1bf4I_`;ZpBLfIU>jcW3@8m)Yw^Q)E3dFFdswZBbMJ0eDN;bV-Tzw1HQiNZ(K zPSq!+VNe&2Of1VElUQzd$2KPx92})Zj#oQ|8Q1x*p2ULJM{7SnUL7;oXkz=Z+RMkQ7YrocsJ4N` z^R#I*r>iFnGc$2bn|9rFb=CkVwrRhfuAbATXF5k2hG1(;^f~R?*b~$f4qtc3u3dhD zddy(GRNr>HcIyf1Gl!4NjM2W_rJnR9uD`D=Z^J$&ZuRL~ufEPV4^{eO!ii|=t?+m&g3?UMDCx9P`D`FlHuhtRF|;c<;5H zwi%IfcD!^M%DZCAdHL>MOLOLi-FFO1l%G}(Mz8Q}{)t$l+)7`{q1`z{4YpR9nE6z8 zXicZ6{?>-}3^&ZTYuBBk&Y)p!9jpEP6!o}cUp+Z7WQb?KV#%Lr5&L=n3F2;uYlimE zQ`GLGUKKt+@>Ff&scO6W`Zn#1Q`JRtKi^_yth^ibbhI}n5+QbpXa6yxrenp3JR@AX z^&HR5M}5U}^Ba8aE5>TCovI!;xMSgSdhdTQQ_O}qu#cT7oZ8W?ojp@+AO7gciFcFA zW|34y$M3djSIiWrrr&SV9+|1mrT$mOYVXf9uf{V@`;uFAkro}NUG5fr{^K_7R=4UV zx^bNLYqw}aB=OsBeS|(Yb}b^+PE$K0`Yup3On63zIFn6HY;}txy%>LCNX3R-Lf7-+ zcFt+yM1Le*5qDdJes!bXQ2!F~E@zpkM~rPq2I!6_-cxLSNZjx?1M0RZU9XHxtiDrx zVs#{a#i+zqp`UvseeUSQ>R7aQ4(kyyD`EuXKBzY^PWbm-;^Q0+Kz(g%VztmuK9cS{ zCb3KC#~(=-7qClM`ef204MVJVKwLqGxJ@_qNEL`H*d_GQN7BUwJSuL44m*-AE?}3? zn}q(K5fikl&rlakIO!zA1NA*fd}TkuK4`pNtZ1*Dp?aIEO07wo*rU25Ri$)PBHwiR z8-~748Tk9&y1(~W26(LQ@0Gg0A5aHkg3SYef1&R03+rM!2Z@*nH5~hYzRo?qiDLc# z$%ab{at&>PN=rb6f{K=#$WfAV2L%i&Do1I+qaZ4J^eZSo-3_2nt_@U1E=p4n=ps@s za#2wN9=Ui_EFLd-)CN4qqQ@JcSQYtwW_Bh!*(UP`uaJFz=9y=nnSFL=(>$SX`2YWq z{{N8V+%S)=SuOp4p=9(e>Hjx0X8H>U8h&tgbXMj0nc0=+k(cPxAoeL`RkKL>u3N6t zR(a^vvdXnPlbrKw#TOsN`E_*giy66e3pgt~9Ar7_kH)wg&mfNkw6eBL!JZShlW1+m zuKXgct6QhID$$5P5YSqL*+&acH*}RD%~a78Lr+)Q*(7TGp-d~a!eks5y_wKqPL9$o z;Vj&o&|`Zp!qW;*`(HaYbnUUQ{!EGYP-AYe(s2;@$rG~$ce^z zh4dkFpVgi+WJu;v`E2(GMecBLX;bpeKyCP#qwt`LC5-zUv!|85X5rwG8kR7su$n2i z&gX}^M~dWiq0yMAg@bc30{Rf^=K-#| zTW)pjpc=a0Kwnj^9njHFkf1#P?e3=5r$)cv+3hd4IJAGcETQe}2?sYrdlq(gK$i!j zRSBcwV<{M&4dL3RfW>HJ$Of!*_$v7r3!!zE@RaSl(bbziQjB|Y>BGrx+8R$;$5FrbrN;)~|1`4n|AX*< z`sAPPV_hx{&sOm9GxX1`bC)r%s3)ODj1Au9E~C1Q2Rt9Rit%{{mJA*ncFV1DmqlmK z*i2cxv7h7))mmvAej!&5#fId*UF43TTKgvJE8OfE=b0DCQ$w|)>u12p^8U$A?!htF zUo0p8#Q*cJa{UzO8If`v6N9bVLS7w)Rnh+!^2IQ0QuQsQ z^>AFer@lZ&4A(Bp+x!APAzO9Ro{VO$*7;ekhr=#R4h=2>R=kBQhNek2kHw@H$Q#48 zwQL+WcZtj?>q4fE&>ocEpB$l0(T2QEMvc_+wCi6d501n|zwhg0{zz?!7P^Y$-k?3G z{nmvnxIsJ7x?|S}Zi2hze{q52V5OaF)R*WtYT4RD1%%wFy_(m8Z5*rUt&$%J%X&1D zgZXZ6&KcB?OdEx9VI#S0l;#_8>GPhlLwE`@@AV74=riN}-)d!E7<~lEsOF?QGOH;~ zG+y&x8TjPwfICvb-+w^guZ5n!e>a2tIZ7MMA7hQN9?g#)tz~zkTU7d#f{F?Ui3d-iMxTf$95;E{nvGBfd$746a$>y+oC|1fux)^&=^`J@v$ zcC%KL{Z${f3%&glJSn}t*&ceuaosqCbiYM=Wi&=r>MAdc6lL^ev54bS(+U4hOg0^L z5)U^rg5#3;(M0=>9@67hJQKQU2$_DX_EvOSn|G1r!K1w+lU{E?#@(hpU=NEPq<`{qkr7;<$_(f6Tvy=> z={fP9v$5H{b5-@B}-@>~p`XY+`$V9X;;*AAPEwV_uD8hBh&; zQr7=rv2I{Bus=&?9s99%ox${dXt+v-c-l&hUd$S1nUBh>*kV~=(Shy{@OY-%zdy!8 zX*}}*x=^(L3_0)nBy^Vx|9lw}^E!4d&YL5*pJTOe$ZY4B*WByMW|xBh!@W&0Mz!xg z>TQnMkPIHLyFxddO=FA~D!eh&W2xV@D>!^SI^h^Bwl3iMn!YF$R?pK`S^ z_u~EenML>mgg_5u`hGj(sk$DyVe&=VpE6)#fMY?9Xdf$pR z1|H4NUq(OL>riOqx#}jC@msOi`$ddSuDVB_#ib2S)waklbhWuQGH--y&sU#ZxQ5Vs z)MJ`!2bO@$tR zMN&x0?$pL-9Nnks+lm@ABj@haZf!ECf23$m|H!02`jc^YX*b(+`(4^CJy@=wl1u(# zopi`0S;_NO>azK+z7w>s+-<~^TBwvZ9YA`7v~1QJeZS*6GTQNen*9FIb!17>`|HUT z`MoiKypQ+oY1h=={{}DwU6G=F zuE?aj-DLbEt;Rt&m@~ax|djB4+rPh*q6xs42Jw@>6GY1+G{T}UNhruxoBa^Oa#4^${ zoVfK2Qof_nt^rfD8QLXP9slD$Pw&*a;TB^a?jV-m6(}(8@f0+HALUJOGknTVKAWn| zxY_oqxN)TDb!;mZX5iBYBN+S0(TU(0nGqlO9*Li%;T60=KG|@;HmE^WhPx^G;ePFY zX&_W%WJV@+ZNkoGU9w@F?VOi3Axj>>O;$~BvgrYBV;kY+QP)*XBSnuk#WV8^a_@uM z|8=e%M4t~1W=s87k7m*!XX9^%&v`uN&mOl~G~*(2;X&;$4XTR%c@Y^fP3xLbg-qS8 z=tul{)HH2xl7XMOfwnMk1_sVi186q-A??zp)H3!gwB;`SAuY?@_|PEyo$^hCcddF@ z%WDK*cfB@U8wgc? zV}iCNFO_N;7T8^?T|*|%(wdR;rCKhN?7BFjjmv0o)YrAyuIVeZKQeEwI?=>ch4@#w z%Chm9BL495rJP6$c+LK2%Xl0H@oaAoQ zZfl?1C3cCE{?|Sd&c-?wUS!f=^LO1_r3KuLYn$NyaPT0qWvg~X^It+{ZqwRd|5fM6eFrWOTt&=Umum+W zMJX;Jk(z;sh^GynW@MO|^me`<=vRYC5cuS+Y)Q}nf@f>hwO zwSg_FWxF-&b8i{>=oM{9s}9fdK4UG|@yp2-JGGu#|Fz`Lo!Ft?R6+7~Y1!@$WW`Rc zi+0;GvVSLb7i~E1W?}7@rKHa;?K1b(|KsGI-P*0KS05L#aIv_(zmmMSTgxl_ zo#3&<0s0(-{mlp#Mt--i=ef(Y|L0#ukI~0o^p@$rPvLO{bbon<y)S6 zIOx2qYbejXqM2G z;mdPP?w(h(OxtTT^6z!uGKj2sUE7y|i-FsuPa*H!t98&;4=2y;)$*D)AL%NK!;Ej= zC1lH9ZJ~aYK2IyU3VT@WPvR|Hg~Rtdma4={2_gXP4-uUGN2% zRc~s4G|<@-#G;q1&H{~%;I@7E+aTN`?8iTx+(|s%BCpU?@Gwr^3I&gYuT0`7iN-?C z9q=_Vf=iPG$vgx;U%{i`vlN`}TAq-(?igVRg1^fG2akf^r{Hn$i3;w+w&)It>&_6< zO>s~XIC%j1Z-j!!n_gU4q~P=>`&ygp_2xJXL7^?E$7A5#6x`PWAB!q@+?!X}KEd&^ zmUD#hoczMp2|)_(X;;`p!2>Pvxvhdn!GC*`FLKO(JqLVvj&NECQt&AFHwqpHKcV2^ z)<*C+_#fCBla_}xpLTaw(({m3p#66Ux$6+}(rv?BWij;Z`zM}W;DFY(JK1nZ8+JpL ztF|Cg)Y5uH7Ds+r?d(V5G{2Ok=cNB(ZP?|O#X(zeGHkpL!wK7l$j)Kzz3u4_;EU{~4X z|MyIF?b52#wUx(CZ|wc!Y0Z^!gx&+tKksWj)K&H=+V=bG3ih#GylH-+UgK$JE=5DS z8x;l@<9+7+OR7r-y?*-Ct%px<)LchSP5AA!=FUtQyD$U~lyY2k)Cjc^cG!3l?+1+{_CE=5#x9X4|C ze#*hp>dI@%PwSP!6Niy`)Cj)5A&fL}7-@v}m2Z?*5AR=oI-QN_utBFn*r*$nyw32H zP%j%^R$6_E8=(u$o*OHy_fSXhof2ULPZW|C>sNR`{G;X7r@EG(KAdKa+(K>Ob5CL8 z}I)#qmK;_%Zt1A^o22mqTZ6j|dj951IQ%ANeug>hA-jSZvMi1M@E4stTR=hv_ z!t(0F3L~AUkrsIVIRT#~;@+9Ps; zX}soN1RrhjNlZ{?3wj9wzWkLiu*2q;3yv?0QGRl$zm8r+w5mBl;m81?8Sko_cdeWB zU+3wdCk#(;)pbR~-tO{X#fkbO=q4IZa@E!LbNAN9%*KakuEGjrKhXglX-A>E7mh$z zp#|ziBS&bay7anv5Y>$K*PX!QW13RwM|uZ$<7S_xPR@QsD$e$}nIWn>iM06!H0_a& zpMV2Y>!;eW{<=D7JFlf%Cd=LqZcFga2V4m|n|EJobyUn7!vTCR$m(D{Z)o&$6a7U` zJNKWq(T1n%FOfw;gA3mpK2cQ*U_2x ztaa;&>Ac(_@Eow0#ieowXe`fW9%lwOTuYaf51lu*JI|8aPnVs)G23h|8vxvS!tR*P za3h)L`0Lm#_Od3ayNC=<|9J@Mv`q-bk-c^WQbq}*e+`Q0wQHaVjn=Z55P<(gk{ z4GkCT@Me2eWD5I88Pq=Gk0$t4rdtS*GZKQbgutxBO$|+22J!_s`C%iLRTI$&`J%S3 zo8(sF;02*Xa+rsMbbPIT76*|DhV^y#E+P+Cdb}teu7Jr_>kZ<4WNB3E)1E676sYG!I%^D;4g^3B3EqkH0~c3QkonPL?#`!lu1wE z=AB9TMeQ-6MUt4@htK%^;^18L1p|D>CyB!gTy+`HvKhZ!99)9VdLytnU*(`>@}Sjl zX3aP)!(pGVF0R=}HPgk6dlEDL>rN}Kf_prP_Ilw@9I_73Sf253ICIgZ1ZK@R8cQ=C zm)p-wcK*2B9&Bf)M8|B#t9KSyp3x3!2JmF@p*5@LUgf9VGAmpxS!9ZE5gx8(a*w&@ z9@!f(IZWHYe*boGCA~_r(SoxPMX6Wz1#cs_LBmy(o0P#?M&1=(tzr(4HJd$IdW|@^ z2A2vt39DqUvdvP-B4xDKthgMDEORc`l%qXc{AcaO{gSZ1*0Rrdo2$iz?;3NR5NwbH zy%GX*wcwj9&X)9;r6hloC#%I~0k&jbFC&#zh=bc*b+x_RY@97th=aQ@cpUul zWi&4p2VaA29L(Q}h|CoS-$W+tg@~+`Ba&tI6{F>h-Ps&yn6#{~iYWY*sT>e&K5!(2Bf9kT<&0#Jb-Mov1}hKdu^g~ zEbRxf%?qzsOS>E$IOp>c5uF1pWIWl~({-`n2PG~|XB)xau|lp_Va6^M2j9muVjecp zgYCt^W0=OCd>UJcgCAoWaga@8hB){cY~moB#tVD+Irt@}u_vbCKynneh(U7p3l{dV z{f)#lAQE14J=YjibC74JN%U_ItsB!99NdFC3yEnYatCN^Povi?1^cx>pGIz+PNO#t z1Bq$$n$O4`ydw|5YwEInuwxa8&f)wOUURx6aAv60B049nkkMQ)e2X~vH4oWIxyLMX zf@IJDvon;}yp6McbTnk|Hcw9X(UQC-KPeeS9u-}EYxRF&njp z9gD5dO{kOl7;*3dJTJsx&m=qP5`o~1UiH@QZ!FeD;jcUR6^-+?6_i;i{3p(8IJ1&1 zcw$LpU2fJ&25Pz_54o9e&f{htuiD}1&^AvTZ0xR^49heQr#iPQBpo+-+O+Tr+SFZ_ z!3Q~|i8$E8T~~WG2I&b%m-a04Rqlg}Its=HS(K3&Fo*l+mHqRY^Cg1@n7vZ7%-Ko(x7z8+(VvjyHQjkg zds!E;HKMCr)_-qmO6wR-Y{}`4d7IGWb9Zu+-I*xaH^8h@JrORQC7av1s0Q&y)~)iD ziLBb*d`fiC+3J8T<%i}33$Sz6u!E-eb@X;{mS%6|7l}4q+;ziX(`vIYSP2c)(l*vW zbn7WcSTyL4#dDQAyaA4`7(k^yLHS8K}EUBXmwx8__|3tApC1B=2i2ryalRzC_>w?z*mM4m=82=eVuF1JSyN zH3uh9=|p}$(?V#5y6fgaWAx{9aKfI0H@Jre=d$;^g!i1S)tW?faduXT;d97Rkgtg} z2U+F@$$)bX{)roUcDjyCKY%ZVW;7qb$bg=dUY1B57$dDY$O^%U#2jRq&u|SLVe%Zb zGdGD2##$Y)rQdRK@UX{T`X@Xs5>b7PZr_;K<8YG0plFcUKyHweXs|_eFdiLTDW=Kh zG%2hXnh8j|&=_L_b@V3VKt+?psd5V+M6u2V@(4$X5ps55KaGHuM2Ct9amJ=8o;*$0 zOYNQ0L^rf-z>};2VE*Z*EO`Wv3DLcL1e4^nmStWhbzp#5Yo%$@G!Cz`4BF3FnriAHXi5S;hyj#F2&Wl{zq%@Z}wb6H*qs zi)#!xnmh;X%-Ny?Vs$`QcS+@{U_nDUsn}U)*-nv#Rv`<)plC29seyft(tS5u9Ba@) zcQH*ir_1{(p;?Os1P$(+tt_BMWuo`ht>Ri8M{K+S^$uPw01H0MJv%WKO3ki)m;U zdJS0!B4Z1mr&-Msr_)<}6n@U-5$+WuxJ4J*zV-boaPt#_qVOaGa3eEdiLC_cn#QkXVMA#k_!{^)%o7cQoc+c6|qULrMD&}w>hb(R( z{4tx9y~jxgoXh+F3FnTbAHWi!`Iryjm?H}fkUB7q@#P(b6VmeT!!-sRWlkjKpq)8h zbnuzg0lUV&RT8XhlsXGdeMMxUFOh{{P&7D|)WFU%^r-+_94FC1S20aCr_1|Rq4^pM z2pZ!vzPeA?)6|d;qFCnwd4zvf@spgh16qs3@;=8|IcIE|eBjbFeJ`~~gi3uo#461( zy~4R~tpTLWLYE2A4}1jQCTF3Kqz())YpqZx#l!9_^IfhfhNH|0DGQy(zJ^8d49!9i zu&_6nAC$u`XCX~EbPidl3)c@KNqRZU{31H|9Rq-#Iwo^EP2VvM%|aKDg&;D{@Oi3e zkvN@J^HKOYmq+-l7$Ii|_S@66SVV|37NL0ZG(Al$egBaxPguniHz=iCmP*Bl_c=WOl7mUb4phQoav(ztoUEv4n{HG4<~oXh)W;apDo z0o*GzxqJXQMe>f!YvxED7&%4Ot~drK63g3bHs=}xjxr|_bI{K0DLTlvI$+n>FGw&m zBXt%UxI<*2&RSgt42lNBlN#7rrmyIr3p%(|Oq0#&^1f1Nx?=%BW90K`(pn{^>GLgC zqAAw7Kpx>o92%Uh?S#S_{3824XXTu+X$pWRvXIw&TWar|rf;!PVhNy!HGq^^=uaW) z$w$zmNZL4i&6lMP3@~f0P$xwe@|rJlO)(rzo~E|u5n;cthAadD3wz#k!Q`-KB{ssx zMT7oYUF{`8zrvxvIH7+}=m%f`&|8k#oKDj}n1*Jdfm+=#h>X5Pb!V~aXYaS?=}|rk zKj-oY9}pwtZ1xFzn(h%1;*3Se-8yNS?xdQV=#C7cnigzFR_f!KXqFhkP-_Hs7V?^- zx$$z^&Wi`+a9TTQ1fR$83$w}MI(%mnB6#1`YeRg@EG`TiR;b~2L|Jt2a>?aW8nQ1JTL^`JW%i$c!ACJdUG5Y zii%LSpdOEdw^Q)YFnnu4!Q)WTD~sno&YfpU1)Lu!~E#NJArx;7tTVbnRo{KPh-%Jo1395X2ye zD|q0q$O8%<1OGt519uuh{jfq1gCM5hfxD0g6g&pLRlx%j3_Vz>5X2@R4=8w`7_-ggl_&p^3-?3LXc4SiwX3BqRcbAPyc<@X+1J z0}Af`8}fjH>tP6nD+Kg+3IYlq2JfffzI%}e(sMl$g`gn4AmW>hJfPrF@OBFBn}R%$ zmg~(UQ3x{A3h0r_u?)efJ{|D0me7Qw8@u zfIN_f>-4)>Q3wvF5m4@X5P3ksqu_fKJTMJ;AT_ssRwo8QWoiN27X%(c9#HTY_zDFN zJd8Y$lIzySBL+c9N`b`#`2Ccyg2%ugSMb0i$OEak&UZdB2&SYGa2|LRc|gHq;I}Jy z;Qx>ZQgB^ty|N*gOpGR&e)BT;JSP{^gV?<;1I|>3LaB%AFif*6g&#PHJRfZpV9~e2J%3%Ac@DoqY54f zBM&He3_Oy=={G)Q2WBA;Bngsv3_Pshf!W9d3LXQ0SmwC@PjVnM2YEmiICva9q~M{a zkp~n!4t|rw>Ha_2foG5hB!QE==OPa%co@8&g1hG-57=C2Kyb`|eFq>oB?KvWU=i|w zg2%u=Rq()K?AhZT~ zK*8PR$O8%<2H&ILz9{zpTNQ$66nQ|weHF+93LXVtq2Ru?xFd;Jf}=PMkK$TTD&G%8 z*CG!nxNjZufPzQCA6M{z{vr~ALJ$L=qTqq`$O8%<1HWCt_0R?+0)-$BK3u^=8<7VT zJPzJ3J=Y_lN+g2xf=C>^K*2*M@_>TJ!P}+f*#Cz&ArYh%;5Y7GLLN}?Ft}U6-J6jI zUSfHm{u*QZe+Yg`C!pK!myrh)JPICHaNic>fi&FO|3mOW8Ufq?S0N85coaOQ;J&TM z1F1RR|3k1fwZPi{Z$lnX@Hlu>!9&}T2U2pr|BpiuNhz@Q|Dheo0}37o4=Z@+736_b zT5oyY?U?%stwpx|Nf+f(qw{@=YDc_4*A?2g0W!xh}O2YEojqu~AO zb9?{qdlh-0z96wZkAfE{xbHRO0R@kOx2wmc{lD*Z6L~nWkT~7{Cpi#<;3i4ng`NhoDtLP@jk1MIKP_IJjHE zL+>FEm^=?){_8p5ejj;22vYDc_$dWRz!B;T;7gtIL0{=oDP#B1Tmzd`_d7eJ*b7X6tr?2}IIYnPSBffmRyi0D+_w;bbNJ+k@r+Ww4OJ6pSpD0^F3OeH5 zLUJd4(MhBu4n9l{(|321^YmpLx!ULH*=WRz_yOG@xqiOqO80eSh0oKsQ4bt)-9$_r zYSfA1G2{#UU(0%tT-(Xhr%_|dN0Si?z<*l@K8ier|GU2C4mPar!cYY^E<$Nu0jiMY1l%%S~kXrSN|s z318~zu60~bUcS^*sC8dQPSDr9btL;TytZ0LM$p#=>&R1hr9rz4jlUuPxy;kueUP;3 zf_K$qFn#$4d7QrNCY$NYCK9JFFOaORc!`kVUD4n{@_+Q*qETTq{$GJ=g2Jn)SXys%!ehQ2j|=Mo$rJ2*!e_#b{oCn2cML*E&}uN6G}y%GFU z!J|JI!H)&U{MU0J_M;JeUkFn0_)kXgpn|*4;AeFd+;`Rp?&6$YcIr70_}K_#=i62ck{F!4?Vw0sNF!V->#$zn+C_Z@K}7 z@JoH?UbG%Nr*t6PJRJN%VIYbhB>Y;zV=eLXS_&R-g`d~zs1Sr(YiM|5Xc-=s!**hT^lBiG^m@IU8PS4u{lHeRMSdfGOw za@e?>I+FKHb-`{zAzP6Ekhml;opYrz8)rS{Up00F;l}BVDwK2f9(cEF9 z$>o^;%6FfxKBX`+6GrF?7c2gJcURf((pgi7_rr7MRA+J zmSSz;s?+Y|#X-l~6>ukF(^N}P0e39QA&qqRj^arQtANWiS?2YEkCQkpfXjIw!N*IS z7Qp5F%5_)q4klQFlc*`1sDR5I2?!&TP=0A7`ERwBcYVU}y(k|B$23=Iur2=4?*z?q zqaqG(OTS$79Nu>mHm0JV5#-uqT6?{tI5rK%qDH_*=lTK25t>I(F%g=YadPRWZ1dn6 z>?&~yFgUBjrKFFu<}KG0Q_XmP-S5y$TI;f_qwaJFCP~F^x5yo!vH0#8End12?03|! zNjLyr3**^76gf?N2QAxtLAF0Z3_zzSkNI)>52J0p^{07}(BSOu3QY~lN7~==$~Ld#LGW|-D~+;8 zuIid?_Trk3R5KF=0HNueR0P){=qwk(l{-LVd7AS$E9Qo+DRvaWmD}sG^EaRfu517> z`=p}?uFP}%b!-}GEi6n^cM+M9I01%}H$Fl{uM@{`|3jnYA1QZ;8n`c5Ck2fbWz=DB zQVm?M`4!jDXtDlo=F0-BB2(B$)}i(pe>A~+m~J6J+DQn?5(2XhH)}L)`H^T(} z*79GlbtR3nbj^fDBY7%N8!1p#>k$~j|eYG87a*|}U}Pz_QKTT>_P>bSat zcb2Q;&X7AmV|h(I%-KF}n5`*Cb==8vd!!cmgb2y)!LmCiJAV5MldUyCJ8;hLQz9}* zs)q#MVNc&F3XZgbXq%rRYv|$_GRfqjfae2ARg1Rl5T2 zSqJYdSHS&_L)HNr%d`4l&WgEVYgW;@bTRl`ZjVeO&+12Vd$8=z$&SDGd{@hJ+5wx@ z55=tInrEW?q+7{;3BC5KNxc&sTQu+oWnJAI++7! zMNr0MnU$i0wN?jA&<2$#_$4wb_y&phviSU7gOf~A|LbD5z5t{Nv;oRwcX6nu_P}1QdS-wf0+-$R< zEC)-jikoeoU(K&$Fc-$tVqaonv&>Fn=m)G2GJdl?Z|yDKWsm=$B#a%XBcb^W9dnIyV$YZJbNNe5 zJ~aLVez`bAwz*k^#)5Uf;1d6@q*A)Lx#OCSRC5rebfNJ`rF2(2xKv8F@LAbD+QvP) zRoDo>H*YTHu$UXBCuLSr8Qm=NY1zO#^1Nr6Ps#1U{*_clH_LoX;%r`Nmebh@n`^ET zp*bmq*pXFU7MicE5c`v=>Uzz)qz)*v(_WT2jx&P}4vb|SU*kw0d!c*HQIY{#XP0@& z^WGz(^KYqxWbsKY`-*48u^+fY-^vm3ntddDe)4%-%jtFnKjeoWw9GE+;!$gX2Zgya z)Evn>fs5@VaqJw{?m#kv9=lB(`yESmAag|@EskA)djm1XGs&)8SY@4b24_EGa^+&W z=Nw!vru!pj<-D!6Fd9qOzpP&7*OCEROjjP*MZ!4`>H@(CyGg8F!%o1q9RzHQ+EpB~ zqPnFYYi*jh7PKiUkrr8D&lJa6pc+&W#_CC~Ahd_OvX3(I!AZ?quvI<;xm-rqz_B_(eO{ju^jG^SN6zjmPq#eVDieGmDK%a+Wq5_oL145 z*CE|?vhH(P_uqeob+}a=%jexYs^*3ydwz2Df3%z{Z{vr`G3c5eyo)kx9X=_{b+*ja zjwYi&3w)b&RB(8UL&ThaGx`FIwu#n?QXV^4Ak`GW87hlk!~wl7<<|d4;9Dy za))~+&*Hh2{2Zd4g0W5=1#Q3Q8ag1h%u5#~)d?=r$`khk-9>->QFzMl?w@FIDydlN zMTwh(e9>S49Q4~AoN7cy{fdZt1s@2514K<2)R^HjM<3fX5t^Y`KWQ{>p&5w<08LF_ z9z1_2_Wi{74Q@y;tl;OS=rS<}?aWJr zxv7>p7SonXf~OigN@nqp^%DANNN}(x^aaj}SzO=sg$qrs^WhP6a2>hpw3b76`Ro*# zj#KqIM26PFMe;i!)xv#``&`Vq9r7&mpcoHlaxL6_oRw2X0w_1zZI>i>M*QEnA7`%2 zWZvbSLAb;roqIPkIlyZqbAB-Eil1DMcsbWl?^%~0ire(I=4-W(n%-LF1pzVh{c| z?x~-1InH;9QE+ykC{dJkMBz9Q1`b&mLdnH*M@a@~&0!XbvsNe`5zdi^gC4K$=hAYR zW3t2=%{Bj)km9rerx7bDps|qGsGTSNPv}=6PssXAS#PI-DbHWftyQoF9rRC~CyIs9 zwOA?8U~ySjY^lU;3lS5}?O=M%3^72?)=Cv_-7A_}XXri#ulpW(;@9V_L*+PxfE;DD zB-!NVm>q;K8`ArGmC$VB{yGZU)=2jKB!({akNF`(beWigcIF?*@9ad`Vwq!eP>DH6 ziYdwr^YuqJ!A!p$c>?x?eoB%amGijX^}NUvyU@Y4bbx#JW^$gG zE}8R#u@l6dTvGKxuA$zuE~PxNOxQnY*=G?vwK^ywNZR~>Jh4`&-a($gZvtB9#{6JO zCb|9x+De@6kG6&IE$mhMCCvFt_FOer?eG^%4=ZU~-kta@~1N>5+6$D#A?;)=dM!&{NfyR#_ zwCpxcDnk1;;TL4i?O@VR*7$kP*;=Uv?WaWK2@1*QxRyR}RMIAMIl&$8!)_iDH`Is4hDhoW_S$?v)b7 zJwlU%l9|x>n-=jKx0Z=Sk;NVLb1uiZxfldz2WHVh@CM1eyVg{WMCHp~2Txpi_B zL&KsVC5q0%IkI&;62*^PS}vqgqR0|b)QQ~)PGeDW7mbB{;@gShQlUqg*sij^sjRp2 zK)Y2JbnC=Joml#NcUBN=0ZkMwg;CUrod=Dd)`_K$0JK(#V7|!*VQ_8-(`)V)1LRCD z6T5Y}NE8&3CvmxYV56jWuG)98X<&&0Wnt6#TO%~63d{U;RD~^-?Bk*OuSgVgCHGmE zi8*Lzz9h``wal?O_yTi~6jM7akln^UGsIA7(ZpiSBFF~K$1H{ez$N16<)b} z`gCz@BzJG9oG83z7s;LfY#P!k>JVVcif4y#ZGQ2 z_INuU;?i=MW94+=r-naE&qg3G%+8OH@-^DUx`A78Jn%S*zb`L!t?L;n`l=`Ul0$5y z5p0jqrsK3~Xln(hRYRL7I4v5gtwcIW*FhYD-!P(dJT%G(o>uTU_%{kpi-w+9p{MU4 z4#9DifiXs~TEXMsM-)7ClM&pnD+F-}URCf=&-WJeWF$gNs2xviv zz}?6L3LXPrs^EdYArGYHyr2UFvr-GJZ`|F3JfPrl@V_f~=w9T3lw7y2c5w(MrW9B_ zG#Pn7!QIrNfeh7I$!QBrd4=8vP{D_n5(&f_kcjN)5K;lvGR~6j%2=ah})1slKgX=D-16nn- z!Xc13ts1&g!D-ddr3y}qhR#ps_-3u_z+=b*$$}(KtA;+I;DPDL0}37kzb}c?Z`R5V z%s?JU5+w5&_#Fx!cpP~^!DHYfWX`@>D?9K6@_;OG+)~BBuT}8COymItkAruUxbD1X z3;jRj0ZHKGaq#vE9(odaK*8hSO>C~$yJ-wPg*;#j>hU=EZ`i`5%L5_Y(w$cDco$dU zHwlh!Rys!*GH^eT5Y*>!@Z$;|3L_6FcpUtQ;Pji7^&FUmJRk%qcpUsy1rN@-J6oOd_1HQS)0}37m|GR?w<{=L- zj`>d&ffxi66$Sz&$O8%<0}m>AU_SBy<#hg2IsieD%D@8T0R@kN7b6)<<|Z`wF3}nDg#T92k?j^?Et_}D>$tx`pvV}{y(Jy z?g;XL!ax}OxPrTvA`d8d82pH?5V)5i4=8vP{8a__l_3u(cobYW6$0P0$O8%<17E4& zf#t{p7B9sjFGZp|Dqn45%d!8TuMh+X@_>TJz@Jd?z;nn03Lbk77mNE8g1`#o0R@kP z-=W~4mB<4M9@illp%8>tArC0Hdo}Waf``Ei6ToK*8PXkOvez48AQ5XZwHmi?|_3BcS{LFnEQ6yVoNRD0morX=-lm z|J@sKLy%g)_Wx1vSqkpkh&-U+QSiT~pp9(W0PK*3|+g(-Mq{~y?lJdi?A#2tu(cT(`s%g6%?9tUq-pWFNY z&=%x@`hvvv++Bq{px|Nf-x>Ko&T77`#Zq-FuM-6g&)GC~>;~Pj=u9-!tQ1CGL6AJD=f;_-D=08;g!Vui2FyMO!c|gIV;CCpv@1Mv6 zl+*c72zfxk!{GWhg~0tW@_>Rz!7CKp_X+ZVg2z6={(mV1#dyj+5&w{i ztK`dZ;8WxQ1&@KxQt-fW3Q zEhMAnqI~kNSsB~Ie>YTh8vg9Cp#B=x;4#Qh!#U>i?$^HGEafl1`U=#*cc7)>i&&9 zxdi=vN4CJP$>;*~KCFZcSqee_67mFny|RS7OkaH^H}{{U z*)mUOx(g{~iNCnFwIIGVf-@GellCYs3`gtn{~5uDRQx+5I9b7I_1j{b>-9Pa|6l}f zvjz3}k4A8ef=7Qcg2NO%cG?K~6CArx=LlnGjNmm1K?;7>2wtV&@t=)gR~7%o2zC^l z?n0do#LpSQwnC7CyX%Z#O9l7+W&|@7Jn*{_baAeyn&ZG9M(|gxX51X4TmymgM({@k z5B+HbYgPP$5v;Mep0b0GD;)epVIYk1xJMN{it4zB6g-CNxceB#{HKaQ9OZF$D-5_% z{kBTMeW-rBQNaTl;b1xCbpBI05JLIe=M)CQsD4|j;J&8e;5-#a^;-j6Pdmpbe>+2A zAcX3-4=H#U)o&*&cofxdix*-SlFk8I{`NM70b2cbjEZ~1!C?v>Z4(aq7h)HZ&Vg7~ zICzc1Ks-Afyh_2{ZNtH?3hrwc4tCTPf*1sCRlI#T*iymcx#3`jg1b9}gSty0@a2Vr zzv2R&E<%C)aPUV34|NO&YZct>3!`$cO3(>;K*4>Tkp~n!a0&8&f`=}>2Z=x-2w#Rg zpy1Ii$O8%<=!!f5PJS$Em_?pn>FJ#Rw|V%I0;|cKg*pgr%tvo^RbF)X0-20V;2J!L ze7VxoPMf-b{I=3lq}{QAT))awqz|WkbVB9O19$Gu$aM9d)Ov71aVJ^;(K0gc9cz|c z#x;@sxO1sFK);XOrV!t7=yn-8q%-LHs&ixk?h2WnTiyB;#5Pm_Lt@d>8P%xLniI1D9#sJf99Z zKLxLsd_LrSv1?-9efa<2!#9#Mt3CH<@gZdV^PUIX?~}vNdvbeBM5v5Lv|JGlUAFnp zW++38|F3-J0x5YTP)FO&t7sN6W)0jMc=tx)eZg~Go2L(5Am?WWDrwBmG%ot}vUe`z z5dQ?NgFd_Y2Y;Xv{+Udf5rr!$*=$Q&tI`A3o?zqEFh{U$jw!(ro5>d1xp)g^7y+xSmwT6w!E^MpBa zufxbBysvD$p!$@;$cJ!*mJSvXxz%AKi1$<8F00OLil{mVV^!YHG7nHAUfalEhminv zj_VsMs#YVvu(ufFmk>nDyx&y>fznipPu3j zE04&7)JAvP#*b(tFV_FH#QYE6Sz3L#dwL^xQX^e#BVRg9yh+uqz2-J<$3>mMcZWrh1ZroK>;TxY6Sf07 z6|9v6Y(3EG)_lGX;p)#Kbgva5#%XnH&i4sERpM<>Dv(b2x@x1#~02uC8-vU`G(L=$0CE4t{eJ=O;-3^S~EL@ZYCU{x_x15y}ueHNaM^-&%xN zu}KRyPiT>3CJXJpMJX4oS7?!IGN5G<(o=*eQwVX&9r~xM_X&;H+Ll(eOK5P~ZG=Wc zo=6q$UvS?@PhSJ4-(={Fv2wI?O?^ENrNJRvu|;wnYp?k{*A!C?YG|_sd%`Zj{j7r@ z(Cqe$W&3C=FW9-Wv45wTt(+TXD>kVBx7U11HZWfH-fK?hjI{^b-pTHmF4$=jcdnB% z78xC(L9(GCWP%;`I#?(|hXj-0(mI(VI1&rxY@Hmk=H9tZo)uah7bBq^wlo;l>t7Ph z`9eG!iRhj5r;;IbbKwAVsn*GKp;>^dCAH;PC%U+Cct8l3z(WX)N0LL`frqk~Gi#m5 zm9f2M8?NzF4XScm>%=bUeUXD7&>HB8OJPH~12mQw%Ad2W^WETvt#u-o^!A!Ra}9HF zX0r3&%k9CocM^{49oVJzzmkBKPh@N1Lu)NG6_HuSLzpJBbr3qjBe+aF{mI0RxbY&{5}muVjEZ*h?(d_T~xfKG}J`3gxcfI4hiJXU0SaYpo6#Z-e4$%!zj99>F&xxL)P!Wec_n z!6r+CXkTM;Rol5%~Ce8$!xdw7kM=ILDPo;?s z6ZZ)H9sIy7yL~UY1GJUTq$@Zp=5}?q(Bf#EsE+S7FOdywlD+qu9b^Mw+bisjspDA^ zcdn0XMPv?G5eCQn-)zr+p%5HQ2$I%EH^JYrI9nf|Saa@NAN_^)eOzuaTBf~im1BMI z`M*ktk0F&FmKTV9f7nH6KE@&v8pry`6PnN9AlEq8N0!ihi8Z7{WE@Bi@jt>=wkzh$ zS|5#)*2n8yr;X(WvYtbO8@AR58cXZrdC7qBPO|gM z<@R9Plgf&F&BYQ&rqz>D?e?d67CR}0n3ffnPOrCx=4&g&#!1 zuwT0S>*zfP8{kR&5DXh3YKzNJ_!~D;j404Dk!&UNbUR--@U1<^+HFrKIr+TM{D3*8 zk^EM6(rex*?6dg?WKM*r6SydFZwGOapE}WkJMpM>woDNnoUuA!tGn2_x~;|ggwUQt zraZ*Ygvpjxcb+!Wg!p$%0mLj-I!1So&|E+SpfS!Qk1m@#Zg55yuw1>oxy^C^kH&KO z^2QvN^TsqXS#d-ru>etY%i#9|(9i-om>&Ehmlc`L!Z{DBv4OM5)UI)y_f}+jJIPJk;SuS;8 zfY}Q+%UmHl2*wt5lnze(Yyp1oM`~Y_W1at{K7MMwB0A5tJ=E|akbM3h5}JJOprd;F z45}2V>pbsqQQ!L@sI-&1^ zHH4{Q`WeZ3dX@?Ob3)%8_Vu^rG1E|LNI;|g+wZV=A(#0X%7jriAjX(RMkq3??b3B9X? z>g_7oa)`!=2K~{&KT=0%sL%{RgrG5cCP(NTPHncgHNypMl=|T z5TR46!Slh&q(z5Xa$KJw^dr&1TULZlcx+CefL_3kik%NzZ2yteuA#f=|L~75XvqRkKWt*>C&gpxMvFS(fz8Jwc zK7z5ybF51p7+}naD0R}liay3Qbb$1iF63!iHM=Db(Riza+5zN^S3NoHc$7DZ{wJUm zDB1&m4=g5ajlh%8`hb{(wuwoildxQ9?nNO`XpHfE5>D8YFqpeo%(?9T^}>D5)@n^7 zx;T^jit%&E#_vPnZ)p;)lngj0VXSa&YWe}(BQ(?a0Hy}yU%~O3*-{4v>ZV&OL9RaT zHJfn_9U=Yw3g*a%)@mpe9Xw)nz?Oc^qTpe9>Emxz#nLaD4P$IwPj}bV?&s&qzQv9P zd5H#nLIu6=?bCIQE(U<q!S)41gE1D+Gm482FWfZ^81@b)oi^F2h zX78sFu&#UWab|GFA{0-arhiE7S#-{dbEU2M4fa%Qz_YCZTrSRDdM(?<88za7<)P%19vNUV4xAK zgL`S)ga0(k`ZJxB4g>}n!BZ*&;Bf^H3^szFDtHY1gIS10Iu8RwjNoCF0q~fD2ZkEK zJqjKJ->NGF0X$EtRPY#hRKWwojo=CekAdqEg&;7(2$m>#96YSxp^--LaRrZ$#K-&( zD+IJ6{6)8gsPAgL0uHf+-@nwOV6oSwwBRE{a$Df=9tWP0Q(*1#U$mNGrgX1;7t0xNjWtfPzQC_oUz-MZQZ?m`|&DX=)LNI6`=X+_F_g42SO{ZetAUv6nd z%BxceIHwgU3luyMLLN}?7 z0=NTrBM;OUBsi@|c}l@UxV4EZcpUuGdK~jF90=WmJWx+yb6Sz|u!7Tyl=MlAV}uF& z?#ajlPOeM0Tww^dIt3DUPeC3~@Gy8(!F~534>-7@@uC>ADu}f2&l0`f#fDa-{K*#7DFvq$DdP$rcnoUtlCfPRfST_y|7L>^FZ zT9GoW;Its+;}+Lb-f*~|L>^EW2!l^i@OaL}g&_qGKZQKNIOac91blQ~pfC^xAFkj& z19?Efqu~80r}LlEfiUub$^dwQg8OD64=8vPydAinZjJ-9kp~n8V&Ity9+-nXpx`m^ zx~H)JPwT+b$OCwUk&ef}Pbqld8RP*4kAZ*sl)}T%T;u_TfjIbK1rNSe!J`W9UV#1o3WXpHK}5lQ3y}vDJPICGaNi>A{~uQfqKl9R6x_EM zc|gIV;2{O~Ex~zwyFw6Mf;^z$fl}lF1&@IT6g;3ukO&ll82Hr+9$1Pzpx`lZpMvXw zWk>`HK@7Z=f``hG2NXOG?oQA3Na$H4f+y3T=W+0#6g;#Xc|gJA;PJE^`~MI@B1kL1 zufKtRpy1)>kOvgpy#je49jE*MFa&$j3BcVekp~n!3SOz;zE#KrX*k>eMhAO%nC z|Kkv}OCdam(Q3%Ist|8ykV`FEKKk2c-RM(f>mG9}+s2}Bh$l`nyc({B9S@|(^ z`7_9SA4AuQvR>rMj$jRDkZV8j6uQrm2R`xiZFFinP$78_2qh*y{lwD~-`{KYDPH!I z0A3os0zvUrOsDk@42$kB8smh*LOm9`gAhtxTmnu-zmR>JhcG) zZGW@Of1cd(Z#ecNDWNYX$zJ;M5&4O}94423?&*uV4tIWzq7Bc@AoD->bfUXC>&zU} zpPe|g3TNw?EV(A1xq@#*B^DL0G=iFf`%F|~c_Lw7w^IY}z_$sNSZqOk{t_y&C^)TQ zc|yTyjmqN*jxXIiBS33VRwo20coizKC^#)4xnIS%p%RPW^h@_n2WSb%Z92jaU>iA7~#H!86xxcgNjI7`J}Lq#Tw>!}yn>!`@2FyPyZ zicAU~cmoxg6g>1MDl##S`A-#r@IF*zQW%KF{y$}39$(|}{ePc%=6UYTBD?Il*+d8; zf*`geh&_n4mI!LEtu$JcpjD+MS8>$VP>R$NOMBH4LMd7rTB^1t)>s?6Sd!m+?sFqo z+E0J4?;rOy+nFb~}gLsiil#B8IHv*(Xc#-Kp5Ck8_ zi%kDf9{&?wX8Vuw0Y~s66UxPE?q3NIujje_2ZB|{pa=e=yx?c(f&VC<{tNWL2c;Bx zSq^5Czox{?a){^e$S8D<`{5xzNi;BB{mhyDpLP9!re2nPVvE40B21McU8dfY@T1-| z=!n4-tfVKOK_#0dU&iZlaS(#?6Lj*jT(@5xXm|mpE5rq^7CO_>G^kU2>eyAMTlg65 zS;~UMy`9Qg2P|ckv#J2KgzHq|`}HfRBjB&%h~HR-D;@C2|DFb1!CelIvg|!t_C}x? zpv`n91h+UOKtLd7V#Ao!DY+X~6S{6@lYLZ{ao0)#2j#uRtt|vru;QC`duC;;- z*J%|x3oDmW$m)9ry@G(nUzgnUXw$EeiQwNcv$+gL)@mQoaKu=LF^Rp zo?Jd;9?_!II;AvP^6X86);O33IHf0-0_vf&@!6}%(uP;yyb!dcGzz&ccl3R;QWHnh zpx?!71U}LE^yzguwLabU~4@jR=^4*OCqf?2MCi^~y+p&8E~!7NZzUJ_)LQi6~eXHLB)k~ZC2%dinu9PmA;`aH<5dsKE5f}a65p`r#hh17}Ov~-Hw&- z(Se)rJcQe{-%(fpDe}?rY#kWfup(pSa>gz~oADqbc(w~@)0yf3R?xoFLAOI(pAmh) zy)}Hh?45NPW#Tme9e5)0Q_vPB`i==qXA$kvnJzTwmK>y+pV#dE%*n#;0-yBc^Qcia z94*kQMXE)4Ll@I3-}L0)Y|1OvAK;&!{PVw+_l>pSpYEBSe9%%}Zho`|1VEL>rd0sg z{T~Q|z0#An+myd1P}CpR*c6ZQZ~s^Mdf-R-*P^_i7*zaT_rOYFyf*~y-w+56ECdIP z>B(Q%l)tWTbVrWhS1~3Ox0QKN=R2}K>donv>0;66(}U8J zhXAke`PWy{WxSd!Z+LZ3XEFqP(kFN1km{Rs_YDJdrnaS}-O5Jib=xi7OoMo!DK|7d zIcXxDx+7O*ebeYULTMWX-<3lezu8v-FKk4W^yC`<))#BJ6qcSGI+3Q{l?P3Oh(461 ztR~j^V445FH@1kQnEy-1L*c`r4*uQVk{1IwVOvg1x*ZnL{jmx1wRcj)g{u(2i!`@% z*~Ro~a>9m3o#HpV?0Inge!2gdvMyqLGlT$EN@&;wYAM{58=RhegGSwx>$0~qY4trh zf;CU06ZhomuN^8)pltY>1O6L=B-g-TY1}YL*R3tay}GMxs`kP9ouVOKFL#pxmq~R} zprv75%LtPo!cfoEHE@wM&fsUMlU;pl6HA>pV0SjOz{c4_qIJ)zTN8*cv5B{|iSMaa z4%5vhel@&2e}YZCicNe+)pD3rn>a^&nw4$3?67j6zBX}hoA|~m!%cmiRPn z>~uB->jTPxdfCJu`IqN^WD{>_6EE^Bhsm^wx3r1tY~oX<`Ic93v59B$MAoA~eU<@q1k#9uZj z&wtw{{!2`Genx%Mw6b}tE2>vsFw7?YsBU?FRGsqp5}Wwjjmq<<*ud*-;vYqq!z_s^ zi{mZ*qS|GNJl#7s@xsXR{Ju8v{k6*T+t|d<)-2EOU=z=-QJ&w>CVoWdi^`hT()rs^ z7ZpP@AIjI+)@C&FksKgBqE8>mJ*7)j@CX|cdF1mL?{)r2Z6C}1rH!=VvD}r>cq(}; zw__iTH@ABtyUA?XcuFaj>-T|1scb56)0tzfXn8cYdA2GgJ& zcBc5&>B-J;A8hn#p02Fi+uk$)<@yP9uUJlD{l`<%b2-5+33$ajOTx*1)ak(bcH?RF zb74}((Xr=p5_1_xzAxmkR^@g~AUs>yG$_i`G`&)K@C)vzt9ZLXZ?>84XBy<;ZxY8o@xb|Cy{SG< z>y016GB(39Yit&HV420yL+y7dN#gMx@(N``MD=m(4O3#Vk$t^PnOK~}c*GUQxLfUJ zXFu3Y_pD*6ZecGVeGBd)sXABh{(h!LW;;4BaT6Oennp7|u0vh~AgYh^GPP3zO@Web zT)gz@(j+U!9(GoY6EuvTz_)*c+7k;W z(3u@P%#UhtUS(P~9H?wq=xmEb)$=tC+T&vq|A075V}+$0tSB!BD}=X@igK_t!zv)z z6(zgPSdFEz2%q)ev*Afk3ElzQAe^E{@Iq#Xh?O#(;M~VQ+rrM1|6pf!a9=Ny72d`% z8*It8vW0po{6n^A6rEA{3^rjD^;UTgmNJUAsXT#o97Ru5K9$uPMQM6Ika>)vb9&wb z&$QMt@WejyZfEZ3Q05sKy6Z*bML*U~()HdyP4Rc`EPde?zhZ}1P~pICuDKv?K(d?}{1 zs8H63!9O!8WHg;Z<=X$KJjPmi0K!+3_d(fMD`S1*IGQ3Hd2r-ED)q5e>i92}p3w)6 zJmjCOYHh94h~g{pAUf^HqZ_|DP&TSE_TL6llv`D0^cecykq6R%O8>y}KGxbo;kLo+ zc>jh)lnX2} z^(*LBnMl2!f}(tlqiF!j&!hamrr1G@y5RYDqcmE)th99e7h3j^kMlohd5LWTK});z zF=>7b}!2- zbT)+`Pw=A(!mbzxOWj9KCV!-Vldb8OE+%hLUY73WYVr`}%u=3_aKzQ*BFeRN^NfUs zZYDic7FULytakWo>U#*fs-xh_IcE}DV7WLQ-8M_!OgZ__HQ zsaj*)|50vZ)0@9TPCon+8#&y3&j&3_kLhDS-kkXiqr-kYgiRPqxBPfS;=j=_48tXO z+Z$o&Oz9+yNXDa194|-evV#46Eepn1lNIbsN!Vz@{2xiZ{rLgCfD>9gG=SF+GPKlX z3(aDfUejcF^_M|xVqvE=M&uh-MVQDXh}WBDNdZEj&d0-)b%%>RHC=>|nl`UW>*)Zk z%ZxB}#`ABPcq>ykJF!?o-T_#nVB{z4uWEWe4AWA;rPnn5jryYQ`O;D^fwL_CFHY_K0sleXPd4Q3`5)vRu#z_f+!UV~^BOoE3<}{bJuU*k@??)CbkEu}7=Gx> zAnxxt&ZZ&C4B?@u@?!|^>ylIfCq;$wKooWk<=8B-;v*}*0fXtAP;O*lL(GRm`BF(R zF{4aw@#<@g@UAU+kXv0YHe>OcsaQQhx-x{+H5&>7ODs&q?ni{FA09RYQ}e9Snz0%^ zDw9?{V9V;gMEqtsGcCB}p}06EMD^s`Z|(s9CsBAAuOd-C6^Ls1A4FXSC(4NWV<;|; zRix^Yl~o)6FGNlMCsB_C9ve=%{~J-$tP^{$4OQFzg;hUTiTcD!l;Ds>$#)u_|-Kn&O7xD=iYt3ENdN5^U(S&F;JT7_&>L@?afx` z*Ki)-G})$su|w&3IFF9E46>DcL3$b4LINw2{@I&IEu_a%zi{s5)ZGSkyP>q88r+}% z3+f?nqNdVnptrUS(kesE5!LzMQX~8WLgsee$pSq-EtTbn&KL@DcoTx-mxKxBW$lnJ z;7Ut%8%mvZ#cVJo*Wj_N?%Oo41~)p-98^mCM$~I)sTWs`cGrO0KYK96*5tm;hNE&} zXk4Qae7W0`Q%%@#&!iJln z@&*bD;@;G<4*$_*;Xtin=+8V$Bi_-x*Bi)6d$LAl$c~J#MHUZa+=^^RG;bsQL9e2D z1kN%mkk|o@yg9%c`H9HS+%BCgou+Ikt*a|8p#gRIG-ez~&zoU6Dnbh@-Rku)$2!^bjNe4 zQ+-}Fz#>>$ySo6RwX5Gy+Co?S?m${lAAgnUlHX(2&=1I*S4w&Sk~INEtwh4S84AsRk`;$m_87z~2z=-Z84v zh`&<@ToU5H6|GshlP9PW(?U#xZ;@}I(klLgP`eS2VT)2pjpat^8imF3PPGaECIonx zRd_EVji-B~1#^zv*Eg6CVK2a8SAM6s;=8m8RitxtKbAL;exd4(`NAkG8P)#>8KD)( zI8S#Q^9HPvMulI${-yNQ$i|jI5_9Sbz8A;m+*t|xYf%3tylPFL7d;XO0iw5$0dK^d zt8Rz$GRZL42jd7s9wB&ki?%l5oyAC%)%XL@qGp+d%ugj_Qywerr?;B&KxY>emyU?h zB;;%aebSV-a&r(2X%XLO7~CB3owq)fE;Z%vdd>jwvlpdaft7UQf=f!fsivUW`EjQ9D;1&5a77A2o6DBnL{uW zux0h$hs1S$S&nBt%5;lf9$jg{yE8)y#kS-TY;cNsNJ}0gNn2<|E51yc zErL+$o5&k6pZY|Jyfe=h8sl~%-;dbET-wr_S9glQ-cEJ=s^J$tmaezvx0Hb?rCzt` zbQ}H~tC>PsZTUP)Gwt|jVN)U;7F&J+i*+LxY7%h}+D)yb~|zuB}Y>J-ZHjoOq#a%#jCHxlVV)~W6lS6ttM zGce-SR1WTWAFofqiLeM;;>Wq*Wccmz|3RgL~FF%I(NU zy3g%nQJ&dQp4rtO*EH!0a;bR|pU%dPrUOZQrIbShI`M{{7wWtw8fWer(PwMYmQH+= zR7(9i^KjO&H_htI-(_)q=y_)zGOz(qt1#ue8VY4mOO zD}95zP+4Aj-NGP{0p*`<*-p!-ZA$QtG7Z{a#}uE0e>boUyUtVza9DSmRxF^YU3j$b zrMJLm;CHd&uO@g0{EmI-SQl=zmu$^5WW)PhpV5gQt?UYcp7s{ybmg_#ooM>ID-UBI^d`@4{4lzI zu^VhycyCJS&SR3dn7~m~75MW*CDSTN`@g{|HhJ;LTMM{An>?WaGm+9^?#63c3zv5yk^v{urPHJhrC8?K z_onEc&|Hn*qR~BJ^5*t>t+_H1_D9pQp0KqGqv_|Ke6YLyzckXK7w^K}dW#nK;-MbG z-rF>G6%F2?yq4?cf=o~b?MFbx$Z*U!cgdYVF2-D%J&r9hu4m*mVtqW=Bg^fgE~_c zgkjK7iP$6wMc5Ld*yu?>7(bGx_Tj#4NiSO3hez1gMxNLSuQifR^x>ZD<6d;V4-c`Q zf~JJ|aDLERjs#frQ(G z`3_zb{Ei=eJ%o?K|J1n-#in|@?i4+gC$fg!Y0^-h#Hw_sV?+4@HmwJx48sawl%-9N ztiW!xc^IF>I`p83;oR4|R(CMxfToF4L*k07BR#=0u9#c~!Lyz)oHt}OdeG+Kuy`Ro z=+toDn>qBL$PqlU)?eMUC1KePy0Dn%x|N^Ci51%=z=*wq3-sv-ZuBfN^z*`Lpm3rj z45=ZDVR(O~y(3_I=5(b6BjFWR=|(wAm}f{@R}78pIamAF6_2cUk?!9|cRy99>z0rE zLsPpEdxyvJyK}K*i5kIcM)vs^f_hXSsJE4%UfpQvJG_x&k-b;~;RLGPI4}C^9q7NN z-AEn9Q{2LAYKnu!;BJ&Q3T%k#PD@8|qgxelRCHN_;tj4=$uy-K9UH}~dR_;eLUzOm z&jk)4W=E50-byx)-S1AuuULXuMUCcvNLjRX4EOV%iy9T>VOCfCUCh}byc#)<jla9Z=tdwm}Eigj_d5&P_zTIMO-Lq0&n6m z2-&vG>zNF`ixS^X){3nvK(tM!GZT1-8VAVc$y73duV#_mX!UzIqN~)6s-{7m{zV_A z@!GDxp)FhFziQbBD`fAZS82l0=t5N|!nb3|lspk8qiz?PHxUMUW@p+wktYYdoL%0l z@jxL&<^xOUk=25v3A{FSc%Og9Qj_W2`J`HdYz}wCt)XjP-i+ZiJxh^3Dqikh#8$VR`>2CLeH!hF#WdYdBXcx z2CiCXPhN1F7}G<#JDG=j_e0gPkz*E$JhI||=Jkj<(%Vyb6P^T0sMi$UkSN6I%MbZdzA*`?g63d*WBF7*MOe1VD-?X-DMOOrmxl^F+P` z&y!NdBi3IEK^8yLjM?SzGOfWq+TNcOXNqEm0c zP15P=2_6mYNGY>8XBy+-Ne2yedruZ*#aW?1+?m|sAaTjTYmN9m)VxX~`xQFtmQCgTv_lGI&w0skH zWVel!wFzzRx8%DX;_iz#b8k63RHFIGN-NjB$S;r+Hfah_w`nDvG;u$+%}Db$^B%6t zD-?f7(-&Z_UJoJT79K(`=R-N)4kM=wXsk+B;=&Yvxvf#6=3z=O>tm#EGI%sgGSayW z&=G2(BiIM@MVYv_GABgPJK#3tCKYLUYKTO?hN!LFJSw#OIDjJOb6?4h?wWWFRuVwI z3wRIr!hkpFKN^6B!<8^O8i>ZIswaIIt~krpkScXnL+Qx^?!;<^(Y$TEb|u`;DZ9Ga zDU42h&V9w-&UwQPLX$SakJ<4BZ^=4TrRQJ3Uu#m8VizK; zS(PR&9JrH5LFbeq+VY4tw7U7g2njylmL9|VTZwJw35%vlqx1|U>1W|$r@aQZ>7|dAD~YrkV1BCd1$qu9w}P zoeQDMtHGWVA>{To!UG|cAj0oM=v@(Jh0tmdt_-15B3uwcYz@L$ArvjbNg*_F4d@&d zLW@OuKnNWc>24wPT%;ESP{dk*hZcR2d~Q(UPIGVzlgX$tvJB- znx-;%y`iZfa2q!9=E~omBKx(X>fxs;Dz`hxw^dZfJuUix6?j@SmHW>X$~SsyiU5+} zdVq(~)NR}eZGeczQWK4qa1G{5@1A|Mf5vced~E>46M}AmYqOa`KShBkb?zayR z`X-i*LbwHD_)TSU+Rj^1=z8udS~So*+o4ED8pSw3wvCh{!uCcg*^W8a3&@%`P-@YH z9lRzRVYC^76jX6lf@rjl;>41nv~OeNqbpOp?|5&?kJf@DHr}7^eTUW;`BO7TB}O_) z_jmJZ=1;!|x$Hs!oigKm`CSicw-fR>*n_6-MBA|*=A4~S>MX^Zp8vpyNG&OMFAs7J z+21r@PH&o86`?-8X+v*Ilh{q)ngf}-vkRvOW-Z=kH?Jo-(}%lxW4R7Sag2*vUmoR- z;T)_~C7(UmTuE`KrF+n57k4_b2mCftt-bsU{thIAQg8DB`oK+fW~pBEU@xTWZ#U|Z z1L->JM%!}0_$Zow01`FI4$~oJm|`y_YZ;%H!hp?lqtW~LB&joX$>o))WFL=^`@3P1 z-&caE!+!WsWBsIsi!zj!?w#G& zg)8kszT_kXt*+FMRviXe9bMGQa9lywG?CFj-tB7X`f#dpkY}N0*av|ekbhJBlISPyykK+`3qKG%(+g-q-qG3u9JLEzo zhj|KH;6f=sL4g!|(7d0pe)|*ys5H>1PqQOkO`pZ~pWsCIvg?OvjG#m2AGVdBo4$Q(}AEX~r*nDQoIX#^V^L zs?Id&IK+1r!)-~`t15#F@)1bXqU6G7~Z#W_#oK}g%5 zq}i{2S8#syC5eSC_oKM8a1I;U!5O-z#M84~ z%1+vIjbCNC1~Grm(EB&|GieyrxdVJ36#`!uEuLQpc5ZOi^zYBk77eKA4bsANx}Oav zH1j5RlzeE@P0U7vG%+uY?S4NdxvdqAwqm z$m(fy=gkz-_#RFd+S5l$pR?+g242q`QhnJpWv9)TuEBEerB&{1vuCiJF?={ z=V1eN#hEkzXi_*xGF@(=Go?nRH>IGCinq%;Ko{a4riP8irKFjMn$Vgjye9qrgjZ>t zFNYfo@G}gy>l(O7H*OGCb?b4?BAMd$4!EV;JDbJ*U@041UZxumw>R~kj>bI2-oOJL z&40=xoKCf9)b4{ox3-d9#PCxxb$SezTz<;E7!og@@|en}TkPUj3@0GaEaM#LdMOm{`%IXPs*B!H z3~Z5u@MwI6QS=@I)VAiMGt$+{OrcbTd?aO}Yg`4OU|J=CdvOkQOj6oOpVD*{G>qE9 zD?0?f7UgfPxl9RU*Cm?Almu2J(J7`xvnvv*GQu+wR{jW&N;F!8dn8&d!YvZ6xGRZl zh9rE_MEQz>X;E3NCI5lQ{M%6X-*K$=enx7aNL>@DeMn79RKm#d3OC5xk(%2HW%aLc zXTDCs;OE^@+Q27Vr6_%*FcG+ui>lOgC$9-aj@?JWt?ak$M&!7y%uD0ZemZ#dm z_FfQiO#wnt<=QFJSaB(BzNgG{D=O7l#=mUwezKI3{#F*a|5PD=eW{K)EJ@b%-&N}32CjKHgOSIz_*iG99t%@7#oJo7C|-GH2_`Iq`}a6oakl7Q z`Ez86W?6a(Ir*!;^iCzkn~g8g8gC;?IYtYsk3j0|1S#EsZ4p-`lC5B38b&e`(`X3S z+BLX=1{V=;4SSI5sYKIPMT(s?N5nNYvY%ejJmG}G|HzX+eWjy)JK<~wc_=^PTa!0g z+Tj&F@lc+-R;!S2N0O(qPfp?RZHkmAntM^PW9i&tuKDhlx`pKO6L7xer5t2~6f$}% z%~)53QoJGU174Cb6WuAUp z{z@|I#A&p@(!*_hh4OAM=!`#z9>v90PZf#{zzSmzc)bnUJ53}mF>O8JOM3&9p^*JB zqcTWh=1+}KXKeCw`X)#j&00Pu&tQo3O4=F<9Xl^rN#viDfIq2wd1dq6VCA5M;X>JX zwyc<{R#AGhkBVtV6(tdppBt{!poSUP=qeF$e+r0F^z=>!PP<~MX_yi!cPQ4;x(r@N zZjQ+L4Bk}nDAr*CS-!(G86#)2!^FnCq7xx%qPqe(+ev!;nT~4D=RWdtME*AM>hj-+ z_$}bw-Tr*`Cg`qb)GS=7%0ge!XjS#HY%yVOejcvW#To{LHkRTvdVQ)XfqXKmTg9Q8 zvWyLVMo+3KCosf^s-r?xDi(nc)rwGdvs+K;Rs=NN#iwMfp}foXKcxjVpz*#y+A1^i z*|`@qr>62f+xUX+wNe6IXZ!@4zMx6!j3WrYXp;GYjEPE+%h4wJb+J^NajZ#xgY>2g zU(o7W%2GD!1vQIA3#l*Y-AH91YYhQPRNAo%Pbj1|xPRygO|6X<14?Lgky1yK?B+dqCpvge@nI0n&QXdZ`}_%|L;+d)6Iu|ZJmA$(PC-6!>(|y%oca9cVxYxJ4$i1E zoB5np)>q*|MPpVxcudEl(cbyTl*819lu{SUt}b!|-vxSw~nm=@GiQX+-{*mh9cTGDZw*5h7vW(ypn%YhNAW;WfF zRYJb?l{DA53h=OC^iX>?uq-`~DOtH*KlbK?=^#HkJFZc}U>>>sSS z(1jS-foqSbBnFdZ*CT4yKzUaPbOWWe+c%Hiq~?=HbRu32r#cOl=4|#O%8JLtd$$5m zSKz9Oodb_XN)-QAh)$5562-D#P|jVDathOX{#9H;bACjZij-KY601~UPajgseIl)Bs*r1f(v=Ugh^QU>fzJ~Z2R5vjB8Mrp=_nHN z94L`rKj%JT8@QU?!TaEYy1%J`x@?CB*15gn&lWzX-YsD9)1K3*7NBd$b8>5mu*Y*s z7GdIZT7XdO3bj<4qkpcgKoJOQ1#{WyIn8UOq)3n-B&8Y@kcc3VI*P!ZJ`{nTHX&dy zinUpJu81O9gJB1YXjW^?O222CL^g$P0;PW1683{4y63J|rD1L0wzQy=ZJ}wC{FDfm zTtt`JfX~B)Kzh)M{k*Pg+oCtQ7C|4jRl3SgfN_k!(%sFsLivloDNvYrP7TRHl>N6+gK; z@K|h?5fO{cGE@M(c}KHZ$@j}`7He~#=7lSv^tgxO%sM_2<5>f1uPJ`@u|rdq?4#w-k&Vb|mVg<9XJW;NA?&JI%=veZIy8xEAq?o*H9kh^My zqQ6F3GhCVCJmHRR;j77Qv7l_Tp>!srF}b{vn|!->%CT`+bQ1NQk<>aAD9%|7pA+OZ_0 zKEQkky-H56looXH1Lbet7Ts9<2lko%x<-EaBDDp&C~28uWFG>0nNq{tZwmO!N-mq1P6fa5-|3nI(>+t^WbT}<%$E49>uBf< zuWY_QUC~SIdI3G3f#!ZK5aXXHh0}_eAieEPO?KF<0y8?Eq-WdyGN;T{5>&BfGihr! z6Z-D504t6UuW3STFNC;!|KzJ{*8ZQrD7Y75zOX>qBeRkVv~)50|JwyYT#VU;lxK`j z%GVemmJv&pKCJjWZC(nQ?s5g*#z|ho)enE6U5 z@m6M>6X`BUFW!b^nk6}16h|S=Mx3K|+mu9i9je(nlLe=>6#{#FnsTFOBzJE`%&F{uhNFz-VX<(=rESmOZP%WtT~6~ zw&C>ej7S|8DHs4*{>`FjAY&-myT-f&LQ<`nppAxnmtI-44#29i$Gw?4@zBw`%Ptvvn zQ0_NQY6kvfh4O7Dg@I4x?hpate}~hr2eFCZtu-4Yt3mKGE#yS~2)mwkl9GN@=CIKx z>D-T4RKInSA`ig}jHFSAuwOI%G~GL-;6^#*LtEZ+ntm9X<+@)FEi%i`qp361cmUzI6rc9~b4RY+!k|4K0zlo(!M>5$k*nMfz|LGh6bpg2{FSGfp^cb>9Y-JU}N zUV!9D$1f_=aIVtv5=0+kbV>P2&OL@%zn9miUVkYqahkm1FX$^w<-e45?2}`ZmM>hE zV{|GX<9Gy*5Q4$8cY(pTL|hw3IUG3PI>pm31K z*loC`tb=b{>$Xyxw>b{*e^bj%NV%p z5RSiHo^_~3GsVbT9w{TC#}SIX2@={Kq0tD1xxNV!YSU>Egpl1W1eK}jE#+^P^OMC; zVE?rr2oswrBB(@rMIg~#1nlw8WV{0dc9Vktg02~GM=`UMpUC$vXlnfvrQHQhU!BmF z$+;)2l2~$>BJU|v*`>qUp6ThsZ}R*5!`hzd#tQkLAGYk7j-Y-;inH{PPCf;XFM8s3 zkl0R?E0^I8+EIA)3Gg-Yu7EZEd z5CE87HvcH)+=l8t{TMy~r0AYVC{K`>c$7S!z*X_2aZjM73V);rNV1bZ3V%6~RsTh- zjH4=*OImx(HmvY`#c@+0oAo0(J%h6Q>_-~-44Wm*kJIL7*zxQ4BN>Z9SLYuoxmX#( z{C?Dy?uErlO+Habhmbg`{~UY`rdH3DK|ERH_T7S|ec};1_Z&X+>4Vhl1-3PF4#II$ zlm@it^aS{z#X;HB~fOFSt2*j;YX2j3iI_k(o8K{e8|S4y_q z^8;@dog=b16oJZ z4lLTG4iQH#9EZJ&p7C(L8sn{X^HWK6mKQ^q_KCy8rOy>7K1URa-tws;X1UMf%G6Fc zfE>WoKGI`~x5I&P9#iW{9Vu9^f)G0hp2LqYL1RQl1NLpMSn-F`@nAq^?BNFXT`uLw zplW?CJ&@HD_FgVc^;bja{SdVZJ9CIuhNzMJn2;t*g9Th|@A_7*?hOwIo2rW1m?h>? zN+`DC7b>cY)R@*P>O{AI3ZNzX#jZdzHsFw0PgZ3;57A;(O@hZ6Y_Iw)*26+hv_#2b zA-C@r!!(0!+E17CpfYnmxf#@E(t9L1U`KGQLG8tl{RrYLyM;%mWAiXaB*kVp>$aZ~ z?9|>;Q(9rCwq}cd(yWd7C+i%4v`-+fN>l9BkJ!bf0zY{w(LswR?X^pY7Vc zE2K~CINt=Etv`7z$GYQu2@%Wc{WnA`tM|PXKv(8yt9SiDo7MZP161OyM&kq?gf@nj zE~D2^P6Z+uoK|!PU0?%q$lg^=V=Z%NhAWtkV(Ev&)sHgVF~VK7c+_7!h|Sw8Br-u>vR6mHF&ya3 z-Ah9})JXR8VZ!8zX7BE$V;*WU>$jJTmDNNRwO0sepk=}^Q!Z_;4B(G*>5>RP$R#IF zgrjn)nWvh_`#}7tb7!RuE80V+Jk{Rp&pj0Br6z)&U_Z4M9Zpo8Ko88Jn%&w2+=~X~&AZ`=i$kncyTu_^BrAZnq-dyYlx zu(mmt3E=kE4{y@6{|9QOsL_hpk@ul~p=vnx{5}pR!HGk1Wpzt(cXjny2fMs>wOSOvZ4EcGP8?U8bw8CA;i)TU&|R*_1j%{h4PQ z-fBVpr>dTQwG#1|u&!8qL?XVP>i!DP2jgvIQI%3>s$Kxy(3(1ZuU0nipQ_f8?AB^{ zMxLZgbJZM=BQNo#9MdWo0$LP*Dk?7jSoH%*?`gRIK~mnwYJ15syWJ`)s&NVQ*Iae4 z`RXU?LPrh^88l^~+Qb7yWEdK?wDd~>fg)}GWuY1>IcG}+_yA2dKFgF-p85YmC5zMu zw)ZGSELQ6{>e1$)!6*X7QZ@+K%3gCTyj zpH#=lZbwTfNY(Ag|5|6VV0~t9D#W)Jm+_?Ehrggq!E4VbTZLAqAH{8cH6iwGbU4R` z3cRHA1BN$iCnbMZ1A*|zZTDnB7g-?!~I?&Hc)F|(4-RBM_C%oPs zhpzzk9Sq!gBmr+ANwvuROSKVe`78WGgH9r(dg^0sbY%9>Vz#@Xl-0FL;q5ERnul zrUnpStM&x+R?L8ZgPyQf{lu|IOrMcxYviaF*xVdPlx0R0v4}Ry@HDjqad)j z15+5PkynU0BuWk4TNMvSXl}Sp{np+t@64%0+@8Tqyt7puFX8)>)a|O5PoCjui{e5r zRBxaD!%Ym%a7oty)$=F=#eiDBT@7Nd4w{c`S3@MW1n%z+wGq!VtWBiAz3N-^(Rb<= zVA%>H$|ka%Hjyn@I()A#lk*IR$hcSSZEk5+|29b3RBylf6{gysTBY^!S3ApQKPqLL z@9bCSGb!6V<)EsU0CzV*LoRx#yhe^0`=dG$Q@v74`YK0lOR0y{W&YWQ;D040+wemo zZP}-$(dUO@tg_9^538N+IoiuG7v;gUaxg1{s-04wSu&~0Z|eKxa!6HZ)oVBfCKQiA*sc+!JW#Qp`MWyb0b^-r)n}A!fJ}S2^UO&_C zS(zTJ0mPWL^(=@xCgAS8-!q{f!))?t&t@Gnc;>5g^T@ zzC}>h5IaqH|52P#gayOC9rVpZoSi)@f)j4oPR9FifF5qcf=!*b_<`zge`K3bfpNv{ zz9;*~aE1o_t^Ps&4^@Z%XgKcS|G#0?(r|CqX&bReXfxK*W|qCPwLQ~!qP>Ca_iZ%# zu{whNxs}d6R%6+*tymMPvBuq7q4~jiog|w!$o-z(f_V&~6u8E0C8uKGNZm>~PZ4(6O3$AHuF+QN{S0u51umAZK2!0us}=ZFwg!AJ zTLAk~W-(;rOg3FF2Gy&!QqoJc8NL4;8el^`$)?ROK||$inyTnynQ8&vMftDPChW)-4fu;}4SjYA&@bCUr%F)cvn}LQ zs>b5>m-GT|*WglMZ*Hw%uT@y|yFQ4yZP8kgw`eUq+APRaeGqHF|;+;4j@|!4I*mBk3Ds$7YnI z-%S%#eG}>HMe+KsY_t`+r5?~}R_LJ?Xx3{JmRTUiS3u&cvI4GePQ&a#%Uz0BfbJ4~ zD1u+fBm?Undtf!uR#lHL6CCt0EM*hksL_W|6KA~#R#N(gY~V)v-a#MDx^JWt&U(+q zj{15m0dXfi9{T`vC4CI-bkxT&*Nybt5gcb4Aa$q&$iKhUAon1%l0J>)e5(O%K|Zk2 z5+?vHw*n2f0L4&eXP_Hth3spAY{%MKfjq51%UwX6@3$Ipm8|H3T=n(vQUCNx`u6N6 z5lpapF|KAPJ2=sU1m>uIqMhUJg-TH#u2VP9Vqu3b-Az9?K^Eljl(PGzac%KVY`N4~u^|Ll572|)hYb#y5}pC}!s0v~;Aws1X-HiEFl>*%@>*&k`y z$?K_E9erKe5U6j#x~-#ofhbGR%3Rjd)FAx~=DdzrFerNYjfGr%`P|eGRgMIM+GF2f zS%H4;(#qKEby!iL_1WK$F%cGiKH#vFbqhz?7;9NmYvq^W`p($c zv;d@513*nH!1J{lc0+ZL^n4BVsE(#@ty*IV<`td+cLpiGHOAd^J#iGMrHFFjfjSk zpmLK|zC03=yi6+}ZY}Rn8|A~a^6c6u@1d1fSwoRgKwU*E+8>1?H?1iDYcaA@S^jFu zse?hq{})A~#pPd9QZ%xcuci~x$eyER_xc+5yO7;$HC?KU>_jcw<7*mS57{28>0Uj3 zGi+4n800TlMNeY%?Hs19 zD!~`f9q?+7On>|6BWRSP-ko&>5kfERZ=mnY+OHzFhCtD96{Uz!u@>exM4`Njq8lNz zD3hi(!hGAaN+^w~Y)>X7#X{?C$)p*vm<1~`=~yhqqU^b0@G zU~5-UR-*m@o3MgLx7No>gQ;UY)M)fdjg*>gpp@&aFpqAd$IjD@OlaV=Rsa9k1Qmsa7YmEzCQP{>>qk*+XTz6#t{iRkT|4XgL#-*Z-NtjDpyFjBY z|I!S4!0~QYxK>s;R|{M$?dS#T?xq3ba~BKo-o26c15NJ^`-?9myXrehX|$@VzA**$ z(YImmEuj&8AZmk_kTC^^nIH89xKV)Pqq6?`Kx~nSI_&%st-GJ~L#1=1RXRduRC1G~ znRK_OwE~+!8u4*UD5t-E5{oCn8+~@~WV;t> zq&%5A=*+A|T6?D(z+8@BWPW!jL=7ib<<-2jYWVBORYTC=JHz#Dq|0>jZJ@PO z`gNh1jS%uVW1-fo@ziCA-rfAsNd29`{NW@_y`Z1$gK5!8y&u1V77AFOiVd0d4p>JG3p0o(Yd;G! zv=)nS>oVeC`9jnJbtlXaj^dkG*NH_)3lv+|ETY(4v#Oz*#7c%yk8s0t={yC885){D zt!7vzv3A4ERU-_(jQus(oKVwX&sf}0b5f*XwIn^H_?m{U=9W>0B8epqA>?|QJ4PGk z^EPcjy-o@)iWqPe!d4}SI z;teP>S7~54&3y!>#_7q`47wurL%2zV0#pCD&2CK$=Q!JuO84RnVQupa)4ffF?z&=Z zm3XXg(RXKHeB8K9d_!ZrQW3Q?UqVfb$bqAOav@ysU(fF?o zk0?ooEtYVC;&n#&~T>P$N;JW;HR19gHz(EW|W1g5T%dy9+Fq z&-?NC{r-U2d++IU&Y8J0b7%UR!)WXP^Ee~yX;+sFFh|Nk4$c1kGyxo>nI@paa41e` z{tUhPtT{}*Gs=91=wKQBU0`xECZ`5AVWG< zu+pP*&4+Y=Je+2w0Ss?Z2~gIbZk%Vn-~xzn0gO+m1lZeOT{YkQFV_GZMn`GSo#d@V z_T0%hB==XhFEHQc>f?Dvtn2wFEi0dYPV?rQF~^l-uBDz^Xg!(yG1G?JLaR5+-diHsoid$**lHpI6XrE6o1thEL2%hCm0iYItuK6rWNF6~&6Yp6jKqy98*?NfCKuDueP$x_fUpZe5yt=WgR zTw`9Z1LqBJ0k>^m34FDO3s?nkhTkl3nqxivt(r`xyg)`#QRa_%&+rvvS3}V0HA3(ooR7bFH-5y zpUs2GI;{+($9^_XCvUZ*nP<%LWKlah^^AEod9fX>IAfklwzW~Go;7C@QkbF^o;N2F z;ng-^7t^n-PCH62nUl!qHZS==CQ`hRu|CsaZV23?lZ`C01<-~BiX$5_yIUh<3rP_7W)-wMrAw8PX6}9+D0JD43 zcLVqaw5c!uEiRqj>VLj`juAgcnN&Ra5OorsYtn$!^m_bH2BR~)$V7vJ_#URov9L`C zx;Ti(my<#Kr=&|PZ5+(6Bn@Nf(O~``aw&!$Xvim#ZL#!TLw*%m5UZ{X;b)u4+t^(v zmXD|XVt9#6iJ~K7_Mv`feQDS=*mFV)>@zZWO&3%U>p6MX3kk_{JRe z%~5YP<}Kc2S0h@{oF7Y)BGs`iz>+*2sg7vLN25oFeNj5|_0&&V^UoMaZT*Vk>RI)T zw!FSu*REy)Sn+hP6g6``tu$A_6K4xI24|VeNHbUL3|NNGp+n&^1nbDJ&4aFIf2wN z0NC>b>B2!ghL8sEJBSs?19+=ndpB~7j@&ko4jsrJB_+A_H4#5efWMDU|4K83p-36aD| zOh_hb)O490S)aS8?U!_JsWKfoi9ZsQSG$5vhF3knH)Q40jQGBuW5#jB75mT^-sCgr z+{t{p&JB0Ioy;#~7k1ZU#b-S(%y{zPP5zVW7j^0GDZE+<`{rBxTcH}PZhU*(Hkqkw z&n%ajK=#5L7Fug6zs5Avw}K96ME6YPXEygh(CuV**~#v*lig(}JG0XZ)A&V%?cc!+ z5q;1AjVv3==NOdroxDzJVuQQJ^>i(r>o8w6c_!b3n8aG}&dP% zBGZt0d`Laihdm3Zs1JM2nP67y_WWiI)dBPPH9n@BVg)@AN-J{sjpSER-MEM!Oh{i* zC3ZfLBW6(zQTP*t3>4H`AFw;JpbAU*msm>g@53taSMnyW*WC=tuOnS~HTpxo0q3uI z+`G)K>;KSkA{0GSQ6nD?Elz&Gf`a{7$oAuArBKkoiV^%7@X-AM^D|h`Exc z*y$RMtX>F8%!f6Kt!pzMcINc=Q|6;AEcH`f0*Cy0?Ucp1KJiW+4Aa3ygoP{mc!(8!^C$06$k1X7f{!@R8gn5*YeNP;9R~H2{Kb_ zF2Awm4HLe7MQm56bj>hh`*lP5b`2ZUG#OtC&}BoMHqYZTxS;od`5eQro!DIOj`4XgPL#OOn}tmX^JDHEN%hCe{^ zOf+RJKQnoTcLlXJ@Ra`lXouybw}~!X2NQ&V$e;B+i7Y_$vE%@S9C5pAGlM!Z<+`kz z9EBg(RbN=o*XBkZH&)P9408_iav7%<8F1FP&8k7`mF&ohs>clI$QfTx$Ih+KbamvP zY`}DNoJa^_x;k$2!K{)UzApzTufi4ydwBJy4g7Lqt_3bv>Q#3uE|M<)lnB}(dQuX zI&O3iz}E--J*g#r7ei{F0H*K`IhdMv@#lp*Ui$4qe-(I%kOMcS_|xb;d}e4iGC}wP zUYUz>?v#egJd|tpHDua(=mvnvHCZkz#m+giLP0mb^2!!z)g~ zE9|b&w`VPnWS;Lp^F^B%^3BMua&<%@OH8kp)2ZL^5oBCBUHJ{)wRs|_`Y?)fSg7;x zF~WT8)CAUO!pE{ux~SP1wFgckjWn<%;V6RFqpm@UWlH_`6Ij$ z%m41v%SR#5;`>aX2pan>->CW1Al*zO&7?9z&nHTyPWzT`&owXqubiGjj>iZzuuNzb zxF_kN{&tM#xaQk{HJ@QsOLk^hU_3Nu$xc%R_Jk$uSx8UyPVf!6b|Zk*Qsc!W6u=7~ ziMeXxG0N)+4$Z+U-|-3Lh5yu5-|^90a@jq6({Eu?S5bOG4Y;YOsEHw5@={<=VA%h+ z`m4l#?-W0X3rYmG55w+M)icoahLjJ!=il&ulm+PTr}>8J>L2*}T=RWpv??CB%L-QP?PT<32YJK#4hDiXrz55M!Rj1SPP z(tZhI3z~X^j||gVfR0CORs(XnQTI4U-1BXix{ksfZRo5U{2=o`f0om48Di-vF__-H z!FSLR$DDd1VgP;dCZBFD0QS;KwpVWQue-2|Yhcf4r?c&s%Gd_boLhW)@)ThA1~xm` zjqQkDKF3Qz9ch9`T&Y2!VSAmz5AAgd^>6d(ra_?4*oTg|%{QCnaOD%N&C;?H+ALI| zBR{XcUWM)JD6gO@Z#VQ;CZhDc>aYAEdL_Pw-`2GO%Ihd!Ut3ps1Lcx2^^{4#{d{ed zG8yHMiP6fNDF2O*QKsN|{d)D4w@|i?X`oC+IkXN=&7OuI)BX)qrlb7W5Uk8Zd2ws7 zQt|><2ECl-{ta=YgzNVo_&w6~dkBVbpK<-(jo(kXejlvu7JcjL-R0@39u>Eyb(Elert;QIY)xcX@+|B`5qDJ`e>(Q49(YvlU0#eLpC5>nY& zM08x0UENJEP#`jEmloP2-P+UdqrUFnE~h6!phkUZ6v)0B6yju^!VX!dU@ixRGoY~L zF%-sp`2-5({GjBWKz{cz$Yg&FeOLw9e*g;O9z$VFO$wZ^PT_{HPGK`B zm?wfl7f_(31H>@u|9~GyCf-(OKH%TyhCY&8w_@nlIXSqtYEZRPwBb^}WAPOw1jDRe>%i4Lc{{ zJN$Y=PXl?bL=6cNI+B?0e`DmTS|E^eGEzN2GS0h>(ikO10O(geKhJwVIvVk)A zKXprpu!k5=US)ZDk590=AY5o;H0=GgoQ}NBht9H`L}O;XW|+Pm7I(TV?qq##&Ejzp zN>`9BTpywIMwuTT$!fmz1oD^G6#eS2^ux99Kaom*lnIL)DOQx$K2b_1l+PNYmCh*V z{v54zLAmBwjM5F|Z*RmZ15m!6GB{2dh#yPh8!LlQe!jS|G8pBLnN5_ZQ2u+Tq4G4! z`p<+YLr}K;#-a>GIW(pg{U}xQO>M0&6s}9obmBYFK2#ubEcQ`#L4DNFX!#J7ECXvuU`Vw%b9Q|f$8P6 zzLv=Jaz2YlfL_kIzO9rflxueJ+Ny1=s8*Y_6owm3J&Ma|$lvPXWPupS+ePa8DMDS& z*adf~^M9B+n7&6a(_`%rhW(4wd+mfV9QnCO9noGG%o$f*0#t#+r@rb;6JEeFS1d%3 z{AsTY!AAC7!X7ok0iR75HE*Gz@4_+jI||o>F%8#9_lM55D|D;w3=VS>Mb4Esq<8!1?c@tYsPY2pt;0KM>o z;IDo$TDW7-N6+HmM{z@v6agiRorBK{`KI?ym(%C4)5Ta}QLvMZmNdoFoTW)hGnDzw zl9hOrC;GRcp)UwM$fVPB!VALMz@ETbZFuHx(F@3T&mi9oz^fw;&FXSmZ9Gm`MaaiL zs3#@}Gq_of9MA+UNB-^voz`$Kr8#KcZp$exaNpP3NJ+qTf`urFD6P>3B?k9@TOFme z#P#b*Mx_)-_N7z-|G4u<*Srza{cCN zt3fXb&CI4VC(*3_O8ZO_qWi*RZZ%8uZ`Rh;oZ+XdxwH;bv($I3zpf_K(bR-GP_y*6 zrWRezv;bYrdv)o-Ny78w&`GuNWMQf|8S7NnP7?}=-;VF#$#25oSups>^fJeH>dcu! zSMPSHSUY>KX^b)xo$Mxv(5yciDA6bj8wDvh(BncC*z?iRMs+%I7$K9*dAqf@`e2T* z+%T)lakLYN)dzD-C+{C*8N31B8%+ui2^nS0Wpv7ptp34_vZHWZL*^`woVP;s3T_+9 zs5?$f3S-nAw>O0A6)Z$B%^e9VBADh5Yeb}8!GA?6xpPA9<{3h0y#>M{QvbMmae?q7 z>6vznNrJXy4wIxdBrz&xR$GunlL(SPS4ZZeXkC)kF-&Ji79`Om`aD*b=#M!1;9X%G zi9Dum&k^Qvy{eQ!!WTg@3msMy%0djXXsA(57%IjIHP5%h^O-XC+h_<-jdtGPXH z`|Ick`vYeQI>G@cKSxKnF3KO#5r)S*{yo)PXHdt25KhRZvK9*l>}d)cR< zBMgtXe~gYWJl=7!xk)McUGrdv`I?VX@|){-UUQ}77uWAWEtHZ=uHTqgFFEJ>Jtd-v~FO38Pw--DaAR!Y8gUF^s2Z(P6I2Ph?QCxn{ATvk^p`N|EGnCyec&dt!)};tjfM7SvIEQ2zF`KdS)8>o0r3GaJG) z8{Se7Ip3?LI*=Htq-D!;&#Ccm_7zdp_5}SXs>j^FNp4frwzI&5J3xyUyXWD zto2rFSH`9ztN4Ei1y44 zjg{X`2s}W4v|Fgnk<|rs%O0T*u@}&aJwoH=plx@Btvzm16Gqzs+DsvP)|sYEA$!iE zcork}{IcfiQ+tJL#Qf1$<#gir5V9z}b^smzrO-FhO{gPQ@3`NtA+SAezh)(S;gUG| z-Iu~3(-`0;e@|B)6&9HWfbu3i?d9~f9mZooJ=rujj}JjjRE zIwgdwZ4L@M2ub}4J7fr_jQx@2sc&65fXcV!8}y|JxfLz@Mrh~L@e92>GV8q9fYx6k zOX{e@f{4ih^Jt6)9T9efl`^$gDOJ*5Ga;7-v{tU7Ec~H0leQrpbyR3$nzyf<4t1&! z8I{A~f=SzkUO6U&f}l$>8hc#$O{aQb$>XUuKOqcCUbq*%U9=X}-x^E6RugGy4dg{h zx=7QL^_MQ^2_fD50w|<{g4RQ#O}`VynJ3^DzD6yh6P@BPT6$DSRa-fkeZSh{miWfW zY7(FEUWx}rwD>)#&d%?JaYpQcz3rsXj;{U*P)@gAYRON+L}FaJ3q(eR3jNg0XN6sy z(T`nEd>aEKbI%LD7Q3Bd>SEA9d@WXqd=?ZR+BG;8w(Yo4VpI`iEqqL%ns6Ioi#w zZoF3ILa-0~qcRHUlyYH-#~rm*1wzN;)>5Nb3G?~?#6<>t>bpNv3|4y>#bjc9H{VTu zpGmADf5{{s)0|q}>Ld0xkQX=83PDWJUo%lT_DtPuc9+@gF0=h@3ff#wOTSXPN+P<= z3pUZk7I8?m@Q`YWwCYklTuW@h`5b0Su`zC6F(DMDwa3*?VwHo;)rwV)Jqtbc8z^(o zQ}0__4CYd`AkjcyYO8~Kr!ec=3y-DfD2v+ZDEX<%P2A5v)LyxT^2DMvb)BEsUohQV zS56P?RV#u;n0Y)dSbsc-UP=>8v{|V5C+W6MjR+G{3@rz)^$b$T>tsRNaY|K?9)YLE z_3oe)qAdKm1AQ-29AruaqR$>Z%S~w{A_}*xaof8^v{)^^=o`^6j2><=;x64|wN!T_ zM$93`MXQ0Q1>Uj7A_7mSy#BcLiy0*1YZ(gkhB(}8%WMTI-#_$cKl%FG#2%C{)9Ftao(NY18r zQ^Xs(Tf18iShfAW(#<+GLuai;_s9(Kb5Hctj$(IW6e__BI#&Z{ zl}U|VL?^3DyViU>Rl^jmee{|rHS0AYbrsXiAAV9!U)lxtr<*VhAWb3gY3&0)v&7pGugZUwDSM2rj$5I?GtN&R|&_#s#ChvlBWxq-zc ztAwAWaCONb@l9PmwboPOcw#*Mq1*mDhIoYI-63G?bnC0`7%D~@f*qM%{8&9ZvOe)s zj-kxCP)84ux&G>(!$qw29{VAU9x3iIwWQ_Lyop{NDP};#)7|KUp(4&486^(D;_W4) z#9_(sA4eSM!G9c?Q2{#L@&KJ)X7EzF ze@qXSl+z#9t2@VugbUpd-wE&Rr+kfaZs#E75Xv>HgP1_}!t`MJ(|B>bC(sYUI?#@W zI#8<+I&y+INtg_>Y_c_TJ+`nEBSN97-KDBMGe3l>YR_sPsw2G-hJz@@F8n=MjIDuw znx1SdhpIVQVk$?uBN2Vmw*3MAvQ^*fH%!eL&-1 z5d(X|qIOqJ*|XM!GfQHyI6`N)Ba&Ivp8t0vW>NczZBfd1C~v33tr z2ISEDnqVDvzpo262UyjINjc0pmH15E?qQcjF}huP#Oi|HkEK6N7Jp4n1#)e$tlkB| z;HaPG*zli?aPZ6xampr?S*PQawX6YJ-I)IQruaFDQs~AhVub0gy__CjO;1e`*OEW% z>eRPzrV7co(}h#Tg=DN9J9dh9NSs|2ri&?rTS2!S7VFWlK7x^snkn`ZK7CIg-g+KeNhhiKSA?465%f*OB&n(m(xCApB*Wiw^9F8twD@NJ6Jj^tF!|;zS!qNxd6{1lX z3-DaSu)C`l(2x~kUGE8aTtxrqCe~4Vtw1^@mIbQm6A@oK{PwnbIZxyW;@qVwHLn&w zKv($V)nXkk*by!zD68SHb6-qQ)}UN-IDxqVT5cTSy+*WEgNSXZL+op*LriR?zOYuD zzy<0g>~nPh`v#;r#q|?5eM67TWj$9r1;j%nUOZ;mUNJ zhjI;coUes%8+Gd!Vl!{yjhQ+^_xI`51LDiUgK^yiS>?eTHZhFjvO9SxCB*jrHSB*v zCms}=V^lu(ATs~NS-M2efg{U}@iXZ^2gQw&!A0;VWEHj!2fLnpEiRDG%+UGdv)gP2 z&*w0Yp2X-N`rc0%kIy|Mrjnm$s22~3n4!{!^xtuHe-^sBKkruS{;1Qx5wS1DX(Sze z_S|_`j0)_Mrf5i*2hfn-NmDc=u7g_Zh}a%SflXKY92GN-#(C3#*zdI1N_CzP131>( z^1#Flf`&OrR561vj~EwD1wzgdaXdZKNW#&mzwt&K#wCu#rW!h~gZ0$F)xmmdz;(EL zYO47M(U&887tz4e;sgqQ_0^A0i_apeT&T`Cx4>0w^@)oYe-dwy-*d3eTU=qfHKm*$ z%%S)2+ouq}KSIiS@G2(s9cM&ea{Dd4I(~Ueua5jF>b)}}<`cHON&mSZHa36rrh5Wm z8Ty#17sW-TMLzW6zfuGib<5Y-Ku9v(cST%>DqBQ!8(tvH<(zXndo!1Fu9;|}vwjuZwwyG{ zGdC{4Lxyy@PH3WgBuB3VALgUZLiEhof`w&Q(Wm|h$P?e8U9XDS=z1K!Do!*F$F0P7 zXxeXRsOL`BwVwhZnKO2rq^|u^=-Txqn_dd+nc-)?Q0 ztM(}qf8>NQ6LkkonoHyV6DLPPJUbJwqiTb*r^E)cw4 z1AYQB0PDVFq0CxTM;Xg9f^S`Q8ZYsLy!;|gsFPNZZZFaZN!mz)U!*4_$!hu~tDNqd zrAEtAe-7hMphIG+Ofw!d;)c}IY1!&)HK%U2NZ(<;xsqpI1Dz)qsKYq|Rq89rocX{6 zgclNr9?XYpOC59$2h24&1nHQ^f@qANG~B!ph$9)IbC6h{uJ)5!8ChOY&-+PXgxnaf zR`^R8^%y^%3iYJxBz`>or=Ao|x{p^w>P!D%H|+6h-9TvqAwP|yvxB815(I>&rKgE)8a0JT?Z}2G+9^c(gUo(` zCWT60v3vr9I9OoA*p5sDHjM4a!i;3CFzFhp{Q|ugChZ9whniwp0Kj&ZKmd$^4=jg5 zS(!ivMo2-d-#sx>YDFwB(6y0}^XaklVx+WINP~Q=kvET37dMi;xq79UFLl9YHKEwv zhTq7(T)Yl1Uo@6(jFQGm=f*PVk$2ZTuWJ=W8>C30+ACT*%$cKc^FJgOy|dLKR@#SA zqUZ2Af`sjjdOk<}no4`f-Dl~ErcwqP{2Zb@2c71A9i}{wa!qw!cPhvB|Vlx(=KC(7!>eg3LBS^Ak6KO5!db+@h5hL}Tf z{TFfv&GAKdYGA5lCv`{BtEtjiBbN2|&;QQGSu zy`L^^LW8+JLwW&UdHQygvN)8}J4tgeyS=lkl*bVU%HFQO?j|kAg*vjk^ob7{HB7DO zE8&wG(=c^xe<_3u`|_D`%04D#AGLmi-TKR?_1W;?pg}1xjQnv3l0%h~sy|pI8@{uB zhK7un3Tf~lsYye}iQaL_Rz$|_vQA~Uv0;t_zkLsME!&2YJ~v1@OiG5)_`!&clxOJR z!BPlWJCshwwWTv-jA=$MKD{h^2;DeXN+D_Zlyk7O-5~59Qcel->yQ`es-e=$88sTCt7KaK=Ft@@3Y1T(2W zScSrKIMxq9y*uJ2HDvYf$lTD7)jOguMBO_+|%>H>9DSXpiAaM@^F6q|dy7#W6P~NjZch^rus&NdK6>>xaqr z=O9OEZz+Kue?^X@$KH}8a;-nDctwtvE`SkxJy-`gn!ZHbMUPFD=2be}8`GpgOkX`&5}}yxgY&<7V?#~Fa2khv`k9Xz=qv5F)(de|rWQ-;aZ$@t~mByhB9^Fj2j6J>G{WFc=nr1q|(q{VH z)skgW8`Bif=sjGgI*NiS_ZL-`N|DQ!OKnN(c>Vo(*mAh1seku!8a)iBaY#dncMtXG zN74k&bg^4G{p=YW#x7kqt-|j&pHUmHMBXzl0yHi7A3S`<|0G}1C6&JSKj}50M=CR( zGY;2cuJj@6xTex|xza?*X|DDxGSB_&tGt@e+O3in=y>0(l3w)0>+q>GQGfQ?r_wOb zXF;po&)!=tjcSE0{95R;$O)_>otYU4%s|eNc&lHzgC)t;>KFENAtVT=yg&i4mXp%$>*W; z&2>^73F<*tt&_0Tlk4U$?50-_YFUq)_6|B^-}O=yx!RphUN1E#gIdsa?AqC#o?zF{ zx1bN$^`7oDdV_@RAOkIVK|jEC?E$DH>|NKGo00xOkxzQrJ9P9$2?qx-$$(?n1f1mVG;x!T^E$f@>P}Z} za!U%J4x6O_dUuoLPrSNQ%VvlN>bMz4u63gm*!8>?bZb6<9Gd}jsv9k2Higm>GXw53tkvY6It58SQORZUjI&x6)s8C0Kc5CI9H`dc&Lc2MxZ@-#E|J#DD z%zIs_b*t2spi{qMtJIjh)|D1+Me4fWiB@ctD#$*R4(WtxSI2U?XfQps4NYsS&eXD9 zN=S8>|F7J~Cwp=q-iA)wE)5}Dy3ilDOPS=OE;QmZH0(+jn)#WONP;`zJa=^Lzvx68 z@4)km9qHs9km77cIo&!4XS7RJzgAsbu8EA!+_F&@y5)1JBMI$7?|hCVTaclS*eMat z{}MzeMx67CS}!)Fm)-7!aJ7Aj{eyB;sVNzsLHDRqM?a>a1_oMei`B!OsAZS*y%iRO zW$l>=9az?$h0uXz?K#&Hm}Twx2%UJ8Cx*0TmbKqr-d1UW()V6lB>`nZN;@SHrL}8{ z5`nVg;S}0(H#$-lNqHxA>K^G&F7y9ahWAo*hA+3H>OL^))`?ob z0Hbl8=;ANHD7cea@rBfm3v7S|cJKu@!Ki80qm{1N@m6%eSJG}0+ksjNqy&72(K}7I zfp@C%yEnWG^OQmRr5^O-0x9dUk9R!wNe|lez~c}%9gv=cxbNWO5ZitIM8sZ)9*6kt zp(i1#=L@CPgnXN-&ORcIAjX!ddP~%X1|O5cNk%H|a7?NQJkm(vVN3Rgq}dd2NFuIX zZ%8kxUmurR8OY5P^`2A0)b`UUw9og_Jba-E0&H4_-u+%`8SF6YbhPmn&~dW&2GDV8 zuVok@Qs@34wJ;dd+AZ~G|mX! zJIPQbCqt;e?1Gd>8pP61FGw@UH_0^OqO_AtN>TH02Q5fi*jL>E^!ys;yS%WqtO*sM2Jpl$W#nLu%CW)RcMooO3 zMB^_@KbjXOmD2zyzbsP-R%3sWBm-I5T1~ntjo^e}G=jNvp1B*?LtXisgyY8dbyw?N zlWuWjaVypIJ6<7#f6yPu#RrOiAwA!a-Y4I6Q;*(|E^@+Ct_Op zsn>5KH4*=o>a9|#E>1E}q^3L4e6l%_F1{npB;yiQ%b(IrL+l7-xgzXhF$`t(*$?*m z%=)ru(l++MzS4BZKho=Xb)BB37~ywwooR|U$~8}SP)sNbW4&mneL^>nrU%A$M@Z3!&=d_yJ#EI67`|0#6-w~?0CNg&iIxtbEI7h zy6T?v8YxVqb^nu&H+94v;&k`_!%OLjk)*8s9m{&5%(>RN4Ap>Uh*K;mPc-0Yt@~0o z*_%k;zc0lT>{@u>J`(?`MEcKt*x~0yjJ4qU^+dY8T$*2Z16a32^_2W#!D{XiciHAa zy%K4k3Tce@yLcwh{`aL&c{YBscfCmb;Z$RG>rL0K`nVOW-6Ah0()b5x>qaNip%0`G zDH06=BN~o!S&(hW?+%)9pmQ zNV4K-yuX}Aod$Uc@rzf-8fC=zkrwJ6ll(RbME1OfwwDdHTt}ISHyC75XBOUIFzDM~ z-OS5x5XQis6=kF`5;&}GruLEKI~@6{3GHYBi?^H5h+6U~V|){YON)iIqtu4JawzA< z(!?6xRGmk0h8WxE` zaC?2pNbPmyB~m6LJ~O{_8LH4uThx>5lc>ftvz|N%0~?D3z0-ve3oY0%V(~444kH#S z7ASqrk&oi&YYpU8!dWn78-1^iRYL;hZX8RIFoQOT1T$!ZNH7B%L{hO{U^hoTYlpLv zbS>Ft~8X_lLaw!afrNyB(|ezq4FVgLyci_8#1g3O$(FLNP4U~ zGfX~fAU$F<=WWzJMt5GHXwN{3MYc1))U7NICEeUe4kiIH^k^eFg(SvNQpU;L2Y1zMg8$8(5$xL-rU@FiqVS$-Nq<0^SWx|U3r-6D>9fjvhl8K z@L-=fx}9-2;^NRS3H^?7V8V#5)rfkZy#EnfTI`R{RJ^fAmd)COvspDaLi&SQSejEi zM9W<`Qa6gukC7LK^aN(1HvTej!~Kua%N}&{)Qm<74I4v259-?uE#b66RuW z!qO~DZb6kGODb#Op@lnm_1#!`4Iv{N(ZnY5kAdT3(Tm2qGJH;e4UYMD&866jAE6W3 zNR4PJuQC`@B4Mn4>2jN8E#v`sJ%K~xJqHXw39627SPVEoU#%6)c-MWkZ)OVn~&sW1q?V{uOchYfa=|K5B*%wGp z43e>dNCTQSSUziv0$DZqDfvTE@5}n0)(5v!UL|02Y>2UwUd*b=8+T@&)-5 zGa2Qt4H^jp{SnEim5@3#X`(#U_`r_|utXfE2EQs#$F3|<>WVkyB#xY`O;1gdGs)rF zYRF_cg(HJ%t3%(ECvfDRpISIYzQuXZ1a1NC|CU@wJvLR2#1Ro*sV3zB^y`S7cK(|t z2OAw7?|Rdq>9Rta`qC}a3|t>=cbPE0vzfP>8osi>Vej;*$@11 zqmNSbOD!e8`n~%cJvc+|L9WzMEi+}SHyL1|W9GRGBwSUJCZfHKTp2u_q|2$IkDao`-<=*nRc9y=YuVD{(SkY-`mxmvoZI+vijQF zas?p|YN@X+l+pj_D3#NCVd}|>}K%j9;C1=Adl4WX+`sQk2dy;2`f z$I*mbuCH~XjXsfE!lBtETQNQT6Zt+d{=x!GYYpwWaw*9Rq_gwnf5oNL%fV?TE4uHBcB-P(Jk^>%U>x59a{4C?z^7;l^iZCA$#3U(4f-POsq3wC6@SLfyRsO?B`lP8Vesi^}Rr6?+uY z;GJ@=c{(8a<7u^302g-3bI9976Iz@`bfLR&YIc_W+t;)^Cp&-gMZ3KwWedq?Ic~MM)g{sf*lVdn?;{je^q3`Jj^!gWa z9M&)E_H|?)*X)aLyRp>~Vy|!?Hgfq=ZpH;qd2k>50%u|xg1DN%5qJCIUZXk?{r*tw zGqU6>*(OBe7Bl@lKN?aXw?^BL-$|e3?Bu0aLNY{RqHz!C#sc}}=5Pv!%M%=Ny)lP| zYu2QqnjKk(1Z6YIoaaSdoLq^1w@a?84&N_-z>yCs=$!*{eDJds_h}pCpX!^;lwkWr za~xU*`%m}^d*DHNU;P+>-LK8Ssx5Z_7>)g!HEQMy`gE)z1v-3nP;4f|;|CM6s z_vzQZ>OY6&p`3~0;zeIN_^2Fj_!2Z3*OuGygK?dXht>CtDZz(_2p7AnuJF~Dg&E17 z^@m0M?WnwlGns*Lp%$IslpCx2j>-5wcK3hx>Ec@S#Bnev!c)ee+Yk7`7_7v@>I^)z zD7UbHvuFO{VzQ_fs|kC~8f?deve4{{!=$i7?Sd2XdCuDpq<*8yF}aDl#3}bO*2@D- z_{ToVYLs)I^HtWMTvKYH|NbBk5A}GMQ%ipsR$C{$ptkz@X}LWo%qoK`VFF@+tnT>{ zt&nj5ZqSK+Wqc6+vwYrIhh3I#_o*MG&5yH`3NOxN?t`K6cX18N(3mrFGZIlo2cMCn zN$Pz%^Nf6eJawOTJd1E1aF@P+R-RAV-d6+9$q|H{|5r`BAaCT1-H^H24o%qY?5HSE z-%GMLYro%t8rtFyl-lAClx$?8`6ams9cSMnx#0f=tKKe>&k(LHZGQptQCoV-0_}H5 zXsU)?K?*g#@HdpwR%SoR+O%^NcfT}y=3`_~Ztl@g*8 zwU9~3)|fB}(ZiVayS(;E&pX_ZZ<3upH2$W%AKlAq_4GvVe@kx1R*JZ;=^Lf;e^r<2 zl0Re->DkN&GSfKYdIvJb&dj$0mH8+O?*`Jnf6C93GH*5FFBu>2H^v?uf8%AN;x9V( zANieNXSg{~nG4Xl6N8j_DAybd(ox3+Q}JKhXbX05?Y3Kpn8}t0JKX~N8GDHOjJka(hz1NN7jr`B?o0r zd9eCRnfyFw8UiZuMzzm>@@$Sg`zJkhU;e|tN{V4&N*BQ6t7v=&FTX_$e^P6O+*O)) zTW3DR01v`vMD^*u3i)>(Q4_l)Oc#4WINkd|9wfyu1o-)XNc7rjsimow?j-*9()pHC zB;yVp%2|>!KKSE4&BZpyxmXSu>J|DsXYd+WfZXLZrE?i6Fe)~P!WBd)MFz5Q6=v!_ z#jITj2y6GlB9#Jqa%!!5bpuZv4o9ezch-ZsEJk@ zyc&Trw=o-UP5XfIS@ZO=SvzpTAb~{q%?7HNR2iJtKwXj=_+dJJG4MCvQ7;lp6c<{> zC9J8=#im1XwQSaB?$EKJz7axCaLL6BM8O}lkI|CwOcl~77m`b~;@UQADn!dgVtb@0 zZundm6F-}^1>nDGjyW0NBq!3dMoTo`oiW5cfnM;o)WZQ?7BiW$gEsc|V4hopxxdZo z{UqjYcsKI^o3#v8;bx9r;7)H#2syHY{)kfg*ChmOyPG#08|P9SXEtjb8~%{=Qb&}RLDc@jGPp@bt*`RZ?l%C}+F%4_7 z!tgcA1YESudcKr~2$sl)lqhmh0mv~(Q&}@!F)EW*Whyt-zm@(9Ki$glg;5XlnrPz|_1GvaL4o{Wz> zHqzs?8Ypi|Crg&dhw3($Jw}!XT2d+9DOr*q0!eSIfrK}Qhb&VwNXZu#zUWQ;tBdC9AO2Tcz{jegy7sWcQ!-yx$S` zSF`(_IAvCKgfV!q5)X1CIb{wzBhZzMa*)F(1 zJ*zjPIt=J^1f8yo4vq^%)70e2ghuIvMuX7d+w^6NCFWs+=@pv?5EZ;up}EuKc4e~P zgTdcMCk zIAv%Gqs1xbao*`FeEi+Z?H0`UF2~zW-EIJ1`qazA_Xvibui-v}^(tthtUy*MpLTdX zTZ89i^zuiaXZOnT2lZ$|-vW%WQFBc{5|*YgL_>ND z&BgZ{Y}WGYbXjdnw}(JR=^)`ooAt_d`f_7SRA?#ZrepJ@lZUlP-(RO`ewMzKbc#Gd zihXR>UDxSGziO=9ATCxJSOomPhghX|@D!Q1Sr=cY);iT#<$8i}lFj=1b^2wUYOLHK zE>@!fGPDLO2MP1?U{x%`jjrPm=}J}(V)FzE$D;B0>-3a=C95hB7prW51U$s5$de9- z9;xv(IfbQZo zyx{hWu*6k5Nf==|IxGDVebnc#Vd=Ids)^I9C_x#kv#z4*MsTst2(nrGU!z^?d$4u` zxy=HgHV?7R^<*91&}NOkM(=LAXZ8G_Z6DsglnPC*fskfKGQ}0ll^->A71ZsNQS}H}qY9_Cu>qcYOPpnGIt}mn6v(A`x3e=*rUeXKrZIR0BTeMXA5g;X_nwlT46>HqqE*) zZ2+-X%m%SuOa8t5hX-1kB)VzaJZZDu*JWhs zqEOqZT&&G!nVUH}qJ!28vGl7(yvP$X8)wk$|BcQMvGlG66z1(A`hGOIYk#A6LOg1~ z4dfD&wWy2eON}kDm2PMAB$J0jh^GHWSA<&nx2)2($P=hI!Dbx=RhXH^#Z;MT>lK{g zZs}A>+l}Vpo{?y?cB)~dQ6^6CDCZ0{c+W^+R}YIBq~lu93t)?Rc(!J0nS zyCOQG!{D|k5T{gE;8={MLr4{PuEwVlJiM39`ZOKh(h|!w&r0v9#V1xZPubIRA}tM%MIkV4S>F(ueQ>|LgQ87Nv3!Z#ssd=?TwM7s(6K2Ja~ma zZL_YpqSwu;Mpbolt(Yb?@vIvcqKkhv5NBMWBiib@ToWMIlQuWhX3YZa8c9L3_Mc5G zPgj%5tCojU8N)C><&vsjHK}MZo!QhwDmS7_syrYzsVS8w?eGycYlFu~)vlR`4}|%8 zNHuzt&HC>zbW1ajdT|4}B-jt2i&ROeRxhJG$z+VNS&#oh2giH(K&~fH_H*chAUVZ* z@NxsWcohR^xhF5L+MXhhwOJSZLMJr$;FazPlsC?1ed!naV{`Ol99{*jm6waOPE?iC zxDi}kiSY3@>yTe)bPGLeYjy7iak~dV(wS)WXlX0G|E9Z$Cu=SXuK~Z%Q`ITux2ov!s>X4lJPnktIPCWVl_T)5Eq|3fV}I;$L2{Se3H#N^)kjntMMuD1R4FN z%{uZjwX~|n#|`4*vmYQ`J^6(BdkTv~(^_AqJ6l!bGs+Vrdz#G}c$r4Degue%4>uj- zr^PrW7y}*dtXEKj$_$(JRxv%*+A^RL#4ErQz=u! za7*3LD%b)~sj}xHFBa1YZ7hQzl~)_3eNCy{2rj8c&%-H`E~#2nlj_Zjw4x0X>BF4d z-UCDt**44)*QyFAtS+mxN+V^wjTsr_iW&)?!PC8MkxHvDM|omqzhkrhR7B%bklr2! za>-B(pfBm@E|n4KB)OhsM!##b<`>Z)Q;^=O$P{@3(1 z3Y+!dB|08qA73>2SF=>%dDiCA~6xIZ1k;hdddpY}U3&8tMAr5WKqz#KkBNAYnBa6?jq! zUv0D2x`acst1$`-@?bQ2E#7^R3oc( z<5S=XlD*Mp-FlIp00?_g(G+rnxcG3JY}O^7e8Pe~gw5WJNt%mvW~XX=Y@Q(dw;&uY z((9e7>Ei}*@d@8*!$++i`gk?;;FIUDS<^1k_d8ePGs+XBcsoJ?*{X9jK5h^fpN!8i zpybJ?z>~=S9Y|Cc=-MvT_;`hQh{CCef(z8IYc)r3gShyN2FRfcp0PB_lS=U}n{~$p zx~FS3M!B9K;d>DQ7ie@hOGJD+UV6L=+9)f|-ly!ht8u|VVTi)6-2;Vrz?pY}PVQ#u z*yxdP?wZ|)>4FPr-*N*ijUqfCy+U=0>H6q&_7`}wy+9+nTRJ`(&PA~pa2XfaYhi>Z z+$c|aqrbw+fD80!cT1)xT!ANC-hTAvF3_YNHTk;X+?pJ)S?`~J1mE;9PdyIWtiPY9 z7kfO!*As64A@uIf)6C3=_`2X+e8USdpY%w+;U0YRzQI7!d3qT$G8(wC=ULkyo$SFQEYd@k;_qzMy5Ld0`FFw7ZoMtNJ(<`%k;6~f ztbd=QJ9}HYdct9LlM!)u#76&sq3VDz10>}fUDeOh z$ssxHf# zZ0qH-lvtlY1t8y@rG2cHmJey^)@Sq9TFm68(slza(NQ(w3v?sx z2Ye^Mvjq&>&d~V-EBkX*9^xXMy(!z;;w(Kn@bUJ{*qm)`c$U^3^oY9kYOmEwHbCUF zbnqZc^T+9sk)Lh7cg9nPt%Dw+gH0!y2l%UiXDez3o}u>!Sz;bXdi0iT>-RNC_Z<8P z(gix{{eb_9k;ZD0W@qTK!A~&H)@N9mrX>AoKzAD^LtPg$DjQwgK+(&LJK zr#mraJF>0soS|c%vV=bZXq1Z*fZjSo*FKrjwruOzGxW|=mV}W`R~O(Rb{X5VtyZQX z946e$X7&3ApFZJtJCsps2`_C^8BP2?%K2D*Ce)6cSWia4A(m@rfy@?>+D-qCd5Y z@cW*bx!GIZ?~i`c+??}0XU?42&YYQxy<(A{0{+oo@FiE&RwmEOes7;I_(xY5{j!uv z`Iqe#zqj2NJpantkfI=}{{^3YWp?X~5<1!b$M609b6!$A5{SP2od22~DW;HK^?N`2 zoDZ5}^s3o}Q4sCY zp<%bX%IH}$hyOJ=QX0p+S~)!Be($_Aj(t}dow}xLb;6GAa#B4Ej%ieMWNm$Tkmp{F zq=a#nZN3yOC7z1=_O-(^QK6%vTre9pUE zQ(N5?;T3LmsQ}9TxBVvFzXG4Nxc>>erb~6f|LZ}%9YSg;_#1xj(S!W-HCYR8DkKnn za*&UlS}PLX7Z*9mmru=#q}ioTASyk`->)5Mx8M6DYHV6oBvT=QXyrjZd0MR|jQG8G zA556A&+pQNSKzaD6Xr;D!9V*TKQb*ou4HslMR-r$?rd(Sz@cVt7sR;}=7kaRl8|ELY+O~1G4K|Z!9n=T3kB({TmSy3&zyyf@)aDZ24 zLvh!Yx`5>H0p4tSEhumMz55Q}ed}3t!Dg!{5lD6(;2UZ~+3WW{eSjaE9-o|8){Qq^ z*E@dinge{;j4Xn%WlMsJKyvQ^e)o);)pfn=_s%`Q_hv(hC=`$s9pH7Ztp(*hzjxvR z?!7jPF4$)kx`1Tl0se4pDDV5dJr3~0*-*3w5(Omf4)FZz;!~AOyX?bobRga7oIPHH2Iu^xRQJ#VF^t)Yp5 zW;P7|`YEO3?d210%5B4avy3`=s3D&<%jnQP)KILZbgeUemRge>8#2r8`iyU#WlYLX zC8@B-q)b0Zrb5;&vyEKd{d(hXaV(#}s<2~MS18vITSA}l<<}!a*21z#+>*rA2-|m` z@x#{}!_Q48F(nC|rf8{ZMyv0xUVzTkqWNgVf1TMVe=7@UNWPCkGuni5YGRYPrk#T!<1%|vN!KA>f4flHQb+)RIPsO zgFn5WADeH?xm?Od)KicIteSUCGQG?8OWV$Gnqi?*rL)BckC7JgfbUN5@xTMdrEBjr zw!{UPsRF`Y)7xJO=un#g$rl$81z#si0Ke$2BngpJ3AW1-(yNd~_z1Vlq*ZdF2$C-@ z!3Dkw@QEVu(A|b#`70u}UCEAdBUNFC`w`fGp;4$W`hd?~XtdQo`;aeNXiU~G|9~G} zXbjLpO?dM~s6c#9z-Nb0lOUzj(&?W&k!&3rY%8yiQ-Qbp1x zbkmBmvG*8u+l5x$g;Hs%u4#kQC8Z7f#pES!@rB+*h{uQS8lO0JAB=f z#+e>Sg;?K9Ta!gbJSo<*8JQ37p!G%884vOcHyV9w0=8k-Wf6ck8ne11{lIfJ;4MfG zdZ(-~WOT3F=7gp-3x=B8szc2^)%kD23`cP=;V5ol4TO!>MyQpiI*ea7;Ymr9KfKj= zvlTHgFfdQ`;XPo$I{-spgCX>^fvY^X8CU36M9U6sGw>o~dzANn#yFgZ*= z%BF5N+S}??Xzpgg@1lIk%jlBM?BXxHEY=O_SUx2m(fwI__zy&U-mbE?uNaGM`UAW9 zy8kiSBe5}^Dni{k(RTvej z;P z1fz2!y#E`<@HmN9m?{WyXf48*zmcp^%yH;6~wO9wsUp zCMx28oYJe(v`bI!;+u9E!|R$Yg0F(~mXhWzM}M=6a`kZB73mlYk7KBr2albXIKxA~ z#p}luvP%{4o zBoJN@F*+4zmQZUY#QKkz-tkKPhao1eKKA`d{3B;mAG`WAc!q&91URI+X0{IYCQIJ} zOW#74?k3OoW-UK<&k4YF6x%JR=7`Zgo3?EPkq1O=NL!%({zH@1FyPSxC^HrD{z94L_?Q z63YXu7-4~bB7Kgr2QQkXt$AiaF@PU}{V=LpBX(Bvx!Vb){NI}1j|c$t6d1kzPVnCk ze)LMU^7|xz6#To0AM|^12(hY|(%JE4l%^f0sA^W>A<0|?<`)(7og^4aJikD8eVRKj zxa;3=h8a+1##xjJ<%zeh`X=gs3>m|?gxo;WmhR4oq^rD1wF0849CXw4pssJ-R8OB|}*;_{6o|%HNg)98| zUpPRS%;9tLIoUa4PN^z5&PnDlUHlzzWGS3Rr}fe3z|lU1L!RQl`2SZp+rN=moeUG} zz>D9`Dp(cH1CAfz;&H3`;462x(d#Ov9@;4mZ$YS$1sy3nV=U=YfQ@%<@~94ji%jeC`1^{y_FJ03@M?fxbd#h>dJI-Wk%P3 zOm9AsL)Hs8Zb|r|0#A9t_cpPwBjt-}PeM;ko~JGXFMESee9t&HC!o2z@zw7c`9#|e!Ow0M?;cnZ{rgsz- zZ};e-wN`CJ(z`&f4|tvL`oL(Vrjbe2-$T@f2Q*z?=MxVZxs!!8GHPDZ6@jib>3a$8 z7A$sePa51Z^^Hj$KX@9w&ZmBurKWK)2suL-B!8hrg(jeebF`OgG=bJj&__Z46X?~f zAz(u#P^%oVqxM!=Y{w-UB(MqqRRl0VxrUo;rI&1iC;xaB5IZi65FY#s;ya{tA1K{I z`>95yLz3S0i&^Y_ix|eatG~r6Gv24T$#13bin9q9N0HILLHJ7wD*&w873d=rF8T%8 z(N7T*8q(j;sH$j+vJiKPm)CAKyHjO*LFgLdM;jl8_8u>QnJ7T0wgME>Dk>tu!T|Ft zupEHZS^`s^bd7@NcJORUYSCo5Cg-7tSfI&P?nHxK;I7`0rBKE2?IhptFYEDtu@X)O zbxUXZ9X&uC)F(l=WC2aVG$p17nB%E%J#Z~WaeNXuoMwTU4MoF&Q#fT2n9e1pS?=m* zVa5=g^BMX?6>ZzWU#Kv8wDl1w7BzTnWC4bdr>$Yd9Ke6BFa}ZqGx0+b-}9U4btrrq z_-l07n9>LIIYbXVYNdCcBlP$G1_%G06s8tYn*g6=2t&a4M2`khD}6}PM?oJWdNsym z7NA%yePfcL3JjkT1FE4`0nUNa6@JG}5uj%?Q1x@LDw(6Y2Os^em&}@prJ?oAl+UK) z*;Dgy>k~aM6y_f&rx-W_6SL=(lpMoQjAcm|fIel_R|xN;uQb{ggXXu_&eHl~QaMkx z>3xC<13?q6MT4ndOP}K#Bnngnp4Ez{-}Ol?)+d!8HwY~+IiQ`@eVzeBdmDwCDGzo+G24e1L58hn|=7mMRn6AcH%s0+_f+b^C0G}Myi~c|sHUNmm znsm&f%O(CFla4Sj#sGt+-CN;w+u%q-ra6GBtZ~4OfrK99U?kuCsnK6YyE^!3P3=kz z$VGpe-d0pJAP(u7WaOlNz2n(B4%M&wft91Mj$)ff^@_#WJC2a-*u!A@4FWzG#gvM#r{bBzUHwO>7`SR(!BrOi; zyIoUL6Y#7kr>RLhHG4^r_|&WfB#X;={#WrCMiPmfVfaCEDSCY!S5sfu8Kb*P4#RVf4*7>BouJU+|4KeE-L3Ezl=}95+o5xQU#JR<$UqyMu%e3 zMRN`de(-JPVlAtlKDk(P*|5(IJuUt(iN7P}&K+eBNIR2R`Bh$M5%}AcpQM20d8+C9 z!T%SUX?hKwm&RXX4Tb^mpE6N{nbuLQ8zeEvpk~%j)nJVsn@^@aSApjfz#g`mdu({{ z^KWR`j^}0&smyQNDB7@YZ+l-&l)ehScAQ@;N3@1 zfH$>Z!JYVrhG_weWMcZP>y)4M+~@LbUmN2y#{-$hYio=&#WHThjP~_TXlBFUj#qjA zm@%fGyNB$Z-2KI;-IU`;GzaI0ND&ldEM)|aLJcr?^~zWH))WZz5FRL<^*ly%69iyu&j~EVp&vxGbh*2D8!=*OKY_=u{`o3EB(GjD} zHq3(7#6$#7 z{)x|)P9Ia20DaR}`Pgrb1(PfiIX8-{RMZlacGPfkRzM1*MX#xm7xXdE%QOhzcgB`D zawJt*e`{PKPy@1t>eoR}pLT^D2K_1v895^L%S!)grBtW< zw7cbJj!%BpG3967P;cJxd!yH&tP*3=2Ci;69}bC|np=`6+M$;OxASG+8^gpzCZm`U z6+!84dJBmcW0)m_ct>|PD?dGq_CF@|`E)%02+xUDbM^_o7(-jdr&%9MeQD44zn z6KVA&g=Nt{)BS)7Kv?S>xG0VK@i8M^0TqF<^)S6(D6GPt<1>XJHIz~+-~!VJ!~~(k zNP8$Eggg83TYfl;_F*u;M$9PkHqt)1!*^0xMlaFMroCHTR0gaqgoS>#IX*W_MVg(k zh59LvBtm=1BRqJ*XkDCc1WlHws3#V+N~Og$sB{p`u2zF8mBPSUq*OYFVkFgUkeB{w z`0z6S;YZvonXYU^me~)I$qi06=d!lAN>CQ$c>1hq-PFc5e&Zeg_q#yhaWyr;8h9n>P ziYn?Vt(@QZlhL#=UC)>_ma7kPd{PU^xBX<~*F;|gdQoebIjDN#KmKIowgEl~-Gh51 zSAAu582y8zw)6ax=%lZEiH|*rNWO}KP~Wu~mv*0cL3X(|L}lFK((cyJqWErg*Eikl z$e`UIkns~Y=eCfuXWtz=8;SiX4q$-5@D1LV;-aHW~G6WZCYwU4d(2B zjqfhB_%hVT=mR`ePz&k<4uedSAh^sfe9T`(lL34TJX`<~|; ze#M~ueJMZoE0QV?i_Ze?`OTQ(svs}|rF$0fSz*;=Q7)p-5YGFqYLUkSzZs1>Cun1- zw9!`B@22WO0eQt@=A?ckLG9F2kX>yM9C(S3|J~>}Bthg$C5pC%c~!M&d9wU2S$^W- zFaK_wTVT8>>#aEmV)o`G^I=?{u04bmdxgtAgtKa71f0f0(FZG{nQ26mi0FqjqRDAQ ztBL4v8qwG^qK`qOfAj)BS&baT4bSrqe;AkbOO!B@T0&Po5=i08VR#44c*#4qJO_hU zd}DO#pJG6qeMznwe*uo;f-~8#%3kEB|1bs)O^9=+GF4&9wLGc_1&lAu0gqCJ4j6S(6^@H);Qoi<-QFzr7R87)| zn6QeaAfipwWTN2d3Sp#>hF}9NhQ$Bo@F4BNivOJ>f^<>5_&q*me-`S8M`2&~Y}%NTw+g(cUgYckGF&wapgHLG+znU-3w~cjjp0MExMe4wC`FnXY@a;y*<^AAIqC)&lXVUq5 zs$z7=Hf?k{#?EpWc|yS{``iyn4|)zhSF9obEr(s5bHe3r#4oQS{);r?Wp&u&Lbw(g z&M&Xa+Uw=d@cDJwTq0~-cDyb-ZPOzTe!M=rLBHeKvdInDn|9sVl(%cbrs!tVvIR|; zyUvXjO1}y{B=oDW$C}E%YB(-#f(>YbL^@Fxns9Sjo&-IznW;QgpbvvSj7d~zuvzZB z-Z!M+3T^JwHa;_-_11fV zbTP~4v40zlc_g3J>1yG+6_e5tSzS#ev-Mt5TEZH`hcmK$ujS$ebPY{hTs%vxWY&?2UI zeXV5M!)&V>zEAZt3PV!zt~1#+uD!))Nr-$>D4*-5eZW zC`m)kBu*t~mEx8>Md0~B@z4tGT=1zulOzIHFKL1NyTsr-CyUA<3FZe_xdL+mtdNvY z`4Cx^@U;<&hr#zO@omNgvK|Z%L%dOe89>gIZSMt6lzNBM_zz8VQ26SoK zfL)ok2z(ELPnkAgbGPMly0R{+ze%E3o1maykW7!N*x8lk7fZ)W(5s550{wMLueVU; z1rALlB4*V|?bgt}1 zl9g#-8CWVo+ykus3d;km%?Yf*&`g5eeKs&HPtkYOzHi|BHya5WuWVLA|5~^kZ_dUmD@G!Qr1hawpF^nu_;l@3@hpajJ?6L6$*7P> zz=q4Cph79m2h(T39+MdY6oR<`rBr;yg0Z7bOdmSB24ZU1u7T5rF9J!=PM>(j+na!G(2pBXKM68rz|tZ`%1bw zHdKoMLTuLscXQ#LGcJUR$V#-Xv4HC*WB4RSfx?I;Fp3i(a6SU52auWs2ynA&@Tah7 zlE*_>?^(~j$FsQ75h>7a3B+PSU?Qqb9Wmq#r3j{0rV|*Ul04GID7R`3ixawm76MRX{(5+feMl)3DY*9?_ZUo-|FpB0x z0>8gnCgoaSafJYE!|#IDIfApktYxtvLT6yvQxEqK2&O9+}<&z9iXz4b(dIH1M4 z1sA8&;MrYxw$-9R4(uK2Gu?(rNH)DxP)2 zVKG%w{v%3MPnC$D*`C{yJNvPmcp0hM#jmKo)?gL?`}&H$E7VBU8h&d+9VZsS)Dilq z{FwT_k2mlMdbgyf-!#<#bb3ZJBy^TE)O2WXRzCOP8Hpe2+c@|as#!3beff+1SeN!z zuNqRls#7J|BXs%QCVsLX>wyF|UeKSlY()Kz#XG7$Ya>fz_6-hz$@qxQ_w$7s~mg892;1SOI@$VAVl z)Zm-XVVxzhBB1!fl_Rt@RIqh$*9Mk+c+rpNur|E~CxlZ0pv->jJ1Ij8q@!0Q3ej={ zA2g8Vw*^gw78(&eN`VZ-^YmtBC2f}e{3O45AS;M_Cf*f6E^Uv=4SHK2)BAgvmkeY* z+LH64_ubPEec1=Frwrke_wyeIvJMwo&h2cXAk;p6e=J>5jL?7@rWh7I{6fs(K))}{ zrw(Er^wS&ol0j^&{{062{vb9f7gbIT?TEd3;ZQ)z#@C1U8O++$i{&6%80y0(4Q8D? z$S-0J6VM@mzS|=z;q@FWR>OSlU^aFJ%u=d-GdxILL|18N@!jec#qUUsf~m!vDI%MG zg&yk_bc>{#dtH3b zGGPJ<~vk(=l=s!0+mR0oG_J`WG^h zru7X@fF_~`L{Y70WATheXZmha1MD@DZVnBgmKo!kQtzo@aCSEc2C;tqYhhH(f6t83 z_Q#l3jv)VTCCecs&Vyw+{9D zCm^#37{q_;6TEOZ9CO0PvWdf47n?rx2|j-W8`f;<6LOhB<7Noio|`uEJtNp?z2y_U z?z!xMzVQiu_*~XMRgkF!q2Y^F)fHF}!Kx&v^hrK!Bx^hNhV}932ztnV)Zvs{)=Zk% zi{D`Va@5=$(t%uq=;_%N>&w=SWFu|*?@#bUqYxWyxt-g3&aIZz{`1@m6m*Ncyt)Qni*NHJ>o%KCnn;XLN zZLRhFE!$itzCUbzUxVMF%_{3VVkgv2ms{UWZ7zAqGV6QDHn#}hon&;>sD{tbZjIma zH`YeK^GUw^Z){M**%onxPx%`nyjMTT|G;zmL_9w}2A6r=NZTy#C;9BZqhXo{ZOeeEB5LAItKa?F3F}401a)$58s5 zww_NM%L?@q>-gRDdF6V(l|CPSf>(}Z9osnZDm;i-3K1wxvw_sP!&Q#2=f*geTm1av zfK&Hac+Q-;G&I~@-WSiHPK9Qk6C{7WRM5beLH9PiC^SI+zlZ)OA0Hsw8`V4Uk*`p3 z^pGe_4EHLAx?oT}dxaJo$Zt81 z4J>|7q7;UZT4!sml~alxF-M_KL+E8mB_}7T|As+S-BxJGe`uhLJ`+ZN6-{L!-AR0Q#dlva zpL-~uH=cFF9cq!GeB*f5oo3CYTBvVuJIKWUzQkH@NA#l}-q1R+Fe+*EZ25o2vT`)!S2Jry(UF`q?)wji@e#cxQzS0b6 zSZNkdU@aR9B51!5g{NGM7BgGovQO*j{MyRo93CA1-;~Mi5Uyp9$TE2z$J=b4;B7Bp zZRZq0ZI^RI&?$?Mt|E<()o{H+>eH#sue?l@UD$gpG{(Y4%v}CjxXTKn2@K+c6N&JX zG6Uau0lTA{Rj>l9V3^iYM-;aaOwqzJ1;6M*mJ?@Tk|jVPsC1T`I7=XzVjPYsmwx@xC(tD4dlV|}NBAvnBSl9B&g@)OWosiuKN5Wo2@b$ZQadh( z_|;^nIR22b->F5Al?$Bq&*-(#R_%tERy`a!{Gv#vRJNW{Hkzy~ev2!s=&~xSVXGOk z?7m{Dtqm_5S(>hG5`faSR8!B+rmVwKHYAn(2V96OyEa)_{AMe*{9h4f)z+u94M}A^ zFJm_)UD+i5xU%Y5ZOZanFJkrMZZy_%qe!M34NrHYh;Snj0727}<$O|=^YY|!;F+c0;tdSML%y1v`2Joz^6`LQ}t(8g6y;>&P;N<|=b z+%mz*wHxOStd2(Uq37TQUY0-BnvGaID!V5Po)5s&1nofRo+MAhXhF{?vZeIpOTDb~ zFhS@L>AJ=7<-8I!lrq`#HVpy-8F1zN&Z zQLDP3gVoDw4QM@SR(|#<+`B->C3%kE68I3#tyPDY$__z~NSpYP_qVy@=<41UHmZGe z90-$ST*wi$LvK+A{FnnpXniOYbdC&e0pM0BN!4vL&C0#_{peag^-|Uf6&rjCKW|C; zc?*6%xK_DRQaM7(mb9jZxN2$7kwMBoKmL3)p5KkJB2y1w)sN~uBu}wueyaOG1~GYe5twGjnc8GBCG%jHhvgrHO!U8)3G^6br%NFR}f$= zTx+Njw2V4}J_`E%L{AIX#xngPtMMX|z6$hj^J3ZXbh?_J90R=u1#OX!?aiZ>jD?hV z?yD<$lLqL=YAs<1I8fem7!y5G2E9ohJ_$o})(c`KUhSS@dL#Xxxh-_LRvxQMKe+4j zKc_O+gdf)cy<3jBUni^TW_^Kf``Yvd6#8jsB+(lLFGr^-{`WQDv!=0b*^JvjAXEWi zfzr$7Lpmj*fc?C*E={bwYcP1+e_S!sJ5yp{3?3mcXwhxQ*mvH=gvAXXYhIk%k;K{Q z!puvk5NcS6)sxc>9ciLe2%DQSGxd@}Y=_Wy-G}e=JR+Y@PJbSg&zGb1<#Ulh#Et#UzuzJ%*FDyl@7)7%>2(9Tv}EZv1Dqp;J>;xAvzF372HRkY>y>sVj;Z18n#1R=D-`vzD~ z`D`1W5kjlrAE=w+x%6j)eAP^LA@R57U(aM4Tw0sp8t{ZLfus^? z0pt>+nNh>kus2rk5x!v->!M#1#ed=WB^NxW|2QL3sOfMn%wMXRZTRsUSiY{c<&9>ukr&EJDAj$! zo~3q?qJ>Jpxxx2HJ+-qN9~IN-RjO7M=-*hw*Un~RbYDCEKoZb`a?nf!j0IZY8v3b-pKmvHwJm(O>CY1)#|dnH?f1Z_Ld+dbdchf zV&Q=}5%dV(aSLlV8A(XaD}1jNX_~|Nt`m9a1qVbKk@01q+~R*R_VGeHS-#a`#*|4zp9sc4jJ1(YeS6eVA{Z%PvHZY!OA$h(_VO7h0?U zu8+A?j&?C+5x$E>Kot~l^>t>qx>*p6morolqzzzMu7V(K#)|)A1wq>Th~+ec;WQ_v z`059zGe{}So#WN+#1%wI#f^@}Pb?)MyFNurc?GbpbtLG z$IfGgjVG%j7c9yV$3bylbkAVf*&BG^klsmi$>qSx- zs=(0YVSe&<*7;gQ@|?l05N-{MKDAbw48=UujiudqL4}Wd6eVaR8v|Q`^+}UAwcxqn zRkVEJ9b$oD>2GnV9>sP6mQs*LnX-Z-MwOT9!ZtznFkd#1V=hH|}Qb3K5a_fbS{r(eY-Xlh#2P=AVgY z0h`u=PguYv7fYiAbO{--D@e~paAN2~5&rGqQ=1vYC$L^e)h8J@psF^36CygSg@99} za1Lj|>0NR*AiOk`fcyZOgmL0dq^YLstYLltk}ya{3p3>M$L?eoXV9s#Rb7nzA89V` zx{F;<6P@c4%zG5wmRjhFE=9N~K<4i;fK-DI9=X)4^zTF!Y!;)2G!LHZmzk9d@f_6> z(9F)ko&m(XF52qIXIMYS5 zs8jgfaRonpH|t)2I>PlC5TJ)dxG7+F%j+~;_0gLJ_}GQ)vi6dQG_7w|c7sMV<@kAM22ESjWQ?fz!G+8@Bmo*zpgsv&)ffv`lpF~`RNm6`DiZX@=sco;W=GzxDPZANf*M%yIs0!294Xb&xVw?|2=o?EVism7ry_zpB zW^J+%DSfLzbjND`YBB4Kba%6tIBQnEGOcB5umE|36I<+Lk%%m87};@Cp@zvuHSmEI z)_h_mpJK9h4Uoq|Umsb?7n`i0pV>RO0d^+lxNBKpS|4G#Dkm;8fcFsF##Q_ylMT*w z_6hcc=OR!L(B0?_h~4bP+xc03e@iEy(#a=bTpjUR7r<o-z8=r zama9DO=Yz3ViJ$?@_$w?QbeB!67EMYM3|b{H+T`A@zQTu8-C3jtdTx{CD)g*j(Iqu zn7oj&J){b6;;tLn{$7Uy$?eYxpmEFj%}X#rKYs;ZyM!&%?_bXIm*P|xw#*@~RHr2| zT zss~tZhZJ~=PQlZqP5oB#y$|59WX^-U@If{{mEKInwY5Xi1ibt~He0`WIoFrNVcvRx z7cOUQ^(!CbW0$kuol@jk{3;QH`mHz6HSop{BDEz9&Ieg1erP%Cz@3lAtsT%KsbZ_p zW36Ao^B+Q@NeaA0XIZNN8_s}Fp5;e1MN$!KS3z4KW!KY*oLjgXtXr`V}m9YKlS@ohksG9qUXA(Yg~azY{C19C>5$ z`3QSw<#oyg5I=ZxSMdHT+2~Yb`jjpqNmqrg@vn#Y+Lc&Z-? z#47&MPL|s>;nOio52?2cr{7nS9vErXKg6f5X2Vi_&DmJm+;RrQ9c~9bkKK#LT(O$< zOsyiHB9FS5g*=n!hm z{~2II<6pW4*-X`QpeJaO;tKx0$N*l>OMVfo@8woS*+xfCYI1*zPZi7$z8vt818KO^2Wz^@BS@d$j0nUJ z56H^JI_kJhHS4jObBG{XLNiz?gL4B7}YZ^&mg?C|laV zJw(h1f4Yy)U&{vcLfRE|iAU~(*dACLuh8ap#}2wwO-h}vq(1ooKd_eNcWJXs(YChD zZJ;F6Eh|(Ei+05Wye((F?Kz+=E@zz(gM|?ZRX2qZE3E#n3X!AY2l*<_+TfO+bRuOj zn;Thr@GeBzEBFVT4M@U^q~iHKXsi$N{Kwe9+zKr;BzOf>fZz%(HYDglCft3z-{Tl8 z60(qPO26BY+(vV-BE)xwQwM|#yeLFk&`sXoLNsyxEFN`fupd0V70)E_(8^fQLnh4{ zM?>x~RGPIqj^sGAfQ95`Fcgq#hY~!Fe6&o7N=w(@Om727+ypI!B$E=du$Y9TSD-=s zxk%KK&tFJ>uF>VD^7+$vPNi*~p?R@X-JYU)Et*5AZ^(fG_9lWB|BdOQ;5i7MxWdY0 z8m8o0acYaow1!(<(F%~gO7LAOq9E-rOUckvC2XIq04iq)VY*io&U4r_DGqhjqE0NO-A;BhFxfdGu-A-jQo`*-bltt#wDKM-*Y0IpJir|#!d*5imz zra4r%=t5xd9wNrrSr_K8#?qv|B9qrAZ<3*);?2a1v2-=+FqWWtSBADH>?(J`GtTs$M-nk0-B5$XOKY#d6LyNkQ{x5JK!w#J#RD@N92Afn z`hGBVdw?H%f^|Qq!j{yKnj|-vq=r;4`MEZnk9!g^$#jcihNs{WBDFy$<>4o6VtZe1 z4WUVPFH*nwc_7B$(j~q0w^Q9&c}ZA{XBOA zb7c@Ex;_wnct4-Kf%Te`iR4r}+aTIOs-Tg73DI!}Niy8t+THquJtVQBz}j{{|6v0= zH;et0K-YNe7b}4;B?O+ZnY0xyyRawDCQxmgdw_M1!lHPQj=wj^ejRzqM(pQjmRfCz zhrxKgVjKqsY;K5+?kwJa!mia5l@S(=mm6WMxh}n*7lzqPeaBMzEab0;*$6$fl>dQ; zg9a@D5KXWVTt7-fKQ3bp&(P!m9g*QQk=%t2Wc5<~j^F;hl&{^yrjBe%yp-o{*Mqx= z7cVHFY;saWcOpRy%~0@;b63v>uTao*1c_$TQr>?vn>y?;_$Z0$b$rs8E;fGAEGqE* zuZ5qfG~m}o8ZdImh6;?3Be-ZOe}6N=f+uV-hZGoVCO+-Xrcy9gq1PwzV&lD_O;W< zsjD|JD<_y`t6pUJc#o~gUnqqSRTa}`ZrKGdu|+xh6=vD{|HG!~dZ-2O@ft3T2(_T% zlvN)lXvK}L<%L)6yKcK}6SZ}P*hvB6hbXl_NS z(4q~nX7x+EYimXiMaYnHi!Pzj*CS`0rM7flrxa5K-g>ZGIUTT4%Hpz&WMzvG-#TgX zJ>_gxoFtM;;z5Xczsbk$K)lXE(b}b;R3VVH+vKZuuvR+mblSFq9Wo*Y^a<^&md9 zjH{9Ss0IS4BCp}OeR0ZMsdPk!jy`z}j|&mAHUxyO?K7ILpbg!J)Fu+Hh1vw?H!Y-yZGJsb za_sB>`37B+(q7b;uJxDohFyMPTzLGa#eCQ<^s`$R;*Gpm{e$J>T}dqNR2Fj0jm6y9 z&Bn!1LyE*FQT=euWySoq-SA#Zutj1@5{k~wE#`Z7qaA&|Sl<41;$Zz8{pCg6h_Ip9 z7PL5H3Opt`i*T#R`Ne!@1ife`ky{c)K{TkCZ;!B5db7oRbd(Lm{<(#SNH`hCuI`qh z4U)g8O5g@b6U`Q z#yYr9W{@tE&qBv;%e2MZc#9280uQBv`!SS^SKy6n1Go4Tco=*m7V~v)v7t%eu~hIP zWFB=<;Qz{uoFz23_!Ky0EVW+D3*TlJCmT;JtxN5e1_(i(x`(d=QIZBeMdX$i_Pb1P z4E+?@Zc}XZ_$u$=qxZ5d_DdI@;;RElVJhtqI)~z1BjkSwa$Vacpd1Eau7Tt* z0lSjyLiEqCB#+@u_hJ)56YVQOsbqOTIqx36>m8OmvHEW4+8hHc0!>M7mMO)lt~>&- zPf4kZ-igw&iI*}1#@@v{yo(5#CDxs)U{P1>851i=bA*EZ(kYdKeo&sHD9g}uSrM|O zck_?lMTBe-l%{TxZuq4L*${L?GD7wqB4ie*nJPZq9UERs^N)GIeM$DQD3$mqD97NwG11j^?Y@k8$?mB5z@R@ECxdW(4BzN8XZBnpMD zPFTK(Pv6G|bd8rF6~%+V>3pS<=C%d7vqRH77P$*U)CldTeAqLZTu5Y?KKRz^h`lEy0nld#O zw_iLJg@2+!IVkc8tmh<6GeHwc&>X*;Ppv>4{Jr^nSp`-;?zgag zWR)b6TG;SN1nyv$3O1Uy0Fru>A+ok(vPwJ%K(<`S2ki%5Ad-ZqDLS{RI?(A0`I7zY zX4;NQ;Q3PNY>4q4rXCGlObESG+RQeSPg&jtz6#M3%6d29xa0$2G|ZCu67N>p7wCu+ z<&|u41H5;d8twl1{MSl3s|jc@cDqkldz#_|G+2DpC#;ttw1uUKx^zCj`xC4of11zN ze!@C7(K?C8n-H*iaz5Yt2`k8Tb_(9UK+LHEy04S475aPrCvXR(6g;E~9_b{eOnwA1 zE=2)|Mvo;JCwy8Hqr0px{}Qmf9Ah*TPyr1{S`y}j<{ z2R>yTveSi>0MO;#&D(y)3hMhhi+A#M=iyIT^Xyy-odODV?&kA9V};r26gtHZPTs}$ ze8#$Dr&D;e%#YoL*Z9>$7m?b!CZI>Yi+c~S!pT|f?L-DFN?!!Jo#^F4qukXa5w^14 z-kOysBzfo-ju-CYmB7xftHO?gZv9<6{~*h~$-)a!6aY0qpLWYe$YWbcI!r(?lyt!Q z*o`F|(aR)m;Ikh>1D*2U?ZN}BCLObWrd3DSgw z5FzR%v^6n_La=zg09u4D!DNCoKq_nK5;#5F8JdZsR^oX&eoScw{L6qpnV8>JkP=Z*)F=QwR8;W1cqd==IqNzyU3N&-`b2bBAf-k?e{|lglB|Qs!zQen zRC)Q&pR>`_<&bdC!qvWkc2^Uno4$53tms~FN%!brXh&@ z@XVQ3S?~lYw73P!eNEa2Bp^&ODO3^!fCvSF$bsdzhkScc-NIoP`ly@E} zGy&zc>NnP%-*Sj9H%%)qWiO&I9%S~trWCUI3UMG31NPaf#+1B8;C%+X30d@9FS&(6 z%V}O*oMLR;{zbz50C-#|t_STNUL!RjD-q^dNwwlX4V7Ndu7lrp%4AU1ECYSp4W_|M?}$ z@0o7lkfim4b_!_2gW-WoZ9xQ8z2|e+A=diR3=Y-Tg5!KbA0UfUV{Z^qnR=i=1d@S`5KG3K7|TOUIlTl{HwKQO3;5O;>pZDOBG(k`Mv*FjP48n! zOx%%tQVkF2^A_;7RoD^C1Xa35LDVE!SCoV@XL)(-K09X~CRa99pFRJGrapsOLA_!MA?PUW`L&O{M<0 z?M1YxTx^@)!EgJHZPy#z!MprZWE?PFvyDGm0sQXC0fO3x$8_C+_(~f%C8biEQyq zG3rthe_L#_-NEz!#g6C?-_G@av-5okVl%A_$QG=#3DX?4uXB}lKU;zjFO^G+!Si74Sd2^I!f3Bb7fC)TFyuVakasKUu8ywQKy zFn;0ptStG-^^+2cY0aoo;*~*RozwGbDTqa{3PLfSlk@nV|FEx;K;5aJ6h?WOK+&$K z=TUQngc26L0(F6Y+dTfm4+uskh|Dz5ez?1S9-sOnYg=GdH(e27Wv(UHH2*QBrY$5> zRR)l5n#T|P$R=E9`CKGbSabkRMAcRTi(ZwW3iRXVmEC-T?X$%(wdN_Nt{R59Cv_V& z`HV%cFm1z;One((c9Ko&YN_c?h4kP^-6n!W(;!=LM*Z-Zp)2CE*DiwMpmDYx7ZC6r)w!E}+Mef>FxA4=yGY>1ZIq?AdV>IXwzll$* zW?h=!byJGQrPSE&uV&{pDz&*Kb?ck>p=vg){(o*22VHO{rYpAv@B0VNekatx{w0aD zRQ6*A^gigR0;ghcfLhE+l9aRqtXfYdhVNX_w?r{TDpwfPXLnKmQ^KpQ6S_gh_x!Z)JXXx&6R55p8jrZ5~# z*{XWejgNXA^YzfpkG}6HR_y?8tI85nb$t`E^={!aZH^NC{n@;k?htc})w-iYFUw#S zizXAkqPOC$(^TV+puS#&Q?ExqF}v)r?ieYC4N?B#^&A)STXP(D#RX%#IN4EM3vsON zW?r|BV{n`VJHyE&;YD~)#m#(5G6{BulSy2Q(L3D4UjRuDOI=^96q0Z;4r8dcM$vOy zU#(ia4v@#{IO?drwL*`ja=HBITZt=m#7X#sMemeG@qj*h6JJ(0sW{j~PS!QL1Um|7 z(sdnE;*JJ0MFs|xYnJK}!4a?;bI}8s`;!v&Fb#cWtjMhIhL|jU=Y8ut2KP;{;ygZt z#aTVe5xODPgkJ`zhvD@dAM_Ah$a1ONv(ohT#r0KU`wEmg?r|g(n~5Yqj4B&%aT_aqo#=B@!y1`9+9)}11kX;z^NQfX+ac6SGn2_m zECkaFim9bsoz~0~lY+wF34>=dl!GBkZOCS$Pd!BGe)f_jSV7pDEU$F&?u{Isibbv) zUST^sC6bq}QK=oXWikDI7>9aEBSHpZXu$Q=ADxXiqLTW+I}f}Xq~rKMz0R(jKbPld z(qA@^QeE1))b3Upd|^iqZpge~O}H6}@D3GG<6(wo;hl(x$8?wQdLk=KH>r&JqHT9Cybe&b2lRf+2s>AVy z-(+<{4RCi7bvd!Re44}2JEMIo+xWpaB!yA&p%}ZtSDfB2C_dX`rq`LJ5an44G4sDH zga??7l6CRb4K@*l@R4)dODd_!=i#2Rel_&krFN^z0rfLnG|}dyjaOt*Z|Hxip6zi2 z{DJ9BfXX(vAO%!56Hgj}TGo3^ijH|1tSw=xpKAUfC=IE0_VoDOv zI@7y#Ha`gx3f>5tSsl5Cv$PZw0Ldd{kyh52RF_X^?#RC~l|Eqi$u*E`Jto_rCoF4} z`4EHnf73WT;Js}&-_zVNu5T(l(yydCt|v_Im8t58MsSjQS~*(Rq*M{O#-%Cs$bYGn zAG||m^O6>h;Um+PLLxHRsOU*tQ7_>|!#6RhS%PQden!jeBf5Wj&O5er^v#1+hzmiw zKG#>D`~|T;rYsw&&u?kzxGke5Vp2+U173Uv_lVa-s6KC$>u8%nPiKp%=0IPWOb`4? zpwDmyt)ZZ|ZNzNz2EHuU;X0?(y11)9`nq`6>1-rj#7Ad8?IqL?#(g@}h<};u=#XKe zh&m@4LWDe7nGikKOLh@Pl4}ibunY{A>TLgny;; z5}jRjzESYb2d`FVd1c71J#;D64}RC6%)9T#3)32vC7b;-{~Lcu&-n3d+6f72vg3sj&({GLf_+N+l+`9&807B<8bqwwhpt?-(j_1 zkf<^SpGWZ-B8%c~Gs@mNVsBA+r6M0eyD zTacFy_P2h5fzxK^>3sCvZq3fO;)av!@se3bt9)mZU{QVdGq(ELGevG>+_<%&$`J!L zvk70C=jeA$I+oBu4VP8G>IEG_Z`zPPY}+4(ejP)#fNDl?6KF?+mb|+z59T>KX82;V z2+uZbGeCrD1f-X6>aA$iV&P2|MLEdPFF{ROePC9#orW-75ioy8jVR0+0UPupfM7Bx z%0bUYo(fdelCRwURK6(l}M60VO3+AKb^z)`6GFjJ-jmlimh#_6%y znG6|ih|S$u{BVI|atB!oh3ihEYmAl0EI!%kSe!~{rqa<{f;-RRzdFbSBfeT40_H^YRk~j^6yx_@>SHMa!Dz z@D&{#jYS(J+ivXOXrC(0R4Asj9=#y=*_r%s2S@Ip{ZxN=Pgz<(BB6oB8pxyg zLN6!RGSN}#*b}Btdqj$gA|-YDbzJY}cqC3@DiWoQzbCTGujAXhIR@#EDby9$^0wU_ zkJ?JhO1nGe+TyH{R94qu%)PGVBYQY@#!0lkQUQftGy*;CwLG_{V?u*iyWnL-r}(;4 z{D+Yayvfv3S#db?L<4i-1oH4}`G%g3RwL6%+>*otlHM3#sH9pbPh5m5{*U1Q9$K~d zAL(yD_jGj05aVty#1y%aLU=77)XRbJYMLe?N#X}dU5KG@Qn&{~$~@Z3k(U9eGMvMp z{@)q=)n1OS86+z8GzyY$X7E3HVN#qf(@7bV*pT($48sgQthWQ{p4ruMf#mHOd_G7r zG&d!R2PChOE0gAkj&91Xxs?$M>Mb+)ue}`|GXOQGP%8|QM=d~vX#L#Z+tDI}S{W`1 z>SY!+40oHL&M1#kwhGh>X7CsKWGS*winn3^SRaSjR8O;uxKs|AMIgFTNj-&# zme>%7uA?+fM7GE)sOzFny5^le?dpQLBJhq^ydT%f+d7Fk=90z%^Y9sbLtjUGN;XKB z&_NJILDX{wKLn!bnM5&3R0X2;N{vmms*$M$<)Rvj_a$D{*O8k=870R9+B4Jns(z04 zmt-pA>nJoX0?~=-(up2PiV$YCBNAK5ef{7$I-Q@c0a)5A3ZhRH@Lr?_KeBGq_2ICow)oxjjOYelHq@`LE<>HHXwx@01$-hqz6Kc-Y{Uz0JB zXe-t+pnY&UpE)3_YF3x^chh^yOM^F)anrwbS_@103CpGl@iw2zm(Y z4SJPoVYv4qaqoz_96=?)Wv?R2F+no{|L7$Cy{KC1C;CxM!t4oat>oosS&oX#andU3oxMRTrQ4W)wulw;(7Y4u~5n z?i(tC;zs6zTe(7-m6oZMm6eQ3YHl%Ro@~)U&6Ld0%uy@DG%YhjDl0RCY&A2pvJ}(r zciy{im>Jx@Kj6)~_nhB3_uT#7bML!K4hgHLfyg1WsDI5IYG@=m8?=9C)An{s+*Rx< zO4uF{{ebR?Z86bG78{Ajvb0ByJXYz9hLemf+3w^m;rC; zW+Kbpg~q&@gLy$No$jb~s(>p>W+|AoZ0g?09Q-3&{Y0BxRUEd@ZP~Q2lhP(9ShUsO zg5-3TS<B;XJxZxHBVvq3K^Qp|ERWkMjdlhghZqEV z+sOj#8GkU;=7=D$3Rs0ER@|*v#S>VK_=%$+u}BoE5xteHgm(xwg46U2%>&;?(6bF~ zS!XWbMI2)KniCvW@&T>qPD9gl@aALVKQr@kbQZvNxJ)2UKp6;qN^HalC z%~Zo9)WGcS^jN-HJ)SOgRjP#zRhL3}~9ol38LR@^Rwl$5MPZ<-XW* zJ9q*W%dW|v5C~Arq7aJB0>va#vD+=hf=KuZzF|VKFZtlIxQ)xN6|Sg&&@vmmy~onz zRArLSG$lbg*21)UEMIWg+%I>qeBy86QY?mPz=^{Lkw&K}ZGB)_fpmPF^`9}cIZYYt zBf+AHKa_;SrC*Ps*zW!+1(NKEMdceq>-|ZvPUDX<%Zc`V3?=pOL&*vx;XCgh8bjOt zNj!lhd+NiJYYe5N^HfumoRUD2G@S5kZ;(XN2kFY4K00R&Qz08)*@>GR8euPT3}y6G z+T3bExdch7DB_Lb=Qr9cVOPyOi@wmLF9rSC(R8q)59-%jNs!NvqG`RAR&fQQO(>F0o&tN8nV3ABhMdMcC2N%!D(S6s z=5xS?fr@0C!U-?1+K;r>IBPYUlKUuA`S`XVN)05M)fUbP6_Z|(-XjzMeZpwE*hgvL zC)olODJun$KAKYcDi8Td_5@0nFquDtrjx6+pV7-DTl7LQPyW9f6)f2z5|Xn)bYv9u z%21~IsaFyxIj<8O*hkUP45g(MN}wSBuqGKb4syF_yUi9gWSY8(<<>rSc9zi5bDPfv%Xry;Uf8}>9$cWNY5-6CDfb|_o69&Q|$0AA9 z0_>QEez)yN+T~B;2_z}Sv8H+>DSVL9v{GRkcfH#vWsp)Q#{z_drBSSH=52O+a2Ti( zCl-T=qQGflxfLxQr^&+yi2fa6@>J*HV)?wKB9F`Dsmv#bejPz41}RY$buq6AG`Ccqx>ZyQ0oGL zd#W>3Nfsj&bOoZ$xJ>#zpsx&iD-j-y-ZO8cXrVZ*0N#IYr_Doo!X}yl3tk)~h#Tt4 z{ONW&GZZz&g~OkiShlzkx~sEcV?N~c+3l#A;OWj!nBgTh!}V&YsMUGkeIGo&N>S3; zox`=_C(H+Yfi~WUm-E{J)EDM7!@lvSGyJ#Z{HFeN#vZ<$|EWKn%jAvor}LO$A6~eU zQ!b>?42<$8EHT60^#`=Elc=0u9dw-fF?d=xCnCRcMbA(m@-)}(G@VNGhGWrFSWNO2 z#2jWY0Y4cYP|Pa=c}yVoM1D{JeGK8Ey5veC0q@)hC(CptECtRTIRfY{e;}8c>Q`?B zq}wq27C0OIaZ*j3mDj=HdWvmV6DSTqDFTT6fovww{ObU5Rk6b>kQ;(D;4~9B zPx|Aaz;V_+RF0FwYcIj3#_-K_8_Wh!v;b-m0AwmOt{mvS z{Z`H&bR(b=6DSWr=TTL;;5GLL$}$z|b|W0Pu^CMzaK2}p901kv2XdM~&2I#hUCPfPN_e|Ms_~Fu~p%0b0%+z`Of4IyDlzA{C3c)AY)T8;M;J z7K+0G2@rOjrmVo8YVxFkr=Q@-_E*ql+W6TD3g#Fck<}&^*b7adYyc$-pf~-2L`vsW z01Cq4F9UG>0#0Mb*=ut*WA8>}MQ7l7>KmJVxl#@^<1Xv|8v&-8zC>}O@JT%e1kf%1 zKxjc2XY`G5JSI*yaAe@n+|f#-!MT#tRHNsO*lohK2JEL$;8~64Tq1D7|1`YrxUsWk zRdx3sPM1e3NokXS=RZr~WiXeY?*r5GH~hHqvwR=U4;JGKXN22j`aWy{jK#(m8rFp9 zE+B*NLrp3eqg2BA9`cTX^8?QLFsAHD5@UUFlV2t56b`5JV=%u6CUKf1eC=TFaQ2UA zNK?itm3(w10xHX-%fo8g%;B_btRIv`;xb93P~5{eoPHduWK`SF7O259QygR%cu0w% zDgTCt^1>4mE|hf|yVEFqCOf-TbRSN$v#_y!?=aexrR>C%%_7bc#6q1?tg2mR8NsvP zVEPiFn*x8OVU#gWiKgS(N*zo|gDFKS@<92`Fp9iG875yDN|WzUmiVdR2~r~hZfMt2 z!=ks;z^YiTp+-AD4J;x{0}wqnj8=_PQslKm>BKnYDO^Nmsaqm6u!)3W0V_=yyQFg9 zE$RW*w)ljQIPkR@M!Ux=e2JR{?ra%Qe)8Zh5i7voxgNO1C&2fBPeC%V^yUZd3ItD! z!OeF=&0_N6^}sDY0iF%M--puSJC#;`HY^MTFXhF!p%gnoseKh9fh1u$?&F~}Y=Y7* z$Ik|>0&K9S9xlKTY7W1inmD4(2Dc0FQt;(7-?d7pMQ@8lI}nN)4OaeE4W+QVQAC^F zrQDuiW=gJ%b#Vaa+HGczr(yYThES+BZJD4%+!{=2SqhZ*R#YKZWVatOtAJ)3^jU@m z_xpr<0)^)#;3^3r{5WObgOzDZxJ4<1?*U~CWYgWs{XUYCK(Nw=I6F0zM%<&+sX!u7 zB&qFZoO+HNm}4Ly#9(cE8`yx`_p5 zQ3`o+pnQ)hvDU=5LLL2#R^0>Vmtb-sdltyI4x#rZD#LxUvjSzO;q36Uj0m*0hU}ph zm_=!27bxd5WnhW%%PxVODzXdoj|uvZ2hsXT@MH;w7JBk>>fJ-=)FiA2TO^)9J@;Ta z^_C$t=3cBr1d|8_OF`20dJ0;QLO}_ut*r$8oI!N>UOxpbQp=DajWrZ(NFDD}?(u0^ z5~w9#MEB=l+I^o=XMm-pMPiu|BtM{+sQJ zVa>^Y%32&k+0s^UNf=D0CS(2DQo`9Lppx=Y>c1ojmJ*Bqz z?w?Q322-Htvjb_~6eXU!)$-(7Y(m-Wc37bvOb4f+K|VWPspQMttU!&^u=K03Iw+@G zf-dX~z_<7;bA!(@m}X2>X3~^wrBaS%5lfppVdlG5t?<#C z*;zRa4DV&q>}g7dkzijIl>{opu5Pbn(wS*WWS{{pI-$TU(5=j*h7VvDgcIm9AeK@5 z+hx8C?@^J!TGvaU#V7FhfNxSJop?aW49cKDe0Fc^FYtd0x^gryg9M+zXGgcxOj`J$ z(mK!{o&!I zHxHy`)8Qq*ZXoTNjyhFvk5VbyQZOq}LH@k!3ZbCY6lJkn8|e8dgPxyuLy+kKvXJR9 zZ<28IH6H88Yf&Go52Wc2L$)-K)<3M=&lWe>J%Zh4jtpjDuV5InqnrC%3LFath_(2H zJ$P@w&mfxk2)s^%p$pAg#n+z245H{ql{@6$`_artaTI%BKT4dT45+|TVzTh+^E(4+ z#SEp5PvH`wu+t<`YVIF3{e+@8;<}p!F_n>6IhdI+&Iy6eZ^#c-Ib~_Oq0iZ!0It z5=0_RY4@SJ^$)Bz0cNu3Meb&U{!7psG|pPoX13A?7dQD56NG+04rpEv-6QBNbkG;{ zr-QSV(Zk9?O9DZ&r(#{`dY~4)0G$Q;Ck1^d9ht2(qIGkW7CGetoE=TW37gD%0H4re z2Gr6@K{t^G*v8@$xt<5U+rVe!bZRYk9BR7t5v%UEns{6qB%>%s@U2ZI(QIxK&~A0Q zl_tzprsklW)OL5c1(zCrWZTJTe89<)%;1-Gf=>Xqkav)M*YeXsq)k|3;4tM zdVtW5zf<6k*By8R8ILc39Gr6lKqnvYz!)8XG64JX@%jN^9B>1^RFkh1e1E|lhM90E zBoC<%ISdTkV8}O7;>u;yW6#o%pR$!2k*RTyz{&Miy8NW!PG}WBi^wH31ktB#cxd)A zmUQYxnEOaq1uijpW`Sovc=BLY&p6q=ol}Qwuu{jTLj(D9gq^d5yFUQ7v(S&qzpEX{ zVC9QRUkdtsrXP%t&;6gKOnVe7h%oH5ljXWR^2%MZpi$O0$@0i0?%|2<^-BHFV+ zsg)Sa=`rn+4bCzCoF#Rr-U225TJ(9Kzr~;47DJP+LthH|j{fw{81jO?LP~@_d~Zkt ze|p31(o9LW>!$>qnm=b&3=MedIw=ADm41FUbH&gLpud)8rJz6UPw$EG*|@TyS-Wf4 zIPP&wll(ag%Q^r2hfd5_qON7`Y_RV4XDx}LoQ3AHC1O_B|gx&3IyBBdTrTLMsopgkaY2)cWEV?CZv zV2bbAnFTb6$5z*9?MlIOx8O-;p0mETq++efGI=UXGjS7JKZ;$fG^(JBs35aIlEJvB zAQw=puB%IliJJ$Wu7an=jdV$kHT2Ki1E!W>G7M4}YZykd@mUpIF_^(s8_n;yfF`_R z!aQOan1ks;KZ;zU)bAQ>W0BvpKvJD`1Z16Hv4$(JoZmHrrY}(%4GM-xHBZpQxzJId z7i0+8fRf$gal$bm1p+GGF9m5ADQPjb-7CO~{s*wf1nkdvGMo(t>DtH4g}FDG3w-m= z2aJQ9d!BiMN<_4wr`aVH*+n*FgXyhXXw_0>Yz6&XX0rLZo)-n~T;3NEH~TW2RAN@p z?&vT5FR3)*g40`K;z@H{nF|Eo2-dTuS#q0Rl}ViTi38JPmT^j)^vcsp?8IOJ)~F4% z6NP|0+-~ZD5H?CA3loQ%uPVzX&hCJJ1o(Y@L{=QN$W>wnU#0wsJ`)^$gv5VPBCPvY zt}4Z4N|EN`gb*yBi-R2%frTpBAZj9jLwE);*5>QBJY#W+s&Dz;$F1umiP~5SqS6eiyzF{Jar3aEnn4-YCCUcTyBW0fxv z;-_79cV^olcV_&Bul6c6ucB$8$(+3idp&(Ae}z&f(Z)xGa6b^+54?sE77PfdVo1fhPlF!&hbr_E|+~$^*_O%6?9XsX%RO zU{Gg+`aY)afbEJlaF4~&Ae{3I#&((1vp_vYV6%(jVgp+YvC1_O-zUfe^{str*mLGW zI1Eru;xdmy?Ey)bzV!UnNNkM^4NF1Nv@e}_PPwImpe&O_dKy>q_N87caY`px^Fos( z8zfiy(9)H@v0S+>qP9r6*cR+VhgbS~b3YREU{oAPz7sw7O7xa~CA>h?h;kl}$&&`2 z&jruJJbo%~2J2LO_@!SsP(D!37oxcPq;c;4zmtDe7#{x-fhAI&#NHVfEn^bXh6 z1$Xr`&mQpPfybJox^Y#5Up=arhQdU40>oOR8;8Y(uH$=WwSnQY5#AKxOl!kIr)m$OlA2e*Px4;`tf*m$5V#EM<`8HB)L{UeCTHhN zR#>d!RphscyY9h1vJbwli^?8c?8Kp`QjpxrX~LOoBTZS+H10(uaY!(|Xg<@P!90;| z2KwvUOsD|*W=!8A^}<&a_o7lu4D`y2p`{5Z>k8yDbTYhJx~9HQD`d5te`l|NCbD9} zU8dByPg6LOm!knfRu+|9aDkmz4Sytd(V6?7s&jzx9T->IuDE&FSPz zO7{wt+OpQO@Kx(g-B)3h1>ax>k@IWbC=ni0n6v^XDj|$rabCMonYM}B`oZ%W^T2JV z-dPwCx2V6p>~J0!}e_OxO&sV)wmEQxF`wOJdjKgu=Q>db`N;QG0!;J{rT@m0&an~ z)L`4jKj$j0It}6D%EO%;(H#+$5W&PYSCV@>GQqqa{^Jc)cp$76jrS=1tw*o9{%#WJ%5}IchMfGkbc*-OaPLBTGEL|<|%cn^+~@(CH9E?gWa*? zn%h;4Ay1ytQBLSZ$MTf;@H(L9%OFvach>4fVQaA8aHS_rUZc#AOM23&HOfr6uqRDi ztKgfFJ*jxDvR;0?C(T%=%$7&?q|56N-?=Bvd|6o`*EF6*Q;Jq6Vcvm_d-k{8rd#2N|ji7vdqcTcPNcZ9;MUp@3LD8=& zx3|fakZPnXS5EC>Jngt(irdXutT`!@BSj>zsOFZfkfXrWzJDXxS-j9dP)= z9-sBLEuYncCTzlWy5k^Y6D*eAgGRgtSsjF|ooP2OYaRBD>juf{DP%naS@AvSyVoGg z0U4W>Uh=u_v}UuiN}kz`y1%aUm$!GPWv@f_Mx>9^*_37DBH|mS6N8@g&bY6;TVOi9 zY$wG1)XTPfd3SGgfs!mqJ;}X8(dq6jO0%$bLXbC=R&7zDngrVqYo-oth1Lne?a`f1 zY=Nhh-koB%Lf^^)W&zU9A7{RyzE~Lg9=NAd0`-kxeG!)qeg8 zCd(_+sPZ;=y3I+WG24{M8FvZ%UtlHA$eTz#CO-+-<-9cr|DiOBd=sU;cN+D76IM+Y zxNkG=%~}<>&LG@AT#8`TM|#?pH%OzSZz^Nt>~7S4yV6>=rP0LgN~XNJEA8H{^w0PL zHey@d&N8v-aKoHL3!ZQbHZ8jvIcXeP<{I`xs&|+drA?lmO8fUK^=Qiu<$gKSeDS93 zRN6=(sn~ar3X|!vT}lIaMmJisOX)6`cB3D6DM|Lvp}?Y0tv0oMOWBw41K_!FSc6>U z#-S$E%)`3}-TA@3xD6d&cHsCIx_}NePjCqk1BxuZRvf=8<0|q+-6-X4B{q5y=w!Sb zU(W>nB+&DnYt_5Z^tVy4@9Rd}-$oW6=tkl1D3S7@Zq)D{Xt%s8O?*dbKxO-saBj*u z3070SHXAn(0v9IpnIQwIU>X~m@{it8o|TikdGFY*%#$LIv!;Jy-{VhgW8hXyzWn@! z6uSH_3c&j*)V@%O&zK9XI5R49>K`^T!$9Wd&M+RTD?feB-NUG^cVimfIZ%sbDYT|g zd0w8A;!WA3G_=b*yV8Vx=#)Z|X(>OyN~Z1m%+AR_MRv>!dnX5C-49)?6m@uCsT(#3 z!nkw#v=fbaUzsK~q%DV(Mqwx6Tfi1QkxcS_WwLacW)-2;nY&*}m4E5NWn!7MkHcc< zp##b!X^k2G*8#*Y>B9X@6y5rP@_;najJUK$sZOOIC}X7zGhoPvplsKLR(z<;mLkls zW(Spf<-a=9^9PmIBT{jhHg^sV(^^>DGpto4XLV+)6`59Z7-kWdyUoOxfWozOxfG{79J`&h%1N?+dmXuHx8EwB{qFJ01F3QHPr4qR1*2 z<6giLOA!7x3%{h3`(!uZN8$TPD37=cFyF#u>#gWy8n;$QHf}uKdq_!_CwHc;hm@r1 z4H3zV>@RGiRyj&7YOYnOO3KHuOs~!qT?CE?KSuZ5pfmUWvGfa z>F~Eo_ly~>3BHQJ? z?P$zNrFCep*5&|_3YO|My|0~A4%!{La$z^`V?Qaar0}ZHiL?B_mY1lY4ek0_86mf8 zMd5d-v6Q+wLh+{mqTDUZzqavi{#6;_u#W;=H+#)T!@p?(MbReOetzuJ;uh3@jXI2C z95r{-`adwV=+w&F>zuM(lIyjg%YQ1-@^h^z`Y$vti&~lKtPUJ@9k44Bx6mT)C=Pyu-lkqq|=~fYp-nOo%fe=QI@rqH2WXrJBQjFqg3ZKwHCSlRmP_0 z`qjZ)35SUQo{KBUji=pa2e>0YAsnYMzy~D^dIo+FiZQLtBYW##P-;q!bc9gu5v3*# zx~Tjk+nP~E8Tw;K3-7Kn2%XTRU#}T z+}*zRveHC;wHY10jHdg(rrz_Hl`zSk2#(+9M%H|@mKq_;HIgVvR!_)ZG^cR8x?3)5 zN{8)gavRo0Dl|2h4ddJM=QPHtzQjOzn>jPs_*o9>>`)uXXAX0KF1IJ^p?&g8Un)=n<_~`J3;mzoBnA$$DD9XIVNp$Jx2jIhsOc{l{C|Tl%o=rpzq)@s_-vFK>t8ajbiiD|(>?P%W!@6qNBr=sVXgLqoHl{JP)JW+UI#OGW>RyI~^My4x zgu|f5Q5|3O4uYHCm=4!cqa}|4mvMsO^qYV~=Qtj4-GksJazQ}c^UWxBml{cDpRVDM zju_ZE?=tpHrkp#k`a#&YFgB{tW6e-cFBd#iTC!aqi(~%Fu^O=RaZ#z2aV|YSoO!&OPLIbm7P_L&(%nH@|xQM zD;(FWGmL~MhtF64RPFpABd-=acX?)_INjPxFpQo#`+E1mez0JHMf2PC$T<#7pEr6 zb?Q@Wyt+aj8c*Bf)!4A#;!WHK;&CsqnkZx65%F=aa# zR-7r-un=4uEekz{_=f0@9*U#(4b|!L@HpDc?}OsJ`x~kwq{Ina2(kWab7Ce96P$zt zCeMtGnJ~ha0hp6lD~{E`jH9s{>Ua`?G;n5(THf5oYJ^>iqrBE?9dBV%HNp|qt{!){ z_{0^srAlV^))HaA*Nljx)INHI*V$5a$@V)C_U?Up1IlWnw)FnnTD8mg0!XSvSK6xW z9N*N12xYC-nqt%SSnq;%>T*Zq+86;1MIAVq&5Esxp_v(KJ!*c78bY@vtN+Q)O5Wj} zRScmcAc09LgKcLlt>~hTaHQZjdHP1xVzH{XZdbLI%p4uMF-J_S$q`=X678u=(^J(E z_FnjXr7R+nUaO;4qj&n~BfSID)VZ>wT{J_T!~Mj6^-!D1k!xy~YnO{d(=7U>+H|J3 z8tWa>OPwo4w)LY(5fm+IdqJ^OmKW9XA|b0JxqdB*?T3&nQQpn{)Dx9rp8*?#JsEk4 zI^s94UgUL1z3{fpw!A3Po1dvJs~r1Nlu7he#3fpc-)w%q2X`M_4ijq9?g{DyZ{h8# zQ<7tAdA}Q>&XG9Tca7p?7Xg?Byr*BHhazeHXe9e0ek0jE$(dHII=wboZ%j{&QJ;~u zD6ckF9W6PEnE!z+=Kr{+$^Wi)iKf-0t=Z}b`5(=Txyl`O$6*y_GRFVTj%v8~`8(Ch zQtVP_$r4?NY=hsHwx^)&N2(Xv#>6~!{vMbc$)gU zEWe@9%!k0gyZR;i^{&V`?`IFG`>=3bot}SKz1U2JY}Ub!=hp z%hj3T?;?&{QU3niw#w$jGV59Oc=-KR#9uQ%9dAZ>Ju6gP**&;2B|WFUDHYN8F8 zc^_Y?o|a-qK?Sy7f5#<~@Y_n~K}cKaFl)@Z7g(=jfM&`=c4Q=r5f<4D$|#3-=}YQ) z$^JPaV8jMgazExe4J*-mtJPtS+W=0vN!T6f=us2o-VPe$QM)_Zb8x`~t+w|a4=O?U zWFT9q8fWKJZH-Ft3zLvqe5+tlD})W`649K_ei7=RK5NxYj%);(hE>+7o8%UD+PzLa zAL^D(L<~3aP0ga0)lk_b)3KK^yk8)B7p_-l$d2Zf!0KwGMo`Q~^%48~woCNwG`%Z* zwo!FP%#tv$XG7oVDt10@d*LCxQ_&pcShIXJ-BHXbFnAZ_gLfi$TWqWuO?6*Y@3JpJ zWQ%iZO?vTFRjKMl9GkBzo@39c&FTAB)qY{Icr%KqPKQ_P(R65&I+1p7QZGj4BE~X? zgxutW&#}?r*VLtvcU>iJgb|lWFK$-9?-GBd%%}<6mB?dU#k@e)mzmHCaoBhMT?@jt zgPxV^g6E1cdTsCLud8K}eHc<(mJv~#PH$1C$ZaI=n60WT+0Oy#u}U=?Qr)=lsx=yk zMY6ogwxT#!6I%O*+D_hPqhoKVNg2-pfk*byEWDoW0?u?7Si{v4JC-tBeB%X%!G-+9 z$R1T}Ze?saU4}w}mWQkBCCc2UCfchaJZGC4AM0v@VKi2jc>rgV-DUH{VD7fmoxMTx z?lv{f-VmudxlPS>RL2jqbY#7$hT0u?o%E*K#E}O|Dw?P{X~&ytjdUzwg&5k%hBjEj z3WYCQkS5)bBG%aE32{$GpUNh+)*m;4w(54Zul$mYhHY2jnTcd`@@GQg%_ct~3~n9& z1tvdCqW89=C7)!YSTAr73fz8-i?J|FmFs8LTw&H+pII^9T~`$+OiWyZmd*O5jTU;< zd2*7CPV4~g5`kNTaWNgZAuig0bd2902*Q2AMl*M)W9((X`F4jImoY*BABTl*8W`j0 z)F9xyZIrPSz#j1} zA0Y~SZ7&(w=rgx0gtT_>=shI77CGKhRkEW?r=$$L@k)?W0E*{d#-?9U_e^utU#Ag!g9WAtD z9U!ZUyE+EC#&2Aa!V3|`Z)a6^i1pi5)$PDQd2QLksOXjwyfVTH@aJ#%X*ZNb`-zI4fQtScWLvac(F-rqsZZ3dSind%8RSBL zMl4`}>4_kwmm%CpWnnmtEmGTFo10e{?g-*u=*Rt0kvhwQH-{FZyRjuww_3NsPu1HU(^zuq?bz`A_)|5+aSy*bUq^xa z<5RUv8;hLb9IDsMHnjvhg(EM}<*e@~d?Bv5K_!6CVOT3O9q{Vx``BFWIDNmd$gvM6Y zYC1MEyHB3uWqx(ZT3xF2wVG1CMFq8sq(UQ!MRJyARPB@K-{1VpNMeyywZDN~nbzjf zDCcYSR=LApbogtm3KacAVaHKd-~Wf&A6H}LcmDAXJFdn_*B7xCeNE#a5d+Ibc;EO& zZ7zo#L*o8>Y%dLHiV}V4TXlh>E_f(+V?<5wOC@Te)DgNH<)uh=>Rhsm?5TX=k|Tdz zB+k128JLEyfHTtI)agp8`mtQ^JRSZHQ|_#DZ0cjW6Z=+LC=EHOrrS^df#K3!dR=nv zQXJm5PpY@cQ7t~)I?uTB?y5lScT=;EG5bFWb{)hL(FPKu->kXZlsMGId#JX7XiX0HlMVQfqPI*^T zXiA}0i=1cG<5kBYoQHndc-D(Y6Pxgdn&7AgF)MymoHS()zWX%g5B2d{bC{5Orqhpq z%A;tf&GylBgpq3_Zdp!k7!e_#JV#0A)X3;>poed{1?jF1GS=&vGc@KLCJGOpp%c^e zI`sEB^%eQ9Gu~Bys>3Av7Eo0ktJEgtZ%lXw{Xq@?R*!TnkWwQ#mkQ)U^J%w5ne7lp z1y#-%xm945xK>Cs)7lCnsl|DWO4weV;-9)ioWfuOi-Aixc4!KQ|V~C{7!R@QMEkRy4%pT=noW>?jTX zjgl^@6Xb_}rxlm5`O@`w@AUuFmC~~Vv??P566Xp;Ux)pw!e0Z?e`bSo;y@b(Ur1xp zupzaRZMih4o?@H20c+}e5Fb}kiv~PivnDOLqIT$OD90WO0pbb+#UOCQAGo(N*;q%S_Rsl`#1XG*}%){rnz;Yg@M$4lZ1HjNAfF~?~ zlG=2|q5aa;P}!`expI&O30-iNQxHH~3jnm^=vjx>;<`G_1;ih}1SX=k1yNGl`*dYZ zlH@a|X<3MNUVh{>EezG}kRLlmXF|0UdBAB(s-iWNzd23As%R5?d&JvK{3qI%?|b8}bx5`7dFV%v#J}8hwi>4R?W$@G z%^0IsodpoTUiA@v^(103V@p--ZrO!nyr?MNmesUTaz9I$PdRu*8_GFjjHf*{#%TP; zYZ!$66sTM%N~571Xgk2kmvZOTa8k1xS~ahuhBh`N`K)vew7IByXMPAoi{zwpQi0Z! zvZJ&pIvcIkxHbsax}!lLmwzq?Y0e;t7*}3HiGARI$K)@v+VdYw{vs$rW1}=@FC#`6 zr$`_b$)<78j|=0VYOV`HI#iD2E+aKsi@iB4M+;Zxq9Cj{{II^GLAAB$o5NZMtOtUy zUhu;@_o@j4zx#=n#cC6BrmzI&E2-jhWt?P%Wrg{|CLpXi)%>v-YeZo89ow4QbkCRhVwsfSbhrg~+>=$Pnj zm2DB5XqFR=>f`mb>fS+d+I+jb_#_=m(2`nvK;^+!D zk3{8Yz#t04Aliyd)^rQY}2Xc>|`ywn@sPJ5GGC!I~a2RdrEOW~W5MmDAA zco_};mXeY&#yNVNHvfQ${I+Dx;jlmcbs4RW(cSgZg#DP~(>q z-tFDAWp;Zibh>}C+Dg9Vn0ICm?VxOT0n`Xt^p$sJFXX;F?zne%A5Fu?>T$x4MDL}( zT7(?i8ZwMb|FVp}I0nNZ2Y5ra=Kd>m|Cf~1Pb-#Y(W5KXZrCE!o^$Z>1RcLsOK_Y3 zhdB(2>5o;X&+*#gcRh}jINd@0`fG|Kn`yK9YjYh_zW^Mmdwg=u#UnghQ{!oO@;O0A z{=N`b=3S8F5+gz$;XREsF|Ezk)axCn?U#MbIEly+7BjC1Z#WvrT=bP-&T8s?V=#>8 zWA+3x@54&Nups7{7PF@*l?~BO`FKkLc^$Rkf*Hiy-r_B3>a835AUMM`-CJt>=L2 z%GisN;trCrvs{Mz=Pz*8H}=?!l+?wW3&y#h(DReE`&t#mdBV-j2edD!`UP=L)!clr-m!ElMPNZi zyn8#|uf<4?n!v`+YYaU&Maz}z7E$G?TCyBoMBS%q)&wDf-ZpteHtG23uovY!Uyqj13X<3J5+TFkaq-qq8!N|HSd z6gBR^vg5voHLpakFVw;XAi5a?FxN6i0#=q9n1H#KId0`*#p?#nR`l+pTJwy02;lYl zJgDtygA4rqwoaK)N;PaPK(Q|02J7+wt`r2^yvW;r26`GQbNOlH3DT&(D|7lGBZ)qZ zR&j>0MxIvm*yGw$8Mh;VHToJ7ZdM~lf-AFI5b#}}Q2!@1cc4OrfeNhyU$r2wfc{}DOg?lFi?To76$r{r{`&Djn6>{H|kyYZ0g! zTHvRHz`Q6-hGw=F6tx&rsW1@mz_2#Gv{-vu{`LSREzxE=(s&$LutaNtWw(+RbaIK- z+`j&RIU262N$?5@@dF@l|~>D_L66UsfPRg&>yEZogw zVZQA!`H2rGJXfnDqp>Nc#fw2ZK9F{#pmqAw;>Dot9zg5pWW9O|ay6IaShXKwJ=?Sx z8n{d=a;#uYeOfq{@T;*Ycjq%&KQ7EhHapvygCTVPFM;1bd*9~*#Mz6&{OvQ^t#ZBn z<~H1p4{73Z%vN6ekX9_$V&#`V^lo3SwUB~AdE-q90_|81>eW|hOJrGopGW@AF*OB{a^NU(!*oD1ZAEo?|1Kz_gYQ?f+I^?aWThmGV zR%=lqMYgPV?i2gzyVcq`dC>cG)T6bp)&t^LjUV2F*uvBrHNDOAw8c`T!glUg_Ir1) zL2Fwr6u3NSz05SJ>3X#H@>=azgXZh^y=Pw5M$4GaqYw?)ptW;!Whx_Ucwg1g)_DC@ zb9xVL&~ohQ#y~<;$O6f%kOi^}xA1b;jVpVtO~FG^cM~FnJ z{%Did#2&W?rFwT{oTC&$fwg(z?wRBrWRYYP7Vi@ zHWFX$09P<4#X0h;Z7 z%Zn+?9g?H}+pOL)c+g}OY9B;y1Fdg<0(VH>&wS-AoE_HwbW}G!1&0v}?n3(MZA#g% z-BLZZD{N!l)Oo}Ril&17TJ!2zW_Ubq<$l`;kEPH9n%dvf)qMpLVMAlQBFX^NgoZ34W%r6{dLaI-re~BH|Dmmlfsn$>DeU@&m0| zIP)3P4|w6cx0AFFwf^+>w_3F}EDZjArce)mcMTVEAcLC+2^-4Fa;IBjqtzd3QyWf( zfv|6x$TM&0XWP!2qApsJ*xN?l4lq$&1!c>A?SWL=taNONXP z#~Y7J{)PJN#$(w_bff5%afJzzVKXJE4nVGN(*qKh_%DG}v79b@4%98RcN!k3QCJmE`odDEbp^x_vt= zWEh~}6U`~l_EPaDTD<)wD>R}=yG{OLCrvKWCS=@+P&Us`K<810mArEE*hRAVOe)NS z#x4P8SZ?tKn&*LC6njML6}l2;#;4yz?kqT>#mGyx)8Wsw_#usjsC*U$x11Y_f?E!| zScC_OY7ZQ~;$XsVEGWCC!yBkwu~tLQ-bo8T#lGDYq^wwLFE`&o>xnNPdN zJkgtu+04Qqysgm7C=@OSHT_I$7YN`91mNk=Qg@QQfG%M~USZLgGtbHvK!oln5B0c;YrIJ(zSb;AkX_zpN=`lQgIwt<{!N6=Ee|DE@o^FQL3t>&{Ae4U zIqrjmmb(Pmz;AqzTV2H)Mdr4=bhWE^{x-V&jSn)V)tzEfqo>2htc};%G zsqE&DGqz~gSG-|VYhR7n&CLTBJWmLfeXHG*vt*k&iLL=c9@Ja8%mayeA};hQaXBJR zx=P$5BJSeWikMSH+@EG#PJqCPBJ%WA7{`gYAFdKNO2nPGO59Kp_r+D>`ftlIQ(ttI z$likS!>h!lin#Z#64yz@y>*qi)*^136_+C_6`Q-MhK!6XZHybinTGTxwYTgg5Ba_qNxQBDiZr`;&8aAK|tXO%61<@GXjG|FpX6)O8tt1W-Cg(80f>ftSv`4grYGq%z) zeoovhG|32~DLe2XnpWFr{V!Tue)@U$KqVkA2&j5?pvqLW==ZvH&ej+!|2A7dMgll+sMaNaX$ zJZ9V$zc{|A*oZ3(qo+@4P2|&W(5_Qh#=-j+r?lIv9EO6J=H$ERi6lLWr_?{oi{GH+ z(^@Zi#v8P%ww_3vPHU<1*f;3RY3)0?;Ttrf0Rk`mhS`kz2Aw#gHKcxLFfv|VKoifv zHSgqB4(u)$8_$N+=XY(2yh*&2{H`_A2pP?zn0oM;WLNiRwo>d_ZDPhFBK#t(B}O+! zff1vTBFSmAyG3Tf!e|7eoAFpd9rLXKkSge`%ZLp{O{2WAC*77CP~_wkGUHAbQ4CcYnWy7M|Chbf6axBmE!kS;soW zP?n^(q~rf+b>)&UD*Fdxa9dTX^Dmyxs?_;kv<=9sPyW@q%EJpN`~sX7x)e}SxZavJ zUC`=P%{4{}xUwzU?3PK?p4}ATE%!xx&kha^|gLLI-l>?8Upbg-nj*RB%cn-`egagYh0^Z)4g_mO4!p} ze(ZJJOE%MwcKu050jieweuw_19CievxQGpYm6AgAs3vC9k?Si_dwX0MKMq&QY%C+E z-=fpEn`m-~o|%y^*qd>}-nCz_XhaFk6(zJB@7*33=8nf#jDzrYY@)DGy}g{Wk-CTK zDZMQm(Pv^o%;=hPQzM_meEEe@=eC^-b5n3FxmuH zX6+!w(l*hLRglO78z?qRPf5JlM1DVkCP(Oz+`}1(S{tU{p7Av-&KWnFm3sXqlzP3# zh41fjW$xJ!n3KOCkyZ61dFlq5UiJU5{P?>um=D6*4V^3{%c|&z?&tD8^jtLyXR8Ysx&djD`XuGQv`-#`lyMvGOwS`I5Hn*Cf~vp*TTtgi$b z<{#)_BnHiX!`E@`as4`6@4;&}KDpJ(8=sPJjCSmG+%hmcpV%*WKIws8GPToYyz|(D z@5dHl_D)MS(1aR#O5{or8F%H171`;L4YaF&Iv?GP z8nCv9*&!i4BiGXjRc{~i6?lZ$ca7D@_ZM{ydj3#2tLiFQZG$jBZ=CJfq|6wjsWPV5^#HbVJSj2{6j^5jd+F@d^I% zC<(s!!Z7bY5&B9g<2=;oWITcddY-$!lbD8p z5BF}GUb3j9>t8O*DJMY9oCk&|5b(SVIbOuIlABu(^1$fyt`fIW#Q83+^W$44;(SWj z>$sotSF(P!I_@XUl;>A{nP%3~dudz1|GlOHWQ713JFYEfq@oQjgh1E~kEu z}h!Eeo$L)EXQu(SwTap6|IjC`-zJsxPI6` z^P=?!j^91ZY;Qr}qFU=e||$>RW_bhE4p_P zZd`_V&SY!w+y`QqmIu!dzsjwPkP1KE8aQd!%Ihc%w`kB3$6M7(OnBlX#M zx3-V{%jRS2$~p&*x#mdjY5rhPY_k756r6~6&W^Kd=#*0*CTFZS=YaRd>9@&E(3CdN z8`9}Gy+r=$W$)p5eIop+UnczMPLC((sq&#1; z%W~IsCiRXcdLKD@9aA^-Hcr%Cl3Xp1@|)`KDLwL7hlu>@9#k$Yp^&ppyPZ!Mi^t~W2=dPW8n@d%5bvJ006;AyQ&jNgv6_|-nUqKi_Q29Co$Fk{wGY%BB;gT=Ft@rosYW7!Q-(HNRf>cObBUDJOO24<#n0R`R(fI&c z3vUlt4-?^P?lmXPZR;;r)5R`&bl7MJ;LEDJt)kejdSc8#y!#YEcuUxlYiluNQQ@;{ zT{u1D#<}X7?l=FidOn95`x(4mIRX_yL&v+q()YYT6H@fn_Df*LdHdG%af*Jw+~x&J z>82;!_aStwHzJyz?WQ-xxdk}e!5yfX`OEO{VfD%dIEMIMvr_dKFa9M+_D(>#axpy0 zyDCkOmgSfiOmByud+7Zn`JLy@xA8so&`R>t&v_?j=;uR2U=9pxt9d64)^WQ?jg@91 zr4?ng?K#RHqK|NN!f)dqIInZ4{+VPS`kdi5QI{fy>k)F+vjlH{TzfrP?dW}cxbDIA zY(%jm^w#o<{{!Qr$wOOq4h}!GcKNzzgkAareR|7z*0VsKBiU+iyH1Ad_xwygv49a z_S|Ji`-Yln^!5XKKe@5N)0oc8R-?RqAJjjRLX{>FrN0p8W>MtR*jiQ;t~u=#d;Hu&of~;rnP0&pjRK&ZG6$PsuF_W za%T|UlBKlWr7z6L5O{}R8~$j=4e@$onHqN`v<$+#4e6Z){hA8A*BGzIP2lx_2LkZa zAiPdXsq$=nX2u0B;jrIhjMw=l@H!*CHF2hMVPHmuETzM3+lXwt;@Y zD-6Q>c?o6A(HlngN4U`mq8A;v*Yu9;yO8G1(O1adE~MDG7-BxLgr?8c=Vgo(vcExE zZ#FG+qj91)NcKHTsMnKvMn-#qw}bI+GA#*pT$wRJc%*pvDbe(ge*f1$+cDV%No zcq-7KwOP2))TnT**8BN!djh%Ffx9S(`(K#f;P$Ab&)2(V?B@XFb01C%oIy$|VLBq5 zH$a#x>PfDzo?yFVF1G$Q0obDD7Vxvh^!$81CBtZgfY*@m;0$8Xh6p9OSyfxfV}g~w~3hJI!%ohzHB6MEt_N*w(2f-r}giO;oV zskHhjz3a8XOiTK}<^rr*5LjCa43@0FP#=`>A5zSg%t0>StR)@suFR7Q0xel}F}}{N zPmrHnKn)k^8IJyl=NoS$=w5Hla9XiQPi%bxviJh-l92KZsjN^eqhX`bR#@GAY`(dd zZ@uFi@8=fjz2t3AQSxGa*tHXmyNKATR$n(B2Q0=0={KL#2^w3LMqez}pOVkdr#qJD zORo)D7zpZs?@ve&XbTIpP@@h@^{KLJzBhlVzS}NOnQxBdo?E83mF0h)^d4TWw|B^& z&+}GZssAX;QS<4{3mAXJ&!x+2YsP!iU)1lG6lQP-k5Wt4*7)~M@g zjJl4_A$UGV(x@MGr}u+Z`Z`JOG1oiUqfhuBWmg^_)7Ad(+!N0NTa2#mMB%Vb)~hG-}kx8 zWaifP`y-#px#yhkd7kGyXM4_b&ap&3jr7J;$e72>!#C}^&CvDsTyfDNN_tgpMiZKc zh0xEPOrHmk+} zZXKl}Yzq!q{k3M{mwgMnqu0lLWAGwXM|_5Zg-_7gjrLJZVZ_xkh`54-0jwU*h?mkZ zqo~CEV%Xr_%XOIGtjC`3uM26;D_G?=eS+4!Vo%OV&5OJ#(69cB7~CDCGFggWmJY^e4^7Y0h_GH^VIi)Lc52x23WD7s6s zK+JlCJyUSvDlRY6TFzZEozsp4VN;y;9jgI^$8A;rE%pQWUDZa#sU_svVxOELKpLJs*1QfDcP1Q#XRkjES3QwU0MU7Z&H1X+CcNsl zx=TDHTw8~9p65{;3W7sW4J4MJ&~Rt*TfsL50I&B634~KBGh?*iBKjM*#)7c{Avho> zovac!{r;-GU6o+HK4N+Z)5v`S$8!4R+aty27t-W>`wZoOfbhgvc6eessP)Z@-tQLE z^?ZACGlf~WdVvo1$OGin|R{y3BdawU{zrM_*BOAuWB~K3a@))A`r!(aIoXWG!{0{#Z-dv!d@} zir#APa334t+o@ zpR{_zUQ=O~RL{a(LDh&w&>FaPk9fmg8%G$B>d80kPL-xHW%Zwh9Xdbh+Hi$M35xQU z?saajtdU4t?@2TZ9w<=dd|51)F_z2aZ+_*Da#PASNb9j2ny?Lh?pR=w^Xsr`<#meH zrTTc}EL*CJBi(ds8%CNp7gFZ}dqTpe3=GT0h7FoO&JQqDEMPexoXskZxHlHia|QMR z4aejA+VaA*Q_(`d7>D&Mei)$xdcQ@S4s&jP29!rVZkqjR+74{y)P2()ne!Z%u^46S zDJ!EJmw|92HLvrU#O@fUEqPCJ+A-RjB&R@&mzyrW*XDGKEqPx2!VT!Rdf2MqFa%T* zgggQ^tYRivrj6pwDtzCHbhwJ_3;Z9PCmIPJLjvkBU6Ok0$vj9VRusNiXBG1}+d1^j zv4H$mFOI+8V3P1#6C|@o5!aKYkat~G7p3QRx+&=`3?h3L(ulY0O5%q`-dbYb3C@dO zf!VF4k=spGFK4T{Ike_2dsI^Vf*Z7x<3AF1l;hq8>0@_9S)tJ?24&Y{Jo(xZE#R^~jbI(XNWtHrrq}j!UE_ZUBS#(oh9E;-a4m=!p3udyr4rp;A_F|niTw$5 zYDD~3C-8ZH0<*NZ<@X^lp9$Q<1m*=N%RhT;(!;B$9C6vBx0~z1v}+ z;$}8+9CPSe{Y6xszxw^DHik6tg&snB zlSZ}A8;nSw6an-J60u4hpIfF>)QfJNG=*z49#MTF$lnoGAnhT=nP$-A+!_32#ih~4&%7Hc#BPM%ky z=)*mBSK|Up7O){4Q7r>r@Hp1>qR8GA77v3$cbq0WokD(LX`Ctd z3M02Wj=V+oPOhQ&AYh&TJt$GH!Po0bUxVS8sXr)I8EDHz0PbJ{et150{=~i@s5y&- zXA-mN&?ojjUCXEwY6Vbt28V!e&kp3RjzJyL4p^wmZ%f*a?~$%oA1T)LH?)bVox{}H z)isf-S$CxtYn_c)6P+*>RDM2{?6pr2E6<^JpV}4i(i|G_DV8=JW_ve%Y7e%EkIeJF zyU#w_Vm${wPxe(}U6u8s|AP-6zBJm;G=%!d)diKS=?4Ub6KL^lv6_X8CiS#z8mcyr zmhOiw{D;}Jdp~qx%3QjXbqTl*7M1_%MDmT=SvW+M=NB%8zsrA&Fx-%{5PsSSueMAB5&fPp!Zj?@vJhTq zgf}7{qse?D+!*;0o~?$fU`Cdu`87X2mv((8CFhLS6P^bLo{0}o8xx@jI4YK5lFkg^ zco4S)_G|)x<;--wmtk>ZB9#DHAc~0f-ob zwgVedeG?IV=hB*k_IGWkW@7P>^-ie6brVV^Kp7S=^3VrB9*RS0FeLo|1VdR^*@EVJ zcOSA3vE&E>w)%eMp39QYllTqLu*nSG9=w^}udBk}acs{3(i>N<#SyP+pEV1=82b1^ z`y%vEQ%!}w$SnkM`xe~B&Dlk4-Jq9>?bWQOz;~~xFj>4Xiw+gD2dN1Vt(9MD>tzC* zIfsJ3u&=l7nt?se-eFPRgJ0MuTEx$1dsC0tQ{YK3n{c~XBt7$`{g&8L3wYOmWnWrO zbUv=x%LW~{PZh22P1i5R{`Gr%q1C$SaeX(l_!M?C-+a`2_7pCW65BmSqfcYnaPV=z zO~dHNyg!^q7aslQW8A^n^EXVpK?Cr=VME(;`!-#k#yirO@ehxen3 z=j@L~oJ1ynLmIyvQ-W`Yw}#cD56;=2?1Yo~&9KbE@(%4Wrch|5w#!l>uMvn<|Hpg* zHJHgJ9L}nKbC-QPh;Ql&w827NnEIg!KxvLxo(b@hBMVCo&VA9yL41*#czPOL{@I?W zw1KdEM?v&;X2@fdbl#pgwg-6Q+1Z9PV~vSto|qVff9ALraN^`O<`_#}2M$}Y#>D@; zDL;*chW}6M-|J1iL9@85!@_JdGv8|H!gSho-rm-Rl|XH}ecs-wyag$3Q^|F~9xWD5 zrwJGA3q;R!I)A~wXv9PyVD6d8B`rZZrfv~_dF~iytZ~vTd81G&SDzJe>ckn848u2m zz(Nfp|6_XoN45OHR<-Z#dA~W+utxad^1Hem!|%1Z=Zr)+d?de zM4^uQYjxC7Cm>5;3*hW%rar?~7%1elf>6i1?RUFu6K6j{d#_?GIrR}b&%fgyq2RyZ zI8-pzoBx-+#NuiVCb_Hm5K#KK<{MH0g*k~@Y=Ks+Hm>pA0{k!MIY~{+amP6pFhEPxKj6 z=((HrO|BkOG@1^fj0dGD9-9ZrlLBcPGKCiX14DCN9WS5p_+bXWNzNU4L?vbeFW7{a zGKIo#!JPBnMDLJW_GF7VaUw0hZC|7$Ow_dr+S7WYw*MA8@xKYuXzLb~iRLZ8%hLMb=f-O~yadrL#?u-_iWUz%%?HZ%~xHD@D8gc*~H)xdfMJdYt_@fkX@G6i?pq+!L!C{kQ2t-pqg+nXUI3klqJ(3 zC&fr-EWu1Nx34cp-=HTS($YryrS)!&l@3=Fmu1m{L}^0YJV0{t$yqlj7XPy^11}r- zRP-{uUiMxVooFB>P~-a2FmdiET3%n;Eh=i}6nd(G)GV%oj&N<{4SF4g`Xjszgftal zkyw6|cXUGu@3`cSdQ+X! z1Tm<;{;~T|?;9N@S4FYPQ1(@MRQzR#cXD?r-y$vnbV_ri|WFM7`2_ zc^=Gmt&T)(j>5C>^6tzj192gj-z=O!MQ>?{?biX2WxFi3Oq58o|!47iiZbse?BH9D^aCREY*HBDz%G4Pl6Jo zIG(yy04ZFgfVWtVWlD{462}uvmHSGC>VMwDeWm7>puvMR_Ky#w;Qn`DA5G~DW>oD> z;Nu{z{!+3lRnPtb==b1JF@pe}^4*bNOdI2|aC4aOx(=rO{iQiUm2|vicPA$uZXmz( z59Bpsuy^?YDazt1fZPQPM#)T%CjVk%|J}_yf{;J|`l=W5XFrRT8lak%g|}-E{XS4y zBhDD4UGgwd$Grr)bw2Nn3qI5FpnM+_?(9KSez279O49KP7!Olr$nD;Es0SN-C?peJ zn?c^|gQaAP>o6E*#``cJ9ANGXh@H%MI10SePnD#P@$U!HjGf2)H2--$vaFMr3E|B%xXeY#z}2m+wehv&Ncyu9ynP+XVt{qd2m7tUvTLI#mo`_hvsV9k*bj?wlxLqK*|& zb>A>EidRUmmKnp08g?VB4>KI5_(!Bc;(=aVOR;|0v2Y5=ZiJ2OdYFnIk?K?RSyFHc z-?#~Jh#u|NTG-Sl>vFvVW!(@W;Islv_3bB1^~9pyG}#G1ig$Wz+7SRK;1WxgvksUJ znS9bK5KvVY1{9i6`zg{vu}&`vo+>SH&4eBasKjfaK<~){E79Q(t}Xg)a6ueyD&UDs zIyzO#5c_0O!ZgVxw#%ePr%4^fhMDy4G-+~Bm|o8Fy(#HY3{+-V^gl(gME#W!NOw#o zO@0)*aRGJAWIpo$AoC1HnlDUv*ZNTT>C&9x@9TJN7*8Ac?#(tjswH?M#bd(T2ORFi z{_cO9Ucvvo;>n`l)`!}?zfPCFv$*Q$1-%M+@lxhrN{ws#)XFR6>-)6jl?|=0s;Qvn zeMp&s3Cr@H#)KtzhBQ9tJJ8Q^8PQ7@0pF+erUkPlMQq-iR?e0(MMrNsF;9x2N^_(}t|~fL%NYdbFOaU5 zr1vbC38_NEMuRT2q3BsK&H25D%BGL1sNS?_j+ElMh(cLPlNoQ|1K-3=Dc~U~$SEwcbO5kpWD`7g*3)~&O zv`Wb7MU&@Alf^N;xDqm4y>!05;QS9Le{LPkO?(aSMKk6@{*83JHyQ5%<$nfvvI(zk zFSC1A&4qFKCVP3BIx5^op8thc zq47CV8`qmCm=(4uGX~$U`zlsb423Yt5Xv#qagD&StLz0UjNYw^ci*0aHz5s^T z!B)ZaUc&x28$~#NDe|-BY*SFh*cfJR8d=jnw10Am&<3X{q{1(w}UPNnR z$@TT#SW6TEZ$0pgv@GfUJ!tonXzgoy(C<%5C&WcADtQXMQ>KppCB(>UB_ofnZ2!jR zwGtfUTAJ{)deDTYrPz>MOJNIb?8U~&xvsS8X(`oJTQ6iY7lO&{eG7p~oIxR#O@%b= zLDA2sg_LTA>_#CwyHdt8nCrjZm7aMwkf#z8ku4KzI#r;W8-;rljuLPDt+J(J+t9!p+AsrBH?#^f)xV&2O z7Ct9EX0vtzu6jFe?@oM-E0vu6s#c>9N!ljf=RqV$7Byw!z$ic{&?RnoIDQ@d#G zY;^h!lJP%JiPoW7`M%t(_=bl1@-TwRqnAgihc#1g4-Vi6TU{8 z38Qt#K%g<5Xv8a+W2ETW-$Oy%+M$SQVXW;MaV9);t?4j{)G*g}qX>Ur8bN}~11B)`%=@Vrj?H>Pfw7LBfoB&$`sti84quUD{55#=6(`_10 zv9BvwJZzUNmevNnrT#cD7h-DK-Gnin<-znK?Rwx)q>Wjv?XOu{qhvMONF5q@&Rw=jkYsEI7>Kz0M-Tv;m)mK|jYZmIQ|^^U zZl~ydsZe@~pRP6v&kD?*j(z=Gse$w-7}>K#8oFDm+xD)x&mi|%Q|{oh+<9#~LP4ii z!aL+&?+%cniHapq^n)gxD{XZtf{K_uQbTcWYs%OoC5Xe@QEHJC*Y9m45YQ@9P+e?8 zHmabkN5SpGs+{=-VYEsNHXCt3WRcs&i#fxkn2^33SpvR`l*(Db@NG z@Kx`xuRu4~>_9H??loIrE%d8d423&e;l3ch&7ae4XvC-3!|ajDM+su+)la2Hbo00r z@<@TjqmHTtq661VqqnfS%c<>|hx-4RVBP^aoJK&}Gfwmo7@F8KV|P_|NgQ}o=OF?d z8f?O}b?j?_c(~8)U~@<+uqbqSSUeT}7+NuSC6dP!SbjT=WHZ~)@_m>bj&DQz_dzW2 zZRq+wthFYk(vZ(!hX0eHvGx&R)#lkY{jAa!-mYC0#yd7!Q;X5n9*Qyw;d5?ljO^jmR3N9eO71OGKHzs^xFUTe~G) zJt!sG)`JdpM3*pvmzAuI*tyj25XQIAFQkx>1r}!oRZqo2?bj+)RGU;hx`H!6@o$+` zAZfKpA#LmS+OR7)gYzyUo$BZWiZ2-dgPLpc8LL`S_+hl@6)nB(4ojlNdKHP_ zSQ|$V6-yo2v9_W{gIcyV--;RONK@HQLh@?aLM1v@EUAvQI_2(4T4$hB&hy#!rrhI< z-0n&=@C&Jvt0_J}w|Be)A@VBNU{fE43M|;p=HfJQU>Jgc)A8(DH4|`$R66^Gv>>Re zssK{{iWEFw07HBI7PPAby=0Y^^lb?Ys3TJ->4=mN#p(Dl*Yz7T!)sg6!Iw9^){-V4 zLHgVlcm_cl5%+a-T%3`DI4CSDLJ`VkfAa6(r@;A(n^Vx2QbNb&%m>c42!fDlIR2NS zeLjT-#Qb@7VpL=dRL4$W-ZC%|-VDqIt?1D&r3D>F+y!Tlf#WU1Sq7X#emFCMlhKNj zzk+W>N(*}QD^&HKmbB(8DK2<4(z1ps$6-6DDqB}~! zYnsZd@$&Sssb_hX!6$vL?m@>Ws zkWt}0!~X}BqUlypUW2yUP$A4p+p!(#)FJ*560kITb1h(qN9JOlx$4>i6NRcRxjt>d z5Wf)xy{#3brsaaZYe{pCVcX@kR8XarOt*YxB(%Z|ASsV`go0Z^k!LrbSd*(E4v-ks6ONgn!SbQ1WrOr?hEC?;n>s z<)~!v_5pa!)#a1RcUN=RX!kZ85?q4f3>KN}*TFWY;k&Dkx7OP|%bo}@B>zI zJYEKmH34^PL3_WKlC0O7>JuYL2VTj*m>AucVhl_+oQu2;03$6|LtG0QeL`Akn}qLR z9bPfcuDG$T!AWUS!c!=N+X&BIrhy>#1Td~oe+TK=>A!VT@2-s6TYh{?Y<=agQK)rDYWOZG_35JHx(u; zSQ9HQmEf>d(60PRhgd&o6v+A+u*zwK(qJ0%i_}wW*N7Hm$nlmGI`)e+*p`W+$vGJB z>>WH3R>9g0L4Hoz`}nU?3o-l`Fd`UD87=Wb6T0oBm^VD1cDT2-Ai^BOT55?p2i-rj_w z|CHja@8Y`(Sn>Y>7>}K(NhZJ-n$W60LFu_9`u0z0Z`@wS8!7Clh}NbaqeH(x2lfbK z#8Vp4?kku8;VHoL`0cm~^}<#{wCZ~^#43#0#;t~dl1gYonOD(*cT$HxrHGER8SVk) zV}rlc_a?Y)P{#tXRQt6$>}ro-gH>cpy&L54TMZV25>6|WhST;6a;*4pA|0(D zXNvt2DY2s5QS>&T$ra`2f;p3VO>lX4$)0)?TuF9OLAV^k(@VQnoLUT~mw3mrk*S!0 zMlpiqrAl%u*x(Z>qpF;A7mU;B5I(6JNa`gpuaYWA)V{KOP5iFzy&x9D1~AbC@w^|z z<|^_lBHa^W4|b~)Ob{7<5Id{N9mMX5bgQa7r%XUNLjO=*S{i&;0gYkTj5>kLT}v!u zE+j;r9{}g5ORGZUb^jLi7_`bcCZzR#NE1Wlg`q429-l5HV1CCpU3%(PlIhad6{}Fq zFu9SKgPI7FZ;1!$P)4|%EV}B@qHwwGze}^C$$SG4fBmuemG(=xyj7f8ht}BT!G2ok zmQ?jHv@jd?>!(d9Z$e$vs&z}=Mv@$B5rgVbrYv`BTc*r~fiO0lE_0Y*x*9M@JF_8% zwF0{wNx#bS&Vgk(f*eQ=wj{r+9mtf;z(Lxkz~Q67LZo&$BbMin9Il96ntCKg$lYjd zoLs3j=+D(#Uasg=3&}Njj(1>u(+VjzOtRmgS~!p3lxanTJm?N6xWI)|7%1sLdB%kD zmVx4tseYu~TSajN(xL>QECI?xCY1jeD7ZT2g9bXoU~p|+Iut4A-GQ_$6DV#)YG4BG zXMkoYw4s_j{thUmfhcEyVlkoAGf+wu3^HjXqgb8r50SNwniifhkQtN(X0j04CWsrdavYxLk*A5!SWMSnvy0&+BZF#Is zY!I&>RZNthDsTNZR^NjE5v!xl;ms&I-EQ{|ZzBI?72C%0!Nf#zH<$OtZ**uAs+Bcw zP&fR~t9RadAI-Bwd{f7}sY$qdBQgUcKm9{|!-=Lu3TrF7EVC5(VeY)+Gc{j}& zmFM6MIb0dTzgG1M7HzM7Np)4>a*grl^=O2VMktJ;G^booOsk=J**2@e?vOa=*8`Ku zGDt`D07!PMOgBMJG9Vq*DXoKiP}~&7ezq;?#D=g6RQ1cSDm1*KoF@KWlh${XC%cY9 z^a55sgH$;S*D$eA$>XIQlV-{CFH_sB;-%sTQGu+SsYyf9Ye6-L z)o+gfH7MphLRK_A-$iaNZmFSNI)1&2+=>rxhWP6%6j1Wl*MeBgru_7^fU>*F%|u%@ zLtl;Tnm(3gH^N4CJxmw7$_>QGC~ZHx(p~wB(fM=e{5e$qcyqg&iN6j${v6(4y2;J> zK&nvosxul9c&rh~lLz6lHdsLYx`U^#kp@pjc7q2ayAd|B8$5m29Xt)Irt#FX8rNAW zxqHZtJ5*e(&RCqz7_OLLcN#D@G%~Q_7IXVjD=vLLFPzHs{7a6nM`a@PywOGpgl zD>Or%Brc0E_%gB^d>Gk{u#w&1t2jeW7ylPYN-y{xJQI00U96?E6tAs?q-5@_w;x1g-2NCk4r1BN?B|*3Mr``O$!1hcIXT zd@ed|ehmWQjey~E*-Ily>?a>}OhVXa0LS+pAd~Z4mW@GW4$L`W{pDIBs$0Fne{6sG zkobk7IWZO?zv{%ebbvgxY9V(0(y;%@-fxj~d4QZ&wN(4W4sn|y*Maf~*LJRcbcfBE z=GMYBv|)7ut9OUF7NIuFH`nUcuOMg*GX_>u{{u}%TDJ0i97$&f%BimBbUcaiT08(A zW{w+yH_L?QiKGdGC;)cix;s+ABhRE-WTO+CbP`R_%LiT11mER~YPM7J{C|QaA zG5iMZX4q}qJo)NBRv~W~z+g_?F+}zzkCx$%y40@qz%%W%W{m6-vA|lMEh{Uti=)KTucFK>~lLZW5D?r<<2^Kjq#~<3}6^kvf%^O7z7w;xyA;`^vpwYrmL2Y_X^`- zj4{&qBw@zGII;u-VkHw^6WNZaFD8WXJ?gPd%Ce(}2*_@PjqF+vl1tg+Wrx@{T$5!|IQJm&bauR) zB=(n7fl`Bquz}6_s&wKzIN?qp;6fI()!Vm!g>w^aepqhqswHV6e}yxQ zQ$=g;H!CFe|=JBu9QBM>3IEV-$uN0<=TusX&Zz55`1k6FMK-64?GZ}B>1K^E> zzb-_6JTwr`D$$7v^25}6jvUgwo=Sp<^O|L(;0k9_U*+lS{uhY|j z=^6R}^bEyr2JBS1CgAt%6f{ZxRvcy5q0ypF~J1Z+g!R;Ik8jJ%G< zG-aW@$d}h0n70T!0+mg9n;LoDjlFdi$yF`l!K(aLfkHhN%QeKpsx)D-JS6B<)*^_% zeib^jSdOS?u01sQbR1(|5fmsIZ&eCjg7NejJ$n_@1|K-OuQm)s7YV$nCcGD`(lbls zL#}ikZ!fsvgGTqo>jmwCl`+wTmsyq8KOrXv)zzTm&RPkxLRIqwIIlj7~aoU%eXA)gw6YdN5&Haj&j-)1NB8O zo){Qm5nGqTNfmi-^j2ixmbun)gEH~IVToJ?OXPWr-|GUiHp!tD+dL7)d7|M2zHzhs zLF8HF@>v@7x01fWH|>pq)m!9T@ua|S3_OCXV(`eAVFSPv91k18ep5Ds&yB^4LdFc9 z_~kd4F!CE=Bfr5^?p90(RVF;mH6|Q5O$`FAZa!6w8%|-o z2s1I!%3#8gLLqO!kakd@&TpVy?SgQ5Hn#~M15pbDQQ69K5L83WeWJMnRZvA!m_jkz zN&^9Smb$_O;57hBQz)W9&QCE|!s!%$mf|s$9B9g$W8@WDc>gNEy7z9G)3JuS zbt{nagtE*u^evu7>9WiUESQ(PKbZ0c8F{l>(1Euwk1MfI+;(|+)EiKH)h3GDsU27W z3b>eZCiXM7SZM!txt;4p#G_~05rxXpMUlu z3<8sMyvvY`J_y_!j|TzZWt#AC>Pmb^?%c1dj<=uj;QDG*^r zDJ(6A4Jv1)&`2tci6}=s6GAI`KYmAc_|;U)fNHj3!FKqcz?%AtHCb(bExi$5`HEWY=P(*i1o;_P2oDpt zR_ZUGgeE6?#D5&6L6Xke2Z@F*Q&}$JFPbt zp#C!20EJU!LpUbnw%GW64AS`{?{-%`& zF%i4)Hyt`CXW)ejIV{zntTYgqUu3)aS0H8a1~Ah0y?u**DwX3Yqy$5q0pbn>i3i9j z6G$Zk1neC?gpK6@`8eAKu*VmIeQE;ug{zTu$k~=!9G0IJ^RLtH!}9qNQxL&j-*1oy z8%hnK>Rk&I)E^vO9}K1O=neXt3YZTZZgyL5-2$FFlf797U8kTgFqCz>PMz^k6hq>Ka^l+EU*VdARE`nhH}t_5VRVFQUJ^ z8dym;uhI1q`FS5Lg@Lpb!Q#Bpl;v|2txB}8E$ulXcXN?WOEsniYrgwR5^Fxb&w9QI z_?2rk;7b{gIq7&;AOtqG-xse1)_lMlY{FZ3jn00FHDo^>?WewF8Ufkt_X86B$;b8&m~w0Prss8 zP_bb(dkI42G=dX{O~00_Sni2%2FuYH6GE3V1UmMOJgm%DgmEpJ7Uqhjfwb@oWqR(|J6`YV;_~T-gA1L5>_=fENBd~^khkR54 z7Yg3`C*}SY*BpFd$=w76Jj1)M{W$g-)N6_xkcW0`sOfhpX`KfkNO$s0zVhp_4zz z`+a$xILztS+_GD`Gha64{R9f3=5<=>7H;*-vJst?`OH^5e>N9L_h!~d8r?gr4?_|5>Hinr+s0HE67ybErkbeH7+Mvwk1rv|qG z0lXz$4f^HjLX*$SHG8S-@H~{+<#{Oo8uQS_X?SVGM0HCP#%To1L&t$?UqL6`CG&ry zg!A%4Bku`nO~-STzXr;(vL9%wE{b*7N_e5#ZR&0ja5<~a&13G89>3A~^YW-R_bg-& z3fXQdP0tWWN`=Tg{`YQv$F|kGJr~1v5@xVzx*UT{;87fzf#5}x#zv98w1c76KEGd z>W*EKUvb@lGI3uxpOvDK+83%4q5?FPW{-C{={bG0CCHL%;TY*C|D3@>U9f}20EsPQ>YK--Ie z;|r(dz|#VpaN^F0;3HIq((tzr0l=%G_IHSTSC4CXhq!HeT$4M*ZPDWr5%))B_`hGl z%$MJtq|$-7TfD)q^551|m$B^G6<*Ej{7t@T5xu`tyFcWlzNOr}9XPOyU(uueS_`!U zyh~t+c@5c^d}HEsgjr*iKw9xCx(ZZ=Fet68t8i4JkN%KbwGIGwR?@n79e5*vpE3a# z7{Ja-)bvlelepwE&G}PKv{{glvaaH?lMnus`vu~90&$nX`qR;bJHf#9RHE)zk4 zzmW1bA5r;@Cj1RYf_ax{)!#U(GVv0f_*>puIalpb^V}utF44+s^6)mf#wwnRvA8R1 zO0UY>nm-1cjFmK!)O0*(G%-kWRG~)K<*k{AK@uzIw2Q3axT9&0C2ueevimfrMx6pEfIT65GjA{#sA zc>sZ``6%3hic*ED*CiM5m!!W}|s7NxOY zZbxW9?v1?5Xv&>wG2%A-}oeyN<2&)1Yj^-o&ehW8l*_5tq zMAEdXlDnk*1rlw_s9yipB&`1J(xn_UNXLQ@F?j1oMd-j~WL4_U;L^CVVKTw>pglu<#65(_WV1pKz# zftpt>t7wFVWtETCsh5uFCN);hohX5O;kG{;W~BEqxi7Au#OGYWC*Nsmo6uw-&MUqM zSRSG^%rYop;q~cfp!M~BP~-{`yvepQpPIJ zqb2YhfrlMjyYl8KRL7TAsGXA&VAxbtSS@6`cYRTm*U-TC} z*CU?wtx%*9mBW-C>p?g4D=`#0XKZM{tbNO`g%6d`%7Hxb(dC%+Ls`0nVxQ?p$ zl2ok%8qQPrK#px;HEeGF@7FYYb=q7-sb^ye5xn!eQO&B#*+^_Lwa^TpwJhq+=0e^& zD{M*CgO#5nwlZ6KL`-35D?t!`m7Nk*4}r`YM^cLry?)bM#iIk|MtM6P*uLqH|h;5%yPA zwX{&fup=+8I6PMPIoY(=7k8n2{^p;ql7G62TDrIIknZ+bKRoclbY^IJ&{P$VT?o%x zmsUZ2#E4&6+<*)m<_@9=1bXm)3Nr*kd!MKG!<4ZdqY(BV0h0mf3+vJqfE((c&iIb5 zF6bv39jpgI!c9Vh|uehnbFv4q)Pkrld2QqN=wq`Ej6<~n*nx(mVu_2U>NyJ)H!Jqz2 zhwMs6*Ge5PlJV};5t;GO5!qn1ooB+^_%jWWlnk-iPn0hy?+16|cpgF^xz16hCRDCZ*NK4HpT-pK8d=(vJW zyR7Wez}#n$yU3LLB7}olDiBH~N{djYRxVa2aTsnR&eE<3rBAP7ze!wy#UXRW7l>Kh zJTQsF#AcBOsixy@G2ehJl=Hs1h>C{+P6Z8im;CZ0jfhnG+>n-26=_4b77W39s^ZyR%)MWPEpo<=J}+ukypeb3-Yqn$ng+;*~1h z3-p>Q5OD^RS+lCFVKD}Kc0CgneGDp)*6q()1$W8HAHBP)VH%L8GFxhm$p03(x!Ddo zqxZ48AUN)b9@ign`aD3-2mkmVX+m}Mf8EZ|(&|b#l}?=N)ikO=^aRqm1P5tzfx==o z7DVr%p{up(QM~pVN^gr9qc9L-Bix|sn=tws7=;RLuBi+&LkJN8;#vZ8veg7p-+&Mz zs7ti+iFoWR1;;2~nV}qkP(?U8xa@QwN88cpRE``G-Z~Bi9(+AjEO_w6Ds%m$W8#c0 zsH8|EBWPX(49ZDcQvpt%W3GaS@5^uiGtP$BWiecY7WYUD=R0G0Y*;=_XhncXK7}%)k({+_Fi&*mvoljGuso?9-ic}*}Id%tN zt>S#Z?AG*YsVX`j(Z4_qRHEGx)S|x9><%a%m31G=8KAssLixf#!Rd@`^_BVJiqqbt z1`6&b&M&3#Bs_WbZ?2uySfV~y8?0~VP6iSeYQQ?H(e@-IsVa`(@!Vh$`mg6t(&Z$j zQB}A0iBGdEIZ26)@CjxDPQ|BL9zRKA`BPz8s<9_&eItxctxD-=BW1mK?j*g@Tu~^u zv69|dtrx93&-HcZFpc#!Q8pI}tcnfYdHz|oJ1zM%ilmXJVCd%wU4JoZ2AggrP)NY;#lvTU|P+FbFBr6TY{1fzCva&P~NT?A2#KyTo z6VN%Rp30g~gZegAhD2c?i82NZ3?$XYs{=_v1ZJY2HdTg;|D4bS*rwTC1elhA%YRIz zxN2kULgst=`yYHUT7+0ptz$ zrzpZ*GF_!;wChf_xdB+;eIHmEHb1PU!1@J?3=Bn@id1%&bUne-2!%phD6MXU@m%6Kw?4KCKz2bIrMar|fl|i_TGc`sTxMmu6X*tjK5YVh zvka6PwN&D2yK87|4Ue0SM4Y;g!tJDBLn~~myX5EZX+}%sp?eoLCKJn8Q(-gx3X5o^ zBvdUeD=fa0T&PhY%j{heAjKIzr* zD|=w75*JnAxYI-_*WNgRo=;V#=BVuQl;t$IU{l0HK-8xvzBtwZjvH}@xUclMfp>^I zq{sEXL)@ooT#l6A?GBNJdd7~3Q`f3`z3@D0hZ<+kZ+(ZjxAeGXcZhpUk89{3*AP2G z47yQ|Oz@A?<6hR|V!orKHp*z%4D@ciYWW-A^;L!{e_pj{3Tan=wINS4cVrL2um@~b zFk?tXkN#~NrCsHU_>ReIuHD&&YPD7V=c=z4u$2pdOM;QLitK zr=++l>v;cRJnZt`7ms&&hv7-_30+ z=S~W7iKo#;@?KwdpH|!w1(={9kOH}|nx?!QhuJ*O@+$~JMM;xZTWa548ALfWkQ+khtj%( zvQbfJdl`y%b4R6vMf7~nbDxemD8y0N(7gUiNc&=4+QoXE6&rKJ^hxk5 z`sO;h{cMAuvu?AA5A}PalsTcvy)X}9ByIi6u_9)<{A(a(1L_laC*v%x8D^9`?pAy!p-M<|`_rgRe5eN722rK6d4P5FK7$4|l2&0hx! zQdK8SkhIOEd~zR%B~#s*n@kXgxFu*1-ksf*CKhqzak|_?i4lcJ3hAlL5JBdXJ(W=| z2U4;;)`LHG{<^O`;QW<71Jf5%iAl#PIYSvzfzPMf;j8z2hH}kJxJPaHKHiIF;T5%G zfxPeIYGJ}XHR(t%Wuu?s6b9zD&B1-?rrdc(?!ub1t+%pJ%m7t=VE-%@9MQODP^s56 z5_J1sd4#2l@6YanZ0p99z4EyBC~S^<5N1MfPsGkXO2dS@D2o$!L}E7F+6}|);_`Vv zS%epOgx-9Vf-{wp)*i5C7nAMmlQ^}1j=F8)_ zOff4)Q*iYj3rl{79PD`kf}GuONFckf($r5ZCWW%O-I?o9j8Ts~Vf&2hR?`ML+*fJh zT7?f>=`~mwu<99!@7f4p)ms8!w+VR5H{|N4)D9`Oc=*N*v=&U%8y%$u{gg}$0~j!c zDs-%$^7cLGU5tY=CfFW+^zP{odTZ+RuH`y_)$qRb!fKceV5qc8+JNkf!S`fjlDSX2hG ztcSAjG>-2fU%-`v@WrDvVTcl4J?qQsWsk0MI;3Z%TZHe}ua8~%P*@c&;M`)%<$z}k zJ{!&%Y8T{YY;b&p8<4perwxWTq)9_|wp-U`iW_&sJ@l^+S7t?3!)KogBl;R3xwMy# zP`eSz1e^N^l8277<0+KnuyFCOquyI1luWCVfqcybH0;GFeh(KPkw5<^jUBCY4*#p< zI;|CBCT3wThBu9meM!4U!`9#bE4n&bNliG4_$yW=-#^Vez$>-N`8miJ!m9)64ju z&BS~yQe%v^&A)(u{pxTT=kAqZ)-4Dja~y4bSUDg*TTF8%D5=(uL6v$l^BH93Rx=hK zbS*64nWElmaxHj26wNHx>WtMI18X6!ncRbFM*{y%>+CV+VqH$(&A&_@%a#*W2(D#m|wQk%ivp`9SAq`3wxkJjS)V4GBlPx ze?*aT;*8j4NR6G0Xd{eQEIim?jWWX7mT3-z6(h{ATEIpYZiKfW9^qgkJl--5mD(@J z2shTKDQ|@F3I?dL^%L>oMtX?8;d%v!pKkKUrSMlq;2F7~Aox-~_K6Q3)gxT(rnG5rVyO;eKkf@CaTUEgrYWsj2LQWkX>C#mX2&1d1gthY26oq? z+tV<03p-4mA5{`<%Mam@&Ik;-xsNJs0%1!7VY6}G{|HhWEti}54VI}&Z!M}YU8x-i z;KY?Th%^{p0)U++fYSzmGoHr%3!pF%U?TuFm;eqK0EO}N>2!>v0g}N5I{p+C0pKYU zK!E{(v?srU$a&WuZZyvwqK=O#31a$Tn(&yCXl(_FvKN&1y~mVu7IDNOI&oe}pnWrx z4oOa}7*VYNYknFw2R}U+D5+o2D`=9cO)X|B$ z_G@Z{H==h!IS#>1+ZHOZt^_?|3+U9lQnf;ObY$sR3jL*|8FMyblcx%ZM|<>DUb90K zwMd!P^;hn6wEC$VAl`Ji&7Xk~{4-TS;ha_w>gKgB(Obayv>m&Vj>qnx@1b!lj**|! ztwl;iJu@*Fs%`MC-($kPaFE(9Rz6B`*3(ES)PAkFb4>03a5VNQQ9#9yMK} z#ERVx(10aMrr7KN8k}*v^xV%V=^4dE&KH!hCK{{7 zqAEpe{^AgK=1=WxOzf5^fB}$jSkEjiy?#vk`ur&r4u8fe<0lPFV z%@Gz&VWACyU`z10)*2JoUIQ$v0UckVjBah@HF0Fa#Bi1=ugA!Xw1*F2GjrGqC6@k| zt9;kVK*3c-{_LEAgF>PSCDTAb+J!(-O_;dKIeS07pQjx6sdix?lnw6@|FAbuGC>AZ zVFNnwoYL8sS7;bO2ES#z$CUR1H#e55(2%-3uef}9alMg03rmo9gDLL;BQLHu`t*6F zoAo?+R2w&Iyji)dHDFydA-rrLK)G^WP&x#yg7%=7zUKLi_P?O~;iJZ5q6R(;ktQss zf#qpPfBaWzXdQbmYHDE!{q2)LIaV_eK+TGkSajE9YA}_n^_h3qN(Gll9N0(EFDi4y zqEBemi%JvfwL#%a#2}~wQAkpMjXo$IE}(t10*Vcr{cPZIT0uzihWt-iZ3!!gMIFH> zPxUb!g@qV>uu55C9a4n#!||}1@%+h`1T!2p>`uzV99zADO~`V#BIgFBW(q!PWHi#q za5hqV>m^v^tpyqyi;oO$SsEFQ=-5k2P3vqVP*-~|AcjW_1+wL}laWgw&k8Iae{_sz z7(&>=evYYx^`Fw{)k5VtILNPoS)BLlTCp{#pYk zfB+V<0x7Uz+}U9QIAs99ls088t}O`w@B{+H17NKQ;8O#@)7X1#E&Lm-&7f8%7ujQ7 z0};j5^$ob@t)BZ<7q)t`F<`Vc74gts8n903Xl(!-6}Y|*yp@6Bsd`^vcv5Af^A9rt zx7thP*JE*h!~nhu(wX8}42;dB`vRjcCaCT)6b>5^Twd=%b zz{`fkn$hhC%&BjFjBg14pvN^pcrI7VVR#51F7pn)TtsheQc~+gAU+Czpf!;PD@(kU z9~!+T#HXpRU7fL)1uAF2g<8(ld#YTm zb3jiu6O&ySG3EjgN~fmfmGFil8nH!r*VSLgJI0cm_yBklfrl}qwFz$w@LpAtTrG6G z9gK(TFO4$wp7h`JjYA6pUQH8Try@G~Dr)^eAqD57N8M3K1M=ZGy0ws&<|~P=%iy2o zFjcMb2PkI@8Wh%QUls<+;pQH?4qVs&5qCduO_lxQ|F?mPii(OmOHrqhqLGoJqLQLg z5mAwnQIV2SQBhG*QBhk(MnyG>x~RyelA)22p~E7ZNkv6PMMZbqwThB-zyxkZZ}R%R zu5Fm|x$pAx`+dKUUyqK@v-9VD{XaW9=WI0i<1JJ1_?gYW&G#yv#^<}`+xx})VYj&T zRr1~B6q{c)PELHqA9tFHd-(~(y_~pQ&3U|E+-HA!#y1lBLiTPOv^}r(2h~-aWp3f_96Kw{ThGsdq)^7USIk?-JKL5Vrag zh*k-lV8v!cT9=jdOThV_*!#M1VWQ0+ZqtV7i{Ib28XFGZ#%1OaqsqT zi+LX7ka(_s@q*qHA8$48F}UW5H{Ud#nYh*;*R0}lJM4eN<+r@l@h%`;{iYYkIc|rk zKLecKFK)#yF~7<<&X7J&TvBD6XBfDX-vu&G;uk+j$x+1xxO9I?KT}cubHC${sQpt? zmk&6*JiA{?H|-KLw{e6T_^ufKzHxHkAFNk*2gi$-w;3k{RtBU8h!3|JPccl~CEB-f zNE^l*+jisJ@svQ7#GsqwE0I%`NWWRnMFHn7@#uCQOx))bJGXPxb5R?rwpXjXo?xx0 z>!2UJbA0QyJH~V1M>k+3oyV|(Wa2H4JYC7HxtmpM)Z+yzGG??f5((#vl zF(+%|c8Li)xJI4mFZ&{YUUyNi{!^&G&MW5*WyCq9UtZ65itRfn`$T`dbt)duwjcZ@-UeT$-s^kVVCQKN-q%0 zj!mB#$LPh7-NvN`*L-o|ZsS=)wvkuW>F3snwYxb&=@$4R$1ONI^3{*wz3|rY(RaTi ze%Q^(4~Y@~-fdiL826SM`6sKeSJfKN7;?Km?7_Fi+S>mRmSG;wFu%NC*arz)%P=4J zwr`k^qEMotW%zh;(fi!z&E^-M-ePsXWoJT}* zjhOzC@e%`Hv3~HQzFtn9fAx{EUf;lvdl}R9*NgkVGENlcFO37lDWA}N9u;4FMN{0r z!`povbe{~psQ%VCa*oqmPYnj1FjhGVu=9IX{_YcBeSE31RCiLBaN=SeOFva#EG=_5 zHh*TErw`>D-wV8#7uIoOS*IR)@JtbJHyOu^&<2jct_5O2gK>Od0ue>rjxi?<=GWlV zjg&>z;=TssIR>^q^?Tzx&O+tT00Q_rpt&)6^CLRApf-SiHB4@BdM+HZ^zhKIL_3EvuD6dikb zVv&oT-mEnkoIV4*S>)~{-SnAl-WqM_yX^E1&Fk$Te8E$GYkXPLtHT^WNTDk4XwOIv zQa$6$LH?CO(oF(2a^~$BL;O8sI146j8fkP~`km3NH#7_v_xywF`}poZjMp0oLWeou z7sR~K*9ZRC=IsM%REIZD{sTP2Y=F0O8|(w<+*}iwgr`Tnz81oX@MsSdI52Toc4pw3i0i;Cy#7JnVj-z|Q5^Z2?L z>TvA*!N}itOL_CSu3-0N$6)49eS41;DqFs;u)1G}N6Ct}I?aQ`Cobc6hU=;v8-Fqm z(HoXjiLE~y&y1o~_#@tgF{t0AP_4pw&Zk?C&&j_ii7(6$G4U5;o8j|qVt9*j6aCW8 z-_cfkn}_-{qoVM>#~H(={i57|G|EuX(PCU2w1x%mYPv(h6*1Bzl7BU}7!GYycjPCF zD7SG$GSPie4SY*qrPB8|l+~}Tw!LwD9>*Mw9$XZ^YF|CS$l&87xlS!vXGtH^i-bxWu{i4Y78QaneYBw|Cyr{>RCKO*HJ`m~ZhI zgU_n;r&MV$4^#QCJeq$lT^9IKs_YxJmA;fJb!_`%wg2{>>->2l+hZKJ;LlL}b>U+} z#S<#KU#OD4P;C2QwfOipDm2ey9C6N{QS8S@$so$b{i5947lmyr`ZB~F_f>C*;lK0I zbmUes=XdV752TsBzdOPm_Yg<%@5V)X|8D~EQy&+;q3*w5y2x8h|AC-V@A9Q?h*N(O zoBM!tmg-7xa~`b@7d=^(Q)eAsG@@F}ztcEVlhKv^>8$$vOwyk2i$9QGJpZVm6H;!#j_2f-P zzu1L+vDx-bl&fjZ*+NCDMnIgY&Eiu51BD)r7|6X6KPNuK(R!KM8Y zx?!tWxZilIWev-Zz1hBwo8;5{X-wp%xl4O#tS(Hqyzd=%GV3OCquuP^=C~X3gLvYJ zi@Pz)B|!{C;NWO@y!~r)$v0oCqag9UlSMn%Xmj% z8yon}f?WSH1_idLmvOK2f#Sw}AtOY{0b_dL6R)wXp))8{IL{p&B1#SzqZ9X#50#(m zRL%aU{KSp)bpw8s!uuXWe$=P!Pl?r+cXdkpuS#J&s6JJ`CRQ9Y-gmOfj=HM5VT12# z@OsXg%GhVaQoV|2)4N8Bg9o{{^#TjkkM!L8x|q_#=+!7sk8$j{0+t_rxRUjmWKf-Q z4Pp7JC81-4`_@q-#ikzPHOV%0s8V-dy@C0?0Hwj|Gr*g1zCyvG5b`p@E?2;tn!d?(4W6`b6iq953gPyO^W+B z#(qgH>`Tf#TKxNvahl=%3NhudarS?S$WzY8MpVBB(N=MM=Ew9!Odl;?I?VSJUZ@bC z9X38NVYtfp$y7a6tuDl`=Mv`o?5wVXzq&=-^l#%U2Ipv@_3~2^{C&-vdyOYeaFShn zfdAtCa`xfs*PUvgtMo-zY!MrK`QV@Vy7*XmZG~v>HQs7`RPD2yeSRSw|2~T=#2tTd zQ(?Z^m*rvPMdNz9x)?EU~u_f5bRpR5#lk z?M39L@ip-=%cEP5T~0pg*#GEur0HV4O5+-p1`quFaZf$J|5ZO|j5tFYqsLl}|Km5N zy&ZyI0I^8EB9a~|UXXn1w1$dLcpb#gA=rn;9ZDDLq*0r_i;U_h9FG}?`gilLP6^@6 z(0}yeXR=bf>-@W(FTRj`5)XamLT%b0?+R<^GZt;kuwyrx<=tqIFR@5(V&^{YPmCYJ z_9f=@tv34;d#Gl(!udQG#;_7`GSU#6_S z)ph<|)sM^hD#Ew?J^%8leaoG`6QS#&KO_811Yx^vWQ53`HPY;; z57cV)0XGrG`&4-4KrPg8*Cz47KyA&$tNg()W|tt9DKeuT0e?ZAva*anZebLsjT$^c z*am5tf!PcgVVycMG~h_N_mkK(5gVi>8G<&6M}xG5fs@q5llmadY?$?$Xb;ks7(RPd z%p9y;5VnM1M~4~-bRG76da5Okuy=-p2`j%_&yBjHXRkWvu%gp9iO&XWV+}2ve4muQ z-z0_)(H0s8Rfr3QXcri|UKMMHXtxdH58A4?snvYR;>lOVgrVA;>&^bFH0m89jt}(u z^s!zI{IOg0IzXqsdCm`KaFE?XCi=El?-1Y6Y-$@F+YYFtCOAQKp?MaS^ZNRsN`ySSn>5`Bc~azkG#t%%`Yr=th$`)^TdhZ=P7i(BayW!PfCbGg&v_Rk32Y zwse>(61%A)eY#m}9Ink$zar4L=$*~tx8d5J;*2<+SDzt#{XY$4tw{o=i`SxgDh z9?)m2438EyAzGw9-8bJGqQwN9PdZO#j2Yud8mUF-6aOGNRSXLiZNKdVlD&;nWgdq5 zW#jS17`j>P9HpI|_?8>;(f?K9<7};f?+uE=uo|Aqc|{HTbTH`KamkCk!w#Nk!#5`pBHZHm&gm7 z#C@S;`bK}e4%H*CI)Qjsk!j*B?-%c$P2xzXH`7*MrYF-^2W%8m#%K$#TkKC{w@QRt ztAATFtH?ADj!o^C$c4nQv(EAwLyAtN;}XV7mU%y*@NJ}*L{X@Aa^eJka(0y*H(LKT zIZpq|NG`Bna*>Wfj8FN?d46w^(cs19(GN|zg` zf1B3zlI=sx(EVkY{E`H?@l^Hg%&UnN9?I*|H@VT0ax zplUdJpyCX)jO1STCFk8%CHHN)ctWF?d&-U}CQ1HC{9}uG`OD%njV>ts>7Jz0z3>Fm zy^vy>`KAAU>AqYpR+xx)yFcDRs$boZ{o8V!M>&XhdB1oMmWv-u+6=?cm&Ndth>x-S7&rc8Rt`)Qr=v z80?%_^e)SvdPO`DrWr-rQY}hkhH2vm+s#E~thm#=V(GABj&qA%5kG`!Cl9txDtd@5 zQeP1>;<;THIbNG&uuc>gj@PCPj+Cab)gwss1~Z z_$O;~FLL>IH>6KJCR_X+Lhhq(?-$|+nnPt>$F{>Z`wr%M*N`InZe7u1DlGoaFedEz zePLb4hgGLs#r?w8^o3>HeVcrv>l2oFpIswl-OFNZxHf;tLo8FhVo;e_8U7zClAA}h zgukI*_@`eMYs0m1!_p&;o_dX6FFpv@Cd_$8MdX8NxinNK#3o=2c||ig%(l)3mrq)tc0$`t!}c4>o0t|4i~piyo~@+Xk^YlHLv+$B<9DpS9-v4%!bm-CD&^9+Oy%&Sj=>ev21eTikfesi6;;B@T_B0Enn`jsHn z>&2s|dn5BS_~$HG{~sb>q#|=I;ungkhT{h2y^-l+&#TD1wyqOnqqJFrt!ET%CB#GP z#fm8HS_9>NH%dFruxh>fslBr=yI5^b=9Z%x$wz-Jg3Qe%hik|(KR&g(6l#?p3!j6XQsC|sdvB{@~Yz~^~XKC%bfwM#0?o^Mv3cYY7wW{XL|pL zhdK~^P9ctKXV=W4u_Vy8P7O&-d^%HGWjNWcjzY7}ch2&5S%bIB25b)CEdC7=IW}|O z5zpIScycR9W$@1f5IrsW=*5Yv)`~5&H~_s%;rs_6Zbi)&`(|l8Nikbo9?jwBMuMpt z>v+j~`1y}RhEvn!{qk_nI&mag8ygbDa+Ut0-Z0i>BF-`WhiXAK_G>w@o za%XEJ&$7<;6^)1N{v4J3`8UoePw5x_{JtWxZQjcik&&j3LYJ=-pUu`5S^7d*j}N8J z3j_OwitG!;wwJ3=H0$K8sP23)>h$(GMe0DR&R({?NNJcKZQ`=EKglRnvc5M$wJuCo zBnszfL6c8oYwr(^`L{fUEqxy^eAoNdy(qTN(Uv7P(HT`0Uq(CFA3K3g`50%o{6y(a z;?wT7zC-?RcClmH@#d&_4}0TzxAAv!oBuFnJ9^lAnEOe@d%j=1_w3^5xqJ*L z_Qx}-cn_XHyayRH#Jjs+y!C3(vF^($) zShvPssPm64l*?Brb!EU+`e&i`vCW6`v@=$Q`7^OrW#Y~g$i$r#ioXzG=$DDMj@xD~? zd>5{dK&{$tUqzsn}yXSqO3Ltc&wE#2^|%buJFXHocC&2&~T17){T! zU*93(Ww!Zop?1b)-_Q$GPft~u@Li4i>r7lip{84x)%43mi|S3R3sspI7k8+8t+;*> zy{*b0e~yapyZrRm@t0Fb;;YOaTgdlReAacY_w}|NTrc=KC`;P-Vn-J?gJBav=rfGye7cGV+wl2n7&vWJK_Gm5|ZHE#6G5kn-4rMRxj3O4w>yw z(@`qcE><5`z31tFzF~3QDn63O&-*2@bglSdv3679Aph=w?+~DE?$g{PxhWt() zsX=qY3*xi0scLJiI{C5%IMqYFzK=xVd}rhH=Z>$MgB<10(Pjo*#&U~!`1nEe8=mN0 zD6Tz+H|r{Y&^aozoM!8ec_`YfZjq6S@@OiYbE$8JJWsT~ZPjV^d!^#%b2w~W_Pp;w z?u#glu&o(k7O4qZZlKy!G$v@7iRbwf{FDvUm4Ut>>Xhd{CdgHU7Cs!E(J#SEOU0UV zwY${A$&0)nPLDoFBUpTzygbD#6wDvf(iJybeVpLjZ9RP(<< z?$whmeOWnLadC@$E#=J${ede*@qDBm(=R(`z90^q&)t;~{&+{+h;dVB!;@d4CD zy5;=>+|w7pZV-bm)^0S8RK1i_i*+~fHCi)YY2{E@U7{}jO%@dwYawaJWlrD~Vx4Xq_&>}A@v_y+a4NZsH!t0N8#t~8i^uLJxI zUd!#s1`?%Y-tAS%dgw}OTb()3G5T^Ik2tYV@qA9bpkJsv{tP9?U7KEzszDR7l@&(`fwJy*(FO(WoS4=LXW;SpI#9LTbV3BG8b?ms8{noQw zHUCcm;?|YgsF`|Vt9^c9pJT6;{`=|UubzC*dbQuZPmAp6R*}?n7jjOap`kNfDtwL-n& zmZuyyU8Qvn7~EKNSl9xLk7bLZ>$QoZ;5u$(xNKtUb=sGP$BGx-vwFj{$Hf!5+BJp|EXdXP4wFr!-K|}vw>g}5YjFlcaG}F+uXbR7;iktNhab@9 z=nZj?I%ei`d^B`DBCdHzdwzVyqld+n&z^Va`i*frPSK5f?CNKS9y(J>O;yhgV*DEI zRm1a-I6hvZO)wZnJtFoN(9sVUI1(Sx9@QH}f#aJ;wcq&b4+V~$g(@M-!(#hW+CL1L zYs6DeYrh$WKP>Jp*47w;*9gNi6#m~ku_x%rMKUQ)%?=Zh_Nt|tESpkvB9ZJB=b6AvC1Ics%0GPhfI?BZ>Cx>@gdY`s<# zFz7>GweshIPu{3KXSnwP$Igvp(=gzE$AnGV+91O}@8kQXZw^gQ2%@b>C zv|A0s^TgpA?SP@-9!KXp+R6Y!&)s6#F6{xsw|9$gcF`v9+$|QqM_PB^*`z~&D;avR0+ zh~hdeD)1XMS68Ry82-o=3qRt?o6cNu{YTpK^FPTwEUrI0ZpXTrJafmiV;16F-w9>d?W!1n_9r9XzKS*JU1sVV+YdQ*CjcYU5= z+?lr=ruXVMPrS|XLA!SPAcKCEIQTCf%F@qrEI7bZU_q6cXT?>2$>K|Tw2Z*YI99yd zqoo^6TzH=4O(%edWB<74-A#W4=!!DTXF2Bnn>z_3ZG$g8=g{DA-Ju^DAhmQkN5&so zkUr#h{vcWye@~42H=e^xBJYScX^4JS(Yy_@MVBp&b-Z#!+dRN<b0}Z5`vhBL+KV@**(-aS73d5*Yt ztf|rWYO!m+W9c|k4$YvVk4m5Ccz3+XY>4;1oMD(>G~6G3c#qUx(oeYIqk}R zuAHoXsbk>gLArsT*mZ**^Q;!PPBMLLcxSa(IN7w;@XTuQ!(`JG!(*!*15Y+>3>dZU zO7%W5#`_SX;l2mIeDO-LbBbw+q3}wFVXEnz0Rs)@qKgA2IWCMe6$FM3q|OpoUGn zn(AC2&O6t1_3+5oewVH-zsoqLk}Zy%=bE+*P7M0;cbUXwW{PI2`|)>~{=@IGn@Puf zFq4TXoGFSamMMWLg(;mWiz$~W|3}C6<)#Ir0-|S};W&J?DKKFBbtW4>=ivR%@x=9} zwn5_2TTQbDu3CNjby*pXs#{Iv0hau%eKP&#eKLzFmnomg##G8w&Q!(ZWUBwaGg(eJ za1$A5VeDdrA zq?wsWrWmGpCKV_d)0i@ua+s`4g-j((WlWV!HB7NLIgEFiJ{V>Ry^;-1a7teN*V_jF zm-XfUWjX0uWFv`tsMj2dmc|sqq^d8^Kd)Z@pPDj=rD`ajnu=vgzlmO~s;i6_Habod zQw>w_EwmX%V7`@Q5B~3_6W+)2zYP4p&B)(vZ#i~@|CZ~}`;RYuV87SL#!&Os{nmH; zYp@l=SvOHMFadGk$IJ1%*|bk_h&^;0y)Gbc9L{$@M#v;R3xp!mEf~Fbk2G)5>6+U1$P6s++9OLbDZN!TpcPv%`N~!q{JKt8wYpWtVr53FOhw%_ ztO4vGF3ftWRR&d2L&dE!5>rI0OtUak8nRawUB2(y${0++6l}&EG>zFSZPaXaLHa-hDm2p6PR`3UK#y1HIqz2H8kBama~29 za!R;^gj4p)NOWQXx>oF!Sy+`y&7cP>FzYh*L-!Syy;4Wu?klKT?8OK)t)z-DJbkas zMBSBpWiSb+V+uB3wO8h2NXA}iR~f<@<<)y-6I!twYcPb2MqWe4u=gzx!Ud4Bo}?vAQ|*(Mj^%G9D`*a?5noJ?xfwSXkheB^dmOTUKEPHed;Q z(DWE_-lG5*fysr$!O$m&gLO|52a9dQ!Q3L^yl0`)Jxw4Mloz|D8>^pj%b?vQEL ztb5Ka-h8Nwk7(>>&WhIup17?@%zbzDvRQ3|Qr)VA#6LEiG}(WbCG7m|aWBu;e33hUQNw8FtrGGR*jt zl41Pk1p1Ip+CU)8{DK<7oUe(4LEjJuOR*SrO~k>%?}&pv{~!(~HM=b`u#S@d(=E*y z{i9pPqUmS1OvT<70%6r}1j4vh0%85{1VYz70%2ggTL$u}H^M_4OzI>K=5!MWOAfeY z4%YOzr43z&-LeA1dM$2Q$4urQZrOrWN8D2PF*(+?$uNx7x5*gHHnhnUtO#h6*%&yW zO%`I>z&2TqRfF1Otum-hy0C6=o9xBrA#Kw134LK`n~cWZ;5M0z!Nc2R7KU0zw8;Wy z!a~|)8Agw6lTM5s)h3%Uesr7c!KBbO8CuVwcubp&!Zc%>Ou|g9O=e<_sZHi%-broJ zj`?HTWDORMYm-e_8rCMev21*s4EdB!KA}xUqNRRfn@nJ)+1w^G&^@V5TCsO>n=HlP z@HSbEp{KOTMhu(MCOsHFwM_k+hiQ3FKm-(SRdCWb1`OVn=Hn%v)W`O zh9tDfddy2~ldagA)FuNPsG$qnq#5lOwaHj?FK?5n7_*{H=3rfFo3vr!YT`67{@vFS zhz0eT1j2$F2=oP=FpEGKeG`GO7E{rcO(4v^g+N$%Tbr!Fu$(qohcS1w$rh|b-Iu(( z=F*qYc^7>NtMlkf%6sWc7G`Shqcfr1LTAF12kA^0^)Q_YOCF^&Va{W8rmv`>C+JLA z`6QhQ-8MQChCEGQ!ocU~OBnq;eF+O+pf6$Yi}WSTTT5SRWHi0hCM{9SG&7Tg5$oto z*sz|?gsEk8CiVJdIumBRLTAG2ayk=MZKgAQO-3r{Ojx#szJ$4N(3jA)mA-@tRrDo{ z+)iJ@d(PTDW7}o$w=}_ob{T=@$?Y;8qo=gXbWEStF7q(y)OJ~dwi%XoS;b6PRJ&}z%9-ub zjoq`_Wl$5NU~an%$ENx1G7e3#?J^Am7q!b=jErlS#aOkZT~=aHe7mei>)GwH6?+oe zW#D(jJGWh$G3xww8H>&f+GQ%HTaw#l4l}xo+NBL`%i3iH<}7cQbr_mLAgsW^e^8Yd z69`){7V}pS2*WQS4%VU#GgFC!L6;H-%drL1E^C*%@2RQF+hrJ9YMF^)CO55JreNe1 z?J^r(ScnBH+hsXMt!kIG*n}>$rMJsojLB)2reiO8Hc~OhS8cyUfJ=XWC^xX1vla z?by4iUDjao=62bHd0X0LH|8$xkRd-%Q%gEz0){W`kXFn=C#J=B$X=|#=pPyX1!r|| zm6A?`Wtew18=~!;4%veq40W+Qp+iQY?%WQUiFKHd4T&AH2BXgFkWE;F-I$)#AtQgH zubfXtFnSs3U=tQ#^A#Pk!op0_$_^RyGo26PFmx3;#w2uNG4^2Nl`Q{-z^hq~5m$A{ zW;A869t$wEg#@oAqsnVKWHAx(^Qv%f8 zK!$!}bllh>OR)v3F)f>fu{)h_SaJW7Z$_jSnNR$kxVAtNySfex96?uR;L3C6DJ zkPT`*x-t3T4vP%>owh6>A*?E7gS{m1WQWYzM^)K)jY&_DAq;++wslidjKtz+sY(nf z>5z4p@*Kc1Q~kjBckL$u z#$#(ICB~9}(YdhtAUS0CMfZ?Fj6FovVFfm$2a_0PX@{u+ti%vTQ_R1qTFjAjGAzMx zMo)&$BhxU;;E|V@QlMO%)tt*U*xe!H#0qpsVc^8$`Urj(s-&8!_FZPCSw&^u>tGQ zjkyUP8N_%lOZ3P{Y&nkvurP@XV$k^>8O88SyO5^Clw}@Sj1?)=1m;|9p(>cESwY(~ zPCb{?Mi_oI8(_h0^bN*o&Ye^(7T!b7vFBbgfRXo;FvGLD&?B9gZ}Z4NhGFT`)Eq`U z>yb@rSYkKo)=^^&zebG4e9H!p>{a6tO$RtIyh3NfVob#v%)#7pkF;SuR$#&=kF3M^ z%^ul;9@HHqqg&_;sC(Tb6EOG+~FCB|-y!L04{ zek{Rk)Hyt|5M!|%P1PP*i}C2f3hc$!9Teyg8G4HXp|yrSg>{&RvG35dhZz4hW~x}w zhz*#&ld8hdcc~%{NO_op1-sY*8?Xv9-=hi8gOTch^gboRxDQ#51sK#z=frRfuk*+_ zjQW_S#MpXjq?hsE%uE>zbf40OScc75`8hT62W^dE7}r3JU=^ldFJ@!)7t{zgV>w2A zNsV9%y08^{G3qO7Ix(n)0%0mf>GZmc-zWfPw=({7nW<)`7;E=(puh$< zJD{n}BYUtAL-l%HBSv9DyGJHr0cK)ahezgP8QRh0@yHrX$0lsVZtU65FgNIRf!)*q zCUrCZlbK09KpUeSZ5VNoUXIyVhb`EGbv@KT0FQSarcE)mmtKw;N2o!pzydT&Y5+6Q ziB8>q*^J%TgLeIX85*e9MH(#oWfU`w!TV(j#*El6bJgpR{jwM%M(&rD7(IHwY(yva zVEvf=GHife7i!!uW3T{IumQ6%UfVAVu@KAEYtw#Ni^*g6%T`Pa+b@F$l0nM^GQdnF zCSmx*{W24?FdtoL#|ZO&S%an6q?ThhhELirLk1BDBe4P#FlO?8nT54z!{n3q%PMTf zCTu-rzwAXz)Rg_w6hzx$G`3(e#!e*wCQKs$W?=<3U>%yL@0Tr@aq51l8%)9&hUQ3W z1f7_I^)skZY>L`1OV#=__RDH4#>T;Vi>{d&4-1lKQYAyEnrLbS%Pinc-b z)w~YX>q4$!2h2q$mRw6hV`!S|$N(8jLpRznoQ$}yr>!w0ivnQSO%wpbZ)SheOF|v- zQ*W`b12e_9&=%N@b*RfBAlfmA1Z(f0?Xd7pN{-E#fjPO10<_-EdNS0D2^fD5>#-TF z7?DQ-Fa@iz7#r1k3o{;OlJBK$jg$-{F!(;&7Lzd@Gs$Q^HlZCe@@ZRiVH3s_(8gHu zC~d6Ksh_5eu^dw|te9blA(~)PH!&*4 z@_I8>Hjd7UVc3Fkm|j8KV)Sd26l=DU!7zr~n+#9PKo{0y;CT7~n$cQCrybAucW$Ew zCK6yfHDIO}V<|bcJE$u3U?ZkgvmF*-Fd44K2z2crL5zKi8o@kl!e;Eo$QlYrK{Bue zOLnpywqnysjQ^;2*^mY07(z*towOy^zQ=(BqjuAoFtU~d2j*azT8~aldY{*nycC_- zg3TED0ml){L;hNUt`?&(>qCwsSc91sW&-PITa3bZs-^)8G5aIle6ZwWY5;rCgXy18 z0~1IPBd`bKF|D39MLXtUEtX&_R$<_0lo(U78|`Qbq3T0Fr^J|x30RF8Xl|fQF%3)A za;!$(7i0)?FoGs)!gvh(k_=!R=3xewVCq*?IXbZkd$AkK8X5l~lNgs@lL5407KVL8 zj}zFND*}yLdf?zJZ}rIdFCJri7^nC;+;8 z=)@7EbBN)T#!PQ7Z8D8cbc8m+5-eA*CBq7x$m5Khls0q??34|dI;c~Ikm1;%PML=#Sb}ku!EC^c72TLKv{MFAl3EPMR*b{o z;7*x_al<;L6|=AuZCH(g!#iatC6B`>EX5>D9?>Z?F&Fc(8f!5T^+Sy-p+!SsopGKMCLn@mk$ad@XJLk~L9 zdP=8k#_TCNgB6&M)zhenX%=$GjEe<9($?*ciFdJhm%;;uy$`p*nY%Ik> zbYeL+M3YnOMi=JKrpeTLG@Yi`ndgvkjK^fm#4Iet0t}l=4Pgd4u?d^e9MdT+Jqw`=MW@5r(stgO4bV@r0E$x&w7!%(qn=l`{u@Xa0rztQJ3lhl?#$G^% zFmnYpgjHC9t`(gYS;vg|5~>KZQ5Qu33`5s2%{ny<7l4w(sFO&g;P8?gK;h9kN%DA7!sw+FPgFB z4r&A~LAg`~Glgiw+`DKS%($DHzyfq*&OMCpIgAPn$LKu9H&$VqdVMd$7IUx|yRj0R zsNqJ;xW7|+(1js$S^fY`F_-b5_8`5N1(^?VXv9h^!LT({C6;3|Ru#}UVkiNIVfG_b zC5ApqO<*x*W9DNdj3JMcFs462hA{F;Y7&z%bRO@17&VXaU&~Aq3*v3`cFe?ltVTOF zV-2Pi(c96A-PnL3^C>AtV#ZVS4J^P6Y(y*eU@0a)O@S~68?h2S7G@fm30^=Bi#ufm zCSyDnVmel09tJ*3&0r)}VL67x(zyf~z%tChkP;HaOl(9a2A|21^f}^VCdOk6TGE+G zd7cEY7E3Vt1==3V(2crM+I%53fN@xjxfuE)Rg2kJiS<~I5o_smn2+W~WON+~V&Hnx z!K9bzYjF(oml^*R%%r@+p%P2WY2(ENs36BnsNyYTgp&548+DabF(s-)E85-+FGtiC&ScA>jgr<+^gqVUMOQ{Kr#41d{ppVH2Mxqt1Sc)}RjlI}}mdsBG z#7rZG#Ir#?!x7Uy<(Q3CpV0&u-$0w6MU`SP27f~hokIZ{f|Ln*>-;f^>=)vF~I_uf=?n9IiD=;2Cn2yc=rYSL0*Cor*jE(K$`gik z$s{bnOmv|opP7iEUDA%l!CkTjTd)aZhjqyis=fs?uz7fwY^5sGMi4NGwhif$W^BM% zEF4M3u?KUoWfTR#_|aXm0)s*+2xg)ilgD&%{(nB5XH1uj#xN5BFlbzt%)=hEWB7P7 zhNTm!GBlaHWH08U=>oRHXv~__C6m#GS=c+dOBSFmyi1m$8=dGprAszr-V{rh>|w?{ zwM&Lx$bkf-FgSv$Li;qT3gb^D5Y}TEw#=X;n0h)*f|aOCCZka_3ED9RbIzbiFnAVC zf~i=D4Oot`mT20Dney3`3~T35GOU|R$u45}#ZWRVm`BMlem*6`RxH5g1!M>-VksH+ zU^9lFNx`rVLzhuw3n>_;V-l8QCR&mgb;*2Y^3aYhtikX&`T!gS%TGAg}Mv7WCJFk8$B4b zg7F`n+$Fj!i;?tRgA&uw0SCRjj>pJC8Gf&Rx_M16K&Xl6&QRKRg7iW zqF!fE#h22VuVGkX)V0(M#@t3m)bboUA2wqpn(koyH!@Ry7oA0|xSP&$83&Sk=(X64 z*_d))m#oKB3nj)hE8AU8h901o^STO)vG73xV^BWJS>J#uXnKe^7`%oIU_6$idky2i zmYL#*>HQc}K<`J>qtrwi0WcbC3#kbVdz_j;8`?1M32Fi}o}?x)&_+#QH|nk+<4@Ds zu%Vcy#pY+|BiQ>aO@V220Q5GSYJ(F!pI#A*VP;`F%l!+Vm~a#9L%htU}y<_ zhmtc>hP@cPlg@J$r%Fyb54tfQZ66RIgB*WI@4lKhl{z{VHewT&e?-FSHHKV6=lht1 z(Tc&>QZt`0EUDSXPl-j+ zC>CNf)?*Jw|447AWZ4*n^_Y*LE;o~A&`HY=$Z&LF0%mMFAhWP_(*cXLF_X3VfULq&Y{K-41F{#J zUppYpSyXA|0U3|wn2AkTi1}|Gkd`+%&#C~UxF?8aO)-As*OET+|vAm-FkqZt4G z0a=IL=)vX>4)BFbn#A(q0lsZXmDSO9SdUgL`{;lyL-WV%i0PjkkZz2sCxf>zj4&S4 zKP4e-#zOV_GfJjjV#bU?OX-FF9Ma1KrS0|mp}U&s*gY?#UG3bbJlI&&ER zVJ+;)f_MzNo#BL0ScwT(hw0dixtQ?l0a=QLSc}!ziow5;@Ew#8qc9#*(1v+fhQ(Nq z)#$;7I~f0gdkDaS7!1CXnrNjBG4gj3#%wIWO02-ty;Ln0Vh@&MST4OA<1la^Rf{oL zfI)6*0OPR{v(b&U7;3qT&c;j(2DeegXvR#;LK_xf6_#K<)}jZSFz9YF+D?fv8B?$T zv#<(n*o0LW+`%ZpDD1^#w3zRq3Ykg5I?O;f7GQ{n5@R^lVlK8~3F`6~-x!W97>hla zf~Ng66((aT=AaV`unDWN7n}Ao{>}GNRh{%^%*QM&LmT#D4Tg1bAi`J-ypQ*F48u%} z!75C{TFk-TZaOD6|BL;x1v9Mde}Fc}q#iPWxjl^k(ECa7FeO0O5sqlsD#7b0o(6I-( znM`lT0t_B^kcUetF*aZt_Fx`{QSwrZMoR@VNzAyg0DG|lO<@OREhUM>W=ufcgJcxL zF=x_2nT)#02W1Y%VF{*V4c1~Sy0MfJ$4sRrF&D!qa52U`#Q1MwCW8f05eKCWQ!#;> z$iZxMq8;5>jX~4M5Qd}fVG_m&EW}hS$2_b>J9c9ohD@iXF%m-xs1b}&Rb^!+jRh5$ zgN;~-Jy?mRQxD2UjKLnv#E?fA1sIJrn2ODqhk=nKj3%tcd~C)N?8aI&J<4{csitEl zj+t~Uzyd5qI|j|52{0SoScM^vQ6h}S#?ueVOf*MP^%##en2s*AVNfCaVI($SGV0Da zD049sEjDJ7nW@HHY{nAQJx(V>6S^@LLuZmvjK+M-z)~zmCzfLqx={B78ATID&SDf` z9HwC|7GUA5gBEFLrj7-5=s`CIMjw=cPcrUjQ&Nn>B+SNaEW~0g$7<|G7Y5Cti7*Po zY>Xa^#}drJDlEYUtiiCk7RDnpQF9N9Pu#9A!GR;;!#qkEbvLlcHBpsKMc_Mpr{H|Ar`nRG@h!$xex z9yBc^!^I?k@tBX9Sc+D3Vi|U09ahJ&A2wmgGmL*XGZD;y%Sb8gPf_nCWV+i#EGc|7d-`n*4%_vih7zute6yL)>Y|7G`>Y4(?Nlw&3Pe?^c| z(BK?fT;b5uROA?&TxNL1Hf5B%Pq*!O%p8*mDdse*oaYV~dBk0Y-tM2apP^w+KU1dO zZvQU|78Pu8gDviI=vh+57{l-ILXI(*G&Njdxp)2SUv?WD;vusPzSAPR=$G9X+e~x# zIXcP&%bep@UQiV5bAy3ZBVv@%l+19PS*BQEmMdIfjjP<{Av+8{*P3{jhM3?Cr&!=T zm$}3W^A*9;^Xyx0v%?M}mswoTx2Tw6mUCR>5;wTcUAEa_C~a=v?R?-Evz%m+1=hI6 z18#HV1@?baF#ZDjy=-xCh%+2zl~e3{pP@d3YS^uIuE$RHjg-Pu_=6?MayB%Fv0Pc zsLy#Wv%wmV^MV7x@T3f^`Qq_XBWLIm+mR7YGtL~dEOV7xoOzku!3x9gH+39iY)b0c zy3~~Qu3v7-IL|$<@|gJzLGS|(8parYh1JRkXE@0v*15?x_c%1|1x&O5-@KS(+~5?q zIL|#UG4o0z<}7!)_9~gG*#9-bK*j!Kj7=sOdbJL4m_^1};Uw#v;U0@T<|>09ltGR% zl9d6Da*hcua+_5iaOZ=0i|RGzUcm_aKcpd!aFTK6nB_7H+~gV?tZ|>aY_ZAEADYS! z8!=;?VS*c+;TDVRn=zogVET{rggG8@@wHa*y6weLZZXNJKQi|KSZOoHtTN-e9|NIw#d!;u$0gG(2!lA3x zW1Pp#GWORx&Nx??WsS=`WR)E@*uUwh&c8{j1tXkdfkm!xl^fjT78?xxjW3amao`%6 z;W!JN;wFpSV}+rjdW`UpS%yApN*QCmDo6|VInVIlYM61>+5dMIB~uJtYYsWeZDx4P z97q4&95cx(>pb8t+YB$rSk+0$38t8-+W$L(f`b14E9Jc#Y;cap++^@$QuPn!j1k5; z#z{`HzyjB}&IXUzV(1@b>N*``jAf=-<;->V|Bj%jpv4LY7QKLRwm8Ru>vizW78^%7 z!z7EG;wtC3$t~{jm>mY*VyKNq)licSl zQ>*H6nj2i;E?3xOo#9W}evESNUA7ySnPZh@<_`s1f`QBQnBxrHqNj|p$TX{*=OI^_ zc(=vIc{aJt@U}I;C_7AYsI0@B;4-IJWs&>a_Wzn7@M#q}%nlO_zsDSNf<;cV!g48KptK9e_Rg0_MThd!$UCs<~No1Enym)T~O zku@V=n*Kx3K$Zi{F~%~}+~qu5TxI0_2Ea5A^Mbk{_&Ia*0gH?aOtZ#$2LH`mG0knx zv&lvFecp47a-S1CW`;u*bIlaXoMx3v+~*eafiF0KJ}C7pFvDfevdLw}KBOXNxZf*h zc*oKDVGVPFNv?99L+f?}$GO90cDTvN7uCDm^UPds|IZ0F6|Atsdhf;+Qo}MsUy>mX z^MDBkKH>;wgi9>5#ySspz`ieA)Ehd;F(#SeESI>8m}*>HMY0Gu+nTJojBMvv1G-KM;%x`aZ5< zjxfhru5pDmZg7`dY%*522EJw_9OW!CTx5=WTw{|p_TOa09AleFhQDtA7X+hUcNTxr z(aKdWafh31a*xAXriKYdzG0g&&g9KT%mprSlNAO(W$|%@EhadyFB6Qh$n?Jbzap4X zaKL5u-6Ca-ai3`hzNrBYbDas+IK=}N*|)7>4zSJ{9&(W#ZZYyLnc)~aoXiWtpY~zE z39fLFb*}S}eV>u4Z_5Bj8E1w$=D5sdR=CdKXN{Z-Y;l$01G|I^On%M)*<^lS&=MST z;PY1fcPt`CIl&|+ImBIRDV%Ldy#=D=5V$o(<)9o{7n*)!*y zXPT>==g8Oc&Sb&n*QA^?Uzc*OG5CG^mm}Q#hLkhDFXf!%GH1BXop0J5?6Aq9Z)x}k zrtaJ7GsZZ#nB~xc0dX`hSP{gz!3FMelT9YRV@huIVve!)T|H;`dosZSw^?SB4Nft1 zXey30%uyzp;T&^ZW|{ddK~-?X1BQQ~;wh=&C>NMv@>X-tIj(bsJKSNLhYbIRDPWZI zM^eot&T#9LfpVW4Y;pTP?ElbzXjs7r`%cRQhd9j%=9u9kXSv1&)>vlnw7F-5hrM!! zng+xegH4N&QOQ2wNOu z=tt^vm~|$(%V{1m$Iy=rATNjrs;u*f2Mqn#;yE?~#+YV`^PJ}@*I8$sdpu%?!Jjy2 zj%Ac_W|-w77kR`D#(&z||AH++_$TIu6CC=Plyi?cMp{zF;?H%ocmJ18Mjo`Cj6Ze% zjH8uPjIqom#yXy7_?+jte!J&?=HThd3}bg`=er3(;x6s(6z4h5Dwnv!3a3uAyAAHL z#STL)C*pbS?l2P^=M2+a;tV%gCv2lzmOmTx* z9&(YX3)T!_=+-2Wc<@ZyMOH6Z*^Nifz6tKWL4|sUi{*OOE zgSXjM9ARicgPh?UceujQ2WpVZJYb7`9jP2N6|6DIp$E0Qvn+6#2dr{psO`u4O$~$R zJpXI$?&vxDe{7`PomSBIXmiXVu5pYFrg_X+_TR1p9An@y?d~LpSYV7RjB|s_+~Ynw zY%|g|z{jf3NlxVjYl0%{tZ<(Vwt39dSi3tEI1wmvg7c3vLN>X|!0(%TCb-9eahbWx ziNH9AxWNRsIK|N8wa0ztHw1wvw7c6JWs_wNobcciEgDWR%kYH7#%Wf$zEN*Uuk=#{h0 z0>c*=F-KWtl7VMiBTR6G3#_xuJsz^deDETx_--cx4K8r$Ia0+I_c)O9AS;aA-E)ky z!z?GBD?^;)2FISK9+%i*-}BWAod^tZjH79bkW-uwoyZ3|f>i|rFVI6yys+Ip;yfe0 z4snd@4BbQO7~>(+?0=CIbChMKxy3~uvBtnX4T!@GW_(sK!|8kG&52+^L4##>xW&ke zy?_%8-RnePk}(#T<|^k|p70k>L`!c{~#%5lx>bP@Fxy74s(tpTws1w zuqqhm1{>VvdDIfjSylu_20WSesw{ZsYXn6r4f_<9}T(7cX3SgJY3)L+OL4_V;U zUs^K{w*U79+X~WebfmIjO2Q9ua=pok#wjK_Qnc8Z36mpRV{SM!2nL7hWO_C3?=aGsHes=zo8ILpz0w%9ny8VCMG z=6dA}KTN7Q$~8{1!2rFoBhl7e@n0?82CTtmN7P%VC-!gtJo9KXlz;1-i?z1JLb;C{l^yOgdbxVPDU%#vhOytY|I323g1#%Hj4`hA zm~|#TqG8VQn86JreUub3%jA_h%2{r5iF<4@^;<@ImG^S?YVT!nQwQ8Hv-7CDMI-2U zW1A!FzsB}pj7=sPj#(QV;}TPBaGp)BGW1a$<~a8_!w#1i`EB1580S8-Y;!R$=)cy{ z%USMnfz93n^sBQ1k*X0h!70wL$PHGw%Q_<;Gq;Sf!vy<(*Hm$Y>&&puS@vCL|1bA$ z2x{EoE_bi@t$0)l8DW1-&pF0PF0jBguJMpHwz*!!N{X^fMZQ5G2I?}%VNNl@BIoLP zDHK!`G`P)U4&NkoV-^|5xyUrvIm_H9ta4U9sbNlUJ4cxLjJ5K6GQm*>KIhOb(WlTt<)|D4n_$qYA`W0gzn|GZVt6!*Br!0&7L3r5Zk6P(=9 z0fxS);~eHX^MNl(xnN<}qG9|i8XkA>>}i<0%<}MS8esVAGQ{L}jpXq@3%+maIDf0u zv%q66u;K+#BIVB^Eo%W(98Zo1s{GkJf;h$MV zEOLcy)>vt&$IQ>wo6zuyGu<_22hMbhPx8J8p7A5t4!p>jZr_vh7T55Z?#PqP&4p*W zX>M|!hg@an zQC2yT7aR(v8UF1v-35+wowMBKF54XY9SuL#KX`D0L%*vYhdIw8SGmXy9&?v%9x*j~ z#t$lcjxjDW9~aaGS#C4Op+}$TmO0E#1|D;!yT>4#+-3Ob7VFp-xg+~v?ytPLg^P8uZd*LZTyTh!oZvjCxyuDM zS!OU{TQSWx3k;`ph*55Gf{|ya&m}G~{Y)KZj)!bA{9OA#@GKRdYlKX4GpWbi;|jyi z)?-fcfLj+C>GO=3BaA%9NSR=kvs~l~H@MGTw%BAbWsN-F)Nm{>I1r@RW|raST4bE$ zIxE~^l}FrRAgu!&;OO(tbmL4h%NZ`R%1t)dV2j6$K3@l3AOq>%{ucyZV0AOjLhlAE z?0cbbN%p*1!zF3Mm%IKxm2FE$gDK2o48?1Ae`)srSH&Ayk)#H)0e!_07;vrKV;1(w-j zgZbfC+YW+h1}|~YaD-b-agSLBv(^S!vb?$;}UB;9TV_aZ@RnD;gb>@x}Q4}EHchIC)wm2$6xO#=K_41An2RKXk^kpHW5`<2ZLX#X!#D?A_-ExBkjVIr}#j z^^7%B)In}8=omBq=y}fM1(828r*Dy>UeCG9V>Y?=PZp<+gqJkT5w58?!5Y)tkHILU1m*kqaEKb8STdB_Py z-l{&wxyTGRxXE2M*yJ($X6^sYWvg}8Trk7Pzgj#@u*?~5vA}(9Gw>(Y#M^Y72Tbvp zSq4iw&IngH!z~uM-z#6y@avo#jK0qPpBE$*tZnB@j@+-8|gHrPMseBfAKFz_ymf-%ldt{~Y1K>m8jO=N!}A z;XFg{b;5CxJ6z`x$KL0BnfE@%xWPE9@3a3ig1Ukk9&(9IuCc``J8W?H1I~J;*#8C} zT1+rrQJ-V$>a%&d?aYZQoEI#9#O`2?k-xBJ7-#Al`+rVQyVmyr?sAKPs*!VmEyfx8 zOH;#P&T*XUoZ=Sexp$q8GkJsh9IYF%hSLn>T;F8Tvi}n@$DzC+E12LS6D)IuTioXn zH*c2uztT~T@aR)kJr{2=bsYPwlahO%mnjZ>L8h2s@Qt2hjCH0tx1+<%w*{+$@E7%% zD-7Bd2OMGOOSTiYSYiCj8en!;W?1-lA36nd`xVbIwP(t_XNK|KeNJ+>ckTXB@0#OZ z^S*-ppAj?^%<-6O9QbRCgE6+4;mFsGlu4GEW0kAiXN`e3nR^a!=o_Yp6P#j}MXqp_ zJFLG+&zgcm1;KqI{~L>nBg`?*CTF?vO$~F8TMT^5)G*3WQO6kL64Tt_JcqumL5^^f zaW*)~!@Qs(2>-1SFv`Gz1Bn&RvCc*Ad`FKt^IZ*dnW4Y4HaN^(jLK9!-5?JNp3WyjQd<=i<=Dn(3~;CLyob-B>NYw8ICZ=IF~rj4KDJ4 zYYhF!$2Jq(CS6l^j4W^?jmtDMbaDQE2`M$9c9vcWcY8G4H|o-qb~s$mA1VVE7pz*=Qvlne!Ds29-9mW&UUACc!HxkGRsV_ zV;oqLYL0W_E@!*boa6#GxxpRoGJ4{ypSZUF}>|6)XaXS;EZGRtW$a+@1$bC=Qc&vx6)aOkb}e@zg7s|HW1$Rd}x!z%mkdbYdI zIR=(}+;V`M9On+FI1tnz=eg0l&pjS9@UPx;fqKj^#yKYPf+fKW_qf8byPfUUdJpiB z8w|b88sIPo?yg}@af&$>d-u7);gFH`?z6*H4wt-#0K<=4S-sf+ZGN;~@`v z58U%?H@IRB8RIMy+~O1uIM2Czo$ao1fi?Dr&-#&Tsb=8qGQkmUGtTtA&vs{7y!Y9B zccJ%yf-)Pda`Zk@&Lmr$X6PM8%3-cD!M^*-90yorffX*Z&JGV5yx-Yw|2rMM9Akzl z?%gl1qG0X*XS0{2D3b7j=>Mv zb{ye4a<&^*F}L7T5D-j8UeT;v5&a!Y$UWvHz))q6n8kym8>~r{140_XSu^wwpi!D^*X?DMqZ;H6I|dd*ID5X_g`cG zw*=uoRIz3bIl?K%xyVUwbB--8GCt!-<`Q=~{YQ@08%)(}4S;EmbCM}ebD9fW;1XB4 z@>=_ULr_+*#nd0$uWYgZMyq^Qhd9JICtqhR@Ze8%gpoP*ImKOWG4XLz^XEFunb&KG zbKGE#TP$*qmAs%M*kHJB3OLL<$2dDL16*ODSI#xIxy_+BIGEV_OBuY$qI#o_vcGq* zG0FmK1s!1KP1X#T8T^F(-(NIB!4gwE<{aBxVBl|!fWxeFgu5K&5&IW({F4rzf7D@) zGhje79OeQim9MeDI@fs2#wYFn=%Q_)Ai@4E2M$NL$T;^o!{ImEPKdsil1_WBWy9n;F1(_hy_k_jidi;^>UIe7C3N= zk#T~7f3es&%mprSlVvto&UwKY zrKF1%ZVU$A}378k?s zvADRvBFkK5-}`iwZ8jNOvpaUIevUFz@x_HRoaJ)pIE|4_RRFOBN$Xc)&Pgmzz>1Sl}Kj%m=TqDg|RaW{v}2HX_Ej$pm*f z$-a;10ApO_4A;2A8jpCu(G3IGwWb*3_?1S^GK)R0vZ#0M|F&RH!SL0#13TAPjQ?%~ zAJuaXUu*w!f=is_CJWr-5d&YbCaMk`wwUDT$E29^TxOY7*15wy9(~3B&t7MazG{_U z??Z#joZ>3yxW)ypbCo-+bC0_`;1Q45VXkHXd+IUH2D3eHkTD)}gCjQ@Kwhva==++J zj!_0aZUjB+M!*Fwv&t$DxX<8CM*ekE!C_{YV1YB->seNF|e;VU9(vvci2f82FCQ07e=5judm4lT2`f zb8K^!iSIfediS}{VqOsVuAXy%4aT_iJ&TZ47J0x5hYmH&IUaMJ{ok`aImR|8x%_?g zSYw6ztaIQ8GRioEhxY%hU_?-4oEyw?pNkCNDz%Jpm$PiM$nf`Nj$;fRX_#ded*!Tf z`IHW`$rcCx!$5zaogdn5Kd}Gjeq>H>b%6ZXoU;Ge+0QYSImIoG{=|{WG{Z;M%ugMu zocozfdEo-*8Ei>4i`-)T7wWOju=+d9sMloSD6gSk8li$Dw^?PA`wXA5P1+h_f|H!( z92dCAO>QuFMus@THWM8B4<9<5;0CkYVu4Mrxe4i_CI`1s<}( zz+G{$Eg35c#o`Fv$+589DE^ z?gHanXNFr`=MftW92n?Ng*Kg}q*e-PH>tTZnD5O*BE=G4l~08=Ggah9c7d? zCYf&vrUgS6N;N0A&PndD$`*GR`h}D+#=viwVS8$B^rQQRA8k;=e$nR_Tc58t{Ommd;%y5l4?y<~cRv8>OVn%qx zS%$h6Gh^(3y!ssBER&D7|BHg0f>lq3#@a5*(Z7tQxjG_GhF5r zE4}-yaghgHW{ax~-sQZ&8i$yElKnp+Xg|p!V(7`Hf)TDV@e~IJ8*v@!-G8bVoH);a z4XY#EV1}`$$q36Vv%<~ZeQvYLeeN@G-g$vT_OqE6L`X^k;IDrgI)ICTDbfg&eZXO^?il3F%d zWs41Vc)-4-)H2F}lQO{(j&Xt$Omm;}?0dG%a)kAh=lS>lfLg7ub8QOfv91YlEZDw@7>CX;X1Q-be()7Z||{ zoM;^96ss(9;DstO!WyI8VUjJT8NAzhfk_T==*33P`HM{fS2>`;4aRyMd5LYSe1hwF z!L(qf_aIw5;LzR8(WDn~iql+Rj_WM5$!!K+YUGTuFLYjDjw9S;ij$W}J#$>*5-S{@ zx~-dU2xbK>ZgS`z=LL>A!SJOT<~*0U$O_llV1vhOv;Uq(^m3nq+~p+WuP|jya+zsX zILR6dudx3Q1PcmUTw?HE=LJ?c#Q3z1aQ;;~!c8u)%?%E`+A8i{GZ41#v!;@>9OFEb zEO3fzEOMPI+|1hl>w=nsI+tfGM%MpWNA7L4&PpXGnBwT4_k6v#| zxcCN{-rxQ&3yKPA+~XcQY%%fx9aym~ncxfy zTw;}*Jm4M!Z&!~o_77;7W1MA*OPph!D?DUv!2WLwb`^}i!wZ;V%$3tiRX(KM?E*+B|xn4m{Wh*QAVb zW|?7uIj*t726uVP7W*IKzj4;j=vz%gq3tVIL12WFB57_@r!K8xluX%u@tT4j{ zb8NB9=)XxF6FlM!LlINJ7^_UP$$17U)(R)N$rbK#;DhQtR0lrTTh)Ri1!+!yNJY+Y zk#j6F$4!>G#|oR=VBldIW5jC{s)_zbM$&qYC%E zxW*QD7*cVlYTI~lj4MpD#v%_{Vek>^F~T+zjC{;?GA z*I7IqW{MM><0MyDWsN)BWs6M)uebW6M#LzGYBI?K78$%j!%VWlIUaL`{g2E$2n1t~ z^g^Z>y3rJHm<7&qokebOn@5b+rSw7_Wt6F#%sFQ{#|18O_!FkCcb|JK@R(~1=6^%O zf)VzAQU@609A~-6BG*{qHg|ckop9f5{&1vStzp1B! zQEoEBUFO(fnXyk9Inz91mVrmvb{uAv2{t*y&@JYiS#Gk%eeSTuV}^gr{ms~u%r%Q#=OXLe;32DQv(8Y=h`wMK@PKJ{c5GkfzUWhxM_*E(ZSFDpWk)Vp2jdJy_9l!6}lwHvAYrY+5ck6V^kG20tLLEO8E=4SG zh7Av_@rYaOu*Lo{9lb}VJHi6nT)I!k@9{SB`*{zSIm;@SS!acF59)LenPZ!cp-y+` zarS@c!JY2J<7_{sIr~r@;q=3ejC~wc}zQ|O{+%EHTg0^6V;Y`P` zPFIoJZ1I5oFP8czDCY?0ndS=T*<_i4i>(1J@QAAnXz-XFhF;R?Mkf5TALGotq?7Mv z1vv$aT;duVZ19N33{UF7lZ>2WTw{t=W*K;?`W(Kb)2(rdN31jOWF6oz2VN$V9Oo>j zUY7547X(KNHrZi=6H^*y`O;2z;3*nnjPX}=x-*<+kp)(`^(v|5?yEa~#@l-say4?2Ft+jq{qU`LST5pxVZ)rrR#51HolYjl*MKUA@IpF2#?bh<6hG4wQ3 z^hfG(_qFP=f7TQ+^E#Pja?Svm<^l8bg1)C42?to^IOqPX<7c{MfJIig!j;!s8@+Pw z_paxqIN_T8JbHr>bM!Bam`hw>>@Te??iDo5=$o|r4EsO*H&XQsXFeymTa;pszFC8; zyv?p)t)xK)Ry6obYvLW|lqt?I`cBVtakbN}bD6uWvdua}&oUL4$q-xbbzVFxZ%zcW z3hM7OH{520L+_VjX8%otN!ROEKew1-gVU^EWrQ5Q+SG7_6B-<6hH2#CKayBnGy0+6@6xZ0`E|0#L*MJI+3qm*f%`S(S1|QLS7Jgp^-4oz&G`nBL{lS=y#-= zWj1)kL-u`FhhO9c-!oFSnP%)zgG_UY1K)SB^~%{`ibpKoDx(?uf8dmq3L;D~&N(Kz zz#`W<@E>~KyU$kdK7%i|T~9lbxz8kLnli;X7PgxtmYZB-gF8HAq@@Ed(I6K&`g0#XtZ<(V1}06-FKk;TerXDrZF>*b z*qXHe6K9-!FV(ZNwh!C4n_~`ijhsg(&UHt;FmT?vZkz+0gN31e@iCu8M`z$k^7i^q7*Ii)huIIW{7P-$V121z@ahP*K4Y6>+xo(jSR(Q-t z&wHHfw%8v&*BzL$I62N^PBC+D_1J%(bKO-|2G4c#+k()qY3Nd!;4l}M;5uiRiJbFG zrk!99JLi{7JBrz0<>BYLZAKn(t~>N{2Ub*uxWz0NAE_QkE-R(Zg~=NQ?m?S|AjztY)J{oHfi3C=RZCC)PbJOgAcFIX2Gaf{*S>i}bHF~LyQ zZb+Z&#yG_U11~T&9AJ?hZgA*@I>c7yT=$qWFP4cv=zUeQh*@Wx!HZ21e=i~^2qq?t zhzl?E0hZel3s`4Ex{2g{2!WAH3*9`7xz?UNQK%6QS|aGp`tY@`;%z zmfmv3;A2kqJ@r=qFY?l5wZVs#npX^l?mu_st=-YyYy9cGAn4!oEniu>=SKz~abor0Q?Ft+tt>5>iC zg^!os*1O)Vmp;|==%&&yHU=-eduB_w{e{56$9}rh-57jeY2#yq=bvwqCT}iXbmidS z`MFze?H-q&bp7CcONA>nklZf)!@Qt#m7a$hw{|y5Pr6YbV^?{_N~83+tGpuch0-NgX=33ExBA(g-u=5py<+A3 zKp?VHy6mdK3-g698MLzApRoV!xi|km%7&CRm4*KO)^6M|{yUK;mxKQrx}#3$q&;}J%8hT7F1vd05hwfhZ|#oUac>~h9~f{q?QZa!r5{~AICx_5o29#LdTR1p znmSQ><5h$AFKyg7*jGwz4)&dwJh-)#zkcxHrQGIV@Z|A#&G(&en!K}Hy^gNm)!-&i zb$fB|Pp^d$WkF>Paq!pg=xFcO9rqIMRsVnP^%B)~FZxGr1Zw#vr{iCU3QI86<$`l?wY|1&ks$V>MoQXdX1&g zxyHQCO_ff5RQa*;%{$63?sYqPK_F1P^uLGDE1ObQ_+Mpn%5wj!Y(d%l|0wGXe^uGs zrKKA`I(Yw+)jRI@;=vQSJIhMPA06yFQMmKsVWGR-*?2_7K;l1lnXq@gtaAC%(xa{& zeAqq0FF)m9!^-C$-h3iZy7Vezn!UF7o|l*Y-2D>=uPD9aT5GjEeX5(gW4V_a*A52H zPrve1cm2-mrt1?2uPpuI+QAD?jAu&^tJ-(THOdnZ=Lk%*?w^b$3f|?i~i|1WydTyL8>hbb9>Vr@8~Z4f&wbac!{g8Ty+6HOI;Ct^S)q3%J-Bq^Rf8u7 z7nNFFodZ<+0_`CD&VE zeIF>j@p|`DmC_a0OIG#{?_WB&ez5PMg^I>{Z~Y%DwAZ1|Jtgjgr~G)}l@6hk1NSoF zA1pnjrvBOoOONZ>{$S~awZTU{aN_d+9_xsz%bsn#^;9=r`s*78fBj_4<;LZu&v^7i z_{!4Rnt6;|ReHn?x|q1SbkPmU=Qm4l>^XXE>587i)zY`zKNkcOL&EH_H9q zb*0DLXrgCor@GnRiE{T_N>BWV8FR6cZ(8nGy5h#cyPY_=v2@*y zgO56Y{GF$}howKcY4E;p`?yK(d)Mi1@Q%w1hVByx9J{REad~pg<>I?bPxyFmj?2G# zsx;fH6@Aa?Zt~7riyq6o_q65oq>sx`#pS_!OIP%2&A$Iv#ifH@t+wmUJ082BrCJvZ+}Dn+oc7a~5B<(yf6!Ic)txs>sk*wA51sC2?|gX1?biCQE>AAFocKuT zEp;s}UiquyQoUDe@9NXt$vbQ9du-sNzq&lxcA2S`ZtvAvx$alRrPxiqTD4zYUyyWI z4t)Hy&&r>C$>_2!k3Ug*?M-SWwtB@kZQIOcwa&}ke7f}U?ZNw9Q1ejpQ>QK7J2JB8 zGIdMoTk4!xyrp#Zroo4tU%sVxyEh4?*eA5u_vzl)dyij`yr0iFmxp)O&bsXTOzE|s z(Bk@Md-=PgR#~kR@z3>U=l&PeJk$Eze^uFYS^IqHTfHi&o&Rbm{7DUMe(`iSeCNcC z+~2S;c|JmbkQeuv+$KWUR)~ls>Hr}y4$+5%Bp9AUpw7R+<94bIr{a} z-HFmo7eA;!=qlrC;m#f&tNW0xZ=CKndY_ER|2`b=*tZXG%6_wSpRK`1oWFZ;x?8`q zPHIbg^WXi|^#wB?8#?^2%LSM9@Aq2x=TlaRtC1h{R@faGsrTw`-rBo+M;`axjvW1J z^e5Xci>FGrZ%Inv^y%)%owZ^&s}*jZ?hf6#N|H8x_(!MxqUGL8Pi9>%{z>P6>vZYcHxEAW{G*@$S4zU4QZ4<<(|*76 z9jkuiflk>oryaVzx8613a^dXh(sMqgTKTrqJ__z=t?`z3U5BJ$LLfT6*ZW z^s(x)bE0(Pr}Qz~*K|hTQR}!@D{`{goh^Mwtw)9irQBuj3&?+;a=ys8)Zf5}`=i08 zpLgz6Kbde@xuA5>E#4ZrTeH{pSFP5qzw(wt>`mbvL zKP#yB)gh-&^?|*6rQ2_^2UcC@hMEqq-i|z3bvf{m(*I-YeBi3C?*9)L?)Bb6!$}F= zi(ZqG3Y8XHtf66}qC&$)MGcJ>ZPc)^tf;WCQLzmTe?#9?XjoLN$Z%0nL&I;hXrWyf z6%`s56}1aq96BnL-}C+X+|Mnv9*-X9^Lqa~=e*DRyw9J{hwFAs+A3yfd6ERMXCLwU z`DeDzd<&T<>;z7hxo@%5C-OX!pwH86VY3aIHsni@i8;fRui@DeT^ z!aP&nr}9Z>`dKWr4K6=2SwHoYD2*mL<7wepGU;FRvN6RXOZvai>iJnnD-W^JpZf_4 zL#qTBlPdS9R?08@Y{!)>O{!IVj)h&Fh&BGwf{uP*f0_)cR_A=}v7zOC8?E*Q7Ivjg zCs5DzlM#%%a)C|hvg~cN>K9sMsZy<)^ZaBA6>~KrR{kpsIy!*G8L~^Yiq5yl8#+XmXtwGwibY)r=FU1&vL|2B&( z0o6(?v9K#@7P;^)3px^kJ*6_&hgQC7{}|qRGneL=X0xBY zk#11L`z~75FZ;)OOs%w2IWxBS$I1=1D;L=M56zO-_DqX$fO1>?a`O&0iB+muvd!|b zs}W||YZ@@>Vn>I{z9GBbrM{wnDp^BvLl;U7Z~EB?84>E4&7S-%U2_yVQi1vZk_BBT zIp6k=)f%>>ShXs^?Pen@5o_u6bJ{Sp8h{zQWQ%Gwz2grqveK(sQM+~NG3pvcto+~B zYT=0G+|c^2On(op+V}ipqlT1ZzlT=o2Yzb{Q-oN~hq_7{&aVJQ^~hS)%H5-GRNK;~ zTJ?L?`9@tmh!yqfkQpr;0XFQDBdXQ+sXw%pdmpXLKL1#lsg-paQ}T0N1=WQU3V|hu zaQFMH@5Q4!C`M&jC%99~i4Mw-6)1+VlZd z((rx)?{tn$pbT@GB!57AM$a2y0n^3Xl?B^*;lNmba5JmY7t2i_(2LH+17r##gz8kQ zXUPD!EJoj35o`Rl8a1}S-Kuqk>{YFd+yO?zn3B=mXtiFgVun`I8DU|4zZuX3NY#!^ zpzj)4+>KV%ZwJ^i8eK0_t>){rF16ySMXdaHMuRneT7Xr*m+h)GdV}`T&REFNG{HhP!;A-eus2ZH+?S1IiL+XnO&O2fPc*mt{Z z`j8q6@35rAr&>KF41=+ma`_Rfzf(uy@Q!IyT~Tv5j@~t3CFVq69kAAH0LXi{BCSF4 zKf+WUxXujzQq?UD!5UzL0XOevKtV~X27-qx@u_YzIH>D~oqCT29nQJL%RMsbV;Y}x z??CXZCFvh)mqXZ%IZzreaqo?C$SjKd|7B z${jjPYv+-oKrLoZy*=nwmRs1B20ON9fM3utT%8N-sgY$pw6^YHjT9r0stm112iTMt zgWHH$*+v~r9eYOyF#j>xrCJTo4ls|^*oHk+mEUMVmxoJ&*ynV()P^G!*!#RJ*n?8y z3j@qgqpD)nih5C_(Wt5tvE-Lk%jjzZaKwOH9XJNm`j(Edq1&svsht{=hVUrtVqmFR zW9*r<+9%WZQe*yggJV9~Jq;UBQ+~4FIyMvmM_`({+ED>qIYrj0PHn*;IaTjsq;2oC z$m26&_K!8$n7*GpCGUJX?Ig9-h)ll`j~hPWG}wHSI6h&W%)Q=F)zM1(Dc2*h`)QQv zabWTFvg{Ko=z+}K)MQtMwms%|gG^ncD~*UX#_cDG8?XcDh1(>%KV^(T&7c@VcSA3# z9mob%J!k2J9URLyRa1doKqCRhI6)bOgQPvRE5)i?i*AuAT&cRSI}GS(0H)m_TY711 zGg79XrB}70ZVXj1idZ(#%(0Hx6qeo_W%@p}YS5}M{SGzh4}&_5@aPHM=rjY9?Kt$Y zdU@zGUH|rBxUD!Oq?R&Q430$}kI)lAA)g8*mJX_K)KV@&g;bLkiO@Siq3BN$DvRIG zZpCn5($DA#It3=o1Qx++DcIJMv>6ydRrcACts~T>)2F?VvWjH=v#rhNWtCn`6 z1F?ov_K!uW*jZ1?318xlGK6d$v*m%$s3Pkg!@=6XHt5GypSFK2OB*;_c6~Z+s`KZB z86xJ$ZRo>%#=V2Vlr|z&(ZSE z*>4?POA(9w<6tm@xN3l<2G>ZupgNdkro(;c+9J#4{m;3rZJs0FYFS+_)4!k>W%J~m zFSuE2DIc`9d}UuySNbpak9C?ZcK(9Q2prZpx%mk*;@VWG-R zDUJJqO@my8Yfl}Sz`6@%@mKi1`7yciD;!dFp{xblyDzl*C~aybI@9W;s|U5T@8Jlr z2AFQ{oaPgEpa#=l$zP+Jd69)(EeID}ykBpPzNQ6Tz_3f?rmv~7_mchken}&&4y~EB zSj^=-{6s^>dvdD@)M>nu>k?h5Ut!J}*`!$`YUnJB2!>CqXN=7jT-_ed( z+oiHh$qh^P>yl1PI3gFYpgkd*l`D1n+1XDGa=oV4s`hia zCVWa~-bs?}C(qK~rC&sm6)GiAa0Mo>U=a?*ylq5gH3S@|nT0Ql0xV9=8&T zPsQ3yH4Wrk#L}N-JyEfFh8Sdt9w3stFO!o7XjX5I)kn!zy0=lTfNmSjk-N0?UMZVY zuJkISc8${Rbkf;XvUdQlH$WzRsn??islCg@RC7WNVue>TRyvKYd)%CB*(y|=XAGz| zQEg>!A**Q#?QLi%<4(RaQiPpMqY%knQRhhLUKmG5c^%3oup07(uY z-~WpIJb;`pPd0r!ZMvi6SH$z{a!)|(TqchwuZ0&=ic?;fj||!CF6&=%qn6J5Wi92zl(z@XrQ>x&UI);JyuG_( zKc_2W*~&ei@aY^hjzi8jLt@eYofdgonMA$xSgYtX6QIXG6OO?g{&W`2R`Y;+tW zYxeUmamtpVX{SmVgo(ag!GZsW3L5G10yfe;Li+ zscE+oPqvlR%3PSXu7AtLV0-tzK|P&l9=wnne?dfU5sts^%4ITDuz2?KdH9cBBAfUX@*_+MWN{Z|yLhm$25i z?q{7gE?z)opnTKE=_8md*`|S|nZlI^yBU~i>}2g&jNUHyjL;?T_Wd0FjdaqaN=0BY zuqt(;R0+&8prap{^_mPGX4^xW&wI^kuz0^gu>ow3{Nx5CJK7jKqSYB;gs}!hK4P}y z9rC+x=t=DBA@w>{&j6c^ceP@@7HE3f(GBc+UG{#1D@R|KZ_&0Dw9E8wvC>BHWth#& zUBvmUU6y@|Sm!>u3$`un4NVw)Oz}^vGDkOJF}#yP%n03JP)2`88&3Lgj9K}xiPFYK7Z+wR})*PM=#FBj) z+Q#VwlnOG3V8dZt-R2X=VRRb)Z7q|M4&B}bHdhc=UN%GYZpiZ`z+7Oac_0RrhnUi& zx(QvDEmtS(B%s+GM?WyHOT&X}GRUPyE5&;Rtv+zD#-H)E*Qh9nZ0tOQSOtqV>)R21Iq+s_wvkYiHj8^Z_%)ILCuV zLBSl+tGYRZp?XJQmjO+-BldFU)1XYZxu@BB_scmp_sJ0*L;K|#n>#LIn1{PO$-Z&MP?k5AT-~A~4i;aKD@pfuZ*Q?Uze=INte9 zaHhy(!Q*KJ<^tb_%r&C#`Od1%)d5@yG*g=zuM06ZM55X=YVD(3o-5f00vkiBn~N#l8<29awo|V%H!K6 z1X%~Z_B?Q~0hL#=AcWYC24HWjY;m}! z*;C^}TD_`O01j%6BGw8t6P_#fYW7VAG`?K`MNLztkt#tc2GV&qxf{(qppj3X*hoG# zreoCvn%h22HcY^oNp5*n%WAjmr96Jr9qin!O=cu`oiwK}-fEsJ?Kk9->7mx;0t;4{;#Z+->zFPZoH(Y*8wg%eh)->{fX$Pi%a2;v%z$1&u?9Mvd30l@Omg9v zypye(CEbNq1vu!KJj8l|$wp<4K8zI1l6zeABI}f3FD7gZ9)49fWwvF@)q`$6&@?q+ z1lTe=AY)&0*R>P}n=I`^@^SPbEm3}c9DPVQ-LfFX(CyjaU~4K->jjdTHDF?Z(PzjO zv}Tr^0ht~;Z>=47M(anW6CN*9^g44HX(TBS+z5#GcC)qJJ9F8bz!S z7|dd^`Rua|t`Y1Yzri$u9Ta<3NV5o73=C>k0Ba4dvEc>{gA&d4v27x?rln}q8k4;T zb{jCbrx*eDr^u0sv^C*pmPtvTgjO~<=-aGoS>=Fe>4JHA|G8z%)qqs& z*#WkU#&Q7a1(~gsUNsq&YM8`^s}Oe59=-kA6YriX+1xyd_XGkkJylLU0mF&sgmm+v z+jGFd=9K=HBYueOr~!7LBb!bjbB67aSJAc=?vcHe6Mb4m7~}nq8Y?Myqur4cQ}+hx zA1mE>opBw@FKca*>9~BP?0Mi0({ZJ+JE=1`ach84zm!eU)H#|auSRRO&Xv7jd(63( zm_$#;N@1>*4qQpZUMlQD(~-?sS(z(~Cu^>STuDqi@2)X(ZI$YlTovF2o8h9S$t?UO zSIetN+shUPxNbA9crclf7tn*Xp82AGf>saQV8Thdo|}vF0>O`W9GSqX^JMW)bigx= zcInhFLu+CZxKMp{iTcC{CZvm@wj0frHl%E^=gU8T!eX757m#!Nrk%K93dDx<#W4jJ zWaP=|S|%-%#Zz!i(S>rO;>2aLR&mTF@{Ho#OJo=2@d?X<+3W3x&FmE&L-V8ZjiIMu zC)E6o_5zJ7)X#!K*(y}^+kkb!UG#en?AKXNcU1t3feB_GKm|)eJ#9nRRxrjB!^5 zup5|fRt(DdoslNhP#cEqf#$@VFam7(T`(`-KwgGrhPx!6gl5|BL)B!# zE(DrvMK2P*0(30o#*r(CKJ&q*txfEf46kBo(1qd7V zu*U+yv#P5HpuKG|XM-g&9X;tWo zUCuIZKqI+>szCHjJCQw&PI#V@E2hzjq6W(|QU%@K3LZ6G(ui8^-z=Ms4q(UMWY;u0 zG5R<8nsQ?D+Q8Td!|MF6&S2wwauXMe4+Vm+RV3ZbJkJFaZA7z58ShGvs)brAGi`3N z0aCWnDtW+-V;a}VGg{VBmmBwYg_^LzLj%K}v0CKv+)PRb1_wG7m~U}ooS;gOIiOOk zy0On%!V@ZCXFY3%zn$ljXJw0rp2cjCe|f0AV1o=QF5Mu<#e>^6$lQ3aZ-ZQ{xbGRc ziE?7JP=)sGkJ>lGzfJMr6hS-q-OxhxQr&Dvn^MT;igDdtH zcCEln^W$7l1t{O#;DUNViDom3fQe0^fUW>$0SnDc1F8X;O_sJ9G^Pb?w%OGKdjuGa z{t;lpRyi_*E_AH7(ugE`(eiEx<)^G$Sy#4(8c+zV1o9Pv-o=5MK?z3dq)v5PO-z3$ zC&F$A_UTAmx53J#y((7ycgxqVQN((IL08AFMEnJ9wlPaUm7p@y9iRZH$V^_{XqN8_ zjD_if`R@AQf;kiOo@SO&x%OnY+u=ng?K63GCgYypEPH3tVdv)oUJ@H|5q&aoQPV6Z zoeV$yb2&%L?q*p=dA#REmdq&_|6skD)#{M8x1b$#YU^z{6=*uu)eX$-(4HAI`JGvJ72YL%%#Qi`Z%T${HSNQ=1)N za|ljWBR*i3x?I+eTc$?fRlO-kX6b}^Q>GTwm=q^qI1}7#MqVZC zUZ5F>js~FrYuS>Zld(horMCRAgC8oCFm?YE;H|u|=6FxRR)#;IuQ@cUr@_txjvCOB z3oIXyWv5`PYe4Qgg#qXvluclJV9@HC_|(b>n88;oe$+De8*H6iD}jakWzwm%WEgUA zea*a+-Dp6ek>NmzpkTn3or=j4a4=WZ!fp()C$s>Y0|9yMRPGR3dHDEL?hs;z$WKsg zv7It)Hf?S1lm(O%ojch!Xe2&cZH0Q-Y$|BNBJn{ZPjKEvYldizihWQWTq#w^``=KL zdl0JGrF%8KuAfi;s?mD3YZZuJ?Xs5NvT?fqX+=C_~8B z;*$pw*|D{J6Od;U-81d|-)WV`wcg#hWi-GyJL=gDr(v=d*kC%^Q_4o_a3J`0ctR?$ z`!Kt{)3}g{JYvPZ6suapyBhAs4Ot~}on1yi(Xa_IK<|-&Jb#*24ZYs5ZtsWgm!VVK zQ#Kr7Vy@!cGG@6#yr*L`^*yU@R~qa(V5y-yAs5)mF5sHe8IHd9Ckxc9Jvf)dRP1Il{eI@M0@#zZNwTIbV)#<o$z5vi$TSpAA^(V4rE{*M* z64L5bt&EtVV8pma5z9R>SOtG?bRUcDi86g2S~ZZdt;3r=kKt`SQLdOr$l1x-0%N5EwSZ#Hon!P**{+0Kt2A{`oQ`TfkapAPXl-?+{I6`p0(qv^Z|SPRTETTuZF0L#p+4JaqY^0TyI z-`)ZaI=TmT4=~u|0$}&gaDd<{hXFRBR4s5ilm#GVG`TdU9p$IkYt^M3%O5s4oZ1MYl#{4`Njzwrd1f157i| zQfsL%#FXS;qTBYpZWip(5ZhGVEaOB#|W_UH*zEm59Z$%(n_9>R^#_tSykM*0?AqG&_bXm zPjiyt1yCu-93!byU0(>hT45(Fwb-t1V1ZGSF?~UKA*MtxK(`4TOsq-km~)|KIWmD= zOJ(r_S{t*>l9Dpj%DUZZy{i_n)DYX%0xU70k;FhPA*KXWcO-;eQU4F!Yb?`_L}1bF zGWT32P2M$f@wrTvyx%I@=sDbOvtG@*b>}is`7`dPR4U^RBXcOdSLua!$QRIU^>@l~ z={k|`4yDJxVg+PQW64jaMaiW@!P`++DeNp@j_LavU^#G9j879m%>~w+7oX~;T|Z=f z2k2Mf-wg%7a&$P^8Ro8%NehX<>faB^ykS1>Okb$2UL_YSq;(bd%8is_5o+9aK{9x2khh0`o)A(EzNyU$&e_0JK65PP|?<+#bTNQN%{Shp`(7*9TPE zSlB^n1~L*1D9=DfWETMozK0dSS_2xc0M&<>()KHA?J=;C$$Mar0@KaE0~iH*9<(N{ zBUXr{2W5H&k<|L2oRfjK%PM3U*q-*RdfQmJt1=jk{tDRu-<}JdIj=F~Q+mU*^1jl0 z{-l{f4=xgYK8?tH-U?V(QjOloSc{e`6WC}#<3tIHX|m>tl%X3@-b5yPjlWc`h1vdR zt3pSD%Kk;RpHF?UTSK{f1adVn%N*c`_0q)33zB>RjTr%tn6a7#yX)^(a5xHq`7g*# z7vO@57v#?u;DYQIWecUf;1z2(>F8IjS7cDdqF)R0bL~XLavI^v(BwmhQ=gup?h*C#21Ndwg?aH?kJg$n=YGPXaOx z<`M;U^bzY|b#gZbiXR;sYg7Ywd~d)D9)?%)x~#pJ4N?y>9_{y|$OI$(Vj{g{qr4B_ z-n!9>Y>B>vHjaj{D`^w+c+-&e-FGIi7091F>X-B&A1Ihp%Tzb!u_1klr3+Xs?0jIX z?05;-0?Y#@o7-GaF(}RSO#t2bK5(=8`pZ9#3!M^V{rD~QM;w*-7^e;##9vVAUmk+; z+pXb{{482j2{u!hs}y$98=-7b11#lJtt_0J_0Ld0e5zFiE--vGITx|iH(_h_vqCP6 zUW5x*z9}ayB3x2C~ixCvJUBqdYc64+AbKa9(i#5XDx6TP0E=8#a*lLcU=W$&0fwlCxQh|}(!BsQH3G#xf z%rPuh-4^huvFSdo5_a-O=!VnfoZuhX{guCeuZ=SP{=E@?^T)v_BcXlxf$bMq{{s^l36Z45>c%K)0w z#}WG!o1_7m{%e9YXF$&RH36S9D9gb1y1~#~uKG1r+Q50{{86>A{j{4naL%|_Q;=>{ zd@5EFuqt=?5o-fxnB8+eO$G!enBxu#7|2+t({q?jBj6ECJ72yBn?^!XsUa&Gqzoy0 z+5xL!u3Ff6KxPjCHz5Joeqcym%i;d9bJ!aH2_w)w2Zv-VhwIGTgH|L;^5vLo3Sn1P z19cy=;=x`B49LPIoG;6HZ2O-zr=(65OGYd|x>{j(0F9BG;_3#D0y(SdUuJ+3zp=(m zqOU+V2i#z|WmXOBUZAmP%vxom|Hgm1#Ag1D27NmumtH}`v%j@mDP?M-1Z<9@s}{L3 z6B>R1R-pFU75JgzJIj5p5$IjO;1TW_78Q^=sFHjo+nSWoAvya>w0vWs%8Fswqrwgl z@aCm2dez|vIF=e;vo!!mY_jD_VkR~60Q+xaht;cEIram=WMv;kEJv1HPBwrQ zaQy_Cp38FPpKxHTltmL9zUn$5LG4KTA&6GWq9n!BV1{oEzSbGUS?CemV9L^W$a;8km$Is=L$m#j` zF)B+IgY7CdYSvYjkDrSd$pZ#|g*>BW-D25AIWhCnU>p8ZVolWOYpJyox|xF~*HDcQ z=)q~uw+%5Jhit?g9ZL?dTaxY9x~DmMk?Xrm?z$H9iNBUj(Clr$KES)k&A$!a;5jmy z>A~f)7a4oXEeEWNoY)ts;tH+NIGBQBt_=Aq`?s{e@JhMjw;1laQtr|+Hdi)L+B>eo z_hu+(pys_r_ClVRa`k~RZdCXjDl{bC>o8MywYG1Xq+iGPSbbN^#n)kLI8Sb3jBI7M z%AXbIFO@Bn_La98KGY1;{}Oww+hq_jd(-V!REf6$SM`LjEA3^fydyL*bAgQpH1>X= z)ZZG-)d;OZcVz`{x1tVskbbtdzFpKL62&kFCA9fj_> zKlx^MWSCoj231p)inK`h4eoj2{2ka0?pd~uR5`MOM5EdryzFrV9a9{GjLz0rMgI9L8RBG!10JaQv;^rf~}9)=WNE!(u%&_w-<6+tIic*?nj~1;GUPO^6r)beE7irNi%e6?A zby{S|i&}Kbheht$=!GxWR$VMdmeZ=9NN#rJB1i}<*8(jq>Sg9l)L3LET;=d`9;Q3gy)#xbfgm&md|VbAMO`8CQVq$zAUS!PX@aJUk_+3ntNBO}@b%#rw;5j3c? zc(HT+&F(Y8{j%<6Mxje~Xt7d;Zg$VMjb1L(it%Zi%r8bGQLd%1^^v1)a8I9*=45N0 zdr)RLZWXg*awg&#R5p(t` z7baxpE%dpWN8S?Lf>52DuSKuiphbeL(IQ2*-r}Ae*H(Pc`~k^@lcF<%0at#U4&snX z70QXXQfZaUztuez&t85jM8DjrMXzksqEU8eQ7xaVWSdM}Nzp7nTZu=K;^4u@0 zZl~%f{BX4GZ0c~zHneg6zT0U*?2ky*YeQx79Y`g}&+eduEi2^6Um0A_3C#Bu4DRvq zGwm4wPIibzj6%CRDn8!jr7u;`OXaYtSIW#1T3UXK+_Z_7j>4(AB^aF1Jj)u`MDW%U z_w0!5TMx>)k9y+mRj>->a0%m6Dres1o@MtzX^{DM8p7A!NxPeG9pAeIDo&WJ^Jm?i z#Aw&8{HieiD2CK2d(g18-zxXK=AItksH7j!Zin8X)y)nc)~aUMqklq*msNM69J5je zZ^K>|B#*4Q8*Z`jxQFHu6ybN%&7_sG{aw7&11E9iL3wCm{3%j=w>vVfVC6ycmvtHE z^Md2-oucE6Da{yLDdO^wI(o#)kjj+-m8y`*rMRR@HkZ2HlD>nW=!IJ^iy+6<{fKfj z)@o%{DatjfrJ+qtGvZ5OH2#P}HFOT*tLRMgN;8Z0Kx$ekH+8X}QzwU=s2{;BUxkyS zZ!`Mq(BG+yx=kj1;yzV+SFzzpy)BrHVWiw9M=J1K8_&ry=N|Xe_~hHh_fxHU`F|J@ zvdKNTA{!CL+?W`a!;(+pBqH8 zrvwdO5*&#x*bTDqUJUok_4g704YEcNS78(pxsMWr1_9l0%dL|3(+@a z?la;t>7g!(njkL1zK%d12J&S7YFd#m*ROV;MNWHoHMuE6-dIg@^UG*%yeH13iu%Kn z9+`L_IjdRb--pS<2ae5;G1GL$t-gzACWGXjat;n4lQcsbLDl(9HxKCIwOJl{z&-cG*vH2^){DuN68<3RRtIFmgN#Rl z*6bGVgLuLtr#*eR*iEo& zCH~J0B}Z+Fh&C)1OzKM`rs54j_!jUHuC=XsV2*2~<7+;g$G^dW5UtJiz~ zfM1hl!+O$~y7p|I1G4QQ`qVG`9@1^XQ{!9b#aJ^^PMKMS6nnHP{2M0As~7-}46P#w zbLaxUBWm(LS3bL*b##K$PZdo~Uq`?uo3df2X;L@T5_n|ew9Y;2#9V6C(}#whwMomD z0a*5Oq}V6&NMb;EMtmofvL8|CQ@Skqe@NEKZU2vbO7+vS;4!+KcRK0Ae72YITq^^n z)a1XCm7AU(zbVr$cOk`5?yuPL$@PDA&xDzILp}u`M!lJuPc{c6^=M zvOa`cWyyMGWMt!bujy*wox_e&)~u)EqDFJTiy)OW8ap=r{*Z3~PsU%G6agq*upO9QqoZ;5~W+l_fEsQSn0B)29=ev zx(1b^=YuMFsx$QjdKf;FVdf)rGM2wgsC7>_QdSwn?5w3ZG%ADkr=(Dt~tDxEH_z4-# zbdEeoJnK%@UdD5S3_MB-szc@G|GDEQv?@)(8J>6}(e^=TlO?rGQlG4=bx+Y{jY8^b z-Ojj<7sfkK2R$c6V`4`w0oM-uhYr+$tAgDohcT$XYqQ{K-S9%{4OS|>E>C29#MLv(wvQvekWr!j!^~Le~RPAFMQtWi=2*706KTLC)LrM+y z(mEy(X^sxr(^GY|dQKIJk5W*3#juNI5A5(_IjDM7GIKL+sMW$P`J3I&h=v#0^quaR zX;1hCM>JWtnSOR*ObuA;yFM4d_Q~$e80(a;)QVFkJ`QrqDUV~C4UQtCm|~APM?1V4 ziY@wOb041#iGLpEaU#g~ID7r5AiWa0Qy5|BPncSIFJtdDv=%)Na_cACpxK-)W{}rH;(1p!n)*v)u`;KgdD$pS>+w;`E5~-ro5rdoYhc^j zUJ1?=NIb8-MP~}nJ{hQ|-jY|%dL5n6s$P}tPp~T(=DAg_eUj#N%KcBe=SAeV2Ddf( z<6tH7;gigt8VP@j`s-WA*RL_IKh9MrXFf$Inpib`W8{Arq=z;`YjAniUlWYVYMkWHRuC^NT>uTzIIxBWHX9v z4qthit$j68M~9mSscJb4n|N8+!0>cIF&?MJ)ovfJ;KgiYy0TX^5ZyID!cK=>qwE>> z0v@YncLP4DMlu>@4K+QlY5S^SS4#NbU{@YxNasPe!9MeEG>n1$8=Y)L>gae)UZ|VE zjTqtl@}demWuGFad;^M$ZX4eN)%T$jE%To-;&|ONbUExir7V92heipMskW##Bb+&j zOn#P7?s>$4%J9vb2#-75|@1@)OR<8OHr; zBX<3=gTmJTf3o)WMj_qaF`FeU>xP>LP;*Epy+F7I_?**C;)@(6G>d7tcvuu6;l)buYRl)Jg zVT?uOzsW*(WpJVDh2ANPo~M$)o5xn-y-?NGJWp$fW$W{dhaagQ4wpK7B~pE|Po?_B z-oyf2-obQRrl%rUb+WVxR-3GDVy5z2LYo?c$I1LmRovO+J|m*MlQYtHp3@wy(DM0* zHP}(wdwDL9MO)F%lNDR(R*tOuyC(08^l~n6PpokK1x_qoDbn9ncs|5yY__RP!`#2 zrwr=VXFAWr@|-FUqx{1xq?4l9VDEu#3+$9hFA=0okfJ62MJkV$g%q~fUFJ2aXOX7- z%`d5Uc}$e&RER%%qKHe~HQqzov^u0xWa3MVY0fSq``i7H`1;S zqDW1-rS~P?hn4PR}S~*4U$W1It@p+drCEpp} zO>M|ZrOUpTiQ#V8N2h~k*c=jCu;hQoyp0@%G<=k(T8hcm{mAMTx|HcNZ#|Tp51Cj{ za;eW;XBr`u%EDI(q;?*;Gkyg(b@|4(&S=UKt$z6{3__RBTqO0^r+C&~oZXLhm+X86 z+ue}#wA=*SFY&M90bYi`iek)ebG)N3)5T{Mq_~XTp+x5yr~)hFSt81W+& zjiR*{d3p39)hF{|lNYXSrN&%Yr-+aBx8b?`91WM9O39U>R`Oky#BT#t%ff9;cB7bL zkGx!0JT#PoJ^>1)N}f|ngS@c~#efWfBAo9A^G+KQ2{LCp#?ocUc6^xnt{LavD>VJD zQBJaKg+q+5dJUsxFp_0JDf}_$cG}kjB|+j}Lo|VRdN4e)u+8#r^p(2IpsL)>M{|n} z?jDmH-iGh_sH+X5T`-E&40-3>@t#e>XSJ{kWmOx_>Q*Th{9L`_L6-n}*NlTYNRcve z2c)Pjnfo4-qX&|=YrH*;-C^k5d+neBY4Rs6_{VQlF@;}A(;QNEmFB?#B^6=oU2Y-0 z|Hn;2nJUeY-rWRJA2M~adA^_oJ1FB|qqmu!FCeNx;o z{E8qyAHJ98GWhgD4Rd4P&NA2VUhq5@fW=-1THMHc;~k`$$$6SXH@2fWEIZn9ga18Q z&`K9QZ~}6;ouSB=Id34q3rz}J-uuR)>PT8jrSHqKcG{oAbCc|NgCJ>CDH2^NZmELY zD2E|O)W09R1?+^@@c#Ig=+GBKua_nNq`nwg{ZHzPmdS6D^7EFFv_H^gli}hyRtA)t zs9Y_Oo#F7qNcg~f(-?h?Ch%3tO_j|Q_Vf=9@&W7aCf#+t>5kz=?hxdN@((z){#&mC z&}c&D=qcO>y+M|AaBm*@7Wb`5`9>Q%h|6r_QR}v^(VA8$wI7%l5xqP& zYFmRoiM&?vinnle10vj(+0!94|3IX`z`IqXDJW70sr3gU?FK&cUx>7PV1{zoZ#9ON zD=F}SF)i$AkRoOE+f2M19>ZkEzYM1slqx7GvbmEUH1n7&GvCH1DcuL3IXob{@-le~1uUG`=l11-ukK>iq?-=R!;diJ%TefMzKcuBah1h*` zxa*_wyK?Pt-|zKQyTpf-UvBfUE_h@!!nVSX&6j4Ch0NHG&6j3gGMlZ+WK7VX*{S@P z4s7Aps8~5IAInXvnApiTsLhSLvB~Z0Zr16P9{zb6g0>D$k&Awy`geRRD~x3cAD??d#<()Y3Im(^ON%99kf;a(YhUvuP5dYB$i z4&RA?V8~IBBVkm3CX+sAkt@5~!w;?9tm$pl2kxmSHh%W~Yt0mTo(8K<{`LXyv`S^4 z8mSh0x6z(C-K6MxS=tS;URG1s8on@>vHW6P;C6P?)vhm&UB;?lcgbPc5xy^Yd*9-T zcXUFFLYSX%9rM?PAQ}eS^AN&w^;KL_vw-Ri+miO?8Uc`)@08|R23!R zAJZZ4SLR+-e-(yj<3cCwR!x%2KW269{>uDpAYOm}CGgew*Lu3@7eJ4c-N>@dx^^$o zZfr@L3={D^RFo(SduW{ZYx7<;dZn>uDJkJ=^RSW)iA(K}@=62mL)n(~wUKxot&n&& zF1&kr<_+9lool!05y_vZh`T*Te;a^2X|DE%4FhR02~i)S{NpaYgaOAUG){C5d>{L2tP#yo*}9KW^ZvmT8Rt{% zA1~7fEg(zwQK8>&eD@KbbSLdVEEW^G>$Bc5Whhd^Uu+bYe@<(1 zWHl(R?a+9S#%P;YX_RgIoN#TC_daKm4a;FroO5J+qjV~^Asj7pzF-6FgRLQ;qoZFo zc=h=n?f>#GsF+Ou1xBjBIkv_eq^e~HY+L0w#(CUc1&O^aB<^-j{L;uz^S{Ilm%5<1 zg3-{cFR#A(QfIfJ!(QY|x>q1ORk%rpC~S@2nY$eQeUjnt4FB5$`YcQPks{G+!7=Yk zg0iij<<|e*__xQ})vz+nI{W%*OPIL6;^pMXsCgw6fD@3VUtxp|GaOpE6=Z8WY#hWL z`g!Krq$t)aN{}6jjADwt{60NC4w;k{ zew|GE@jx47uafy4=>M=dd&S`8|A%?*Q3JdI_@li=MiJ%>^iWHmK1Y`837(qy=xEHmcgTj+A=@DF6~{h5 zBOMqsvttt+ufz}F4{z9^ar0ZFvDaWPf*s)rJ0#cqiC1Et`{@GU+^4y8??k{O&ke9} zpf8U#LaRi86U=_gElpq!+k@1RKpkpV+p8bwC1@S6NdSYyRnbvw74<%#8{#!+>mFB) zwha;^1xJY*v5#oJ>>DHmd|Lmkh)%1~epm{O21Y-qYc&Eh>?u6@)U3X4UKhZ6?|!WJ z9cA51L#h$&mGA(feTMRc9;IOPp}XmIScS5eE4yDU&59V&`gXhH#1}9U{f7YpDPQbE z>~R~zk9Bq*7I?Kdr1KPZI(4d_bb@(#jQNuulU5IrIC5-<#xjF!{RUCl*|5uH8|?6Q z*{4OS*bgAw?HF%Mo!W(Pm@GU%Rf!YEv(;AQpS2|`(2i)CddPfvngz`%uN+_kvR#M8 zp2hxOih4Osi#A!LMX#**uY2l6y%P_O`v62MP5BG!AoO&et&S-@3%YmGcz<}I7bsnJ zW7Sy+dnF|CZF76c1Xs^~YNfr-tqY!z*p>bCgT3>XfX3bTo z$9aB)oerBjQe~$c#rC3I3_D%+4Aa*}2|tK~W2PM2b{|qPG9NYvv}+GyEB!~L64t1# zbx1{IPdOwf?9^a6$m_=%&{$S{obk%pgH(weKIonuUludID%xXQqI4m`rR5>&sYfJ3 z>3HN)DV0LM)E0;S7tHRV5w?Zs*}Y`=v64^z#A#wT}? z5qhAt2Z258A)Q>y5#Z#r?tdhP5m+~G(l>OlqGXS*YMrCHm z4lPz{F~gxhXHh>*CVj(;3e7%k;0~GdEmcLzXz-J`XT~S zi}`G?<9S#neurhgP1b_<5#Lck)L+@5dkh78GS2~nY|r75zlcWARvd4dtA*5PKHJ-P z?pO8E?D3y}^Vq49 zy4gW$1~c71wa;Sii@kjtvj@oWY4`PPk`kc&wbSC|_29YVKMZiC3jAvO=M$LAlC*Ph@nCs#gVT#>+v ztDk>t)0$w{NqhvFd^Q!~nLTS{!T8ZirqVj3l&(Kf9QpR=GUH0_G@2sV$9J83Xxv6X z$07ewz2Ddw;h7rIeJ+c4lRMs33vC2h{z$6K!yQ7TCz?~-nUQ!QSuTq7oP|$Tfg)ng z3r0g$Et56~?8N}yu}6CNMtvc(dKEoug~qMU1W)iF*lXZLcDmw~6l+$Oun8Ig>s zdtcLJuu)I3d+gMe1MRijiKs?sx#x{vIn>$h(2M0v2i2BpQ`luph}y&;SjLh8{K%67 zV-1$EB4~|2Vyql`y9}u@Ur?VJvS@;5s=W`EPnPf)*MVjEkR2`$f8BxcqYrh}u-hd3I2_a)G#=jrEj#O2*FeOwNkG_g*l8j%{iL)XCL@kOhAc)Vve z?~lTx;8k7#Zw0*cD33F)=YsJ~(OwN>uSc$pqF0?49y;bQlv1zzv(0KNH|k$3AT9NmEo*a6x46FQKY#UTEJ!LEe1 z5};Yi-UKL-_$iF2(u}<7hgQw}(7$8Q2{?tk+99ivp?G)-d9_}4sz&2t;1j~<49b!i6dF*_<<{u5rM70RU^fFe3d;{T z;oq!S2~D~WT^H+_dSX;|FppzW&1S=jm2I%%l3^u5(%9D<6=j#f&X56R7aqm-!ft|H zD)DhNfG^!C;(Rw98_&^OHBqfnseak4MXtQTW`^^`P#ojbDsj^wM#}tY5WRB4G>H7^ zqM{PnHVrQ~%YdQ`iF12qo!EK#q0ry$MAMAEziR?t;`U6L+WZ5SwlL}iqV95L_^Y1y zxMUNI)6IZZD_d2!>L}eJSmmm#iM$HHD^#lI-RVpZ4k@@|{LI$s`jFydC=WwXcm;vK zf#jFmtWMhKp;J}z1}u8|mB+)^=2y$~S)OSwRrDbgCiCOra_2-5;m>2LO^D}KFrIBh z-cknk1|lc_McrENRKX}2(js3@oKDd!ztAE|mQE)gqvSSFMDz8**_Zv2zSP|Y%h`VY zp|M`AEx*(gBZ28GJ!SIEbiCXpr_I1bjx3r%|B4C^8UJ#OPM9l$@euv8-nFcP9nrj; zPar4MwinwlqYLxY``(H zDbQnNv&tq~vZc@f$H-Pg=Z~9bBAbn@ag);nO@Z-;M`5q%HS_YBY(EO28JpG|Xj~1V z#BuENnVxwO3B~wb4+)*HJOE>T3;<$e>B%e~>CncOBarqgQw4Cs=Q>J&T-kXthWH-j zWLyv{@v}hXvTzo@EnhJ{uj>*J`45eg6|-2+TW%TOA)SgDusdZd+Kkg%YO6yAKoK3c z&?7yTwj$9DxOV~He)j@+1(`t9^~r4sh^NZK33Rsa)}S{^TZvb|J74mvDq2IG%sho$ z?m2}Nl(=$y1HJHlD0pT5DcB+zoLogWC>-<05ZAwl`I<`3_#S zJ+NajuX#uB*)>A4V0&cFsnk&-OHW0r0x4~zN?8Xl?{>WcTBGc8*xn#Jv_FMiDcepp zT($311}ozZX7hWDPaCXUnKK*rq-V{&{4=YifVpY&08S7@4~m zTD|OmfMuLQZ^@IyzDMZtxX4ak4jWX_-R3w&L6uER-?>^ zW^cZW+aj6#2^XqGr+H!+;nk-Rz&%(onw_^plhD4?SZP-B=-0=oas6lo_Yhv)wCLok zhdnHlPp2tPnSVMxNGPSB>sbxF|EHHQYfdMS(&R~4?2vX+#1)qw>*6|ui)7*%G`J80 z#z~|H8nSxFVP4pTy{>**eg?JFLVu_XZ)QRB0d(ToixtS8Gw6MageOsDot&0rphcjF z;d{(1J0Yo^W8A%@0b)|JFNo)B94P$7kqXDkK8lFgGV??g-wMlHHa>VXM7oqN3+L!^ zUM6!B*=9z+q3hVHIan!|%@h%pSaCB^;!9yAu0AxDizdO9oD)oS)zCRM&!y+3tLf|) z?l|Mh!K*dEE0BeAG1o5F&o!L9ZY~{ZzR&9MKQ&G7Q3<|$oyRPwz5iJ6`jD!T`SYlw z`hFtsQG6BkrY=Z#&cjLm|4-fdz*Sw{jsL=hz=j)6OwfDrnpBin*F|N8g+)b$g+&b; z8ZKH?xNy;C4Figb8a6EILmMvK*hUQ-ZfvuL4L91XVZ)6z+Hk{0n-vx|npil0@6Y#~ zuX3;YmwvvVf9KEVe9q^b?>XmtuB<~dy8B)P!Ax9DtmU69gbD`3?Z>7*=*6g1U7@YPy9 zq6HE$7ZVkuZsI01MKsPudtOwJSdM_S&-DeQZ7yYC;o>ykjAKgR74Y-C%*>F{k1merql8ConZ;65qz+B%D&T? zx^g}>9nJ0ssIpF7SxM)WX1UUOp*b_;3}~JjGgUpN5M=ZLc{$y8TvDJWw4Jrmb?_Mj z)2S6-{hUDwRBC+CQ>hW80(3&;E5Y zq;#Gd-2*~^nukf!9}G2|nkT+TC)%s#`KIIAPs}5c0okO0uMg4TJi~;u8KpDVP)e4M z{W=>QMyF%V!5LxzTGTeJ(TcNuv*xsoV`;R=fYl5wyfyNaE}K#DHj%u}874GBYe1IM zb7#^UXP(2Xamyp2S@k2+@d%p;x&iF@EshZ;kN}O>v2&Qnrac;}n*%E#&%$Ebuw6l^ zM4an8DYD~HIdux1Y5)O7^>g8H?o7c>c?<#MHl0h8m&)%IOObsFs^x?XM0|3of*e_{ zfRo}GM5;E=9y3)b?bY|F?aGRhi1{RvC`t2urzMqp_Uu>N>4@tNsUrwi%d+_hmn-0f zWjakD*Ob;=?3?V(dYgI6dZsF!7yDwTl!eKcB3~@qRX!jQm-r^* ze^V|2>yWcA!5bT7{Uub>_ZNMqavn2z?9<0t5u*-8hA&}sO_Xga*a~-^dFApj;wIIM+G92Apz)renvA?TOditrglY!R97HNd7UfWueAU$b!n8q5jI4HU z%|&O{Dw_qpNH!pwR0=!MvfUFxm9R@?7i``ECM{$FQ@V#A-s3f2i#PzcQ5Hg`tCAnH zpVt{jZJyDYipY9p^QxDlopvFewom3>LHjqs?UjjFkhDY55mgy6aet%zNW&SZgCM=K z7AYCLg8A9N6?hPzaUpn2BfP;qW`5SmGp|@zVlCgOZLl$D2^NVC{9RX#R$obWS+W5+ zz>8PXJ?F{pD~Ta_GBX!@7LSI$d1*BVQ6(tAjwq3vb4h`ZD|3CbBS%N&xm@3=-rBv) zcJJWzArhu@)AE+6?gK zd|;;06B=QaeK1};o9ZO|N3pcBNAWk>_eh$(?GfSN|` z=sFO->AMQcc?iW{)t9OsXvH%BYE!~1yz#gwX7i{ zboMe483S?l2n#^sWd1cYR+B8hhVnM^%<7&37w>3U&K+3xjP3JqlI%xA`A1bua zlu!FkPfGCaIi%B!AeA7?K8>c&yGQmvL!O!Ms8_82G&937R5XL}Gm%QzQL+maUKA$f zQ$=1U@=0JIYLEPd4Yy-_!%XO-xRKSDEWs}lak3!f$p#h5jV2eq(R+L`8%Jr!>@mjc zKp+UB6a44_kOEn_m<-Bf#bV-GJuGKsI(N6Tu&@|Av>$V*9V%hB$u8AwlS$X7s)>}aMTFDA8kBv?>X(_Hp$@~aoY%84Sc-i03&;ij zft_UaXV7hlp(=bL9a93W6U15Lst4gfLjfraLDRiSe?PR5m^~p|4QlWaM|K&q5yNs{ z0WD5|ANNlt91{*rF9mwBroaLW zvIhdq5NTA))}>_7Z8B&^lEY2cGsW<57w%GDa?B7U-?7FcqT~1IgnSizokd+w`7@6_ z)J#Q4F)$Vd-Xg=G}DK$aO$^;sAhdv$W=$P_w{Ta{TXyA_m(Bhw9|+{g?& zk1%IMC%muoGX$JHjq4edIzP*x#64oy(?n%(>tx4gF-;vMOtd9*hr?!vJ?RFN8;!yM z6!R#BH?Wi6co?nt4^##%J6A{tZ;^GRlGKZM_>f!*dqB2pCjAmoglYS+oU>fl535fN z!Djupi2 z$;=zcI8i3uggJ(xurjO^jy)zq-bzoA4qwt%|8d9h5rRM^fH~IO4|d7+JcZ)q{NEFVjzu z!eZiPCz!J}?DIr;IxG^M3Bq)?m^`~RH4dI0CeM1LxZmhz-$_$E6Rlw}t~z)REJm%H z(M*ArW^L|nNqHh7u*h;{7lg3`hz4PoaIzUej8}qlv~Zgzy(Duvy+4b4MoFqvNt`~5j?jRsT<1+;0Hs3Nyc{JW%;%A4 zawH~xo>K6O7J#JUS)t9M)$<&q*)LZq*4;l(DXLZ2+%j6|Ft;kRRufeKllz@u)P$v` zl^KNIq_tq)GmEapN+{i6!)?rr+iqi0?9_+3T?}II^&+9@I*>luhfY!-Nsf;+>WDe8 z2W3tvRcBwKlroe{6~Nn=Vn&RZ0#0f*DWXSIDix7krCNfNJ&*l`vA6?LCwx68Ah|2( zMujIJ{hm%oCr}R@FkUTz1G*Psq(J8@{1ud`6888ItJCKJQmmBCD{xHmLdx4jiq5>P z6HWFdzCgPS@8S(^5ZtFYXZ}wN4QFbwz_Agmp|1V{Nz6OZOoL(ypcR2QgMK9l*KDak z0W{|%KnJvP60;|)GH>T30Pi-p(|GN2^X+(F9oM2_sT!_Dh1e#W%kZn}k3}#O+O3RM znNo(Qa5+F3*hX$hrF`wFp*0Oqz99Gaw#!d;iCdN-!-F;}P6!RnHIO6!2;%t7*@ zb;{Xy;OoJYL(QtGB}}BdO4S{-Uh2t2GCj&&0FA)>MLf2W$24W*@oTYNvx86iA``0y z#GQAoVQ7uAZaJf@&Yo>dU!7FIx^MBGJ^ zm1p4LY_!JoBVP|fcT0Nw4VtM|39|eydMIzfclpjrik%(^x@eEgNFrcWf^^F+O>jsit)kl8HL!}c zshaFPa@wVwA1Gbr%+~H)MP__`r+{^sRah}<5h8l@sdY+(C$K0q9&709g3kQ=ZhSru zS>0uhjz11}kyUq-;fSmQMCM&3FTdMG>&Elj(1tqPPrz(gB39=1U2AKC0D-nMspg=BCz|AC;=vC*tdX?w}G*LYpo4Dzq!nb{3ZslGJ0Ws>rQHc2ptViF8tPeyBaPQOXeQ zP#NcH02K|~gJ}CHmfzD!H6@D z%{<2IBPSKFGlh#Dg2q^JAGueu=olT(FKeaCDr7X)0FqW-7aByhBb6e>fZa8kHo{zKSwq_Kx**;K&Y9#Ilv7n%ck^nYrOEOdny-<|Tv2XN2^NL| z+R3)o&@6SDhOYW9dXS`o58~o1s6K$uAVT#@=KL8cI%8GZOrCsH7M)AB(K&N?;J>B39*(29r_A=Y~Hfa#MSCe zto^VhT#NIiABNonJ1Fy&9fUpJH=XAcr=!#|5;fnx$K7s?*X>pv7SmzJa~Z2|a*_{i zol$FxyNk_*u+wF$CY}vD!>|JjtwYqoE|Gn(y_L&MsE+A|)(Y~oG`jyVNR%vDjS=Fd zN3`t%~@HpmNK zrTG1_Td_fzQU}&53+lj{<;FU?L9b%0QJkd3-k_8*L-D0Xc=+rSiZ^8i2GX<2#n9Nf zT!U1OtXSjZux$;_oq4i4@_ME4Rr4Aw+}jQ)2<{5)Z@V=I9YfA>_xa(7SuC}mfkLZZe)wM#UVXd zPg_)@|FaWumXb7`$woZJPE6*L#O8YNUd1`e5SFUu&N*C_&CXo zYHBm0yI~B=`o}4H+#R;)b*DynIF>+KkpYA%yN4DN!Y|@8Dvpg##-03FVh}f7WJS)13$9S3BKzUQXcxZW}f)PwLRy2@b0c@Yi z&oPG%nCY+!WnBYy*dkkzitPHLeEtdFiP6n)xYO$iCv-1=g4spx6U-?pmBgihb9FR= ztWLi{DOpgsTn_o9xRs#+CqPDJu=&}9Cm2I=!`N!pHrTo1{~FriY}Foc*bBdgx#dDAWE`au*4&4StP;Q3zX^R4tJ>WGV$w-B||d*>u5&FvaciKkvqT6`&o{x zSKdz94l#1@F0H&dtkZtF&Ru6VqEaLmHBwVPv;~XYSuW>&L)W6xnX;^+seeO{Ed@!H z?JCWF=USx8WX@VJt^!(17wNovk9_|||4eCI%Lv_GVbqQ(I0I*{Fby5YGqYKABLh`( z>RR`7EaY67{|(YAm1PR*yKhv-SLa=BCi=Oh5$&U>By z>6gMLI#AwO+Cw%!NfKO64?nV`TCVse)z*1JFI-|(6Xa1tmf9vp*Ft%$35`jI*Zc`x}8+ke~Sz%fTdyE(q@+2XZb0AJm+uCXF2?(;#e)D1Mtv(`7!uTmPV~Rmyzl<>%YP z&}L{ebdRD08c4`MtYwdf-XXiuj~shYlE33S#ar-@O(*KS2u>iZ_zop5c}S9fMR?7D zR3guQhxRF!9dNvbwPtLH>3~%V;+)_e0I8OR-^H+rTN__#$J`_gMS#E#O6cO=!#upqLIlPu4x9u?DvDo==Q* zmy}9jXLFM&PBHuxAuZFS)(W}wFsXGxXW8y)CTDd|`x3YhRYT@-aQXzPOy#(e7ALw8 zMvZJ$O10)bBf1d^i&x|n-Ol4mm7A5+a+pkpVK*D4gbQ`*S@k`VX^_n*MCUuB+UEH%aMRtC?`t#pWLa4rpN zB@I5OT~EQfpfJ5&kE7NujPJWA?q2F*n+cUID(=#|k-?%CkU94jx zRh;FotQWVr*#$4r+4|---$~I0JhF<{ zMwUS?c9G%lGtX)lyDQoXw^j8qD3AP1JA&S3*r)0KL0q=(3m7Ci2*O9q2QtY6-=ZmN z@N_bW-@q6VXuzH*NB6+@$@~ojiEL=>LClm|B$CP+LaU|*%e++Q7wb3R3ha0(s8qno zLm2g_-`2~54Y$$o1GZ3lWd0A3Ns(ngpa}y{m`#o7;APJI?}zws9*;rUtWsGj#i}@z zOxdTD3@%LtgVHJfc4QM| zK|5yPJaxP8r1_<5Ltg_ja!5anmJ2O^98GOd1T9Clk>LECaV(7kjj%GqXl>Ba$I zE@-JT_eV5h_gX@vZZgCz#9kJO4uY`8h5&Pi%?dp7Iv}a%$wM2Z9bw*8evH(BTmU-AVx zR}xg84mD9BwAe6O8MLvd4$5i$YM}933(n$ZtMh!2uXgH$HaJd4X}!=my}Xh2weF{w z+|S_Fp3;r9Pn|yLpYiKcB7va?7XaN%FgjOSSo^vu;^c-5{<0P~q zaaYkt#?e$O0F85hs>RoE0B_wh<{gT6({13MW-PuGZ<$ zhM&>{vUuF6kF&fTu$=|lT4+5W&RSv{2xq-I$Z=Q}bnvP@_DtvquS2CLPe;z>9mL<% z?;rZA9fX}DYhil}zi(f)OQ6+)u&-jy82KQy%f1fGSs*8GBI+?dZ}Lq(C4NJwIpeP3 zy?h+aF$^?*&EerqzT@YQwuQ>)!y5{tl|UO9N7FPaq4mnHO;oi|COuC%`egp|RH>KD zoLVwGyX#_}Yc(t_e;#2zu>p8P6kK8p3D; z&}zrgG>H*t+`>u{-nfl6lw{;Hi?T>`AxMI3MSzLTZUd%lrtD0^6*S87&G4FK&1Qxt zF0ZqUFPO-Wb;&uu@SRATF8c-9r);6M^sBLq&oGF9 zI4c@M$Wuw=y-L$7LSkAG2!c4rD!0OT|&>Lip%GSTQN4Gzt3n6Wk zt-r)$3tpn#^u3`CTA}!VMF9$B!LKmq%9ot8IMIRYb*X2ya_VKnuN;5a{wvJW{ZeQN zHMb^&yJg}Q9Hd)L*n;p7*S(VW5E(h!p(%x$(V8u^Q1P#A*-N06{QA(KQw_aZcB7wE z3p>1rw!^NGnJ*F)TVNl&ULr2qvrL29@)s$`fZX>YFW4Qj?L{UHMKJgj0!C8z)_XkB)BROj$vu{vU}@|^*}4^z7s#ZoO!XS!=l{mMoJDsk!UeDhvxW)qmcnwb zs;YaL!MjDCc$sDzk*zPYPCX3I`DKx`&uJbLf5XhTtY^=DPUJnxhk3yj)8nH@U?s{j zSl*UxoVobx^rU08o|!jM&u#L|Z+yo^0)P1%V!}MxrE*cdb_DE3CK2Sx^K}^*ggfGU zF!JahLhYtqKCM{ak)P;cykcIAlsEHLG&Qs|!kTB1=uQxRGiDn#49cQyWLFBy`4BXC zv--nYr3L?pt_~vQ&~iYWWt%2PVB&Al<<1d6Qtcl@H&+6b#B+;w#pNp1DQkXQqs;>a=6U?->0{VFxuc z{LEcw55lgIwW{3+JA9$N5O$|*h3)MnL){aNX@utK$KBo0KLysu}E|&NRw<=xh9Et1-SuO z<^x<<{jyMLO|MzIr+uCw7sRo9E(kwd^9s5Hvf~x%xAV2osOAhZNbTh6SBjS_Xa9k? z+51-#h-Ne2cN@dSVCZlbgcb;+WkE}j4S!&WiygE>9HiJVu{vmDe+^Bp8QQQ+>SMk; zNVfVBq-6HdxOs!7S4MkEwQnu&qZS3SMgi+kuj&L*#pbj{4eSCsNA3z;P}-ytqtG-8JpM;Q!k9$}tlKq}0g3n{ zfjH_5+Fw`j=#Be3;vAce$${nragN=Uf~0UMEK}2Z9t-u6qdTy510bd!T0h8FKTi=R}tutY*VFJd2aw~a1v$*{UO0K8Zr-2-2sFXWZ@2k<7CAS zikB{Hcc7CeFDNLNU8s6jdPdFMq~lIj=}E_#KoM5lTU~mg*T{m`s8PKvevKNXMvR(q zHuEku()!oPBFM$7xJWiE=d0#cSmhwj^=>^Nbu$02$kod-fVUo&Gtjyd=k;dO{Da-U*^JH^KkPjz?=ICj8#FP z2>u<_mQRd^OdT9AL^Vqm{hh|kkX3(2r!IEXnFbtFP=QTj<(XK2a&#rn^|DL(nG;M! zW4fVbfV}exeRLRPkXu!qT379)2u1SLPL6w3e*Dn#R#)nF&2EIfT_2}}`oU^9G(|We zPHG^WReytBq(StxpgIn@w=4#$bSPf?2F^8tinFy?0&Pr@FY}tI-dP8MU5GbWAk*@rYq^DX%RH$4!cM^4VCb@W)tibnfNv}OOv^8qnU~( z7d6a`j=Eo0vRAA>y<-6%VSqY}b zF*(pOL7YR}1G{PL5->-<5mqsX^CsE}QY3TU#nMI4&cD+)C3*xJ-xMgV>6}u#R-e%XQSgD(plNAckyA?cm6?*_>HE2(BBJWxni6fR*YQ~#n`L-hk8Rg zrPQtejIU^D@sCh)r8$=`jwvlY)bQ$e3AK8TqDp1ckp1e%^(7Npj%*zv%@SzN@s~zu zrLy5YVs5ANxad7Q{0xGY2qdE0Y zkPh+xlT16HIfWjA)*e=9O*86Y?Mo~EN$2fNm$#?+k9T$q@*wlZMG~x7zY3R$0N7-S z-$P3cVswoYG2Mvmv`F+Y$dD}AgD@YJ@4>^63mG-lRkOaTeSHILV#|n~fhiM*5Z9g~}n8_2O z?!!$>GmPuU3@Hu7yf{Cm^V(Giu>QPmA5F*s+kH61P9*e)?qV8|h?+m@oD7Zb1PRET ze_=J>{6j523_DSl{EO5Qr3w%km@jt+7`zJ}ceb7X#kxnC`>3aB54C)=!=ALCA{UUY zbA8zmw0aQd`ZDfRWbL+UKi8MFqaVQLq6`vZJ>LH(Tbq8J+{q1+1q?R_Tq}M zIgOA&LR8zJHH6W+pz--a1iF>zzOxBOs)5G-MudNMQgvpit)03)p@C?9gkO8z3lWsJ zQr=K7AQL0~v%F&$kPfTDk{jud@+MwL>p$;1Av)n}>VH*8M7CZir^Ne{=M+F1y)d+p zrO<}LXw}dLWOpQm>?Jv;f*sI6LMqq;ZA%z!5L$;U^7UfF~&Qdi?E)Feo<67oF<7n!MZO|C;jzKF{794}tSXk}HkQg3E zQ?2-KXjojOS_QIB0q2;G@z01Uhf#E~nGHoZfpCRW3~cuBV<=y$EK#h1i&)92_L9)@ zWju+WjiYH!xzNhE>J_aru6jkQc$|bz*BX&17)MjBHfWq^ibbnj7R35_ExQUscX5-7 z&aRta^HpdpCE^H@O6AJ7Sic_g-W%&b&D(RinUzKlH0k_k;RGc5WW@wJK(9Qg7;k9` zie=jb|KzC!IR`7E+1IWk`yAsHNo@uR@!KwFSu*!n|6~>|E;^Q!dgW#XeD!r^a*kw%adC^;Xhtm5R|vB4WCdGe%j1` zqkZ3{+seLA;Bv!qa=d@ml#Kk)Y(|g>%CdO;DPP2p={u*GV6lQ;*$jwGDU^pM`1$Q!1j-BL z8J?3mdEQtUTJm0KoVWcXhHNUdhKzd}2Mv=8K&u}|)2gLIV><9j3KaWUTf=f_AR*&z z9kc}5_enpOaKQ>6Z#!XU%ACoti^ABN%P?#{o10ACnz<{M%o?^>8w{iHHFC3@Fm>8oX+H1uiIJsphb?|DW@Li z=PHIfnYQS?pPpy5L6;v#w;rsdTbDq~gvKJwaimBeJkEcbq)heO%iID}{ZX`e#8mB> zQ~j~L7F{}(zTPVERvl8@VU|dD3Rc+{pnhnn7K!$3(5d3` zB$COOHA(nDKFO%6E~DtWo4U&YDn+t635$(Z$-7B@-ADUCBU zKhUY)YSOe^&}RN zb;<9(>9jFvf_d9Xz*)AdMuPq4>6jo`9co1l)Sa-iWsZ;Zb77CKS^)Mi>;hThqp&qn z1xTt!N)^=r?%sZGyT&Z$d%B{$!{_Ixe(wt{tGumB3q2I$bv9wk%G-s2q6}f&8v)2s534~;f!Br=IMiI}CHJRnf z6l_4&!0`5IYWg+GkZQ`-WdCW5)caH?OR8ot7IdSN^?*q~dKe@}mdqf5Y-O_|1IyXF zEBFa45a$)75~M(Osa(EH3LuxSNwD=8GXyIS#2H)SH>%t!1emz23s9h9SQTHwMM`0@ z@1m@YT=MEa-5*sG`r4>gch(w_jFm+*Y3*8BH4}wFSvQjjOdkrdD#f3UO$E=geLRj9 zfL02vQ?{#Cr$ii&R{J;!)#^Z^WgJbldZ6Kk$D_rnuLAnq@mMS4Il9n;c=^{@SdACn zR12Z7aj7z#VO5YJQ)W@tDDH{nEo9)K&_c%llr{>Zr9j&vYi8*@_8}Yh3!s67RIn6U zTNtexTC?m%H>vB*@>8vSe`zk*Q6p0N$0grj?@$J9J%O zYYNpEk=+VvWy%S(ujdgQ$+@#12|lAb(a)9PC-9aswg!fNmmQQ%C-}`TUqt6^(qjXg zQDnvK^%KabK_;FE#u?2MDN4PjhEjCY^Ezm(faPt4=6vs!qqIjt`>r-h5p<3>Ae+<$ zd;IYRWjDd*QuUL_rBmhtyxpYe>`ce~OwSci9Q#>b5WH&~o(Im+RCJO?!ctZn*1;Z; zeJA;+PV%_cgm_%dRm^WPo+5dvJK!}Sx=>P^{2HHBZD|) z>rsTeW07l?WhWDu8tX$Vr$tEFtPZ&bHpAIdCo|LQKq@>iRU*Z;VX2G?Q5=zP2IV@5 zQwUJ;kB6qI0jd;syevA!e|pjoY^{n$IsN!p6Au2|SuH<><{Ek2M%Pkk+=q4wh2_P3 zHifN`L!)RHQuQ)-Hg)b48y4bzp(ZwAFggg*E^Af4AN}xZ6vF1ZGxP~;yJzE{NSUv@ zdtmV^-f6IgWmy_!+X>5wa2>FQWNjKFa^)OGWaszIs=IV=b2oxX`3<2tX|CEtxn1{sD%44gw2c~S-N=E8DTAPZhl@fD{stX1;JZ#=71kxV+31PYOIma7L~70SX> zVHK;eF8q+rjF_BXGM7in`Rc9|q?PMsb@T`;nR<2`>|XJo#*1~IoP8S3#I5S5;aVy3 zn1X)Ud>Zqpp0x)fL;$t&U*Xwn?L4Zk5iw!s!5}h=3`hKM2it^dvW>`*E-2skWS32Qz?GDpbAgPUV%lr68=E|syBwg!3U(+sCW$nBJ^XZTN>lJ~;FB(y}$$Ysl+V(pe#I-cry6nfhAMt14^}V%F7z-*PKbo`3&|<3^nx9!2|+Glp(><2Uy9E}V z8;uc@<}t2yBBB9HMcgwbJ+PVl%%kIt_3~P-heqOh7}sX(HD7-OLGoqoJPemFn~^hs zYbzYaZYW7{fxRJNFP%IxVOPq`vvHh!S$wvC_SDq=&^o7WqlNozo8=nhK$~e*hDjn` zww>)icS_BUP~CRKIcs$e)@XSRd)><>YvDQm*ePAF9Te1-iT|zk(^cm<-trXk%#yY$ zh?U*vup&41rW|vw{}e*Y+;i#6C34ZZ{!5q*uRa%zYI*ite3nZL&qbqECS~vvIvOo! zX84bvGI-411Etjp*Zxi|xje&vmbY=jUURyrpqJbYVs@e`Auw0ZpiNU{%6yE2+sr5N zEwW-hIo8Ws1>F6mpiACUUaBOWrx{O^^UmY7YGm48^IJ0UuV@!p1&{u>?mQx3*7Ut0 zqk!{Pid3fTI1m46kV)s$fb}Xo!&!JLh1tgCuVmIOtIj8-7FnklzYGS5?mBMoevf|P z%FausKfyah-p+jV1XBHb&3!Jdu(JJo-6M^`3;ppd zG%vUi6IRON3;pLN^~?x$d@Wz*pVSZ5Ur4q+vh6}zdPw$Oh#RrRlLfJxdtk|BaMoU# z@l%Y~iu|yw&T=ZUNm=f!ra=N$BVt#9L>S!I~B*I98+>NLoKj-dj*&^XO{2`QDyjR0@lseARk##~aJ z`4`@~Pd%8X^JN3JfzdUvs3DwBv z%NRAf79A|M8m10GmP{_A7)&KDH&cnrokA_X+&_Ct-KRt4)BdW}d;*CnDftIk+P8{e zCCawTsb-e!z1;DolXJ*=r(BbRd`aO!dCfX7sBN+u7VjGy04JAz?x2L$q8y2ppFc=b ztvYCY%CA~GW#&Tq`5+SGXAU~r4I{;AiiPyw{=={Xud8`h!}g+WK7}ZNHVUF|M#oe- zh`hbfe_Rs8{avJ~L)L9}-6R8kw)n50k~y;Q3c|_o=l05Pj;GPn{-%BDi7Tjhmb`#O zbmOgi_t(j`tNm;vUP%BOyVVKJoZY*UshCzUV3T(*3mPGfN?CR#e%eEk)R|&3{ywgJ zg$^PwU+F(CGVM0`*J6LN#Fy$}CK&B9G1qC&xw!(x#t-FG!*pKCqi-jWtkWE6L#$ncI4{z;X+@%V8QSb)u zw>kGK4aCXW^R@~szZRXw`%TVG*OGJdg9mdCV7nsZR?4<({j;WZKeX5V`QCv3e6N}| z4ffbW^6^jmPb4^<@oCJNU5f!ZN$qTk#J{8OtgAjvhv|Usv~>=&4tW+?Cf3_w`3qL> zb-(9#zL_OqXVoW&B%j&jQ*CbL%_o5O)`j-!xM3n?oekhYgM;0sqQz$_lHpzCJV}oF%K4 z(mw;TVJR7K)zwmp!6NQbUe7!JNu67WJU0=MOF%dVdp*JlQguBB7?JhYBkbd%Q3t$t zJ%iSW_zS^CWC6hIYooi}LfiXBbq@2Ovbtq`A(beV7Ya#)^^8I$+ELHrwz`!!fS^wn zE<=zzLJfFKL8m;cfaB52(B3KUEknCSW`0(8$bKOgf0j-+BFjNprC9S>rzp>U7CRUJ zin)~jd{5*1bUzTM-*qY?b8c|N7XgwwU);Mt3#(|WyFa=d_&{HKSF2QkY`B3OH*zN{ zST1+60(Qy?MdUOf3ya`o%bf;%yU2eobN(GgI8)bPXe(*&2#)DYe$tKT#L4^{X{@%_ zOu1rw`>;6(>yqXxzf1_sLXnLg{p*1MJj^fWc+&@M0Pa907vw+y9#DcT{2Wcn3i0Q# zLec9c@I@E?OFd-k=O{f_PJRws_Q-^r!1`p4f>v2{6UFX)gS?D2g88-&B<$DMxGH5Q zzPWdQyI}`zg&p8I3pTqCB$5>S)}g($61GovsdgG{)lgHrt7~nr)5Tv*fzsuSViJiO z3Z3MuMwBO#BCJq$E$s0#7By@)iPUmYE3fZayF&BO-cgNqj_fYR;A8KM3(P&xxr^gw zidHndH{_VCX6lKEWXpN^%~*#|zmNhvrC7aeRj^TZ-;AZ3W#%pLn&s?U{8yfw^4`IS zsMD}uWTYn%niE*S1N_TU+D|sz;-4N9xijY{FR$?bbLrHC3qKEws1pk1`tSNrk@0guOkBQ-@hw(RBe(|%0 zpYfc5Mw^?-FEtfv%AV|y`YZ%-^7qs%Gy-+k8pU1nwB&(sI4gs~I)?sJ#Yey>DRr z2L`qs=+H*9Y(u<#TE6F*~Mo8@<$VDO$(4a~D}>@tH7?>B#L z2IW?-#loT#BR6K#S$Vp_E4J8#;&KeZtzkpCDQWR0Lr;I+z=2;GShvN%jTW}QU~pGI zdzH~o*lP7GtnW2=*6$ry;VCf>p0wYECeUXS80s_hv{wyG*=}I&K&bq%mCx@t^kxf> zB%gS<7O;Y?gB?a;*oChf-1kOk20=%GxxD3za*sDn5_fl`lWuFJf!VhAxX_gw zvHXlGBj=ILf#j)|1#B|&EIacE$+&XGmS1k6TfL^+Wy6`tQy(3Oi1}pU?apk)VMXZw z$IH_*laniYEZt4Z)%DCWRaseKidJWf*luC-J%-+VuYony298;{^L~R5TiEn~!P6cx zu*AUWo*ql6{fc3@1;{Pa!XH-=UuFuv(;CI)yZDyXMz7z(_=gRiU}2(#DHaAT3@_k3 zOLq&HY4C~z1`5_}YFK45&b4x-mhXm6SFYRgv%YHNE3I?5(3R_Q_)HwL z>WrY9Z;!Qz;^Ug~_&Q7XLRSs9NnP#u6#3(<_Uzr(alrZs?; zNB>GsFb0W##N=FPp>3HwkJ~gGEyGuD1dr4-LCbfWrpDr~>x|V$KDsSpN=2b9kn0*3 ze<|~)b?e?pN?7}VQ?Ql^H4Ys5*h$^bUA440xA;K^Z(n8LyoY{M^;T2T+@?_@m+)~z zf9UMf($4z!#orow&Cp$b#nhkPyy~~--Rzm`&?`LUYmLB>GCooUUpsZeNw35#n$-K; zSDXS>_89ox8(V*P_Si4Jn7_@W>lR?o$BN#~yn5*px8O#v!sEHK<<*omRe2jT{YJr- z%=1CZUmSXTfvJ&O^P7M2)>W;q|NNAeO-A0$=!PHfF?4G&H@#9w~M zFIitfLVY#H)UL^&`EJ>g_0Z?tWaxoA4ZN-4oh460cWaus!_;_A!`lu$WyIjsV+Nik zZ#wk+RFm=GSq2V0xV+$dq@y_XXH~(L><15)IE>sGM$lEf@qt?%x|?uDT&-jBJMR2z zK?@1F1#~O&?wz|FdfR$qA=grKR=(}fT^}JICx1`rEjL~N6bZS$;3|GJZS3(}bKhsK zYdr7R7u+UsoA^)nRV;QGZkxDmd`882OP9p$dBQEZ+s3EgeY~NEwede!%yj6kCEfH! zzxw>r0@86U<2La>AO5C8pH~sq#-okrTz@?ZZri$T`tFnGIrO4D;|s2DjC|vGhaT<| zUs~UO{Zi6#_1&hsvvs3Gcbn{Vw`3ig<`yhQ!EM`->86e6Z#v7NyG?>cG;YYolao^` zs%J(yj!8P8u5>q3dG-V(7hCG)>+1rav z**99)Z=qZEfiOJtNmKT~9LhdunM1D7%_gw~3&YEvW$FK}m*(7T8lcS*iApSJ%4e4CYWf=_?c7zFb zhT#LY`GTh<$KKp!ncc3C4GQTNwp-X?;eR^F$eKCHQzLVmjOzuP_>oEnB#HW}B;4B~oemYHs0sfDes(rqTucnkltWly}#_I+FUo+f!SNa0tOn)J6= z7+4Y7LRn#WV4W#^?pzF?ZJD_i#(lvk*IO9gZw?gR@;}UPo2}dy*$~9=b?c1bOV`Q! zbLlq!>FkekaB;Jby*<<>ou6`I`01YdGQ-Hb!$98`Lj`-oaL+f5@diGX9Q&!Jl}32T z!pu8El?%i0T%#QM`Fos1EOg#8kF7l2j4DOkVE(V<Wcc*t*kk+i4KZ!8L#${^H;EQpZ|Id4?zGTNw8zRd-(ciwZ!&Pi zLRW6s%JqNV@IAK~SW{|oD>(e7Q}~0#__s`rgKx=m>B-3x3g5D|lg;V4Mde%aKIF)T z6*BFNPT9o@w%n`hlUB{LsK&3*CGxtz7F*4L`5L!0KN(+ufd_Ck@=`zM>lW$)11}?69!+ zhuTn6*>_g6L=L5`I9L>GwHhd77ok%XC|L`OZi_6J!-(f5(^7P zLgnMj0Zu6Sf)V31!P#iHy)Sp2oqXbT)sGr-)7ha;6Mv4u)9VetGmIa!e9z;C zKM=;R`#|2;>^lvt82G>#Biq$;tv42Gq#0(P%QMfyMHXIbp{tg9t|?#Zu*u)I+rVlI z2Q18Z*P+k$^qB`&-!p6rvN6$kUBKMk>S=phwmn%h`4|LyJW2AwImu^SJ?t?nb*^$} z7+z-!(=yehHR>}k-)~@MvVr{;jszy^tAIBUktAO~H`yOqS1iw+o1E;;h480ylTSFM zwAyHNTA1~K!Lw@&%z4njzIUC{vgr0PZx70sXC$9cQP6CdEf&uEj=_hYHZcC%2D;TL zJm1)|=NUsE{l0-U8w?z2GBDNRu3n|p%WpUQasw+osXsD=t{)pXXa!uwCaXBO(ePuR zHL%A*H^WkkyLz2gufM~{r)@HD>}LiVy$YsPmf8oDbVYvt3w0sTa%S^6;U&y8&^sWK|b@qnhNB$<6)vVV52RVWNobWPzZ zc3Q;&6u*Mv^b)I37p6##!Y+-n*kF-zTd#};Utv0aR!mI}j-ce)VhisEqc*6I|-KI{p zyTm(f!BXxr3HI5^i_0Ide4piS3FG%!euCw@)<|^Hm+xdHUv|O9)y6W0=1TAZ#}VkU z4~M!$@L~DXMakFB$_%3yhT)YD8<$D^YN-Cki;W9q|IXBL*us`q4E_=IN4Gmxc)|}Y zME${Jlxd-RXrZ*%(0hMxV1_M_+emJ~ciI9cSov-%pKj%wEHtL&b)>CMetvQC6%{3C znJsp=hKF<#%m0s$WgOZ`I<21VBuDBa6`rWGO#y1pH83H=z;X*S=Ud#ujTR=HXXvi8 z1Z+Ba78YArZ=vTLBcEnrp#x`gjg%#%+5)%(!~ARKzBkg&*Fzf=%YF~cW8vJvFU|H=o=19 z2wcZ-r!n1Dq0RP$CVOft%F=@tHot5Nex$=#!wvHE70Ks$OP_FR{rHtsx___H>3ZM5 z|MR`U^MR>IoO9mX#=ta(jyJjiFEC~l2lpH32E5@&qj03&(3fkR zt;1Sy)Izs6xcqiYAGXlx4L9I~N9ql(VyjiyY2nfKhTN|iub0g1W4ocxorAPEA&&3wZ3O$sL!TR22CW4HHiRB%Y#Vv{EkDunKfJN6Vy{(+VzOk>Su@i1FjofbG|M|uqwiR(3J7u}4VEwHIdMxfKQJkKgZ3)#Dwp!@+>|To> zv1jL*p51CQ-f7{1#vh{WSj7aZIJ(2g4Y&odmMV7( z>e$WW$+Q_~+kjD4X$lz9pUD4!i4Uw|{`W4>gsjhK{+@q#fu_yY#O+W~HKt~L4;a|` zpn-{&p8XYr7giZqW8u!K1Sfw_nF6|Qt3PViq{_i4JpbeATZaleIb$aDD(mfq_Y zP)E5XxbczJeO$#ltI%!X(Kd3=cjf6Dcta>%WNI9Bm4W}~n>f=}QHrdq|LZQ|UP!;flp zH<ZQJ*>$k%S7d$%k#7D&9_KzF|K z|NWJ)_y$v;4|^rdu?3I&tdS3YCER(7aprg{mu2CHz7o2Mu~s3&!lQj9^xSGP&ik|} zm?z)BkWN%VuR3H(_`m&?FvHfw?L}Lbn3|;&7?@~%YRJ;vF*0GX;cvOlKsu4upX;|Q z;Yhv6HRY%^Wx6eZ+lyTOu;r&&{()X}gjYh(t@f30r&Ua`ibvav>Yh6MD`Cr1a_p__ z5_jEdYMN7GU`X5l_c#4VKR@cZ$5f=F+Q8=946LygEVg+1a;4L{aZeb5gc<`oEOY~C z{r!f1#HL?vdQq0mpwhwvO>g-bmcG(Lr|JKr`H{yerdx$l3y-$xX)0E4<4#E1|Mxfj ze}4cSZ7>zgf5^b<#|=zbqmb79uLjWKFPQFIYc06NLbvH%ezm1{TIe+We{`_GRV=p( z8!bHArr+3Vn%+5BAa!40f1>XPrt&2}w9w9kO6_G+|IHo!qi^jNTM>7rG}dk^R`0@) z(~Y#YJ5_SuH?pjtJ6x7n{74o%P+9>1`D0mCjTQYC%B4vR-w+q zqiyYZ>kt2~S@=a$;DjIBcg^5W{=c;SNB^!_Vk_ddeOjlfSo=>6jJ0^_^9IlCtS}G5 z&l;HcoPloJdo2A(ZSR^g)n;5|q1)44e!$WTEIbh8kMyqTDkfTmJPVJu?Ss$AEng&< z*YuhSmA_)(|C*^%-=9o@K5VMgW2Z<*nku-~tI%ZO(N2~6 zHppvVO1`$De4nXE&A&n|+-~th0_cBo_hHDU7q3d{<=rM)|>=$!B^~H<|;AcQLYL zf7$3|tuoMcy;6&RREBA>=^eFUitaWAYOt`b(%`OPhVL@*F~cTYY+;?1ud(tqRYp$@ zp?|^WLJV`vmy^$_NNhGT)!#O-<3|SOw;AYe_2hil;6vXtuNG^37Gr z=Uum@)9~G!@7(kUEIsyaV+EHUzxiMbC~d&v?!|Vl+~{UG=We27*|4!{{JR#~Nl%8w zKPne3v*{hRi^l%L6ez>O?h%8#E}B_kDjsVSPIsY|@3Qg*?-@O};(@M%2BPm?TakR- z>3ttFciatI7#nABS7&ETC|>wWr;lHkU1`ct`bop@uyDYI#~FHf`U6RZo;}UL@bu$f zl$R=#lclsWIrge~sYYm}g^d@;J|nUelbeV_MSKEt_lX70?~nKNh3oO5Op9k5!x zySrEyG`G8kn^$$LXrH>y1q?Q%(`THZ)3<)0VRIPxOcu35{$&*um(8Z&#$26Y-&wlr zd*7ksXO?MLGDtUgkAcJ5bOno_*Xf%hnsyqV*7&MhH2$O)4Kxj}xI(8lG%1J^+B-Dq z1g_Ny6=&)f#`M&1>oFQ1GGF}442^HRUgHn`M8|D21gVqn;|J>oFX^q*+t%y&j_dS$ z`lxtJh*#F@4BbsZ1CP=1#nbg|AUl7f;|nHhIM;k>QKK#>b#%OLh)%Cqs__9sgqzI` zAgz1!tU9E>Ts*?}QNLI>Pro>(LBmC6NcNc9Fb2M$@y}1wL$f)dws-|6_G4FPTStA0r%_H@@>l)7%@fTQEB$>twjcJ5Qhxk7?@)igVU-D+INl4xcP57zB5C^JF`py zJ#<5w@6k6mo@w|->+kjS-I1g7J@RwYuyGphG1L7(K*w9p(Xb(AsC!?Felc~4#J25v ztXKEZ83SE)`l4@XxUEFP58u!gkFVAZ+i2h|5uGmX(3e_7&FyRB&HWJ77wYs_io+i? zjAEaw6I%YJm!8FobOX-3SmSLo_NkR)<2s#QVHnRClfJ}^{njR({*2)(AKskK;|(p}nkm8s}bUD4hj z>Ui%zYuJ#b;h`NG+S_%$mY?eQVo%4%lxn!Bm&R8Z;&cp=>xN*WR21rr^UaO0adU6T znFadA196?+`g48z%Oi(1KJ>DVHyhg6XRe579H@KX?EyO9o@X?SnjSr1>T~i@F6wXp zwHYF6PF>eyh;6qSvim>O1?@}S5PPm}nAofF2Tj9Tf2}!UwOQ^P4Y8)K$B9RE{&i@u zs=v<67g-y(t>L0=9P^bb^aY@ z8MlY&@i>nOHY#ye|Ssi;)XV`0q=#}5=gz6_WY;ZKJn5|*zYNgiy)bRz! zYPhvcm(yzaOYd$PZ#q!auGi_qx@&yua-7(m*&5MimebXSI-eP-k7%wmjA!3yo$rvL zg)ysje2?LPub3fO@TSI>m@mHZY#l#fR@sAQ4KfXjiH$>bhEz)rm|3t-YWzX72p!y{ z<7b*>caK@TLQ6G%pZS12^*TOqgN7&d&~UuzY5z>!6Ky{rT(jFcHn#V>T2}gkU`%{L z6`Oj&1HRA(p#Cqk0j&RvY=El&3v58_3#ERsH}=I&Kk?=K{{o2*wD;xw|6&=?m-GLN zWkCPe*Z&hf+wu$JLmzj?`kn}72o6Fy!m$Xw5PBmp{Wyfa2o(tZ5c(qwKp2QH2;q2y zN`xwe!3aYTh9V3@7>;lP!U%+FgpmkeK{yfNB!rU@PC+;oA&M{xp$1_z!We|FB8){C zhcF)DG=$R;&OkU5;Vgu+5hftiB1}Y>gfJPQ4xt`l3c^%`283w{=O9c+n1L`8VHUz{ zghqrWgmV$*Ak0OWhj1Rk`3Un7E{1{H1T-)lY5LTH2nGRo(yHG=i z-r*M?%cM>{*6S#^-l~Xle8b5rk)5xy?+JOm<&CBY;`r-}kis!O7ombUxsXMqCxw9S z&!n_guvpwR)&a-P9Y~zq-nj@S9p5QC$D^_n4pC7>oD8G8I<$gGLztA-3gU(y1viYi zWYYq7-mJ-2fHs<=`Qnm@1sD)kMF22YROgs6 zkT(Su#*@o`;%>_b>IP+qOXRp0-9Cd<3xZYA4Ah)~nzat9i=%1|)&ehpuZ3&ch$-iibqvys!wzGg_9NcR}Quh)*n=LkPTrz@yo@a9Hr>h43-Cac^Em zJYQr4uAP@5=0-Bqh|N{a^dasGu$lO+^gFroPdnXHtscpV16#^0>AaJum2HDsO62^% zC5mL@=oU9Q;U)L)R&wtXE$a%Cq54EyA$XWu^qXY#?3Rs}#7fG9_z}v&IE!qAEu3BE zM;wN}18y_o!A`gxi02sG_@7$hxsgXW;UWBCVfzd-8v!|;0w-&|I38naic&|LhE$V) ze6cf*e6cf*bFnjyx16TqQcSWlu8_idI+9;o)am8Lh|^moJs&4Jm4fLwei^ml>9`dC zOvkY?)MzT4-Yn~BPi~r?F~v>OaqRx?o$?_ndK?AU^C&osc85At{Z1z&yR`f$I5Ok( z#*kN$Tsq^(jEQ4!lH(HgL9l^i*~AfoGsDPgh=EA{`XZ!ojHg(0I*wi4uTwta$fwiu zv62Cua2#F^pU!9cpD%+Kb$FQ>$+go9Oh zY{`)qFGMp+!bmB(8_ihvbc-#YM;>|bN>qN3Pq7aZnetZK%az?PWn1!)WelIX!MJfvDw{OWocwdKVJkK%)OwmkF`<>uzuV?N4OCv5vXK3AP{(oWIX#JZ)y`+wA#QkSgOGA^+ugdhrT$ z!K+b*y(0pBA&^Tkzyt7Lwn; z5^dT?Qhgg3>p_`$mD@Mt)L|L2@+wr(pgQgI~qd!-`g_ z)OnVW8<|?gX6$Ba1uOaxPirQGg0d{HB~u=IjoVGy9KAEIL7Dg6hcf41gSYmwA8r9o zwy~kl@Ckot5BHgPqc{MHaOVl%SIGwwriuP}Az z-AMJvk@_80=ERXYp3SZUPVOPGEa6jkj_{p$^2MjhC*$b$5`N}EU@{KJLb6~PyO`rP zW*Jaoh$UwOwdRl6pgUls&FQm^Pep9^8+_WrFAXinQ?wAcVR-V1QS$8NpgZdfc{!jw z#1FZjDLZ${9}?5Zw>~7sIxM@c0H!LAJZG*zIkoK5MSLo#LqFfbr;}LUGkEfeGvuqx zzmeTkw36*?@X5-RZl4Sr{CX-L zcQ_!&u0p8;|ADk6Oj|;#zmsXpPLWSCEx>L*$TYUqAHoX4KR8sR8tl(&kFr#MetVP^ z`wQBmtle+7N6Cl%;r1w*rXOOiF1hIPv(*CC{$F7#MX_CfQ7T$Q-kJXE(w;(Qn*QsW zN>QxRU)&xgqw=GF%}0?F`AbvLB67s^U$^!Ya>MlBF{u>A6aC%WqvU`79;s;2pj*=4 z5~62&%BjzGOessHD8|Q)hiM~up1(X5E&4O%j&D~15?o=PTch0pj3*Q z$o}Koqnv{N%JwK{pTEjPOXP<|-nMWJ#GSloy#r~{@rwgvpOzC#++F3pBU$4EW3z148~9ScoMq>gd< z(9?;sQWxlYpbOB3DcF)uLZ(T8u3Xl`Errx`a}Re=vM%BM+LCwQ>O~-TjcV}qQpunPNTOY#oh1C+#4NqW~Ff3&@vRyy=!LD?P6Zlr@$E>9YoZ zPTH~YPEeGoIs@W#IotF0`>ddxbgef;?kRUe$<}MVVLq#yEbZ-{AKs4bem0tgQbnLG z;B1%I_jbLeW}AJGD{i*ytZKk-+3cHKvCN*T;3B(0!R_`m1?Su6DEOcDbOrxv&room zJyXHo*s~PeY0p;h2g%BBdM5{tLLj>axw{7Zmjq(xpi4?Wid#kUtWtM?A{A1{i_)r8 zq|#N9N>@WFqbiR=D)&|@QhB|y1F1|lV_ByHB(riGJ72K zNDfCeMLl6qPZ)7h4{Id#{Bnb)o*&jN8&EZVnL@>gEFYSA`h~jaQo=W$E&=sH?~Vg1Uoz6p)M0 zheisW&5Ak2Y!QktZ_L81Bt8@PP<$2QR6?z2gp$u;PcYRMD;oVw7tJ*V_yj1j&|p7~ z|FGdqZ$?jtpx(QohI`|pXps}*UO5y+7b3X}64=77NFcO<=Osy@xHq=|#pT5lO}x6F zUur{DV#lwY8^RX{@r8LJf}*QXajgxN8_LPSzvigw>S!j)_u-wLm@IX60n$~E0}ss~ z3#h881JSU{3($}POc>pDB)?3Nqh>D(?9da8uWauL$lCaI!KC8*>!Ff97{jP5;NJ4^aEIVGF8KK zQLR7fcUV1t94c~ZP=cfL5!=P#7iS`0K2mcqG>0)Ib45&3XF-ZOF@@3b5gYOMkbz^E zkL+1uMNhmgt&b3l|K5GB4Fl^q%zLVosW4jPm#$hLtG90IKX zgISl2A;~^dA$&;KgIR!#Oo(Ed1sbpd2TjHR;9~Vc0QnG8c=e^opM`?5fX|bUzMYsY zcm6RE%Fa^wE%K>Hy*`7v?sFc`LlgZMSF z>9s_eb&Xv1T7qltgvY!t);#$Tkma*LfB}^Cp^R+qe+@!kT{OkM zcP=U1FFxvP3wiluci_-~lNYeZvE*!|aMtImn#-Ipz6FYWkq=tW7W3=~@J!8@%eHxi zUFKnkLzwtMpwOtAe0*8Hymy<|Lw2ik^9u{{N=Q*}J_)fFkpm^Ei39r-_ zEtl0#c*l=AE|QCn-VGwtEV7qkk-K&IO(Yf)**2u-qX)N9Fi^w>qQcmM1Il}z@G338 z{N)qg2y3G(c+%@J^j$N;6kh`9TgHPJm45){0{X>2PyxRv%gF;f$P@uN8!uY_kV~KR zMisnk2T&QXBG9t3@m=}Clisv`@7mc4iOwRjl~A)p*gZg%q{DC51jM^?!c$(4;0qAN z_`(bFvZuW1a?w=xo7NxX>^85<;HV))Kbpe@srgG-qj_fvQu~A;XFL7FUyyyGKz>7>%QMb#D~n%1zt>_aD`th6mWQux zu6bEre~w#hy&%0e6aA32@(13a$!t|>wbQL6sT^tLdq^iWWr-K;ERaZQkpjnc@-fu! zf!0XLia&rVLm1)*f8d?vtFh!qKk%HgfJ1(^9WMt_47h;9rKb%OF&7`dJ^9*nSS>jH z19HbbiLIcCWt$Vba!S;krkpKj+?yB}+yogtjPcndufI1j7}NWMuHHP$l}*K7F~F$% zFz2(9)9*|C*;iZ|nTYt>Razn(p+I)GYN15Oe%)KW({0qKMj0Ry0x ztf*NqKyg-d8T?1H+VW)i_Y%did|^3xVhiY}#ilr!FOqhhg8zX%0ONNm={p~~C5oN- z;#wtr=ZpPH`py?uE9pC5T&$$;eBlpM`py@Jl=Pi1{;Z_$eDQ{ozVpSeu=ilP-)Ry% zePrX`OAL^`dwIS4hC~x+suhdlxoTCO010;j;uA%kma@PXbE5mpabXtRsdE2RsmK4Rs)Uzi~?2zjt4vy5bJnMMDb9H6|fYr9Iza) zA7DSg!GMDSM*@xn90fQE@HD`2fDx<+;{m$?o(6a<;IV-H0s8|E0UQGO6~M0m)&SN3 zo(_0AAXWxHy3dXt0~w+guovJ&`9LyJSvm>P?wICt0DA+@1sn)CPrjE-^esOR(H@xl z=L7ZuoDVn%@B+Z$fEUV>w}K2KvwNJIWpw^{W#?K|mUJasVr#{CH_A7+nPr1wd2* z+JGYf!>9S3Q>FE2qB4IJqTPTV2YAfs@{~st{qs-9b1&dXExk{dmlHP$&jW#*132h( z`5%uajt!oN=V55Wh4NRACdz_eL-Zs>FOk+`iSpP&@l_D=4EtPsS5?hS`%;V=B{zXR7#R;w%-Pg8pFoX+byb-zs=8uD1s=!d z$bg?#d^j(m_%Ku?hb`%QHgWt>nehz6jAyA5XNVb{m@&7#WX6q(883WRG2@$`?ZAvD z|1dEqKe!)@BR87+rMDaFL5tpKw(U-w9eqs=;R=6$yU5u?iJbShi=5?Z zmAGAtoVRxnIa?@lj<9Z$w?5{T7h`59k@BVvBIQl8{CA1LeM^+cz6q-Xdy|VDMM{e7 zg%BMJFvYOziEfft{w`5A+C?@kVS=4u01HK?daVE~zYAV3L@W&XuYeMQNHj7v9QPWT z+9mEb+E|%i{#~LER!i&k#H0A|$6rtM0QlAGiBSN@ypgzKREd)BxY%l;Afn{EO-jC7 z*)HF4{0q>9E|#ibd?hv$N94Pg-bnmu@B`>TKRS>S9rxOdQ#9gC<+8s3%O@+~#*n(b z1@hhBCngp=pai*WaPB~0RpSG4;vW*zY9CO79Jf!|M79zhO_0OOkWZM;FBXHmnUBIe z;t)N3VLYM9zU$>b{*c&bT`6DxW1`Qo3(z2rw9o1&%Ms58`z+aiU*eSVSK5WSzDk&T z1%si5x&9Ffb3c{dzQn{xN{Cxvgg9SVzP&Hey_E5zNpU}w<@*!GK4kmK{=@-mfgJE= zqO#Z*rrbzT9DB{0Ec6t`w*_+Hn>z2cZzd{`SIKX0q9J;y2B?O;sfLR3Tcv8)Z;?(N z0JdAV2uU+^V<+TfsCa=kBhk9L;<9m9KWSpgCGOc)_Oh(y^G8%VWl*RI` zX2>rVD0$21JUB;?w||msmaSzoWG|;omM7jGFhIuLdj%#!tXRf?wkNP0T5b3XQJ3C zpZZ>+XAE&RpIR2eCT#5p=NWi`Psb-AJ%n|F;#)ozGU%&n3b24txsr#43wo@YCM;Y{ zx$A1?VSSnhcmdX-3v$+>yxCadT9ulJ!W{i}tY8-h-6UceK!7NPKevn8(FXu8Ks=Pw z#o?L_uI1EX;zP;xd5C&AH!ePvtoJ#IdMAEbSx<|26!j?EQPgYFqTacP{+|`~N>id< zEl8zz)UQaU4`7pA2ph`4gf>R=K8_S2XI_ClnfN#N&zdXep?0^B;~v^UpPqs(-&6^l(dY%tkr+!kwE3#?JRC=+Oc|LqbS+bE$!(1%MiU zwwD$FD&9lbG^bktsQKrTTnC}O0Oh1C04W1N2({z}Iw}4|Z44jGA5Ec0EC3uzD(JNZ z01^#8oVh}6R8mpG;fLp-$YxZeEdceDr%}EdjJ3P!E1|%|9E)UzW&la?nG2Au{s=;O`g-LE=<2h)oc- zxk~W+InvRK(8oiukJ|^(m0I&pGZdAwKZmeRWh|9}pH1^`Ih3fgh4o)5{(C6Rf1Enk z73ZrjOw;(=AJh2%NDesL8(w~2`*y3l+HTzks?r*MM{T!mQ`@b=+c5k5Q2eJ1cL8i{ zzI(QJmUV-)CV2e{Zb;i|t!lb~TdiJl#sn|FeZR$_Oy6&jD!JdHMv42a>nC_+*d{$R z!5amYp58PiOKZLBEo_i-(D|DTW8jvJgR#jlgp_*FMS5z3#Cgw=$Uzst+LC;0qL*of zFEGRD#}Lz$c0tmb>}6ZQmFNTRQ&!4wowwh*Ony-3^|3CH<@L~WULZ%-dzGiXiQ2eB zP-ZerV-#V2sXYKDZG08BWhh&vr}hG111LK+sedaUs`twAg)h~6eNp%a^{gscKE<;v zM0-v3h67BSie9)t-aOSit9+N5hU~gNYU{cSG*uv65Mf0mjDC1V1{=Jx!e^k%#_Wg5 zls1$b_}TKr2Jb=ZrQ}-;-pNPQy&Ff-hUt&iSG)*FLl*#5f1*1Ce9pTfM9I1#N;-7( zAk4;eu(tT@Jb!#{w%oKi(JPjXDJ=NItJv^?Q1{Th=}@Igp2aTp$GH_uG|?jG2c9!4 z3q?_XpN%2l>jDwd72b{eksd&LMirRdnC0_!08btUfF_S|0^;d2szK^RlihH6T0 zpGg&VG(e`SW*)~$+l=sl1}fW7$>M03_%^?@37!Z_$*i^`}- zcUz&^L}f=v6V_KnqU1O9pveShtwk@QF|3>r3^NCoeH&~5c|g>(SaNM)W605Os0kRI zP!Nt4VX?do--t1T3X8T=zrCi02Et72&`BE9jnD;#!%=`?$^=!1@uHo25$_hn!ErHc zu>Rny;cDRck*~Rio*RY8C#$--UFZx&v|p^8Hy83R|rlMlfD@-63(*oGH^&?i;ng(eN-)Gw_( zKL-OAfQ6dw5ZYejcW9|bZk2C}fdNsc@=ccI4}sNCYa0-m%IyUf7>8mx&018pD$k0X zont4X$jQN-=u98-?HoG;a0cLPz}bN3py+dg>uP3V3eCj$O#|gj1Du4axP_jI&B0W_ zT=YaP;4BQ?EWmSk5P^GY-j~NM^)x^~Ah*z&fKvgp04e@t1J07W%H8hTg+YjEKc=9A zKM(bsy!c0nVRFhw&mK^RI;(1?LDfL@asyNnbm*BzgO`e9;}NU|9^@j|Z}iG!^g7Qk z13MB?YnmMF0MUJu7m&3(5+%XuC_Gr}cc#eK9!?Yo*-A!d$YtM!u6LGvx6C_6I;*`N zUBLvy@s)F$z!q$=3J_+F_$rzGT%upU$?*!OB4g#8$?<{Cz>MW{>f%*S72$yvL?zcda$~tyf@^W;d_sK~ ze_fmaVp*`tvRg>rb)Zs`J5#x+FdwN7gemCTMsb$!*JHYnok9UBXfLhDicdi|OIVF` z@~MY%g)S?EqF+-k~H<>>VUqPsqGL|zLI;W5r;&8k|VyL3P zkeG`>XMCQT4I!}>M8UXpIG!P~!{IoF#B+*LL*gGG9>za#Xf6nef#sy!kQh`B^FRy_ zv&v~d2#ML{v>SxbjdReAlL0kJV|a5(!hYu*z*&H^0M7+H7x~y=r9=aq3+)o)^9`&= zM-;&NKy6Y4Bp(5+1^Lwi=7H?;f-$O*Xent$#nUiWtu=E&mvf=WLq*jT(dSSp)Ky4rl8Uta_7zn|xkUkRWG!%{kq=oS` zKpG6Wj?%!`4KUUX569v`TL^QEg)m190sbq%YYU;aFrJP$Ero^P5#s@m0i=bo7ho^I z0e}MlhXM`-JQ46jz|nxC0nY$D9k2)#e+FQ8;fIeA9(n^YQI2Z$w1u&U$V89Rgs3fy zg8=8r-}H60g|R2Pmlnq30Otc94@e8+34j;MU9DbOzpo)$hWSDZV_!g87%Ks3VH^QS z3*)JP&GMoOxA^2wV^HLOAPtHY^3e*ntY<$&+s%nEBUU3G0gM6`Mddpc zZhvi41a3TV-A|Lp^#e{Rnt&rU^*K$>0xnESqD_$$GYD|5#DV+1X=cUe`nl<5#drI; zrLj3;3}(+vJ7r#+EIOJO>o8<*nHQ&uj^@RNP70@K7%ApYnHSH&q+#4B zoMPbL%D&icUYw!$`VsTuOtl&xF)z;Qq;TTG&jM5C#m08?BKZYW$Vw44(~eu4*~UV#Pp+#|Na6^+_fxT=w< zv=uVd*b42g=rmm>+k|v5Z-^N9*Id(8a0kN8M3JBYkm*HA3!)rBWo4}wv@&J+>xq6b zE$ww7>x^GFm+GYujxBQ!Ln#i{C;a27Ywm+H@zwel6d4Y>e4OfL;HfqWL5iewXJZ)n z^;~bUwNpFo5c;AZzM?S?U&zfpl_3SNf`X&7>8l#)2f_-OY{wIgnMmd*6<`nw&~)x& z=;%bv7_7K?dw%P$g6NOpf;>|gzaof zi26;HTRZT(+toX9RD`ca8`xI*7cK{+ zO`2^b2O>k@w=LJ&pIx7*{pq6=fxBp$?x6jtP?q3l@Lsz1=a~-LpXFNnvs^;^^Q{1B zmKq4Tb&A(LR)FtRx(YOc)R~R>n3_)Hz1;qX@doV3Q0!{5=N_L#3NF<%A$i^L?tYNS-JshAESQF50OK1k@%|xyx3v)p~W)-Ou6E+)llS zuf$dr1;NQxeKi_@a@aeT!}qd80p?Ka=s#gT1ThSp7kc%~aB@+fjkiPeJE!)B69*>@ zfLZ~r!xnQc^SX+aaFDE3;y+bvtS}HIBdCSnG}PWuCs5(fU0DuxX&g3s?Ph|nbKk{s z*fV}e_nFAYO*vFLPG(@In#d3zyEvc|^-GOk0I`(%fEzTON|7Jqi-Nf^qxwO8IhI`( ztb35N&ad->DUn}OrBbUlcF@b?>iI;WtbNq;7n11P_iV^J(GJK7&w7KD*ZNHDwflwL=-^=l z_fa^tmu|rrkv}w=u}VoOG3|MjW2BH+nmRnu6#H-WJlg+HJ&&0BanGY=R+e1xIy|KI zYX_wL+5u_*f1?9ZC1j7ndiOMW=I;|dtqJn#dbeDz#&hhpqpl*CVl>j-l^Cb@&j)~X zK+hH*fT(N7-iA2cl{h=NYLH_?Y>U&GDYu0(fVLBU09LC_Eh)2Kt(_YHvCEND+gI%(!61}d(^1@<)`6b5;;f_jpjcK-b;rn^PkG-Q zcU}kbyaNpvA};tr=}Qkkm}I#QFx|DCcy`D-?b`kzdV@>=r(D&N^B|WTC{b`rlUi!- zLOPv}9_r}Y{(^Mk^Z0y}0U-nFOMl&Ie|Z zq3M7^9h4w=;xQl1?NU}kE-~poS^=?6m77|0SUwk_d__QOu(*&*u8N^Tz1k=)g;uTu z#bjX>()P~-YSTdBkgE{SkWmKEn*^>`5E|9{RWT9NO&1j zi(Q`S=#?iMnQ1z&Lsc|EL)K9{5RN(4WZ5*sonQszLo?h<)B%Ph4lrD6rMp#pilYlj z99>Xe6ce%6`ki?mVdOv*qIv!G3{5c*{xWgP$xXv6> zSYi$-Tw)F>WQO%2g}<9a3X9Dlg|+68!U5$FmoI*=9OClDugxKa=glF7HsuhPFTQWn z<@w7)3ehhQDSR58;+KaM{zo5DkUO79{4AZlekQLq98viH@LD?>)BQAFYh=0|yw-3w z;rIE$#n?ddFv4Pe7~zig!wAukIu0into6po>Sb`UK2B{AaN;E*cP{e=26tn%q9K2` z%v|pAMBIqwI1#r^-ntx~BHQGkb>4vF-sK+rt2^FZ!OH=T++6`T7j+K9mHHfpx~k$H zTvg#4wZW_}R6M2MPC-TFKf9e`13p#VP9bk<@o*+C`BaN{kw5$@J~jOi+^f7LqSwjF zR)npfHlFE2aFby(DuD5e5Jocy8EN}3h(aH;nOTlL{I(djGV=SiW?k{jx^k6SS1vM# z-!j6q9OsKy&ARe8v#z{j)|J=Iy0XWtD?c{t%2Q@t`CjLB<@!GEP+y)Uf7-`A_G9PY zY^dgWiRKYgSNr+5@-P*jlr6Bn_kXt%irJ$bu+^kZO z)VVjBrM?)e6wbY!fiHwv3bu|8R;kH|(kjJsZ+!sg0{)M%O4%62e~(ove=@3~Rca0( zPP%RA=cb=@`?yK!i0^aflWvnlM^n`Q;*)O6Gmgqf>3y|ZE|rRpJ}A@pXcBxB%SDMg zLd@%bV69g7tJKppBYCF_Sm;GJd&Tf3nxZxo)DF~PrvWoXU%FCEhSMKzb-^j)bdJhX z#Vn6LIpnB~Dz1HUI^Wkqj;ii!k$D@)Q6)HPX|i^M_eOs3RczO|g1jnEegJJ*oW#8; zO(E-R@|cP4png=Vazp<%O3;@l9IuvVutQ&tu!H)5PkTASqZZzp?DhcIKiM4xFrd!8qWyk?)cLja`w5Pm zU)zTDCUrkS=ksf?*SUY{wH2S7t`K6J`i~WWS|PMT{SjfM+dhKXwtp3Vjg)4q);kf))SjMFi9Y zeEN$By-AYDiHIov0tuM>)) zB6wBC0o3nby-#Q@-lBi%zkYZC(p8(^iG5-B38CRI(#0I;Qej^H_unU^ZU4}UeL?pL zDP2?$ea+~+9QTgh`wg{(g1 ztb6sHI~zLOxwApvxwE0eojV)2;=yyA=RZ2$xwApvxw9V|Oue+>&Yk`L+N#$5pIxuB zcDpyF{X(7p9qZU-rLTU%687qmB`hFYirpR7=YB(G5;tUiOo!6ZUA{EsF3(dnl!Dvc z<;|U#N#2R+8@2T)O6*UgPuYrD+^$b4mX6~_AQwZaGA?3<@wt2VjUSR!CyIgTK?Ovq)p;V zTE&~yoo86~sjwh#ro!TGrLa)E`DmBWE;X0XN~$aF89&rLI)9#t5_vHimB4rNAUXsJ zY+Rfim}$xOc||e#GnK&5sSJ0`#b{;8pAC1P%nvrh=1i4Ev%czeZu?cQ)gh~AvV5l7 zVEKm)A2K4j>D|QDK6&5({!+!mGTh|em^GxT>V#oKlCfFtl|Ji`T$t5T95jE4Tx7|K zceR`-tFB8-%B~tQeCSAVyWGAO-p4_?X_mXlKl{>o=gFP{?=;zZ0Dm0Ep6%w#l7orv zzHQm^`19N~S%XKQ(vis*4<_m@t5ps;F{~?tKn6^3TlRm)38|AJ6epZ3!HMw2p1b8a#CHu&Tl7pR~0Hi@Y&&C>k3#mR^Rc!h7rv7~zg*Nyb$0UBcM~y9D#17VcFufN@)tk!*7|(1e-b0pKf_mCnMAAK zv3v(Blc@05R*IIsUDcuKik7MeS66-NE_MbhT1pOj0bT4nXktBH^v0PX{`Qdc)_s4L zYiIbz57!@YSCfm6c<`VbkoJ6co5Y`Ls=a5&u9lI>yv*Yw-!%B?CVsAg7a4e!fdM&jEzWM)7S#dx19o!z zi9L(u-k04#tah-*sRaDjVB(Di`b@%n6L0>6{EIu~kDGW)Cw!}kuhTGw^F8{PO4w*J zfK1hIvx#r{1pHQmH`&`ipzRazJ35pD1`%a#d;-4W6Yy1^fR6%ye5y5s4W@`42C?PDL*E)T{wZqhBQgF5F0;AE`P_%^7{@{%WMDQ9iOvz zt)4)8*UG2=;++ub{8!VP3+3^bxLu|5SFfb7_D4E%3chh|S6O+9+e4moaZ5lp|J4f= zMki_3lY(2mZ|N+X{|fcUfq-6kQt*}g<=GdxJ>@PE5gdJACrbS0sAKii3D{ z{xv<+7pCCbH|baBBQZD7txP2by7iQ|{nhOvo$GL^?8bv$Nw~x$m2}ffQ-us)hx15# zk(L`ZY0(a^Iq!KTky?{fYhG(OpZ(BN&VSF_o3XAHSFrKB=f97Zjqkr&RX)D|bqZGd m Date: Mon, 22 Oct 2018 21:59:18 +0200 Subject: [PATCH 09/12] Fix Visiond (#402) --- selfdrive/visiond/visiond | Bin 9041704 -> 9069496 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/selfdrive/visiond/visiond b/selfdrive/visiond/visiond index 85f62f56af24f9edce239d8d1cab82c76d06e2fa..471cd66f7912b748d07738bf4add8cb0a1275f2d 100755 GIT binary patch delta 12346 zcmbW73v^Rex`6k|2_&T{C$yBdV%rofq|nl|DbQM>Des3scxe%kV0jdIm5V^NXi`T> zv6nHiIJ*qvGRUwf569ernbSJMHK21Xf{Os^#ib6x$B0))>qVu#L+$HZ@-> zK0uzw_S#2Fa{A(?V;4(S(htq$W2mP2lQEO2<;bz`QUkg4`wDlJsgcGq=4R8Utfvq3 zRh`Du1zt1o8ERk=_}M&-+XPUv2)qXUa@IAB}?g?7iAC*CKGfk^=&Vf*+gMQ1Gs7Uecs)zE7GZ$qxAR z`u)<&dU+CIOQg(xgDp$6u%%7$gY(U5Qje^X-qy*srA=!68tEfFd3&mhH%PnsxXrUP zFa8pFV`Vx$gVP0mnsJN3C;p(>TLnIyaht&Zoy95DxI6mxYGMu!!QnZ^rwRN8#+?E` z%y_N99bHJ6sjGh1quroZF*0@pErw_GZT2eBbjDr3(%==3o^#x3>x0!R#FZ=l0X$ zIedL)4ps3A#2s7$uVVJK0_XO10(UX{MuBVgu>O34qLw)X1kO8X6?h%9ZxcAT4~d-F zcM(q3Kc9lCVr|hOXZ)PG7&i*MhH72XSZ>zpPYk@3W!MKNUtH5g+w+Y##<!TUve0krxoqs2i2Oz! z8bi48N`W7nE&38SZGpu#86A$u#>2a6dht~mjflu8ho|-QmIS~WMGE}RWVAbwggQ~< zlOQ%SEbt{Cs)_ zmL7Iz=`*JCTrz(qmzUUzK}zEzC$(w3Sr^=!t)FaYoCu{pS%_y^^f@y< z&>%Hv9YAXkCN*dP_7c>C*Wl>tUQF$v2K&fZ4UX|HzSRI&7RW15MdN&JC=jAFw zV|wZ<4^am5f=(j;HN%9iki6_Y9_5*eoPb`ZGz~6O%;IZIUPj{pMl+R}u}kCNWz`BIRe2NQ+6rbekknR`ojR zqP$YAElM&4bj#$}qFbheO^;T3*eJ16W3l;1KqsiTx1m2S^!ZYp zU+?|8GVa&$aI9Y?`01J7@nZd_CN~T|j9>!}boJs;6WuOhvT@%}pxY(LHf|U;ZkTV} zkCxHxLj5j)pYuj<8jqucHhTVMoHyg+1R+k4$2qgC*GTqV5E8)I4*hg8Po&}9=+J}o zQ8zmJzEEYTnE=Ocr46U->FYN<0gb;-w0V#0=?h{|kL)q78D*GIiF^|rc09PlxFu~m zH1Znk{u%I`ankOe3D31siF&ZZm?0_Cpk)LtwK{26&z&~@#cMDEMM-_ty>k=ZZ#Nur zpkUr|o3}o(A4sBFpJ-}7XRubl30GNy%RexkcTcMz?*yAa0nWk%8I6??8t4FqA~yej zm-b+n4wXb%z~+A*b{%aez{&W?#O_M4%>n*U0%Q(vgm&lVv>e>0D#{mhFyaY|$$jSdtXgz%YJIQpUwLGF6LC z`A&*M7*MJ@ORvZ}$`Pti@9(R$=MF~WVHl2LKMbKP8)dJB5-p(2QjACDD@6w0sAi2Y za#Y~G`APxNgpsQPpJNRuM=_QQxW-d~$3`203cNPj2vy)0S)&tqit)t)rBdsMtd>zQ z94#w5UN%ZejW+5>DYLYO%Z|^DQbtD`iG@l*IrTwyKTJ;hRvp?++Y!?CTyP(_f&W^L zc3**4Ipra0*UdiT&4n=|Jpv6oXvj!OUAn(o660wpCOv4L^s|F}hB>UjicQNF9HDqN z!jG9jZhi=4Cy|%{|2U?19sYZAdz+k2Y}u0-FE{A z5*^(zQD3?cOjL$v-dls|P{YWh*%KX-=p=@9g!Mr_$tC$CvhMJZOwWa*Z^L0g(u&wk z{%yRokR88Lr0moZhDJrPlA+ZgWcS;lay-3CNFg>o(%ngt3L9w?I8Nlo-M{6=bb)oh zz}q3My@$6WTKjq4w%GCK#Y#a650t_4gjx=_E17es!lik^q>cz=JGx&zMMoAy9&Oq< zzxW#Cfq0%AVwHd;*lbtUFQGwUykySz4R&ycE_BeP1v6znfia-;Kcu0+X* zHok$zNZt`i7CJu9+oa<_nxp%Z#nFVZeYBE8yn`rGp)MY+H0Y{n>#hpA^oDEW2qI|b zAkRDqL6&0>S!luNxe($@%2MQaP#e#M7Pc02fg*oIB7U9=%^D-VxS~{9NDdep81kfn z*bu3~E2T>6R4@ojEUFG7tYuLp7L~A7eAR(nww`SW(6i4pSYny7P#ff373%6T<$L{D z5*m3*=#kJgOVCao`LD$~m)cxmLgD*P5L1+fd7 z?#J{OBCj!r-5*z$n2RE+1$QSQJeW-HlR;h85XJX@I5>iTRYPYWH=LN~C`<*}hb7Y!Yv zq06+W%qcD^7(moqyZJg_T3Y1$SY&f-K&BQY$`o_V)F`+ZWf*QwqpYO|#tRc9g-ykhArtvc?zZDW7Q(Au%5DBp((; zyf|N}97-dwF_Lm4_|_J1BfkuXEYsn!3zS8-L<(rTm<$^qS)jc}XbnhLh;J1bGVeNc zvupL61<%$%wKk|jLT*q5D@$bsrc-B|&rI=d- zSs&G_?r)S#J<)}sV|D*EC67j;t&86&@c&L+SN?-CS&p{6-AZn>g^%4(zK^P2=~34A zC9NPCOS!>3ORd$L-=KXGqykz<6(kkcTNS@z43VSasZgnx2qr2lGYgnvZkNOkb#w4^(g{beZ3--at1Cws^K zBMl@SBm?9QkiqKMf84q2-L&J|*F$m$2~WK2VCD!s?owtZKK#ebq3Y!GnaAe4r)+cl z$+z!|41Uds-yZlXaroI+=RH`%uLbbG(w9DSuHnl-MiIZ>#Q!M%Oj%+6*aK7c^J@%T z?@s&En#V7UU&F6G@%t65U-vB?|5OLR9+fcsJ;U4q{8|A2>;1u%M~{`=czr9skH8Zs ze)Qudt)HD5!S7G-KhM8?--q@4!e5Wk1`7Z0-u4dupWLkRH!nu88)K7gr?wvfLw*5* zcd+gFd&cUE-;CiG9r%qE{e-27F5tXUJkkD>=Tgq^E%18^`uXoCE(iNNyS!w!usSR& zFM8jH-$B?_J+&f>hWK@sXCGQjIlo53?(3kgl}^fen|Io;_AmW5LL7eWh5H#d zzfUMC#U5}k8S+dAc^iwyNfSOn64q#+f3KU=UUpYf*ntoPuI(Xe)o3ZZ@=6nPS=l-w72#H z7pE)o`AEun<@j{{_-*rBFM&OuuFKY}yncL|j&H@ud0E4T@I}e_(a@kXFOyE9(}y1b zyPXU7LXi}As|CR?gGgL83r;O#0ruJG6G~I zNIpmb$S9CP5F1DlNHK^Vqy%I%$QY2ZAf+H>Aa{e5gWLl$4rDw?1&9Nr5@Z6%M36}! zlR>6{Oa+++G96?F$V`xXL1ux>2AKom1epsm4`e>b0+59u_kr9GQU$UI`f_)^&+|7A(&5s_F#dv zLieGhx}_^x$cvy?@FluaLfEW`z$haTdpLqM1X0CgLBfs{7%6T(VfdsNf~ZCb z=43t!1qMyJBzEHgP_DQvh^iPQHVeY+w_zoOsms@SS3Wp@8?235M}M?2S%Rk#Nme5~ z6Je3|_dLBCA)OT&ZNPQFZ4L>Z5DO3<6(`55Go;!&SGUOoFEj&;Ib#c@R>N z6aLkHOz_D}+7*ZCucHPj9-X;il^H5vLOWIsKm$B- zW5cR7$xkHfP(w9&0;f;lkai-{p`9yDFqlNo&XuyKKa!2ltd!A;WSP#`3Yw-4+Bzdi z6Mml3TN3f#!`=!hQ=OaNm@Q$;*E^gzRM41?Yp(AYh+PvKz3QBc-fn3}l6OZ^;~$fD zj=QKq1BA(dVL=6hb~C%0 z5H@4C!KpBe$Bqn#Kw!)c&fdgb)&_NrqK6jLiANn8i5eG$?4m=m60?8Rt-sScTwe{C0 z9AGBMDzD+WtXUcSuWIIh zi2q%KCrkX@BYU}nL*n_T3_eccuZ}f%zQprqa_%N`B!m49BcN2`n8+n@oItt6aRNIf zj{Y9b-Gs<9_DTU*P=my=peBh2gT@3}B)%zNK*mWNr{t9QyAK!x%#k<_Tqbd`#>BQE8BP_^32V z20SV)631l>NF4W7yTtLRbkzGEPpWTmm)(I!!k!zwfR5Pup`KauupdszjA5k`$CFeh z@rDKUfA-9pkE>rJne#)&v!g-cxNrRuhXp@5eb4CkRL`|qeftV!fugp+r&m@gC(P=L zjICDEVpF}>jI{atq9;c#)#}X~mA6f*zq?ki+N^wRX75UU)mEkM7Pm(fgRhKNHze~X zagD^^5Zo*A>3=u;8zeqgaKFU=L*!{PxI6r=+9v{9q=2UdZL7!FMXE? z=#V(BP)Oq4!oOSM=-(spo*cK)W9ui;y(hT_w@chAxI^OTpCfU*@Xwbx`a9i{Az1{J zN*n{qB<>LYiu^kkrxeudjxNgc%|TeiI)oAByp$UEfRN^2}7%7m?L;V;x574 zC0;IgP~tU$cSwAv!QCVz8EQ@$E72u!zevIc!IPa#cEmYf-+n`sj(O>4ti^}%f>{opqBRI{UeI%(;vQjS{p6#1-u7p;BMiO*^xQy8~4 z7W$~&VV>mX8hBh+$+3`XJyuuVPrFnyBBUl9o72}n$pzlTU+60xME3jRNjIsP)w>qh znRw#O1U@Y=+_wy3xSyxUH+OSCWw9Uj_b0KO$QOYR((v8@!VH?LS`0TJXiV6;Ra|(G~da2m8e=bK*}I zk*R#Ii0x7l`9D#_JrPBW|A8X%!M=U?|5wDG?-#L9Dk9-0ib#qm!uA72By8+2<(u-- z`tYXo@*{I;;K;O#_86N04oYNeLPfq2FbL`IpR^rXy8Zbgx-#3Gxsp4Bu?vj<#n#{0 z@jpAcO-gkw(WP$6iOBX;&dA z%^z4s&6!TR`$lJNm^i^(b{X%*pzU@#axVR9yc` zQvt@c|0*)B1mesh?!^h_PMg~aIoSam?CPh1ef^WT4hQ#x7=Bz@*ugCUA2_%{Jh&gP z>8BWX9^y)G_9vlk0-ZcFkmvR2JVD6Qf_cua>9?{(K`4M`IL&h{LaBbxX$HAPf6#gB zvt^c?Y4G?}ifO`uTYZ*dQ2wSCS2rKH6~v-9AFys7V=&CBIIZYM+N~*yW(Ca(R_?V&(a*hMeXZKk?u3W-YZm?B;+PNGESsH>A+xx; zDlQfzPOplywVktAr?NUswD3dQJ8rHt7W-o0Ss0^|JcW?K1RRLJ*!MsAebi+llfukZ z?0W`I9n+mLu;4qU_bT9<34C1)@v=8U8^mx1@u4Kr7E+aC#|waAUWe*?6?8(Jy&;Xz zeIMCUjEdG4)8>zCSr#$6{@0IehgD|sS{r$>ll9h+?X4k}P%#YcQ0cxKw!^4Y=k?e? z;`O|q+YVc8p&}AAIm|xCZf8Apn6(tDD4K2&n7*uNMUhIH?l5UzD^Z97O4JvaHPys9 z3E1?Nw`y%!sgR`wzAE@&3I!P?qXL#_889yiO{F78Y2%qYSJsCW5>F3~(ncE=M?5_z zlosM3R2_{LXFSadE3SB25mr3$^f{rx7Y0HvjMhq6HYfyk%NS!iTv;&G zY{X2PL74~^FCp=4U3$M<9gbv6fsx{~vo}!0dKgc&aYnTeNa)CM+9?aSz)D_=wDkXZ zNFsHN*UWBX5aP=qq=0{ha-TkQlk(3lg%9qJ<7LA8Qt?$c-lYCGXD>ABii?nCB*nAj z%~U>BFL4_F%tjQWi6+KwAzlS?g;dkAp=qA;$KQr`Fq@oTvH2ds!8{6mVZ64Ntth3_Czgh5jQxDC}`>ke}=R7r8DrjWMw#wwjsapvf!?0J}4ko z0=8iNL~YAzo)qTGdfu4o>^%VUw!%?o$%n%p;C8>_JMX^$rfh#}chdQ@@zpa+L0X<6ZhoSUSjgq3TcjKq<| z$nT)eM)oH;doQmFS4<~P)-sLF=#SS|P1g39)(6;1b=vse%Z7=do=H4QAVmS!LpC-s z{$L2eo?^@tD)u?KkLP>?YzEF;Q+*+Y#d*%x3r0dVIyGNgo{EVv5u2h&PG88^5@$0- z5m`-;p+aO(L{`Q&hO-v?GR(v{a$paChSA~*wB^PmJ8k-=0__`fUWjdHr-?rk`l?Ph zu`i>2RWBdyQ$?r126eT;(pUIl7Yl#AzF3=VOW;*PzehbQcArb3AI^h5a04jc&eO&( z1trLy3ak&KSCIW&hbKp)20H?JfjYC>!OosR7!$TbyaIO4;Ys42uO-HS(#=l&H+0** zS^^Dq-eyip>=Anzc=sO$$~rqgqO2?PwYi0-p{z_tyw8CpL=VBs{e=GuNjX*m{j6Kg zOJ^g}2k+GqS>M9*Vq4Q;YyigSbN6ZwWnp~>unstn5tHV%|8}5uTDm|phlBPSK|yv{ z<)FtSg1nJIyD$h&vK+KEA}9z!d05_N4Dx(G=z-tgqn0Q`vFg$k%eW6rKq?HRb^H}cXGM-S!VFUSLJ8V37lZy6t6R?T)v(I$V zBJB=(YN3{492gPF7M^WPk&WJ1sO1`|Jx1z1B6VS8YOsYRqha+1Z9osn8>fwJi1oU<$4#H^7|7hrN=PXmgE|0$wLMBO?@s8BgQ1AmfFlTFEe;LCldYH-WEh zemC){kWtuZ-ZJgJ?`87iDJBYSUIwob?k$EQcvK=L6Brm;zqU-fwA|un57m%Hwd2}6 zn%S&opZb$_%Vdj(#XIcu;AQO%RP>5Ytw>E3Cf_Ah89{cg?eS-m zUcvNNKG!ZOVgKeYw6!MGXxvxY-E_g1@U0lVfouueb@w$b&1`Y82dcxaAG)sPDq-!y z*BbnfC$ts*U7M+fwd!6iE3DCzH??oVrWg9OEw?fa_Me>=TI>t-O0)e{6CxeZa-Nqt z=+tW8@|`7g4^-eX>2a3Z6YUwG1wn(|;+Nms!t6K_nBKp z_-1+vd|jS=-w35ZPraBFf2Xz{;_z+wOXuwByl<00l0i~H?f^;E^S-^a?!BbD>|3BX zLZrWR&5^Vbw5TI3jUM~gv|;+pchXKSb-R=PZS!O2i#Ow~BE0VKWnA`KFD-eX9Pb6- z&-D4V=k{Fjr;NwTL-?zBZNb=4d532m!dnYy|FQgnyT3Q^k0tv3n3(MMEsJl*dja_K z{gDmFPZr#Kk|0;{M#!&s%i{gonl-ng8%V;S2_LPtn}jW z%?O%@>hz3u<( zw{>#6z6&M2c?h`NuF&TrImea5c76BX^>028{@AXIIqA8v*d|9T9h93sd?;>8Dad;7gT&kso`_lXPy^q3wPCvo#PF7#3O9#mSae!ok3AX7n{ zASEEvK&FGt0GSCg3uHFP9FVyn^FZc<+zYY*WFg2RkW!GvAWJ}&f-D1B4zdDdB}f^_ zeIUO8Sp~8hdsx&AT@gDuDxHK*WbRkHg1U8v8;lwX{|}4J?m=igKETYLp4{8J9PObdi9Yf i(`o+t+T<97l From c9fa92b3775e74f3d190690eb57b06b05af75827 Mon Sep 17 00:00:00 2001 From: rbiasini Date: Tue, 23 Oct 2018 12:05:11 -0700 Subject: [PATCH 10/12] remove badly named file (#404) --- "selfdrive/assets/sounds/Icon\r" | 0 1 file changed, 0 insertions(+), 0 deletions(-) delete mode 100644 "selfdrive/assets/sounds/Icon\r" diff --git "a/selfdrive/assets/sounds/Icon\r" "b/selfdrive/assets/sounds/Icon\r" deleted file mode 100644 index e69de29bb2d1d6..00000000000000 From 195139999b5c1912fc67b4e764527b21d06c4dc4 Mon Sep 17 00:00:00 2001 From: James-T1 <3042407+James-T1@users.noreply.github.com> Date: Tue, 23 Oct 2018 20:57:51 -0500 Subject: [PATCH 11/12] Update Genesis fingerprint for longer version from Saeed (#406) --- selfdrive/car/hyundai/values.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index df0adf191d26cd..0017c0783116f4 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -27,7 +27,7 @@ class Buttons: 66: 8, 67: 8, 68: 8, 127: 8, 273: 8, 274: 8, 275: 8, 339: 8, 356: 4, 399: 8, 512: 6, 544: 8, 593: 8, 608: 8, 688: 5, 790: 8, 809: 8, 897: 8, 899: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1170: 8, 1265: 4, 1280: 1, 1282: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1314: 8, 1322: 8, 1345: 8, 1349: 8, 1351: 8, 1353: 8, 1363: 8, 1366: 8, 1367: 8, 1369: 8, 1407: 8, 1415: 8, 1419: 8, 1425: 2, 1427: 6, 1440: 8, 1456: 4, 1472: 8, 1486: 8, 1487: 8, 1491: 8, 1530: 8, 1532: 5, 2001: 8, 2003: 8, 2004: 8, 2009: 8, 2012: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 }], CAR.GENESIS: [{ - 67: 8, 68: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 7, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 5, 897: 8, 902: 8, 903: 6, 916: 8, 1024: 2, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1287: 4, 1292: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1334: 8, 1335: 8, 1345: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1378: 4, 1384: 5, 1407: 8, 1419: 8, 1427: 6, 1434: 2, 1456: 4 + 67: 8, 68: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 7, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 5, 897: 8, 902: 8, 903: 6, 916: 8, 1024: 2, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1287: 4, 1292: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1334: 8, 1335: 8, 1342: 6, 1345: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1378: 4, 1384: 5, 1407: 8, 1419: 8, 1427: 6, 1434: 2, 1456: 4 }], CAR.KIA_SORENTO: [{ 67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1384: 8, 1407: 8, 1411: 8, 1419: 8, 1425: 2, 1427: 6, 1444: 8, 1456: 4, 1470: 8, 1489: 1 From 3d05cca678738ae8195649111da7083953f965b1 Mon Sep 17 00:00:00 2001 From: Vasily Tarasov Date: Tue, 23 Oct 2018 18:59:34 -0700 Subject: [PATCH 12/12] GM: disengage on radar fault (#396) * GM: copy cadillac's radar header DBC * Remove unused interface imports * Rename num targets message to radar header * Catch various radar faults --- opendbc/gm_global_a_object.dbc | 33 +++++++++++++++++++++++++-- selfdrive/car/gm/radar_interface.py | 35 +++++++++++++++++------------ 2 files changed, 52 insertions(+), 16 deletions(-) diff --git a/opendbc/gm_global_a_object.dbc b/opendbc/gm_global_a_object.dbc index b4aa31a3e179f1..8847bab39df0d1 100644 --- a/opendbc/gm_global_a_object.dbc +++ b/opendbc/gm_global_a_object.dbc @@ -67,8 +67,37 @@ BO_ 776 ASCMAccSpeedStatus: 7 NEO SG_ VehicleSpeed : 15|12@0+ (1,0) [0|0] "" B233B_LRR SG_ AlwaysOne : 3|1@0+ (1,0) [0|0] "" B233B_LRR -BO_ 1120 LRRNumObjects: 8 B233B_LRR - SG_ LRRNumObjects : 20|5@0+ (1,0) [0|0] "" NEO +BO_ 1120 F_LRR_Obj_Header: 8 LRR_FO + SG_ FLRRRollingCount : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRModeCmdFdbk : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRNumValidTargets : 20|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ FLRRTimeStampV : 31|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRTimeStamp : 2|11@0+ (1,0) [0|2047] "ms" EOCM_F_FO + SG_ FLRRRoadTypeInfo : 5|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRBurstChecksum : 55|16@0+ (1,0) [0|65535] "" EOCM_F_FO + SG_ FLRRDiagSpare : 30|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRVltgOutRngLo : 44|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRVltgOutRngHi : 43|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRSvcAlgnInPrcs : 38|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRSnsrBlckd : 45|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRSnstvFltPrsntInt : 24|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRPlntAlgnInProc : 37|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRMsalgnYawRt : 47|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRMsalgnYawLt : 46|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRLonVelPlsblityFlt : 35|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRYawRtPlsblityFlt : 34|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRMsalgnPtchUp : 32|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRMsalgnPtchDn : 33|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRInitDiagCmplt : 40|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRHWFltPrsntInt : 25|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRExtIntrfrnc : 36|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRCANSgnlSpvFld : 29|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRCANRxErr : 28|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRTunlDtctd : 27|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRAmbTmpOutRngLw : 42|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRAmbTmpOutRngHi : 41|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRAntTngFltPrsnt : 26|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRAlgnFltPrsnt : 39|1@0+ (1,0) [0|1] "" EOCM_F_FO BO_ 1134 LRRObject14: 8 B233B_LRR SG_ TrkRange : 5|11@0+ (0.125,0) [0|255.875] "m" NEO diff --git a/selfdrive/car/gm/radar_interface.py b/selfdrive/car/gm/radar_interface.py index bc35b3459b537e..a14cb1603f90f5 100755 --- a/selfdrive/car/gm/radar_interface.py +++ b/selfdrive/car/gm/radar_interface.py @@ -11,13 +11,13 @@ from selfdrive.services import service_list import selfdrive.messaging as messaging -NUM_TARGETS_MSG = 1120 -SLOT_1_MSG = NUM_TARGETS_MSG + 1 +RADAR_HEADER_MSG = 1120 +SLOT_1_MSG = RADAR_HEADER_MSG + 1 NUM_SLOTS = 20 # Actually it's 0x47f, but can parser only reports # messages that are present in DBC -LAST_RADAR_MSG = NUM_TARGETS_MSG + NUM_SLOTS +LAST_RADAR_MSG = RADAR_HEADER_MSG + NUM_SLOTS def create_radard_can_parser(canbus, car_fingerprint): @@ -25,12 +25,16 @@ def create_radard_can_parser(canbus, car_fingerprint): if car_fingerprint == CAR.VOLT: # C1A-ARS3-A by Continental radar_targets = range(SLOT_1_MSG, SLOT_1_MSG + NUM_SLOTS) - signals = zip(['LRRNumObjects'] + + signals = zip(['FLRRNumValidTargets', + 'FLRRSnsrBlckd', 'FLRRYawRtPlsblityFlt', + 'FLRRHWFltPrsntInt', 'FLRRAntTngFltPrsnt', + 'FLRRAlgnFltPrsnt', 'FLRRSnstvFltPrsntInt'] + ['TrkRange'] * NUM_SLOTS + ['TrkRangeRate'] * NUM_SLOTS + ['TrkRangeAccel'] * NUM_SLOTS + ['TrkAzimuth'] * NUM_SLOTS + ['TrkWidth'] * NUM_SLOTS + ['TrkObjectID'] * NUM_SLOTS, - [NUM_TARGETS_MSG] + radar_targets * 6, - [0] + [0.0] * NUM_SLOTS + [0.0] * NUM_SLOTS + + [RADAR_HEADER_MSG] * 7 + radar_targets * 6, + [0] * 7 + + [0.0] * NUM_SLOTS + [0.0] * NUM_SLOTS + [0.0] * NUM_SLOTS + [0.0] * NUM_SLOTS + [0.0] * NUM_SLOTS + [0] * NUM_SLOTS) @@ -44,8 +48,6 @@ class RadarInterface(object): def __init__(self, CP): # radar self.pts = {} - self.track_id = 0 - self.num_targets = 0 self.delay = 0.0 # Delay of radar @@ -70,22 +72,27 @@ def update(self): if LAST_RADAR_MSG in updated_messages: break + header = self.rcp.vl[RADAR_HEADER_MSG] + fault = header['FLRRSnsrBlckd'] or header['FLRRSnstvFltPrsntInt'] or \ + header['FLRRYawRtPlsblityFlt'] or header['FLRRHWFltPrsntInt'] or \ + header['FLRRAntTngFltPrsnt'] or header['FLRRAlgnFltPrsnt'] errors = [] if not self.rcp.can_valid: - errors.append("notValid") + errors.append("commIssue") + if fault: + errors.append("fault") ret.errors = errors currentTargets = set() - if self.rcp.vl[NUM_TARGETS_MSG]['LRRNumObjects'] != self.num_targets: - self.num_targets = self.rcp.vl[NUM_TARGETS_MSG]['LRRNumObjects'] + num_targets = header['FLRRNumValidTargets'] # Not all radar messages describe targets, - # no need to monitor all of the sself.rcp.msgs_upd + # no need to monitor all of the self.rcp.msgs_upd for ii in updated_messages: - if ii == NUM_TARGETS_MSG: + if ii == RADAR_HEADER_MSG: continue - if self.num_targets == 0: + if num_targets == 0: break cpt = self.rcp.vl[ii]